summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-21 20:44:55 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-21 20:44:55 +0000
commit5cdccc1b253b56481929e25ab9da64fdac589eba (patch)
tree5073a31c23682b316c5570f88378ceec5d816b43 /nuttx/configs
parent66c11ef077dee8cc367de7e539d5c6e03be78826 (diff)
downloadpx4-nuttx-5cdccc1b253b56481929e25ab9da64fdac589eba.tar.gz
px4-nuttx-5cdccc1b253b56481929e25ab9da64fdac589eba.tar.bz2
px4-nuttx-5cdccc1b253b56481929e25ab9da64fdac589eba.zip
Mirtoo update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4860 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/mirtoo/README.txt24
-rw-r--r--nuttx/configs/mirtoo/ostest/Make.defs4
-rw-r--r--nuttx/configs/mirtoo/ostest/debug.ld313
-rw-r--r--nuttx/configs/mirtoo/ostest/release.ld (renamed from nuttx/configs/mirtoo/ostest/ld.script)0
-rw-r--r--nuttx/configs/mirtoo/src/up_boot.c30
5 files changed, 368 insertions, 3 deletions
diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt
index 7867a6640..efe6a7aa5 100644
--- a/nuttx/configs/mirtoo/README.txt
+++ b/nuttx/configs/mirtoo/README.txt
@@ -12,6 +12,7 @@ Contents
Toolchains
Loading NuttX with ICD3
LED Usage
+ UART Usage
PIC32MX Configuration Options
Configurations
@@ -442,6 +443,29 @@ LED Usage
LED_ASSERTION 4 ON N/C OFF N/C
LED_PANIC 4 ON N/C OFF N/C
+UART Usage
+==========
+
+ When mounted on the DTX1-4000L EV-kit1 board, serial output is avaiable through
+ an FT230X device via the FUNC0 and FUNC1 module outputs. If CONFIG_PIC32MX_UART2
+ is enabled, the src/up_boot will configure the UART2 pins as follows:
+
+ ---------- ------ ----- ------ -------------------------
+ BOARD MODULE PIN SIGNAL NOTES
+ ---------- ------ ----- ------ -------------------------
+ FT230X RXD FUNC0 RPB11 U2RX UART2 RX (Also PGEC2)
+ FT230X TXD FUNC1 RPB10 U2TX UART2 TX (Also PGED2)
+
+ If CONFIG_PIC32MX_UART1 is enabled, the src/up_boot will configure the UART
+ pins as follows. This will support communictions (via an external RS-232
+ driver) through X3 pins 4 and 5:
+
+ ---------- ------ ----- ------ -------------------------
+ BOARD MODULE PIN SIGNAL NOTES
+ ---------- ------ ----- ------ -------------------------
+ X3, pin 4 FUNC4 RPBC5 U1TX UART1 TX
+ X3, pin 5 FUNC5 RPBC6 U1RX UART1 RX
+
PIC32MX Configuration Options
=============================
diff --git a/nuttx/configs/mirtoo/ostest/Make.defs b/nuttx/configs/mirtoo/ostest/Make.defs
index 1ea95a10b..d38134194 100644
--- a/nuttx/configs/mirtoo/ostest/Make.defs
+++ b/nuttx/configs/mirtoo/ostest/Make.defs
@@ -79,13 +79,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)/ostest/ld.script}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/debug.ld}"
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)/ostest/ld.script
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/ostest/debug.ld
endif
CC = $(CROSSDEV)gcc
diff --git a/nuttx/configs/mirtoo/ostest/debug.ld b/nuttx/configs/mirtoo/ostest/debug.ld
new file mode 100644
index 000000000..0db6f4801
--- /dev/null
+++ b/nuttx/configs/mirtoo/ostest/debug.ld
@@ -0,0 +1,313 @@
+/****************************************************************************
+ * configs/mirtoo/ostest/ld.script
+ *
+ * Copyright (C) 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.
+ *
+ ****************************************************************************/
+/* Memory Regions ***********************************************************/
+
+MEMORY
+{
+ /* The PIC32MX250F128D has 128Kb of program FLASH at physical address
+ * 0x1d000000 but is always accessed at KSEG0 address 0x9d00:0000
+ */
+
+ kseg0_progmem (rx) : ORIGIN = 0x9d000000, LENGTH = 128K
+
+ /* The PIC32MX250F128D has 3Kb of boot FLASH at physical addresses
+ * 0x1fc00000-0x1fc00c00. The initial reset vector is in KSEG1, but
+ * all other accesses are in KSEG0.
+ *
+ * REGION PHYSICAL KSEG SIZE
+ * DESCRIPTION START ADDR (BYTES)
+ * --------------- ---------- ------ ----------------------
+ * Exceptions:*
+ * Reset 0x1fc00000 KSEG1 384 384 (0.375Kb)
+ * Gen exception 0x1fc00000 KSEG1 128 512 (0.500Kb)
+ * TLB Refill 0x1fc00200 KSEG1 256 768 (0.750Kb)
+ * Cache Error 0x1fc00300 KSEG1 128 896 (0.875Kb)
+ * Others 0x1fc00380 KSEG1 128 1024 (1.000Kb)
+ * Interrupt 0x1fc00400 KSEG1 128 1152 (1.125Kb)
+ * Debug code 0x1fc00480 KSEG1 3072-1152-16 3056 (2.984Kb)
+ * DEVCFG3-0 0x1fc00bf0 KSEG1 16 3072 (3Kb)
+ *
+ * Exceptions assume:
+ *
+ * STATUS: BEV=0/1 and EXL=0
+ * CAUSE: IV=1
+ * JTAG: ProbEn=0
+ * And multi-vector support disabled
+ */
+
+ kseg1_reset (rx) : ORIGIN = 0xbfc00000, LENGTH = 384
+ kseg1_genexcpt (rx) : ORIGIN = 0xbfc00180, LENGTH = 128
+ kseg1_ebexcpt (rx) : ORIGIN = 0xbfc00200, LENGTH = 256
+ kseg1_cacherr (rx) : ORIGIN = 0xbfc00300, LENGTH = 128
+ kseg1_bevexcpt (rx) : ORIGIN = 0xbfc00380, LENGTH = 128
+ kseg1_intexcpt (rx) : ORIGIN = 0xbfc00400, LENGTH = 128
+ kseg1_dbgexcpt (rx) : ORIGIN = 0xbfc00480, LENGTH = 3072-1152-16
+ kseg1_devcfg (r) : ORIGIN = 0xbfc00bf0, LENGTH = 16
+
+ /* The PIC32MX250F128D has 32Kb of data memory at physical address
+ * 0x00000000. Since the PIC32MX has no data cache, this memory is
+ * always accessed through KSEG1.
+ *
+ * NOTE: When used with MPLAB, we need to set aside 512 bytes of memory
+ * at the beginning of this region for use by MPLAB.
+ */
+
+ kseg1_datamem (w!x) : ORIGIN = 0xa0000200, LENGTH = 32K - 512
+}
+
+OUTPUT_FORMAT("elf32-tradlittlemips")
+OUTPUT_ARCH(pic32mx)
+ENTRY(__start)
+
+SECTIONS
+{
+ /* Boot FLASH sections */
+
+ .reset :
+ {
+ KEEP (*(.reset))
+ } > kseg1_reset
+
+ /* Exception handlers. The following is assumed:
+ *
+ * STATUS: BEV=1 and EXL=0
+ * CAUSE: IV=1
+ * JTAG: ProbEn=0
+ * And multi-vector support disabled
+ *
+ * In that configuration, the vector locations become:
+ *
+ * Reset, Soft Reset bfc0:0000
+ * TLB Refill bfc0:0200
+ * Cache Error bfc0:0300
+ * All others bfc0:0380
+ * Interrupt bfc0:0400
+ * EJTAG Debug bfc0:0480
+ */
+
+ /* KSEG1 exception handler "trampolines" */
+
+ .gen_excpt :
+ {
+ KEEP (*(.gen_excpt))
+ } > kseg1_genexcpt
+
+ .ebase_excpt :
+ {
+ KEEP (*(.ebase_excpt))
+ } > kseg1_ebexcpt
+
+ .bev_excpt :
+ {
+ KEEP (*(.bev_excpt))
+ } > kseg1_bevexcpt
+
+ .int_excpt :
+ {
+ KEEP (*(.int_excpt))
+ } > kseg1_intexcpt
+
+ .dbg_excpt = ORIGIN(kseg1_dbgexcpt);
+
+ .devcfg :
+ {
+ KEEP (*(.devcfg))
+ } > kseg1_devcfg
+
+ /* Program FLASH sections */
+
+ .start :
+ {
+ /* KSEG0 Reset startup logic */
+
+ *(.start)
+
+ /* KSEG0 exception handlers */
+
+ *(.nmi_handler)
+ *(.bev_handler)
+ *(.int_handler)
+ } > kseg0_progmem
+
+ .text :
+ {
+ _stext = ABSOLUTE(.);
+ *(.text .text.*)
+ *(.stub)
+ KEEP (*(.text.*personality*))
+ *(.gnu.linkonce.t.*)
+ *(.gnu.warning)
+ *(.mips16.fn.*)
+ *(.mips16.call.*)
+
+ /* Read-only data is included in the text section */
+
+ *(.rodata .rodata.*)
+ *(.rodata1)
+ *(.gnu.linkonce.r.*)
+
+ /* Small initialized constant global and static data */
+
+ *(.sdata2 .sdata2.*)
+ *(.gnu.linkonce.s2.*)
+
+ /* Uninitialized constant global and static data */
+
+ *(.sbss2 .sbss2.*)
+ *(.gnu.linkonce.sb2.*)
+ _etext = ABSOLUTE(.);
+ } > kseg0_progmem
+
+ /* Initialization data begins here in progmem */
+
+ _data_loaddr = LOADADDR(.data);
+
+ .eh_frame_hdr : { *(.eh_frame_hdr) }
+ .eh_frame : ONLY_IF_RO { KEEP (*(.eh_frame)) }
+
+ /* RAM functions are positioned at the beginning of RAM so that
+ * they can be guaranteed to satisfy the 2Kb alignment requirement.
+ */
+
+/* This causes failures if there are no RAM functions
+ .ramfunc ALIGN(2K) :
+ {
+ _sramfunc = ABSOLUTE(.);
+ *(.ramfunc .ramfunc.*)
+ _eramfunc = ABSOLUTE(.);
+ } > kseg1_datamem AT > kseg0_progmem
+
+ _ramfunc_loadaddr = LOADADDR(.ramfunc);
+ _ramfunc_sizeof = SIZEOF(.ramfunc);
+ _bmxdkpba_address = _sramfunc - ORIGIN(kseg1_datamem) ;
+ _bmxdudba_address = LENGTH(kseg1_datamem) ;
+ _bmxdupba_address = LENGTH(kseg1_datamem) ;
+*/
+
+ .data :
+ {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ KEEP (*(.gnu.linkonce.d.*personality*))
+ *(.data1)
+ } > kseg1_datamem AT > kseg0_progmem
+
+ .eh_frame : ONLY_IF_RW { KEEP (*(.eh_frame)) }
+ _gp = ALIGN(16) + 0x7FF0 ;
+
+ .got :
+ {
+ *(.got.plt) *(.got)
+ } > kseg1_datamem AT > kseg0_progmem
+
+ .sdata :
+ {
+ *(.sdata .sdata.* .gnu.linkonce.s.*)
+ } > kseg1_datamem AT > kseg0_progmem
+
+ .lit8 :
+ {
+ *(.lit8)
+ } > kseg1_datamem AT > kseg0_progmem
+
+ .lit4 :
+ {
+ *(.lit4)
+ _edata = ABSOLUTE(.);
+ } >kseg1_datamem AT>kseg0_progmem
+
+ .sbss :
+ {
+ _sbss = ABSOLUTE(.);
+ *(.dynsbss)
+ *(.sbss .sbss.* .gnu.linkonce.sb.*)
+ *(.scommon)
+ } >kseg1_datamem
+
+ .bss :
+ {
+ *(.dynbss)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > kseg1_datamem
+
+ /* 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) }
+
+ /* DWARF debug sections */
+ /* DWARF 1 */
+
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+
+ /* GNU DWARF 1 extensions */
+
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+
+ /* DWARF 1.1 and DWARF 2 */
+
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+
+ /* DWARF 2 */
+
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+
+ /* SGI/MIPS DWARF 2 extensions */
+
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+
+ /DISCARD/ : { *(.note.GNU-stack) }
+}
diff --git a/nuttx/configs/mirtoo/ostest/ld.script b/nuttx/configs/mirtoo/ostest/release.ld
index afa76da1d..afa76da1d 100644
--- a/nuttx/configs/mirtoo/ostest/ld.script
+++ b/nuttx/configs/mirtoo/ostest/release.ld
diff --git a/nuttx/configs/mirtoo/src/up_boot.c b/nuttx/configs/mirtoo/src/up_boot.c
index 9dad76d0a..8acce6c45 100644
--- a/nuttx/configs/mirtoo/src/up_boot.c
+++ b/nuttx/configs/mirtoo/src/up_boot.c
@@ -55,6 +55,9 @@
* Definitions
************************************************************************************/
+#define GPIO_U1TX (GPIO_OUTPUT|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_U1RX (GPIO_INPUT|GPIO_PORTC|GPIO_PIN6)
+
#define GPIO_U2TX (GPIO_OUTPUT|GPIO_PORTB|GPIO_PIN10)
#define GPIO_U2RX (GPIO_INPUT|GPIO_PORTB|GPIO_PIN11)
@@ -67,7 +70,8 @@
*
* Description:
* When mounted on the DTX1-4000L EV-kit1 board, serial output is avaiable through
- * an FT230X device via the FUNC0 and FUNC1 module outputs
+ * an FT230X device via the FUNC0 and FUNC1 module outputs. If CONFIG_PIC32MX_UART2
+ * is enabled, the src/up_boot will configure the UART2 pins as follows.
*
* ---------- ------ ----- ------ -------------------------
* BOARD OUTPUT PIN SIGNAL NOTES
@@ -75,6 +79,16 @@
* FT230X RXD FUNC0 RPB11 U2RX UART2 RX (Also PGEC2)
* FT230X TXD FUNC1 RPB10 U2TX UART2 TX (Also PGED2)
*
+ * If CONFIG_PIC32MX_UART1 is enabled, the src/up_boot will configure the UART
+ * pins as follows. This will support communictions (via an external RS-232
+ * driver) through X3 pins 4 and 5:
+ *
+ * ---------- ------ ----- ------ -------------------------
+ * BOARD MODULE PIN SIGNAL NOTES
+ * ---------- ------ ----- ------ -------------------------
+ * X3, pin 4 FUNC4 RPBC5 U1TX UART1 TX
+ * X3, pin 5 FUNC5 RPBC6 U1RX UART1 RX
+ *
************************************************************************************/
static inline void pic32mx_uartinitialize(void)
@@ -92,6 +106,20 @@ static inline void pic32mx_uartinitialize(void)
putreg32(PPS_INSEL_RPB11, PIC32MX_PPS_U2RXR);
putreg32(PPS_OUTSEL_U2TX, PIC32MX_PPS_RPB10R);
#endif
+
+#ifdef CONFIG_PIC32MX_UART1
+ /* Make sure that TRIS pins are set correctly. Configure the UART pins as digital
+ * inputs and outputs first.
+ */
+
+ pic32mx_configgpio(GPIO_U1TX);
+ pic32mx_configgpio(GPIO_U1RX);
+
+ /* Configure UART TX and RX pins to RPB10 and 11, respectively */
+
+ putreg32(PPS_INSEL_RPC6, PIC32MX_PPS_U1RXR);
+ putreg32(PPS_OUTSEL_U1TX, PIC32MX_PPS_RPC5R);
+#endif
}
/************************************************************************************