summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-23 16:41:32 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-23 16:41:32 +0000
commitc6c6b1ec49d53c1bbaca39028ff0dec3cae8be91 (patch)
tree76e23f8a031b027662454bf1bc980891d9bf5cfe
parent6b683ebb8b07e50dcb1ae2b5fb08a89c59341041 (diff)
downloadpx4-nuttx-c6c6b1ec49d53c1bbaca39028ff0dec3cae8be91.tar.gz
px4-nuttx-c6c6b1ec49d53c1bbaca39028ff0dec3cae8be91.tar.bz2
px4-nuttx-c6c6b1ec49d53c1bbaca39028ff0dec3cae8be91.zip
Add support for the Penguino mips-elf toolchain for PIC32
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4866 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/Documentation/NuttX.html10
-rw-r--r--nuttx/configs/mirtoo/README.txt40
-rw-r--r--nuttx/configs/mirtoo/nsh/Make.defs20
-rw-r--r--nuttx/configs/mirtoo/ostest/Make.defs20
-rw-r--r--nuttx/configs/mirtoo/scripts/c32-debug.ld (renamed from nuttx/configs/mirtoo/scripts/debug.ld)2
-rw-r--r--nuttx/configs/mirtoo/scripts/c32-release.ld (renamed from nuttx/configs/mirtoo/scripts/release.ld)2
-rw-r--r--nuttx/configs/mirtoo/scripts/mips-elf-debug.ld313
-rw-r--r--nuttx/configs/mirtoo/scripts/mips-elf-release.ld315
-rw-r--r--nuttx/configs/mirtoo/scripts/xc32-debug.ld313
-rw-r--r--nuttx/configs/mirtoo/scripts/xc32-release.ld315
-rw-r--r--nuttx/configs/pcblogic-pic32mx/README.txt17
-rw-r--r--nuttx/configs/pic32-starterkit/README.txt13
-rw-r--r--nuttx/configs/pic32mx7mmb/README.txt13
-rw-r--r--nuttx/configs/sure-pic32mx/README.txt13
-rw-r--r--nuttx/configs/ubw32/README.txt13
15 files changed, 1407 insertions, 12 deletions
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index d0111b5ac..edcdb1b95 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: June 20, 2012</p>
+ <p>Last Updated: June 22, 2012</p>
</td>
</tr>
</table>
@@ -2214,8 +2214,12 @@ nfsmount &lt;server-address&gt; &lt;mount-point&gt; &lt;remote-path&gt;
<ul>
<p>
<b>STATUS:</b>
- The basic port is code complete but still not fully verified.
- With any luck, the verified port should be available with the NuttX 6.20 release.
+ The basic port is code complete but development is ongoing and many features have not yet been verified.
+ Two configurations are available:
+ An OS test configuration and a that support the NuttShell (NSH).
+ The OS test configuration is fully functional and proves that we have a basically healthy NuttX port to the Mirtoo.
+ See the <a href="http://www.nuttx.org/NuttShell.html">NSH User Guide</a> for further information about NSH.
+ There are some remaining issues to be resolved with the NSH configuration but, with any luck, the verified port should be available with the NuttX 6.20 release.
</p>
</ul>
</td>
diff --git a/nuttx/configs/mirtoo/README.txt b/nuttx/configs/mirtoo/README.txt
index 52350bb05..7de835d68 100644
--- a/nuttx/configs/mirtoo/README.txt
+++ b/nuttx/configs/mirtoo/README.txt
@@ -375,6 +375,24 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ Experimental (and untested) support for the Penguino mips-elf toolchain has
+ been included in the Mirtoo configurations. Use this configuration option to
+ select the Penguino mips-elf toolchain:
+
+ CONFIG_PIC32MX_MIPSELFL - Penguino mips-elf toolchain for Linux
+
+ And set the path appropriately in the setenv.sh file. And good luck!
+
MPLAB/C32 vs MPLABX/X32
-----------------------
@@ -771,11 +789,31 @@ Where <subdir> is one of the following:
This configuration also uses the Microchip C32 toolchain under
windows by default:
- CONFIG_PIC32MX_MICROCHIPW_LITE=y : Lite version of widows toolchain
+ CONFIG_PIC32MX_MICROCHIPW_LITE=y : Lite version of windows toolchain
To switch to the Linux C32 toolchain you will have to change (1) the
toolchain selection in .config (after configuration) and (2) the
path to the toolchain in setenv.sh. See notes above with regard to
the XC32 toolchain.
+ nsh:
+ This configuration directory holds configuration files tht can
+ be used to support the NuttShell (NSH). This configuration use
+ UART1 which is available on FUNC 4 and 5 on connector X3:
+
+ CONFIG_PIC32MX_UART1=y : UART1 for serial console
+ CONFIG_UART1_SERIAL_CONSOLE=n
+
+ If you are not using MPLAB to debug, you may switch to UART2
+ by following the instructions above for the ostest configuration.
+
+ This configuration also uses the Microchip C32 toolchain under
+ windows by default:
+ CONFIG_PIC32MX_MICROCHIPW_LITE=y : Lite version of windows toolchain
+
+ To switch to the Linux C32 toolchain you will have to change (1) the
+ toolchain selection in .config (after configuration) and (2) the
+ path to the toolchain in setenv.sh. See notes above with regard to
+ the XC32 toolchain.
+
diff --git a/nuttx/configs/mirtoo/nsh/Make.defs b/nuttx/configs/mirtoo/nsh/Make.defs
index c13ca4985..a5506381e 100644
--- a/nuttx/configs/mirtoo/nsh/Make.defs
+++ b/nuttx/configs/mirtoo/nsh/Make.defs
@@ -46,6 +46,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y)
# Microchip C32 toolchain under Windows
@@ -56,6 +57,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y)
# Microchip C32 toolchain under Linux
@@ -65,6 +67,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = xc32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y)
# Microchip C32 toolchain under Linux
@@ -74,14 +77,25 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = xc32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPOPENL),y)
- # microchipOpen -toolchain under Linux
+ # microchipOpen toolchain under Linux
CROSSDEV = mypic32-
# MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
+endif
+ifeq ($(CONFIG_PIC32MX_MIPSELFL),y)
+ # Penquino mips-elf toolchain under Linux
+ CROSSDEV = mips-elf-
+ # MAXOPTIMIZATION = -O2
+ ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL
+ ARCHPICFLAGS = -fpic -membedded-pic
+ LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = mips-elf-debug.ld
endif
ifeq ($(WINTOOL),y)
@@ -91,13 +105,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/debug.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/debug.ld
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
CC = $(CROSSDEV)gcc
diff --git a/nuttx/configs/mirtoo/ostest/Make.defs b/nuttx/configs/mirtoo/ostest/Make.defs
index 37c6e5db8..026a4cfa4 100644
--- a/nuttx/configs/mirtoo/ostest/Make.defs
+++ b/nuttx/configs/mirtoo/ostest/Make.defs
@@ -46,6 +46,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPW),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y)
# Microchip C32 toolchain under Windows
@@ -56,6 +57,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPW_LITE),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y)
# Microchip C32 toolchain under Linux
@@ -65,6 +67,7 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPL),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = xc32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y)
# Microchip C32 toolchain under Linux
@@ -74,14 +77,25 @@ ifeq ($(CONFIG_PIC32MX_MICROCHIPL_LITE),y)
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = xc32-debug.ld
endif
ifeq ($(CONFIG_PIC32MX_MICROCHIPOPENL),y)
- # microchipOpen -toolchain under Linux
+ # microchipOpen toolchain under Linux
CROSSDEV = mypic32-
# MAXOPTIMIZATION = -O2
ARCHCPUFLAGS = -mprocessor=elf32pic32mx -mno-float -mlong32 -membedded-data
ARCHPICFLAGS = -fpic -membedded-pic
LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = c32-debug.ld
+endif
+ifeq ($(CONFIG_PIC32MX_MIPSELFL),y)
+ # Penquino mips-elf toolchain under Linux
+ CROSSDEV = mips-elf-
+ # MAXOPTIMIZATION = -O2
+ ARCHCPUFLAGS = -mlong32 -membedded-data -msoft-float -march=24kc -EL
+ ARCHPICFLAGS = -fpic -membedded-pic
+ LDFLAGS += -nostartfiles -nodefaultlibs
+ LDSCRIPT = mips-elf-debug.ld
endif
ifeq ($(WINTOOL),y)
@@ -91,13 +105,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/debug.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/debug.ld
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
CC = $(CROSSDEV)gcc
diff --git a/nuttx/configs/mirtoo/scripts/debug.ld b/nuttx/configs/mirtoo/scripts/c32-debug.ld
index 8bc4a7efa..d91aa5e72 100644
--- a/nuttx/configs/mirtoo/scripts/debug.ld
+++ b/nuttx/configs/mirtoo/scripts/c32-debug.ld
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/mirtoo/scripts/debug.ld
+ * configs/mirtoo/scripts/c32-debug.ld
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/configs/mirtoo/scripts/release.ld b/nuttx/configs/mirtoo/scripts/c32-release.ld
index 172260bc6..05f0ecc06 100644
--- a/nuttx/configs/mirtoo/scripts/release.ld
+++ b/nuttx/configs/mirtoo/scripts/c32-release.ld
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/mirtoo/scripts/release.ld
+ * configs/mirtoo/scripts/c32-release.ld
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld b/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld
new file mode 100644
index 000000000..c08ba13c8
--- /dev/null
+++ b/nuttx/configs/mirtoo/scripts/mips-elf-debug.ld
@@ -0,0 +1,313 @@
+/****************************************************************************
+ * configs/mirtoo/scripts/mips-elf-debug.ld
+ *
+ * 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-littlemips")
+OUTPUT_ARCH(mips)
+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/scripts/mips-elf-release.ld b/nuttx/configs/mirtoo/scripts/mips-elf-release.ld
new file mode 100644
index 000000000..ce64e67a5
--- /dev/null
+++ b/nuttx/configs/mirtoo/scripts/mips-elf-release.ld
@@ -0,0 +1,315 @@
+/****************************************************************************
+ * configs/mirtoo/scripts/mips-elf-release.ld
+ *
+ * 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)
+ * JTAG 0x1fc00480 KSEG1 16 1168 (1.141Kb)
+ * Exceptions 0x1fc00490 KSEG0 3072-1168-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 = 16
+ kseg0_bootmem (rx) : ORIGIN = 0x9fc00490, LENGTH = 3072-1168-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
+}
+
+OUTPUT_FORMAT("elf32-littlemips")
+OUTPUT_ARCH(mips)
+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);
+
+ .start :
+ {
+ /* KSEG0 Reset startup logic */
+
+ *(.start)
+
+ /* KSEG0 exception handlers */
+
+ *(.nmi_handler)
+ *(.bev_handler)
+ *(.int_handler)
+ } > kseg0_bootmem
+
+ .devcfg :
+ {
+ KEEP (*(.devcfg))
+ } > kseg1_devcfg
+
+ /* Program FLASH sections */
+
+ .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/scripts/xc32-debug.ld b/nuttx/configs/mirtoo/scripts/xc32-debug.ld
new file mode 100644
index 000000000..7582dcaab
--- /dev/null
+++ b/nuttx/configs/mirtoo/scripts/xc32-debug.ld
@@ -0,0 +1,313 @@
+/****************************************************************************
+ * configs/mirtoo/scripts/xc32-debug.ld
+ *
+ * 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_program_mem (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_data_mem (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_program_mem
+
+ .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_program_mem
+
+ /* 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_data_mem AT > kseg0_program_mem
+
+ _ramfunc_loadaddr = LOADADDR(.ramfunc);
+ _ramfunc_sizeof = SIZEOF(.ramfunc);
+ _bmxdkpba_address = _sramfunc - ORIGIN(kseg1_data_mem) ;
+ _bmxdudba_address = LENGTH(kseg1_data_mem) ;
+ _bmxdupba_address = LENGTH(kseg1_data_mem) ;
+*/
+
+ .data :
+ {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ KEEP (*(.gnu.linkonce.d.*personality*))
+ *(.data1)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .eh_frame : ONLY_IF_RW { KEEP (*(.eh_frame)) }
+ _gp = ALIGN(16) + 0x7FF0 ;
+
+ .got :
+ {
+ *(.got.plt) *(.got)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .sdata :
+ {
+ *(.sdata .sdata.* .gnu.linkonce.s.*)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .lit8 :
+ {
+ *(.lit8)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .lit4 :
+ {
+ *(.lit4)
+ _edata = ABSOLUTE(.);
+ } >kseg1_data_mem AT>kseg0_program_mem
+
+ .sbss :
+ {
+ _sbss = ABSOLUTE(.);
+ *(.dynsbss)
+ *(.sbss .sbss.* .gnu.linkonce.sb.*)
+ *(.scommon)
+ } >kseg1_data_mem
+
+ .bss :
+ {
+ *(.dynbss)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > kseg1_data_mem
+
+ /* 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/scripts/xc32-release.ld b/nuttx/configs/mirtoo/scripts/xc32-release.ld
new file mode 100644
index 000000000..2c8471ad8
--- /dev/null
+++ b/nuttx/configs/mirtoo/scripts/xc32-release.ld
@@ -0,0 +1,315 @@
+/****************************************************************************
+ * configs/mirtoo/scripts/xc32-release.ld
+ *
+ * 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_program_mem (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)
+ * JTAG 0x1fc00480 KSEG1 16 1168 (1.141Kb)
+ * Exceptions 0x1fc00490 KSEG0 3072-1168-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 = 16
+ kseg0_bootmem (rx) : ORIGIN = 0x9fc00490, LENGTH = 3072-1168-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_data_mem (w!x) : ORIGIN = 0xa0000200, LENGTH = 32K
+}
+
+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);
+
+ .start :
+ {
+ /* KSEG0 Reset startup logic */
+
+ *(.start)
+
+ /* KSEG0 exception handlers */
+
+ *(.nmi_handler)
+ *(.bev_handler)
+ *(.int_handler)
+ } > kseg0_bootmem
+
+ .devcfg :
+ {
+ KEEP (*(.devcfg))
+ } > kseg1_devcfg
+
+ /* Program FLASH sections */
+
+ .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_program_mem
+
+ /* 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_data_mem AT > kseg0_program_mem
+
+ _ramfunc_loadaddr = LOADADDR(.ramfunc);
+ _ramfunc_sizeof = SIZEOF(.ramfunc);
+ _bmxdkpba_address = _sramfunc - ORIGIN(kseg1_data_mem) ;
+ _bmxdudba_address = LENGTH(kseg1_data_mem) ;
+ _bmxdupba_address = LENGTH(kseg1_data_mem) ;
+*/
+
+ .data :
+ {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ KEEP (*(.gnu.linkonce.d.*personality*))
+ *(.data1)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .eh_frame : ONLY_IF_RW { KEEP (*(.eh_frame)) }
+ _gp = ALIGN(16) + 0x7FF0 ;
+
+ .got :
+ {
+ *(.got.plt) *(.got)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .sdata :
+ {
+ *(.sdata .sdata.* .gnu.linkonce.s.*)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .lit8 :
+ {
+ *(.lit8)
+ } > kseg1_data_mem AT > kseg0_program_mem
+
+ .lit4 :
+ {
+ *(.lit4)
+ _edata = ABSOLUTE(.);
+ } >kseg1_data_mem AT>kseg0_program_mem
+
+ .sbss :
+ {
+ _sbss = ABSOLUTE(.);
+ *(.dynsbss)
+ *(.sbss .sbss.* .gnu.linkonce.sb.*)
+ *(.scommon)
+ } >kseg1_data_mem
+
+ .bss :
+ {
+ *(.dynbss)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > kseg1_data_mem
+
+ /* 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/pcblogic-pic32mx/README.txt b/nuttx/configs/pcblogic-pic32mx/README.txt
index cf20d37ad..76d92e928 100644
--- a/nuttx/configs/pcblogic-pic32mx/README.txt
+++ b/nuttx/configs/pcblogic-pic32mx/README.txt
@@ -211,6 +211,19 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ See also configs/mirtoo/README.txt. There is an experimental (untested)
+ configuration for the Mirtoo platform in that directory.
+
MPLAB/C32 vs MPLABX/X32
-----------------------
@@ -535,3 +548,7 @@ Where <subdir> is one of the following:
ostest:
This configuration directory, performs a simple OS test using
apps/examples/ostest.
+
+ nsh:
+ This configuration directory holds configuration files tht can
+ be used to support the NuttShell (NSH).
diff --git a/nuttx/configs/pic32-starterkit/README.txt b/nuttx/configs/pic32-starterkit/README.txt
index b123cfa48..8ef5aae27 100644
--- a/nuttx/configs/pic32-starterkit/README.txt
+++ b/nuttx/configs/pic32-starterkit/README.txt
@@ -428,6 +428,19 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ See also configs/mirtoo/README.txt. There is an experimental (untested)
+ configuration for the Mirtoo platform in that directory.
+
MPLAB/C32 vs MPLABX/X32
-----------------------
diff --git a/nuttx/configs/pic32mx7mmb/README.txt b/nuttx/configs/pic32mx7mmb/README.txt
index c006908ed..1406a3cf2 100644
--- a/nuttx/configs/pic32mx7mmb/README.txt
+++ b/nuttx/configs/pic32mx7mmb/README.txt
@@ -196,6 +196,19 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ See also configs/mirtoo/README.txt. There is an experimental (untested)
+ configuration for the Mirtoo platform in that directory.
+
MPLAB/C32 vs MPLABX/X32
-----------------------
diff --git a/nuttx/configs/sure-pic32mx/README.txt b/nuttx/configs/sure-pic32mx/README.txt
index 40ddc25a7..bd206a262 100644
--- a/nuttx/configs/sure-pic32mx/README.txt
+++ b/nuttx/configs/sure-pic32mx/README.txt
@@ -277,6 +277,19 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ See also configs/mirtoo/README.txt. There is an experimental (untested)
+ configuration for the Mirtoo platform in that directory.
+
MPLAB/C32 vs MPLABX/X32
-----------------------
diff --git a/nuttx/configs/ubw32/README.txt b/nuttx/configs/ubw32/README.txt
index cdd3cd385..257dbffff 100644
--- a/nuttx/configs/ubw32/README.txt
+++ b/nuttx/configs/ubw32/README.txt
@@ -221,6 +221,19 @@ Toolchains
Note that the tools will have the prefix, mypic32- so, for example, the
compiler will be called mypic32-gcc.
+ Penguino mips-elf Toolchain
+ ---------------------------
+
+ Another option is the mips-elf toolchain used with the Penguino project. This
+ is a relatively current mips-elf GCC and should provide free C++ support as
+ well. This toolchain can be downloded from the Penguino website:
+ http://wiki.pinguino.cc/index.php/Main_Page#Download . There is some general
+ information about using the Penguino mips-elf toolchain in this thread:
+ http://tech.groups.yahoo.com/group/nuttx/message/1821
+
+ See also configs/mirtoo/README.txt. There is an experimental (untested)
+ configuration for the Mirtoo platform in that directory.
+
MPLAB/C32 vs MPLABX/X32
-----------------------