summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-17 23:52:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-17 23:52:30 +0000
commit006c47cc2840ff87ce0386842f94665909891fc4 (patch)
tree8b2a7f9d46d53c559b737bfdeaf4900cc6c85104 /nuttx/arch
parent1a29cde8f665b81892b0b577615455bf5e3d9ff4 (diff)
downloadpx4-nuttx-006c47cc2840ff87ce0386842f94665909891fc4.tar.gz
px4-nuttx-006c47cc2840ff87ce0386842f94665909891fc4.tar.bz2
px4-nuttx-006c47cc2840ff87ce0386842f94665909891fc4.zip
Add start function
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3621 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rwxr-xr-xnuttx/arch/mips/include/mips32/cp0.h36
-rwxr-xr-xnuttx/arch/mips/include/mips32/registers.h146
-rwxr-xr-xnuttx/arch/mips/include/pic32mx/cp0.h29
-rwxr-xr-xnuttx/arch/mips/include/pic32mx/irq.h122
-rw-r--r--nuttx/arch/mips/src/mips32/up_irq.c10
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/Make.defs2
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-head.S440
7 files changed, 715 insertions, 70 deletions
diff --git a/nuttx/arch/mips/include/mips32/cp0.h b/nuttx/arch/mips/include/mips32/cp0.h
index 3e3b2f7dd..54b0a7b8e 100755
--- a/nuttx/arch/mips/include/mips32/cp0.h
+++ b/nuttx/arch/mips/include/mips32/cp0.h
@@ -45,6 +45,42 @@
/********************************************************************************************
* Pre-Processor Definitions
********************************************************************************************/
+/* CP0 Register Addresses *******************************************************************/
+
+#ifdef __ASSEMBLY__
+# define MIPS32_CP0_INDEX1 $0,0 /* Index into the TLB array */
+# define MIPS32_CP0_RANDOM1 $1,0 /* Randomly generated index into the TLB array */
+# define MIPS32_CP0_ENTRYLO01 $2,0 /* LS TLB entry for even-numbered pages */
+# define MIPS32_CP0_ENTRYLO11 $3,0 /* LS TLB entry for odd-numbered pages */
+# define MIPS32_CP0_CONTEXT2 $4,0 /* Page table address */
+# define MIPS32_CP0_PAGEMASK1 $5,0 /* Variable page sizes in TLB entries */
+# define MIPS32_CP0_WIRED1 $6,0 /* umber of fixed (“wired”) TLB entries */
+# define MIPS32_CP0_BADVADDR $8,0 /* Address of most recent exception */
+# define MIPS32_CP0_COUNT $9,0 /* Processor cycle count */
+# define MIPS32_CP0_ENTRYHI1 $10,0 /* High-order portion of the TLB entry */
+# define MIPS32_CP0_COMPARE $11,0 /* Timer interrupt control */
+# define MIPS32_CP0_STATUS $12,0 /* Processor status and control */
+# define MIPS32_CP0_CAUSE $13,0 /* Cause of last general exception */
+# define MIPS32_CP0_EPC $14,0 /* Program counter at last exception */
+# define MIPS32_CP0_PRID $15,0 /* Processor identification and revision */
+# define MIPS32_CP0_CONFIG $16,0 /* Configuration register */
+# define MIPS32_CP0_CONFIG1 $16,1 /* Configuration register 1 */
+# define MIPS32_CP0_CONFIG2 $16,2 /* Configuration register 3 */
+# define MIPS32_CP0_CONFIG3 $16,2 /* Configuration register 3 */
+# define MIPS32_CP0_LLADDR $17,0 /* Load linked address */
+# define MIPS32_CP0_WATCHLO2 $18,0 /* LS Watchpoint address */
+# define MIPS32_CP0_WATCHHI2 $19,0 /* MS Watchpoint address and mask */
+# define MIPS32_CP0_DEBUG3 $23,0 /* Debug control and exception status */
+# define MIPS32_CP0_DEPC3 $24,0 /* Program counter at last debug exception */
+# define MIPS32_CP0_ERRCTL $26,0 /* Controls access data CACHE instruction */
+# define MIPS32_CP0_TAGLO $28,0 /* LS portion of cache tag interface */
+# define MIPS32_CP0_DATALO $28,1 /* LS portion of cache tag interface */
+# define MIPS32_CP0_TAGHI $29,0 /* MS portion of cache tag interface */
+# define MIPS32_CP0_DATAHI $29,1 /* MS portion of cache tag interface */
+# define MIPS32_CP0_ERROREPC2 $30,0 /* Program counter at last error */
+# define MIPS32_CP0_DESAVE3 $31,0 /* Debug handler scratchpad register */
+#endif
+
/* CP0 Registers ****************************************************************************/
/* Register Number: 0 Sel: 0 Name: Index
diff --git a/nuttx/arch/mips/include/mips32/registers.h b/nuttx/arch/mips/include/mips32/registers.h
new file mode 100755
index 000000000..37f404cf8
--- /dev/null
+++ b/nuttx/arch/mips/include/mips32/registers.h
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * arch/mips/include/mips32/registers.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_MIPS_INCLUDE_MIPS32_REGISTERS_H
+#define __ARCH_MIPS_INCLUDE_MIPS32_REGISTERS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Standard synonmyms for MIPS registers */
+
+#ifdef __ASSEMBLY__
+/* Zero register: Always returns 0 */
+
+#define zero $0
+
+/* Assembler temporary register: Reserved for use by the assembler */
+
+#define at_reg $1
+
+/* Return value registers: Value returned by function */
+
+#define v0 $2
+#define v1 $3
+
+/* Argument registers: First few parameters for a function */
+
+#define a0 $4
+#define a1 $5
+#define a2 $6
+#define a3 $7
+
+/* Volatile registers: Registers that can be used without saving */
+
+#define t0 $8
+#define t1 $9
+#define t2 $10
+#define t3 $11
+#define t4 $12
+#define t5 $13
+#define t6 $14
+#define t7 $15
+#define t8 $24
+#define t9 $25
+
+/* Static registers: Registers that must be saved and restored if used */
+
+#define s0 $16
+#define s1 $17
+#define s2 $18
+#define s3 $19
+#define s4 $20
+#define s5 $21
+#define s6 $22
+#define s7 $23
+
+/* Register 30 may be either an additional static register or a frame pointer */
+
+#define s8 $30
+#define fp $30
+
+/* Reserved for use by interrupt/trap handling logic */
+
+#define k0 $26
+#define k1 $27
+
+/* Global pointer register */
+
+#define gp $28
+
+/* Stack pointer register: Stack pointer */
+
+#define sp $29
+
+/* Return address register: Contains the function return address */
+
+#define ra $31
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_MIPS_INCLUDE_MIPS32_REGISTERS_H */
+
diff --git a/nuttx/arch/mips/include/pic32mx/cp0.h b/nuttx/arch/mips/include/pic32mx/cp0.h
index 6ad9e6d82..5bd50b371 100755
--- a/nuttx/arch/mips/include/pic32mx/cp0.h
+++ b/nuttx/arch/mips/include/pic32mx/cp0.h
@@ -47,6 +47,27 @@
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
+/* CP0 Register Addresses ***************************************************/
+
+#ifdef __ASSEMBLY__
+# define PIC32MX_CP0_HWRENA $7,0 /* Enables access via RDHWR hardware registers */
+# define PIC32MX_CP0_BADVADDR $8,0 /* Address of most recent exception */
+# define PIC32MX_CP0_COUNT $9,0 /* Processor cycle count */
+# define PIC32MX_CP0_COMPARE $11,0 /* Timer interrupt control */
+# define PIC32MX_CP0_STATUS $12,0 /* Processor status and control */
+# define PIC32MX_CP0_INTCTL $12,1 /* Interrupt system status and control */
+# define PIC32MX_CP0_SRSCTL $12,2 /* Shadow register set status and control */
+# define PIC32MX_CP0_SRSMAP $12,3 /* Maps from vectored interrupt to a shadow set */
+# define PIC32MX_CP0_CAUSE $13,0 /* Cause of last general exception */
+# define PIC32MX_CP0_EPC $14,0 /* Program counter at last exception */
+# define PIC32MX_CP0_PRID $15,0 /* Processor identification and revision */
+# define PIC32MX_CP0_EBASE $15,1 /* Exception vector base register */
+# define PIC32MX_CP0_CONFIG $16,0 /* Configuration register */
+# define PIC32MX_CP0_CONFIG1 $16,1 /* Configuration register 1 */
+# define PIC32MX_CP0_CONFIG2 $16,2 /* Configuration register 3 */
+# define PIC32MX_CP0_CONFIG3 $16,3 /* Configuration register 3 */
+#endif
+
/* CP0 Registers ************************************************************/
/* Register Number: 0-6: Reserved
@@ -146,7 +167,7 @@
#undef CP0_STATUS_KSU_SUPER
#undef CP0_STATUS_KSU_USER
-/* Register Number: 12 Sel: x Name: IntCtl */
+/* Register Number: 12 Sel: 1 Name: IntCtl */
#define CP0_CONFIG_VS_SHIFT (5) /* Bits 5-9: Vector spacing bits */
#define CP0_CONFIG_VS_MASK (0x1f << CP0_CONFIG_VS_SHIFT)
@@ -157,7 +178,7 @@
# define CP0_CONFIG_VS_256BYTES (0x08 << CP0_CONFIG_VS_SHIFT)
# define CP0_CONFIG_VS_512BYTES (0x10 << CP0_CONFIG_VS_SHIFT)
-/* Register Number: 12 Sel: x Name: SRSCtl */
+/* Register Number: 12 Sel: 2 Name: SRSCtl */
#define CP0_SRSCTL_CSS_SHIFT (0) /* Bits 0-3: Current shadow bit set */
#define CP0_SRSCTL_CSS_MASK (15 << CP0_SRSCTL_CSS_SHIFT)
@@ -173,7 +194,7 @@
# define CP0_SRSCTL_HSS_2SETS (1 << CP0_SRSCTL_HSS_SHIFT) /* Two shadow sets */
# define CP0_SRSCTL_HSS_4SETS (3 << CP0_SRSCTL_HSS_SHIFT) /* Four shadow sets */
-/* Register Number: 12 Sel: x Name: SRSMap */
+/* Register Number: 12 Sel: 3 Name: SRSMap */
#define CP0_SRSMAP_SSV0_SHIFT (0) /* Bits 0-3: Shadow set vector 0 */
#define CP0_SRSMAP_SSV0_MASK (15 << CP0_SRSMAP_SSV0_SHIFT)
@@ -229,7 +250,7 @@
#undef CP0_PRID_OPTIONS_SHIFT
#undef CP0_PRID_OPTIONS_MASK
-/* Register Number: 15 Sel: x Name: EBASE */
+/* Register Number: 15 Sel: 1 Name: EBASE */
#define CP_EBASE_CPUNUM_SHIFT (0) /* Bits 0-9: CPU number */
#define CP_EBASE_CPUNUM_MASK (0x3ff << CP_EBASE_CPUNUM_SHIFT)
diff --git a/nuttx/arch/mips/include/pic32mx/irq.h b/nuttx/arch/mips/include/pic32mx/irq.h
index c704f879f..0b55e9229 100755
--- a/nuttx/arch/mips/include/pic32mx/irq.h
+++ b/nuttx/arch/mips/include/pic32mx/irq.h
@@ -101,68 +101,70 @@
/* Interrupt numbers. These should be used for enabling and disabling
* interrupt sources. Note that there are more interrupt sources than
- * interrupt vectors and interrupt priorities.
+ * interrupt vectors and interrupt priorities. An offset of 128 is
+ * used so that there is no overlap with the IRQ numbers and to avoid
+ * errors due to misuse.
*/
-#define PIC32MX_IRQSRC0_FIRST 0
-#define PIC32MX_IRQSRC_CT 0 /* Vector: 0, Core Timer Interrupt */
-#define PIC32MX_IRQSRC_CS0 1 /* Vector: 1, Core Software Interrupt 0 */
-#define PIC32MX_IRQSRC_CS1 2 /* Vector: 2, Core Software Interrupt 1 */
-#define PIC32MX_IRQSRC_INT0 3 /* Vector: 3, External Interrupt 0 */
-#define PIC32MX_IRQSRC_T1 4 /* Vector: 4, Timer 1 */
-#define PIC32MX_IRQSRC_IC1 5 /* Vector: 5, Input Capture 1 */
-#define PIC32MX_IRQSRC_OC1 6 /* Vector: 6, Output Compare 1 */
-#define PIC32MX_IRQSRC_INT1 7 /* Vector: 7, External Interrupt 1 */
-#define PIC32MX_IRQSRC_T2 8 /* Vector: 8, Timer 2 */
-#define PIC32MX_IRQSRC_IC2 9 /* Vector: 9, Input Capture 2 */
-#define PIC32MX_IRQSRC_OC2 10 /* Vector: 10, Output Compare 2 */
-#define PIC32MX_IRQSRC_INT2 11 /* Vector: 11, External Interrupt 2 */
-#define PIC32MX_IRQSRC_T3 12 /* Vector: 12, Timer 3 */
-#define PIC32MX_IRQSRC_IC3 13 /* Vector: 13, Input Capture 3 */
-#define PIC32MX_IRQSRC_OC3 14 /* Vector: 14, Output Compare 3 */
-#define PIC32MX_IRQSRC_INT3 15 /* Vector: 15, External Interrupt 3 */
-#define PIC32MX_IRQSRC_T4 16 /* Vector: 16, Timer 4 */
-#define PIC32MX_IRQSRC_IC4 17 /* Vector: 17, Input Capture 4 */
-#define PIC32MX_IRQSRC_OC4 18 /* Vector: 18, Output Compare 4 */
-#define PIC32MX_IRQSRC_INT4 19 /* Vector: 19, External Interrupt 4 */
-#define PIC32MX_IRQSRC_T5 20 /* Vector: 20, Timer 5 */
-#define PIC32MX_IRQSRC_IC5 21 /* Vector: 21, Input Capture 5 */
-#define PIC32MX_IRQSRC_OC5 22 /* Vector: 22, Output Compare 5 */
-#define PIC32MX_IRQSRC_SPI1E 23 /* Vector: 23, SPI1 */
-#define PIC32MX_IRQSRC_SPI1TX 24 /* Vector: 23, " " */
-#define PIC32MX_IRQSRC_SPI1RX 25 /* Vector: 23, " " */
-#define PIC32MX_IRQSRC_U1E 26 /* Vector: 24, UART1 */
-#define PIC32MX_IRQSRC_U1RX 27 /* Vector: 24, " " */
-#define PIC32MX_IRQSRC_U1TX 28 /* Vector: 24, " " */
-#define PIC32MX_IRQSRC_I2C1B 29 /* Vector: 25, I2C1 */
-#define PIC32MX_IRQSRC_I2C1S 30 /* Vector: 25, " " */
-#define PIC32MX_IRQSRC_I2C1M 31 /* Vector: 25, " " */
-#define PIC32MX_IRQSRC0_LAST 31
-
-#define PIC32MX_IRQSRC1_FIRST 32
-#define PIC32MX_IRQSRC_CN 32 /* Vector: 26, Input Change Interrupt */
-#define PIC32MX_IRQSRC_AD1 33 /* Vector: 27, ADC1 Convert Done */
-#define PIC32MX_IRQSRC_PMP 34 /* Vector: 28, Parallel Master Port */
-#define PIC32MX_IRQSRC_CMP1 35 /* Vector: 29, Comparator Interrupt */
-#define PIC32MX_IRQSRC_CMP2 36 /* Vector: 30, Comparator Interrupt */
-#define PIC32MX_IRQSRC_SPI2E 37 /* Vector: 31, SPI2 */
-#define PIC32MX_IRQSRC_SPI2TX 38 /* Vector: 31, " " */
-#define PIC32MX_IRQSRC_SPI2RX 39 /* Vector: 31, " " */
-#define PIC32MX_IRQSRC_U2E 40 /* Vector: 32, UART2 */
-#define PIC32MX_IRQSRC_U2RX 41 /* Vector: 32, " " */
-#define PIC32MX_IRQSRC_U2TX 42 /* Vector: 32, " " */
-#define PIC32MX_IRQSRC_I2C2B 43 /* Vector: 33, I2C2 */
-#define PIC32MX_IRQSRC_I2C2S 44 /* Vector: 33, " " */
-#define PIC32MX_IRQSRC_I2C2M 45 /* Vector: 33, " " */
-#define PIC32MX_IRQSRC_FSCM 46 /* Vector: 34, Fail-Safe Clock Monitor */
-#define PIC32MX_IRQSRC_RTCC 47 /* Vector: 35, Real-Time Clock and Calendar */
-#define PIC32MX_IRQSRC_DMA0 48 /* Vector: 36, DMA Channel 0 */
-#define PIC32MX_IRQSRC_DMA1 49 /* Vector: 37, DMA Channel 1 */
-#define PIC32MX_IRQSRC_DMA2 50 /* Vector: 38, DMA Channel 2 */
-#define PIC32MX_IRQSRC_DMA3 51 /* Vector: 39, DMA Channel 3 */
-#define PIC32MX_IRQSRC_FCE 56 /* Vector: 44, Flash Control Event */
-#define PIC32MX_IRQSRC_USB 57 /* Vector: 45, USB */
-#define PIC32MX_IRQSRC1_FIRST 57
+#define PIC32MX_IRQSRC0_FIRST (128+0)
+#define PIC32MX_IRQSRC_CT (128+0) /* Vector: 0, Core Timer Interrupt */
+#define PIC32MX_IRQSRC_CS0 (128+1) /* Vector: 1, Core Software Interrupt 0 */
+#define PIC32MX_IRQSRC_CS1 (128+2) /* Vector: 2, Core Software Interrupt 1 */
+#define PIC32MX_IRQSRC_INT0 (128+3) /* Vector: 3, External Interrupt 0 */
+#define PIC32MX_IRQSRC_T1 (128+4) /* Vector: 4, Timer 1 */
+#define PIC32MX_IRQSRC_IC1 (128+5) /* Vector: 5, Input Capture 1 */
+#define PIC32MX_IRQSRC_OC1 (128+6) /* Vector: 6, Output Compare 1 */
+#define PIC32MX_IRQSRC_INT1 (128+7) /* Vector: 7, External Interrupt 1 */
+#define PIC32MX_IRQSRC_T2 (128+8) /* Vector: 8, Timer 2 */
+#define PIC32MX_IRQSRC_IC2 (128+9) /* Vector: 9, Input Capture 2 */
+#define PIC32MX_IRQSRC_OC2 (128+10) /* Vector: 10, Output Compare 2 */
+#define PIC32MX_IRQSRC_INT2 (128+11) /* Vector: 11, External Interrupt 2 */
+#define PIC32MX_IRQSRC_T3 (128+12) /* Vector: 12, Timer 3 */
+#define PIC32MX_IRQSRC_IC3 (128+13) /* Vector: 13, Input Capture 3 */
+#define PIC32MX_IRQSRC_OC3 (128+14) /* Vector: 14, Output Compare 3 */
+#define PIC32MX_IRQSRC_INT3 (128+15) /* Vector: 15, External Interrupt 3 */
+#define PIC32MX_IRQSRC_T4 (128+16) /* Vector: 16, Timer 4 */
+#define PIC32MX_IRQSRC_IC4 (128+17) /* Vector: 17, Input Capture 4 */
+#define PIC32MX_IRQSRC_OC4 (128+18) /* Vector: 18, Output Compare 4 */
+#define PIC32MX_IRQSRC_INT4 (128+19) /* Vector: 19, External Interrupt 4 */
+#define PIC32MX_IRQSRC_T5 (128+20) /* Vector: 20, Timer 5 */
+#define PIC32MX_IRQSRC_IC5 (128+21) /* Vector: 21, Input Capture 5 */
+#define PIC32MX_IRQSRC_OC5 (128+22) /* Vector: 22, Output Compare 5 */
+#define PIC32MX_IRQSRC_SPI1E (128+23) /* Vector: 23, SPI1 */
+#define PIC32MX_IRQSRC_SPI1TX (128+24) /* Vector: 23, " " */
+#define PIC32MX_IRQSRC_SPI1RX (128+25) /* Vector: 23, " " */
+#define PIC32MX_IRQSRC_U1E (128+26) /* Vector: 24, UART1 */
+#define PIC32MX_IRQSRC_U1RX (128+27) /* Vector: 24, " " */
+#define PIC32MX_IRQSRC_U1TX (128+28) /* Vector: 24, " " */
+#define PIC32MX_IRQSRC_I2C1B (128+29) /* Vector: 25, I2C1 */
+#define PIC32MX_IRQSRC_I2C1S (128+30) /* Vector: 25, " " */
+#define PIC32MX_IRQSRC_I2C1M (128+31) /* Vector: 25, " " */
+#define PIC32MX_IRQSRC0_LAST (128+31)
+
+#define PIC32MX_IRQSRC1_FIRST (128+32)
+#define PIC32MX_IRQSRC_CN (128+32) /* Vector: 26, Input Change Interrupt */
+#define PIC32MX_IRQSRC_AD1 (128+33) /* Vector: 27, ADC1 Convert Done */
+#define PIC32MX_IRQSRC_PMP (128+34) /* Vector: 28, Parallel Master Port */
+#define PIC32MX_IRQSRC_CMP1 (128+35) /* Vector: 29, Comparator Interrupt */
+#define PIC32MX_IRQSRC_CMP2 (128+36) /* Vector: 30, Comparator Interrupt */
+#define PIC32MX_IRQSRC_SPI2E (128+37) /* Vector: 31, SPI2 */
+#define PIC32MX_IRQSRC_SPI2TX (128+38) /* Vector: 31, " " */
+#define PIC32MX_IRQSRC_SPI2RX (128+39) /* Vector: 31, " " */
+#define PIC32MX_IRQSRC_U2E (128+40) /* Vector: 32, UART2 */
+#define PIC32MX_IRQSRC_U2RX (128+41) /* Vector: 32, " " */
+#define PIC32MX_IRQSRC_U2TX (128+42) /* Vector: 32, " " */
+#define PIC32MX_IRQSRC_I2C2B (128+43) /* Vector: 33, I2C2 */
+#define PIC32MX_IRQSRC_I2C2S (128+44) /* Vector: 33, " " */
+#define PIC32MX_IRQSRC_I2C2M (128+45) /* Vector: 33, " " */
+#define PIC32MX_IRQSRC_FSCM (128+46) /* Vector: 34, Fail-Safe Clock Monitor */
+#define PIC32MX_IRQSRC_RTCC (128+47) /* Vector: 35, Real-Time Clock and Calendar */
+#define PIC32MX_IRQSRC_DMA0 (128+48) /* Vector: 36, DMA Channel 0 */
+#define PIC32MX_IRQSRC_DMA1 (128+49) /* Vector: 37, DMA Channel 1 */
+#define PIC32MX_IRQSRC_DMA2 (128+50) /* Vector: 38, DMA Channel 2 */
+#define PIC32MX_IRQSRC_DMA3 (128+51) /* Vector: 39, DMA Channel 3 */
+#define PIC32MX_IRQSRC_FCE (128+56) /* Vector: 44, Flash Control Event */
+#define PIC32MX_IRQSRC_USB (128+57) /* Vector: 45, USB */
+#define PIC32MX_IRQSRC1_FIRST (128+57)
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/mips/src/mips32/up_irq.c b/nuttx/arch/mips/src/mips32/up_irq.c
index 3ca1359ce..0908637df 100644
--- a/nuttx/arch/mips/src/mips32/up_irq.c
+++ b/nuttx/arch/mips/src/mips32/up_irq.c
@@ -76,7 +76,7 @@ static inline irqstate_t cp0_getstatus(void)
(
"\t.set push\n"
"\t.set noat\n"
- "\t mfc0 %0,$12\n" /* Get CP0 status register */
+ "\t mfc0 %0,$12\n" /* Get CP0 status register */
"\t.set pop\n"
: "=r" (status)
:
@@ -107,11 +107,11 @@ static inline void cp0_putstatus(irqstate_t status)
"\t.set push\n"
"\t.set noat\n"
"\t.set noreorder\n"
- "\tmtc0 %0,$12\n" /* Set the status to the provided value */
- "\tnop\n" /* MTC0 status hazard: */
- "\tnop\n" /* Recommended spacing: 3 */
+ "\tmtc0 %0,$12\n" /* Set the status to the provided value */
+ "\tnop\n" /* MTC0 status hazard: */
+ "\tnop\n" /* Recommended spacing: 3 */
"\tnop\n"
- "\tnop\n" /* Plus one for good measure */
+ "\tnop\n" /* Plus one for good measure */
"\t.set pop\n"
:
: "r" (status)
diff --git a/nuttx/arch/mips/src/pic32mx/Make.defs b/nuttx/arch/mips/src/pic32mx/Make.defs
index dee8fa333..06ae7d535 100755
--- a/nuttx/arch/mips/src/pic32mx/Make.defs
+++ b/nuttx/arch/mips/src/pic32mx/Make.defs
@@ -35,7 +35,7 @@
# The start-up, "head", file
-HEAD_ASRC =
+HEAD_ASRC = pic32mx-head.S
# Common MIPS files
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
new file mode 100644
index 000000000..1d4215b0b
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
@@ -0,0 +1,440 @@
+/****************************************************************************
+ * arch/mips/src/arm/pic32mx-head.S
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <arch/mips32/registers.h>
+#include <arch/mips32/cp0.h>
+#include <arch/pic32mx/cp0.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Data memory is organized as follows:
+ *
+ * 1) Possible space reserved for debug data
+ * 2) Ram functions: (.data):
+ * Start: _sramfunc
+ * End(+1): _eramfunc
+ * 3) Initialized data (.data):
+ * Start: _sdata
+ * End(+1): _edata
+ * 4) Uninitialized data (.bss):
+ * Start: _sbss
+ * End(+1): _ebss
+ * 5) Idle thread stack:
+ * Start: _ebss
+ * End(+1): _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ * 6) Heap Range
+ * Start: _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ * End(+1): to the end of memory
+ */
+
+#define PIC32MX_STACK_BASE _ebss
+#define PIC32MX_STACK_TOP _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
+#define PIC32MX_HEAP_BASE _ebss+CONFIG_IDLETHREAD_STACKSIZE
+
+/****************************************************************************
+ * Global Symbols
+ ****************************************************************************/
+
+ .file "pic32mx-head.S"
+ .global __start
+ .global halt
+
+ .global __nmi_handler
+ .global __do_reset
+ .global os_start
+
+/****************************************************************************
+ * Macros
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: __reset
+ *
+ * Description:
+ * Reset entry point. This function is positioned at the beginning of
+ * the boot FLASH by the linker in KSEG1. Simply jumps to the __start
+ * logic in KSEG0 (also in the boot FLASH).
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
+
+ .globl __reset
+ .section .reset, "ax", @progbits
+ .set noreorder
+ .ent __reset
+__reset:
+ la k0, __start /* Just jump to the startup initialization code */
+ jr k0
+ nop
+ .end __reset
+
+/****************************************************************************
+ * Name: __start
+ *
+ * Description:
+ * This is the KSEG0 startup code. It receives control from the reset
+ * entry point. This lgic This prepares the processor to execute
+ * C code, performs some very low-level initialization, then starts NuttX
+ * (via __start_nuttx
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
+
+ .section .start, "ax", @progbits
+ .set noreorder
+ .ent __start
+__start:
+
+ /* If this function was entered because of an NMI, then turn processing
+ * over to the NMI handler.
+ */
+
+ mfc0 k0, $12 /* Load CP0 status register */
+ ext k0, k0, 19, 1 /* Extract NMI bit */
+ beqz k0, .Lnotnmi
+ nop
+ la k0, nmi_handler
+ jr k0
+ nop
+
+ /* This is not an NMI */
+
+.Lnotnmi:
+
+ /* Initialize the stack pointer */
+
+ la sp, PIC32MX_STACK_TOP
+
+ /* Initialize the globl pointer (gp). _gp is initialized by the linker
+ * script to point to the "middle" of the small variables region.
+ */
+
+ la gp, _gp
+
+ /* Initialize Global Pointer in Shadow Set. The SRSCtl PSS field must
+ * be set to the shadow set in which to initialize the global pointer.
+ * Since we only have a single shadow set, we will initialize
+ * SRSCtl PSS to SRSCtl HSS. We then write the global pointer to the
+ * previous shadow set to ensure that on interrupt, the global pointer
+ * has been initialized.
+ */
+
+ mfc0 t1, PIC32MX_CP0_SRSCTL /* Read SRSCtl register */
+ add t3, t1, zero /* Save off current SRSCtl */
+ ext t2, t1, 26, 4 /* to obtain HSS field */
+ ins t1, t2, 6, 4 /* Put HSS field */
+ mtc0 t1, PIC32MX_CP0_SRSCTL /* into SRSCtl PSS */
+ wrpgpr gp, gp /* Set global pointer in PSS */
+ mtc0 t3, PIC32MX_CP0_SRSCTL /* Restore SRSCtl */
+
+ /* Call the do_reset function */
+
+ la t0, do_reset
+ jalr t0
+ nop
+
+ /* Clear uninitialized data sections */
+
+ la t0, _sbss
+ la t1, _ebss
+ b .Lbsscheck
+ nop
+
+.Lbssloop:
+ sw zero, 0x0(t0)
+ sw zero, 0x4(t0)
+ sw zero, 0x8(t0)
+ sw zero, 0xc(t0)
+ addu t0, 16
+
+.Lbsscheck:
+ bltu t0, t1, .Lbssloop
+ nop
+
+ /* Copy initialized data from program flash to data memory */
+
+ la t0, _data_loaddr
+ la t1, _sdata
+ la t2, _edata
+ b .Ldatacheck
+ nop
+
+.Ldataloop:
+ lw t3, (t0)
+ sw t3, (t1)
+ addu t0, 4
+ addu t1, 4
+
+.Ldatacheck:
+ bltu t1, t2, .Ldataloop
+ nop
+
+ /* If there are no RAM functions, skip the next two sections --
+ * copying RAM functions from program flash to data memory and
+ * initializing bus matrix registers.
+ */
+
+#ifdef CONFIG_PIC32MX_RAMFUNCs
+ la t1, _ramfunc_sizeof
+ beqz t1, .Lnoramfuncs
+ nop
+
+ /* Copy RAM functions from program flash to data memory */
+
+ la t0, _ramfunc_loadaddr
+ la t1, _sramfunc
+ la t2, _eramfunc
+
+.Lramfuncloop:
+ lw t3,(t0)
+ sw t3,(t1)
+ addu t0,4
+ addu t1,4
+
+ bltu t1, t2, .Lramfuncloop
+ nop
+
+ /* Initialize bus matrix registers if RAM functions exist in the
+ * application
+ */
+
+ la t1, _bmxdkpba_address
+ la t2, BMXDKPBA
+ sw t1, 0(t2)
+ la t1, _bmxdudba_address
+ la t2, BMXDUDBA
+ sw t1, 0(t2)
+ la t1, _bmxdupba_address
+ la t2, BMXDUPBA
+ sw t1, 0(t2)
+.Lnoramfuncs:
+#endif
+
+ /* Initialize CP0 Count register */
+
+ mtc0 zero, PIC32MX_CP0_COUNT
+
+ /* Initialize Compare register */
+
+ li t2, -1
+ mtc0 t2, PIC32MX_CP0_COMPARE
+
+ /* Initialize EBase register */
+
+ la t1, _ebase_address
+ mtc0 t1, PIC32MX_CP0_EBASE
+
+ /* Initialize IntCtl register */
+
+ la t1, _vector_spacing
+ li t2, 0 /* Clear t2 */
+ ins t2, t1, 5, 5 /* Shift value to VS field */
+ mtc0 t2, PIC32MX_CP0_INTCTL
+
+ /* Initialize CAUSE registers
+ * - Enable counting of Count register (DC = 0)
+ * - Use special exception vector (IV = 1)
+ * - Clear pending software interrupts (IP1:IP0 = 0)
+ */
+
+ li t1, CP0_CAUSE_IV
+ mtc0 t1, PIC32MX_CP0_CAUSE
+
+ /* Initialize STATUS register
+ * - Access to Coprocessor 0 not allowed in user mode (CU0 = 0)
+ * - User mode uses configured endianness (RE = 0)
+ * - Preserve Bootstrap Exception vectors (BEV)
+ * - Preserve soft reset (SR) and non-maskable interrupt (NMI)
+ * - CorExtend enabled based on whether CorExtend User Defined
+ * Instructions have been implemented (CEE = Config(UDI))
+ * - Disable any pending interrups (IM7..IM2 = 0, IM1..IM0 = 0)
+ * - Disable hardware interrupts (IPL7:IPL2 = 0)
+ * - Base mode is Kernel mode (UM = 0)
+ * - Error level is normal (ERL = 0)
+ * - Exception level is normal (EXL = 0)
+ * - Interrupts are disabled (IE = 0)
+ */
+
+ mfc0 t0, PIC32MX_CP0_CONFIG
+ ext t1, t0, 22,1 /* Extract UDI from Config register */
+ sll t1, t1, 17 /* Move UDI to Status.CEE location */
+ mfc0 t0, PIC32MX_CP0_STATUS
+ and t0, t0, 0x00580000 /* Preserve SR, NMI, and BEV */
+ or t0, t1, t0 /* Include Status.CEE (from UDI) */
+ mtc0 t0, PIC32MX_CP0_STATUS
+
+
+ /* Call the do_bootstrap function */
+
+ la t0, do_bootstrap
+ jalr t0
+ nop
+
+ /* Initialize Status BEV for normal exception vectors */
+
+ mfc0 t0, PIC32MX_CP0_STATUS
+ and t0, t0, 0xffbfffff # Clear BEV
+ mtc0 t0, PIC32MX_CP0_STATUS
+
+ /* Start NuttX. We do this via a thunk in the text section so that
+ * a normal jump and link can be used, enabling the startup code
+ * to work properly whether main is written in MIPS16 or MIPS32
+ * code. I.e., the linker will correctly adjust the JAL to JALX if
+ * necessary
+ */
+
+ and a0, a0, 0
+ and a1, a1, 0
+ la t0, __start_nuttx
+ jr t0
+ nop
+ .end __start
+
+/****************************************************************************
+ * Name: _bev_exception
+ *
+ * Description:
+ * Boot Exception Vector Handler. Jumps to _bootstrap_exception_handler
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
+
+ .section .bev_handler,"ax",@progbits
+ .set noreorder
+ .ent _bev_exception
+_bev_exception:
+ la k0, _bootstrap_exception_handler
+ jr k0
+ nop
+ .end _bev_exception
+
+/****************************************************************************
+ * Name: _bev_exception
+ *
+ * Description:
+ * General Exception Vector Handler. Jumps to _general_exception_handler
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
+
+ .section .gen_handler,"ax",@progbits
+ .set noreorder
+ .ent _gen_exception
+_gen_exception:
+ la k0, _general_exception_context
+ jr k0
+ nop
+ .end _gen_exception
+
+/****************************************************************************
+ * Name: __start_nuttx
+ *
+ * Description:
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * Does not return
+ *
+ ****************************************************************************/
+
+ .text
+ .ent __start_nuttx
+__start_nuttx:
+ /* Perform low level initialization */
+
+ jal up_lowinit
+ nop
+
+ /* Perform early serial initialization */
+
+#ifdef CONFIG_USE_EARLYSERIALINIT
+ jal up_earlyserialinit
+ nop
+#endif
+
+ /* Call os_start */
+
+ jal os_start
+ nop
+
+ /* Just in case main returns, go into infinite loop */
+
+halt:
+1:
+ b 1b
+ nop
+ .end __start_nuttx
+
+ /* This global variable is unsigned long g_heapbase and is exported
+ * here only because of its coupling to idle thread stack.
+ */
+
+ .data
+ .align 4
+ .globl g_heapbase
+ .type g_heapbase, object
+g_heapbase:
+ .long _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ .size g_heapbase, .-g_heapbase
+