summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-che.h176
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-config.h321
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-head.S2
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-memorymap.h2
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-serial.c6
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-timerisr.c24
-rw-r--r--nuttx/configs/pcblogic-pic32mx/README.txt155
-rwxr-xr-xnuttx/configs/pcblogic-pic32mx/include/board.h4
8 files changed, 435 insertions, 255 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-che.h b/nuttx/arch/mips/src/pic32mx/pic32mx-che.h
new file mode 100755
index 000000000..3eadccf2a
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-che.h
@@ -0,0 +1,176 @@
+/********************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-che.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_SRC_PIC32MX_PIC32MX_CHE_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CHE_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "pic32mx-memorymap.h"
+
+/********************************************************************************************
+ * Pre-Processor Definitions
+ ********************************************************************************************/
+/* Register Offsets *************************************************************************/
+
+#define PIC32MX_CHE_CON_OFFSET 0x0000 /* Pre-fetch cache control register */
+#define PIC32MX_CHE_CONCLR_OFFSET 0x0004 /* Pre-fetch cache control clear register */
+#define PIC32MX_CHE_CONSET_OFFSET 0x0008 /* Pre-fetch cache control set register */
+#define PIC32MX_CHE_CONINV_OFFSET 0x000c /* Pre-fetch cache control invert register */
+#define PIC32MX_CHE_ACC_OFFSET 0x0010 /* Pre-fetch cache access register */
+#define PIC32MX_CHE_ACCCLR_OFFSET 0x0014 /* Pre-fetch cache access clear register */
+#define PIC32MX_CHE_ACCSET_OFFSET 0x0018 /* Pre-fetch cache access set register */
+#define PIC32MX_CHE_ACCINV_OFFSET 0x001c /* Pre-fetch cache access invert register */
+#define PIC32MX_CHE_TAG_OFFSET 0x0020 /* Pre-fetch cache tag register */
+#define PIC32MX_CHE_TAGCLR_OFFSET 0x0024 /* Pre-fetch cache tag clear register */
+#define PIC32MX_CHE_TAGSET_OFFSET 0x0028 /* Pre-fetch cache tag set register */
+#define PIC32MX_CHE_TAGINV_OFFSET 0x002c /* Pre-fetch cache tag invert register */
+#define PIC32MX_CHE_MSK_OFFSET 0x0030 /* Pre-fetch cache tag mask register */
+#define PIC32MX_CHE_MSKCLR_OFFSET 0x0034 /* Pre-fetch cache tag mask clear register */
+#define PIC32MX_CHE_MSKSET_OFFSET 0x0038 /* Pre-fetch cache tag mask set register */
+#define PIC32MX_CHE_MSKINV_OFFSET 0x003c /* Pre-fetch cache tag mask invert register */
+#define PIC32MX_CHE_W0_OFFSET 0x0040 /* Cache word 0 register */
+#define PIC32MX_CHE_W1_OFFSET 0x0050 /* Cache word 1 register */
+#define PIC32MX_CHE_W2_OFFSET 0x0060 /* Cache word 2 register */
+#define PIC32MX_CHE_W3_OFFSET 0x0070 /* Cache word 3 register */
+#define PIC32MX_CHE_LRU_OFFSET 0x0080 /* Cache LRU register */
+#define PIC32MX_CHE_HIT_OFFSET 0x0090 /* Cache hit statistics register */
+#define PIC32MX_CHE_MIS_OFFSET 0x00a0 /* Cache miss statistics register */
+#define PIC32MX_CHE_PFABT_OFFSET 0x00c0 /* Pre-fetch cache abort statistics register */
+
+/* Register Addresses ***********************************************************************/
+
+#define PIC32MX_CHE_CON (PIC32MX_CHE_K1BASE+PIC32MX_CHE_CON_OFFSET)
+#define PIC32MX_CHE_CONCLR (PIC32MX_CHE_K1BASE+PIC32MX_CHE_CONCLR_OFFSET)
+#define PIC32MX_CHE_CONSET (PIC32MX_CHE_K1BASE+PIC32MX_CHE_CONSET_OFFSET)
+#define PIC32MX_CHE_CONINV (PIC32MX_CHE_K1BASE+PIC32MX_CHE_CONINV_OFFSET)
+#define PIC32MX_CHE_ACC (PIC32MX_CHE_K1BASE+PIC32MX_CHE_ACC_OFFSET)
+#define PIC32MX_CHE_ACCCLR (PIC32MX_CHE_K1BASE+PIC32MX_CHE_ACCCLR_OFFSET)
+#define PIC32MX_CHE_ACCSET (PIC32MX_CHE_K1BASE+PIC32MX_CHE_ACCSET_OFFSET)
+#define PIC32MX_CHE_ACCINV (PIC32MX_CHE_K1BASE+PIC32MX_CHE_ACCINV_OFFSET)
+#define PIC32MX_CHE_TAG (PIC32MX_CHE_K1BASE+PIC32MX_CHE_TAG_OFFSET)
+#define PIC32MX_CHE_TAGCLR (PIC32MX_CHE_K1BASE+PIC32MX_CHE_TAGCLR_OFFSET)
+#define PIC32MX_CHE_TAGSET (PIC32MX_CHE_K1BASE+PIC32MX_CHE_TAGSET_OFFSET)
+#define PIC32MX_CHE_TAGINV (PIC32MX_CHE_K1BASE+PIC32MX_CHE_TAGINV_OFFSET)
+#define PIC32MX_CHE_MSK (PIC32MX_CHE_K1BASE+PIC32MX_CHE_MSK_OFFSET)
+#define PIC32MX_CHE_MSKCLR (PIC32MX_CHE_K1BASE+PIC32MX_CHE_MSKCLR_OFFSET)
+#define PIC32MX_CHE_MSKSET (PIC32MX_CHE_K1BASE+PIC32MX_CHE_MSKSET_OFFSET)
+#define PIC32MX_CHE_MSKINV (PIC32MX_CHE_K1BASE+PIC32MX_CHE_MSKINV_OFFSET)
+#define PIC32MX_CHE_W0 (PIC32MX_CHE_K1BASE+PIC32MX_CHE_W0_OFFSET)
+#define PIC32MX_CHE_W1 (PIC32MX_CHE_K1BASE+PIC32MX_CHE_W1_OFFSET)
+#define PIC32MX_CHE_W2 (PIC32MX_CHE_K1BASE+PIC32MX_CHE_W2_OFFSET)
+#define PIC32MX_CHE_W3 (PIC32MX_CHE_K1BASE+PIC32MX_CHE_W3_OFFSET)
+#define PIC32MX_CHE_LRU (PIC32MX_CHE_K1BASE+PIC32MX_CHE_LRU_OFFSET)
+#define PIC32MX_CHE_HIT (PIC32MX_CHE_K1BASE+PIC32MX_CHE_HIT_OFFSET)
+#define PIC32MX_CHE_MIS (PIC32MX_CHE_K1BASE+PIC32MX_CHE_MIS_OFFSET)
+#define PIC32MX_CHE_PFABT (PIC32MX_CHE_K1BASE+PIC32MX_CHE_PFABT_OFFSET)
+
+/* Register Bit-Field Definitions ***********************************************************/
+
+/* Pre-fetch cache control register */
+
+
+#define CHE_CON_PFMWS_SHIFT (0) /* Bits 0-2: xx */
+#define CHE_CON_PFMWS_MASK (7 << CHE_CON_PFMWS_SHIFT)
+#define CHE_CON_PREFEN_SHIFT (4) /* Bits 4-5: xx */
+#define CHE_CON_PREFEN_MASK (3 << CHE_CON_PREFEN_SHIFT)
+#define CHE_CON_DCSZ_SHIFT (8) /* Bits 8-9: xx */
+#define CHE_CON_DCSZ_MASK (3 << CHE_CON_DCSZ_SHIFT)
+#define CHE_CON_CHECOH (1 << 16) /* Bit 16: xx */
+
+/* Pre-fetch cache access register */
+
+#define CHE_ACC_CHEIDX_SHIFT (0) /* Bits 0-3: xx */
+#define CHE_ACC_CHEIDX_MASK (15 << CHE_ACC_CHEIDX_SHIFT)
+#define CHE_ACC_CHEWEN (1 << 31) /* Bit 31: xx */
+
+/* Pre-fetch cache tag register */
+
+#define CHE_TAG_LTYPE (1 << 1) /* Bit 1: xx */
+#define CHE_TAG_LLOCK (1 << 2) /* Bit 2: xx */
+#define CHE_TAG_LVALID (1 << 3) /* Bit 3: xx */
+#define CHE_TAG_LTAG_SHIFT (4) /* Bits 4-23: xx */
+#define CHE_TAG_LTAG_MASK (0x000fffff << CHE_TAG_LTAG_SHIFT)
+#define CHE_TAG_LTAGBOOT (1 << 31) /* Bit 31: xx */
+
+/* Pre-fetch cache tag mask register */
+
+#define CHE_MSK_SHIFT (5) /* Bits 5-15: xx */
+#define CHE_MSK_MASK (0x7ff << CHE_MSK_SHIFT)
+
+/* Cache word 0-3 register -- 32-bit cache line data */
+
+/* Cache LRU register */
+
+#define CHE_LRU_MASK 0x01ffffff /* Bits 0-24 */
+
+/* Cache hit statistics register -- 32 bit counter value */
+
+/* Cache miss statistics register -- 32 bit counter value */
+
+/* Pre-fetch cache abort statistics register -- 32 bit counter value */
+
+/********************************************************************************************
+ * Public Types
+ ********************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/********************************************************************************************
+ * Inline Functions
+ ********************************************************************************************/
+
+/********************************************************************************************
+ * Public Function Prototypes
+ ********************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CHE_H */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-config.h b/nuttx/arch/mips/src/pic32mx/pic32mx-config.h
index c09adbd21..279ff1a46 100755
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-config.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-config.h
@@ -54,28 +54,97 @@
************************************************************************************/
/* Interrupt Priorities *************************************************************/
-
-#ifndef CONFIG_PIC32MX_WDTPRIO
-# define CONFIG_PIC32MX_WDTPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_CTPRIO /* Core Timer Interrupt */
+# define CONFIG_PIC32MX_CTPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_WDTPRIO < 4
-# error "CONFIG_PIC32MX_WDTPRIO is too small"
+#if CONFIG_PIC32MX_CTPRIO < 4
+# error "CONFIG_PIC32MX_CTPRIO is too small"
#endif
-#if CONFIG_PIC32MX_WDTPRIO > 31
-# error "CONFIG_PIC32MX_WDTPRIO is too large"
+#if CONFIG_PIC32MX_CTPRIO > 31
+# error "CONFIG_PIC32MX_CTPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_RTCCPRIO
-# define CONFIG_PIC32MX_RTCCPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_CS0PRIO /* Core Software Interrupt 0 */
+# define CONFIG_PIC32MX_CS0PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_RTCCPRIO < 4
-# error "CONFIG_PIC32MX_RTCCPRIO is too small"
+#if CONFIG_PIC32MX_CS0PRIO < 4
+# error "CONFIG_PIC32MX_CS0PRIO is too small"
#endif
-#if CONFIG_PIC32MX_RTCCPRIO > 31
-# error "CONFIG_PIC32MX_RTCCPRIO is too large"
+#if CONFIG_PIC32MX_CS0PRIO > 31
+# error "CONFIG_PIC32MX_CS0PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_CS1PRIO /* Core Software Interrupt 1 */
+# define CONFIG_PIC32MX_CS1PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_CS1PRIO < 4
+# error "CONFIG_PIC32MX_CS1PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_CS1PRIO > 31
+# error "CONFIG_PIC32MX_CS1PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_INT0PRIO /* External interrupt 0 */
+# define CONFIG_PIC32MX_INT0PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_INT0PRIO < 4
+# error "CONFIG_PIC32MX_INT0PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_INT0PRIO > 31
+# error "CONFIG_PIC32MX_INT0PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_INT1PRIO /* External interrupt 1 */
+# define CONFIG_PIC32MX_INT1PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_INT1PRIO < 4
+# error "CONFIG_PIC32MX_INT1PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_INT1PRIO > 31
+# error "CONFIG_PIC32MX_INT1PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_INT2PRIO /* External interrupt 2 */
+# define CONFIG_PIC32MX_INT2PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_INT2PRIO < 4
+# error "CONFIG_PIC32MX_INT2PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_INT2PRIO > 31
+# error "CONFIG_PIC32MX_INT2PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_INT3PRIO /* External interrupt 3 */
+# define CONFIG_PIC32MX_INT3PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_INT3PRIO < 4
+# error "CONFIG_PIC32MX_INT3PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_INT3PRIO > 31
+# error "CONFIG_PIC32MX_INT3PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_INT4PRIO /* External interrupt 4 */
+# define CONFIG_PIC32MX_INT4PRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_INT4PRIO < 4
+# error "CONFIG_PIC32MX_INT4PRIO is too small"
+#endif
+#if CONFIG_PIC32MX_INT4PRIO > 31
+# error "CONFIG_PIC32MX_INT4PRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_FSCMPRIO /* Fail-Safe Clock Monitor */
+# define CONFIG_PIC32MX_FSCMPRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_FSCMPRIO < 4
+# error "CONFIG_PIC32MX_FSCMPRIO is too small"
+#endif
+#if CONFIG_PIC32MX_FSCMPRIO > 31
+# error "CONFIG_PIC32MX_FSCMPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_T1PRIO
+#ifndef CONFIG_PIC32MX_T1PRIO /* Timer 1 (System timer) priority */
# define CONFIG_PIC32MX_T1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T1PRIO < 4
@@ -85,7 +154,7 @@
# error "CONFIG_PIC32MX_T1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_T2PRIO
+#ifndef CONFIG_PIC32MX_T2PRIO /* Timer 2 priority */
# define CONFIG_PIC32MX_T2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T2PRIO < 4
@@ -95,7 +164,7 @@
# error "CONFIG_PIC32MX_T2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_T3PRIO
+#ifndef CONFIG_PIC32MX_T3PRIO /* Timer 3 priority */
# define CONFIG_PIC32MX_T3PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T3PRIO < 4
@@ -105,7 +174,7 @@
# error "CONFIG_PIC32MX_T3PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_T4PRIO
+#ifndef CONFIG_PIC32MX_T4PRIO /* Timer 4 priority */
# define CONFIG_PIC32MX_T4PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T4PRIO < 4
@@ -115,7 +184,7 @@
# error "CONFIG_PIC32MX_T4PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_T5PRIO
+#ifndef CONFIG_PIC32MX_T5PRIO /* Timer 5 priority */
# define CONFIG_PIC32MX_T5PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T5PRIO < 4
@@ -125,7 +194,7 @@
# error "CONFIG_PIC32MX_T5PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IC1PRIO
+#ifndef CONFIG_PIC32MX_IC1PRIO /* Input Capture 1 */
# define CONFIG_PIC32MX_IC1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC1PRIO < 4
@@ -135,7 +204,7 @@
# error "CONFIG_PIC32MX_IC1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IC2PRIO
+#ifndef CONFIG_PIC32MX_IC2PRIO /* Input Capture 2 */
# define CONFIG_PIC32MX_IC2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC2PRIO < 4
@@ -145,7 +214,7 @@
# error "CONFIG_PIC32MX_IC2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IC3PRIO
+#ifndef CONFIG_PIC32MX_IC3PRIO /* Input Capture 3 */
# define CONFIG_PIC32MX_IC3PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC3PRIO < 4
@@ -155,7 +224,7 @@
# error "CONFIG_PIC32MX_IC3PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IC4PRIO
+#ifndef CONFIG_PIC32MX_IC4PRIO /* Input Capture 4 */
# define CONFIG_PIC32MX_IC4PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC4PRIO < 4
@@ -165,7 +234,7 @@
# error "CONFIG_PIC32MX_IC4PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IC5PRIO
+#ifndef CONFIG_PIC32MX_IC5PRIO /* Input Capture 5 */
# define CONFIG_PIC32MX_IC5PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC5PRIO < 4
@@ -175,7 +244,7 @@
# error "CONFIG_PIC32MX_IC5PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OC1PRIO
+#ifndef CONFIG_PIC32MX_OC1PRIO /* Output Compare 1 */
# define CONFIG_PIC32MX_OC1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC1PRIO < 4
@@ -185,7 +254,7 @@
# error "CONFIG_PIC32MX_OC1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OC2PRIO
+#ifndef CONFIG_PIC32MX_OC2PRIO /* Output Compare 2 */
# define CONFIG_PIC32MX_OC2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC2PRIO < 4
@@ -195,7 +264,7 @@
# error "CONFIG_PIC32MX_OC2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OC3PRIO
+#ifndef CONFIG_PIC32MX_OC3PRIO /* Output Compare 3 */
# define CONFIG_PIC32MX_OC3PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC3PRIO < 4
@@ -205,7 +274,7 @@
# error "CONFIG_PIC32MX_OC3PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OC4PRIO
+#ifndef CONFIG_PIC32MX_OC4PRIO /* Output Compare 4 */
# define CONFIG_PIC32MX_OC4PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC4PRIO < 4
@@ -215,7 +284,7 @@
# error "CONFIG_PIC32MX_OC4PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OC5PRIO
+#ifndef CONFIG_PIC32MX_OC5PRIO /* Output Compare 5 */
# define CONFIG_PIC32MX_OC5PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC5PRIO < 4
@@ -225,7 +294,7 @@
# error "CONFIG_PIC32MX_OC5PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_I2C1PRIO
+#ifndef CONFIG_PIC32MX_I2C1PRIO /* I2C 1 */
# define CONFIG_PIC32MX_I2C1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_I2C1PRIO < 4
@@ -235,7 +304,7 @@
# error "CONFIG_PIC32MX_I2C1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_I2C2PRIO
+#ifndef CONFIG_PIC32MX_I2C2PRIO /* I2C 2 */
# define CONFIG_PIC32MX_I2C2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_I2C2PRIO < 4
@@ -245,7 +314,7 @@
# error "CONFIG_PIC32MX_I2C2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_SPI1PRIO
+#ifndef CONFIG_PIC32MX_SPI1PRIO /* SPI 1 */
# define CONFIG_PIC32MX_SPI1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_SPI1PRIO < 4
@@ -255,7 +324,7 @@
# error "CONFIG_PIC32MX_SPI1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_SPI2PRIO
+#ifndef CONFIG_PIC32MX_SPI2PRIO /* SPI 2 */
# define CONFIG_PIC32MX_SPI2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_SPI2PRIO < 4
@@ -265,7 +334,7 @@
# error "CONFIG_PIC32MX_SPI2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_UART1PRIO
+#ifndef CONFIG_PIC32MX_UART1PRIO /* UART 1 */
# define CONFIG_PIC32MX_UART1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_UART1PRIO < 4
@@ -275,7 +344,7 @@
# error "CONFIG_PIC32MX_UART1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_UART2PRIO
+#ifndef CONFIG_PIC32MX_UART2PRIO /* UART 2 */
# define CONFIG_PIC32MX_UART2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_UART2PRIO < 4
@@ -285,17 +354,17 @@
# error "CONFIG_PIC32MX_UART2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_PMPPRIO
-# define CONFIG_PIC32MX_PMPPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_CN /* Input Change Interrupt */
+# define CONFIG_PIC32MX_CN (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_PMPPRIO < 4
-# error "CONFIG_PIC32MX_PMPPRIO is too small"
+#if CONFIG_PIC32MX_CN < 4
+# error "CONFIG_PIC32MX_CN is too small"
#endif
-#if CONFIG_PIC32MX_PMPPRIO > 31
-# error "CONFIG_PIC32MX_PMPPRIO is too large"
+#if CONFIG_PIC32MX_CN > 31
+# error "CONFIG_PIC32MX_CN is too large"
#endif
-#ifndef CONFIG_PIC32MX_ADCPRIO
+#ifndef CONFIG_PIC32MX_ADCPRIO /* ADC1 Convert Done */
# define CONFIG_PIC32MX_ADCPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_ADCPRIO < 4
@@ -305,17 +374,17 @@
# error "CONFIG_PIC32MX_ADCPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_CVRPRIO
-# define CONFIG_PIC32MX_CVRPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_PMPPRIO /* Parallel Master Port */
+# define CONFIG_PIC32MX_PMPPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_CVRPRIO < 4
-# error "CONFIG_PIC32MX_CVRPRIO is too small"
+#if CONFIG_PIC32MX_PMPPRIO < 4
+# error "CONFIG_PIC32MX_PMPPRIO is too small"
#endif
-#if CONFIG_PIC32MX_CVRPRIO > 31
-# error "CONFIG_PIC32MX_CVRPRIO is too large"
+#if CONFIG_PIC32MX_PMPPRIO > 31
+# error "CONFIG_PIC32MX_PMPPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_CM1PRIO
+#ifndef CONFIG_PIC32MX_CM1PRIO /* Comparator 1 */
# define CONFIG_PIC32MX_CM1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CM1PRIO < 4
@@ -325,7 +394,7 @@
# error "CONFIG_PIC32MX_CM1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_CM2PRIO
+#ifndef CONFIG_PIC32MX_CM2PRIO /* Comparator 2 */
# define CONFIG_PIC32MX_CM2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CM2PRIO < 4
@@ -335,67 +404,77 @@
# error "CONFIG_PIC32MX_CM2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_OSCPRIO
-# define CONFIG_PIC32MX_OSCPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_FSCMPRIO /* Fail-Safe Clock Monitor */
+# define CONFIG_PIC32MX_FSCMPRIO (INT_CP0_MID_PRIORITY << 2)
+#endif
+#if CONFIG_PIC32MX_FSCMPRIO < 4
+# error "CONFIG_PIC32MX_FSCMPRIO is too small"
+#endif
+#if CONFIG_PIC32MX_FSCMPRIO > 31
+# error "CONFIG_PIC32MX_FSCMPRIO is too large"
+#endif
+
+#ifndef CONFIG_PIC32MX_RTCCPRIO /* Real-Time Clock and Calendar */
+# define CONFIG_PIC32MX_RTCCPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_OSCPRIO < 4
-# error "CONFIG_PIC32MX_OSCPRIO is too small"
+#if CONFIG_PIC32MX_RTCCPRIO < 4
+# error "CONFIG_PIC32MX_RTCCPRIO is too small"
#endif
-#if CONFIG_PIC32MX_OSCPRIO > 31
-# error "CONFIG_PIC32MX_OSCPRIO is too large"
+#if CONFIG_PIC32MX_RTCCPRIO > 31
+# error "CONFIG_PIC32MX_RTCCPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_DDPPRIO
-# define CONFIG_PIC32MX_DDPPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_DMA0PRIO /* DMA Channel 0 */
+# define CONFIG_PIC32MX_DMA0PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_DDPPRIO < 4
-# error "CONFIG_PIC32MX_DDPPRIO is too small"
+#if CONFIG_PIC32MX_DMA0PRIO < 4
+# error "CONFIG_PIC32MX_DMA0PRIO is too small"
#endif
-#if CONFIG_PIC32MX_DDPPRIO > 31
-# error "CONFIG_PIC32MX_DDPPRIO is too large"
+#if CONFIG_PIC32MX_DMA0PRIO > 31
+# error "CONFIG_PIC32MX_DMA0PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_FLASHPRIO
-# define CONFIG_PIC32MX_FLASHPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_DMA1PRIO /* DMA Channel 1 */
+# define CONFIG_PIC32MX_DMA1PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_FLASHPRIO < 4
-# error "CONFIG_PIC32MX_FLASHPRIO is too small"
+#if CONFIG_PIC32MX_DMA1PRIO < 4
+# error "CONFIG_PIC32MX_DMA1PRIO is too small"
#endif
-#if CONFIG_PIC32MX_FLASHPRIO > 31
-# error "CONFIG_PIC32MX_FLASHPRIO is too large"
+#if CONFIG_PIC32MX_DMA1PRIO > 31
+# error "CONFIG_PIC32MX_DMA1PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_BMXPRIO
-# define CONFIG_PIC32MX_BMXPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_DMA2PRIO /* DMA Channel 2 */
+# define CONFIG_PIC32MX_DMA2PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_BMXPRIO < 4
-# error "CONFIG_PIC32MX_BMXPRIO is too small"
+#if CONFIG_PIC32MX_DMA2PRIO < 4
+# error "CONFIG_PIC32MX_DMA2PRIO is too small"
#endif
-#if CONFIG_PIC32MX_BMXPRIO > 31
-# error "CONFIG_PIC32MX_BMXPRIO is too large"
+#if CONFIG_PIC32MX_DMA2PRIO > 31
+# error "CONFIG_PIC32MX_DMA2PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_DMAPRIO
-# define CONFIG_PIC32MX_DMAPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_DMA3PRIO /* DMA Channel 3 */
+# define CONFIG_PIC32MX_DMA3PRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_DMAPRIO < 4
-# error "CONFIG_PIC32MX_DMAPRIO is too small"
+#if CONFIG_PIC32MX_DMA3PRIO < 4
+# error "CONFIG_PIC32MX_DMA3PRIO is too small"
#endif
-#if CONFIG_PIC32MX_DMAPRIO > 31
-# error "CONFIG_PIC32MX_DMAPRIO is too large"
+#if CONFIG_PIC32MX_DMA3PRIO > 31
+# error "CONFIG_PIC32MX_DMA3PRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_CHEPRIO
-# define CONFIG_PIC32MX_CHEPRIO (INT_CP0_MID_PRIORITY << 2)
+#ifndef CONFIG_PIC32MX_FCEPRIO /* Flash Control Event */
+# define CONFIG_PIC32MX_FCEPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
-#if CONFIG_PIC32MX_CHEPRIO < 4
-# error "CONFIG_PIC32MX_CHEPRIO is too small"
+#if CONFIG_PIC32MX_FCEPRIO < 4
+# error "CONFIG_PIC32MX_FCEPRIO is too small"
#endif
-#if CONFIG_PIC32MX_CHEPRIO > 31
-# error "CONFIG_PIC32MX_CHEPRIO is too large"
+#if CONFIG_PIC32MX_FCEPRIO > 31
+# error "CONFIG_PIC32MX_FCEPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_USBPRIO
+#ifndef CONFIG_PIC32MX_USBPRIO /* USB */
# define CONFIG_PIC32MX_USBPRIO (INT_CP0_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_USBPRIO < 4
@@ -405,76 +484,6 @@
# error "CONFIG_PIC32MX_USBPRIO is too large"
#endif
-#ifndef CONFIG_PIC32MX_IOPORTAPRIO
-# define CONFIG_PIC32MX_IOPORTAPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTAPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTAPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTAPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTAPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTBPRIO
-# define CONFIG_PIC32MX_IOPORTBPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTBPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTBPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTBPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTBPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTCPRIO
-# define CONFIG_PIC32MX_IOPORTCPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTCPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTCPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTCPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTCPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTDPRIO
-# define CONFIG_PIC32MX_IOPORTDPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTDPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTDPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTDPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTDPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTEPRIO
-# define CONFIG_PIC32MX_IOPORTEPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTEPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTEPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTEPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTEPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTFPRIO
-# define CONFIG_PIC32MX_IOPORTFPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTFPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTFPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTFPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTFPRIO is too large"
-#endif
-
-#ifndef CONFIG_PIC32MX_IOPORTGPRIO
-# define CONFIG_PIC32MX_IOPORTGPRIO (INT_CP0_MID_PRIORITY << 2)
-#endif
-#if CONFIG_PIC32MX_IOPORTGPRIO < 4
-# error "CONFIG_PIC32MX_IOPORTGPRIO is too small"
-#endif
-#if CONFIG_PIC32MX_IOPORTGPRIO > 31
-# error "CONFIG_PIC32MX_IOPORTGPRIO is too large"
-#endif
-
/* UARTs ****************************************************************************/
/* Don't enable UARTs not supported by the chip. */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
index 69afafbc0..275406d0c 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
@@ -540,7 +540,7 @@ devconfig2:
CONFIG_PIC32MX_UPLLIDIV | DEVCFG2_FPLLODIV_DIV1
devconfig1:
- .long DEVCFG1_FNOSC_POSCPLL | DEVCFG1_POSCMOD_XT | \
+ .long DEVCFG1_FNOSC_POSCPLL | DEVCFG1_POSCMOD_HS | \
CONFIG_PIC32MX_PBDIV | DEVCFG1_FCKSM_NONE | \
CONFIG_PIC32MX_WDENABLE
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-memorymap.h b/nuttx/arch/mips/src/pic32mx/pic32mx-memorymap.h
index 9cf1e8a13..e883dcef6 100755
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-memorymap.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-memorymap.h
@@ -176,7 +176,7 @@
# define PIC32MX_DMACH2_K1BASE (PIC32MX_SFR_K1BASE + 0x000831e0)
# define PIC32MX_DMACH3_K1BASE (PIC32MX_SFR_K1BASE + 0x000832a0)
-/* Prefetch Register Base Address */
+/* Prefetch Cache Register Base Address */
# define PIC32MX_CHE_K1BASE (PIC32MX_SFR_K1BASE + 0x00084000)
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
index e35d3e1dd..07ef32e4f 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c
@@ -145,6 +145,7 @@ struct up_dev_s
uint8_t irqe; /* Error IRQ associated with this UART (for enable) */
uint8_t irqrx; /* RX IRQ associated with this UART (for enable) */
uint8_t irqtx; /* RX IRQ associated with this UART (for enable) */
+ uint8_t irqprio; /* Interrupt priority */
uint8_t ie; /* Interrupts enabled */
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (5, 6, 7 or 8) */
@@ -211,6 +212,7 @@ static struct up_dev_s g_uart1priv =
.irqe = PIC32MX_IRQSRC_U1E,
.irqrx = PIC32MX_IRQSRC_U1RX,
.irqtx = PIC32MX_IRQSRC_U1TX,
+ .irqprio = CONFIG_PIC32MX_UART1PRIO,
.parity = CONFIG_UART2_PARITY,
.bits = CONFIG_UART2_BITS,
.stopbits2 = CONFIG_UART2_2STOP,
@@ -244,6 +246,7 @@ static struct up_dev_s g_uart2priv =
.irqe = PIC32MX_IRQSRC_U2E,
.irqrx = PIC32MX_IRQSRC_U2RX,
.irqtx = PIC32MX_IRQSRC_U2TX,
+ .irqprio = CONFIG_PIC32MX_UART2PRIO,
.parity = CONFIG_UART2_PARITY,
.bits = CONFIG_UART2_BITS,
.stopbits2 = CONFIG_UART2_2STOP,
@@ -341,6 +344,9 @@ static int up_setup(struct uart_dev_s *dev)
priv->bits, priv->stopbits2);
#endif
+ /* Set up the interrupt priority */
+
+ up_prioritize_irq(priv->irq, priv->irqprio);
return OK;
}
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-timerisr.c b/nuttx/arch/mips/src/pic32mx/pic32mx-timerisr.c
index 1ef888d4e..906ec0cc4 100755
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-timerisr.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-timerisr.c
@@ -59,28 +59,28 @@
* Definitions
****************************************************************************/
/* Timer Setup **************************************************************/
-/* Select a timer prescale value. Our goal is to select the timer MATCH
- * register value givent the board's periperhal clock frequency and the
- * desired system timer frequency:
+/* Select a timer 1 prescale value. Our goal is to select the timer MATCH
+ * register value given the board's SOSC clock frequency and the desired
+ * system timer frequency:
*
- * TIMER1_MATCH = BOARD_PBCLOCK / TIMER1_PRESCALE / CLOCKS_PER_SEC
+ * TIMER1_MATCH = BOARD_SOSC_FREQ / TIMER1_PRESCALE / CLOCKS_PER_SEC
*
* We want the largest possible value for MATCH that is less than 65,535, the
* maximum value for the 16-bit timer register:
*
- * TIMER1_PRESCALE >= BOARD_PBCLOCK / CLOCKS_PER_SEC / 65535
+ * TIMER1_PRESCALE >= BOARD_SOSC_FREQ / CLOCKS_PER_SEC / 65535
*
* Timer 1 does not have very many options for the perscaler value. So we
* can pick the best by brute force. Example:
*
- * BOARD_PBCLOCK = 40000000
+ * BOARD_SOSC_FREQ = 32768
* CLOCKS_PER_SEC = 100
- * OPTIMAL_PRESCALE = 6
- * TIMER1_PRESCALE = 8
- * TIMER1_MATCH = 50,000
+ * OPTIMAL_PRESCALE = 1
+ * TIMER1_PRESCALE = 1
+ * TIMER1_MATCH = 328 -> 99.90 ticks/sec
*/
-#define OPTIMAL_PRESCALE (BOARD_PBCLOCK / CLOCKS_PER_SEC / 65535)
+#define OPTIMAL_PRESCALE (BOARD_SOSC_FREQ / CLOCKS_PER_SEC / 65535)
#if OPTIMAL_PRESCALE <= 1
# define TIMER1_CON_TCKPS TIMER1_CON_TCKPS_1
# define TIMER1_PRESCALE 1
@@ -97,7 +97,7 @@
# error "This timer frequency cannot be represented"
#endif
-#define TIMER1_MATCH (BOARD_PBCLOCK / TIMER1_PRESCALE / CLOCKS_PER_SEC)
+#define TIMER1_MATCH (BOARD_SOSC_FREQ / TIMER1_PRESCALE / CLOCKS_PER_SEC)
/****************************************************************************
* Private Types
@@ -143,7 +143,7 @@ int up_timerisr(int irq, uint32_t *regs)
void up_timerinit(void)
{
- /* Configure and enable TIMER1 -- source internal (TCS=0) */
+ /* Configure and enable TIMER1 -- source internal SOSC (TCS=0) */
putreg32(TIMER1_CON_TCKPS, PIC32MX_TIMER1_CON);
putreg32(0, PIC32MX_TIMER1_CNT);
diff --git a/nuttx/configs/pcblogic-pic32mx/README.txt b/nuttx/configs/pcblogic-pic32mx/README.txt
index f36fd2ee8..d24c8395c 100644
--- a/nuttx/configs/pcblogic-pic32mx/README.txt
+++ b/nuttx/configs/pcblogic-pic32mx/README.txt
@@ -150,94 +150,83 @@ PIC32MX Configuration Options
Individual subsystems can be enabled:
- CONFIG_PIC32MX_WDT
- CONFIG_PIC32MX_RTCC
- CONFIG_PIC32MX_T2 /* Timer 1 is the system time and always enabled */
- CONFIG_PIC32MX_T3
- CONFIG_PIC32MX_T4
- CONFIG_PIC32MX_T5
- CONFIG_PIC32MX_IC1
- CONFIG_PIC32MX_IC2
- CONFIG_PIC32MX_IC3
- CONFIG_PIC32MX_IC4
- CONFIG_PIC32MX_IC5
- CONFIG_PIC32MX_OC1
- CONFIG_PIC32MX_OC2
- CONFIG_PIC32MX_OC3
- CONFIG_PIC32MX_OC4
- CONFIG_PIC32MX_OC5
- CONFIG_PIC32MX_I2C1
- CONFIG_PIC32MX_I2C2
- CONFIG_PIC32MX_SPI1
- CONFIG_PIC32MX_SPI2
- CONFIG_PIC32MX_UART1
- CONFIG_PIC32MX_UART2
- CONFIG_PIC32MX_PMP
- CONFIG_PIC32MX_ADC
- CONFIG_PIC32MX_CVR
- CONFIG_PIC32MX_CM1
- CONFIG_PIC32MX_CM2
- CONFIG_PIC32MX_OSC
- CONFIG_PIC32MX_DDP
- CONFIG_PIC32MX_FLASH
- CONFIG_PIC32MX_BMX
- CONFIG_PIC32MX_DMA
- CONFIG_PIC32MX_CHE
- CONFIG_PIC32MX_USB
- CONFIG_PIC32MX_IOPORTA
- CONFIG_PIC32MX_IOPORTB
- CONFIG_PIC32MX_IOPORTC
- CONFIG_PIC32MX_IOPORTD
- CONFIG_PIC32MX_IOPORTE
- CONFIG_PIC32MX_IOPORTF
- CONFIG_PIC32MX_IOPORTG
+ CONFIG_PIC32MX_WDT - Watchdog timer
+ CONFIG_PIC32MX_T2 - Timer 2 (Timer 1 is the system time and always enabled)
+ CONFIG_PIC32MX_T3 - Timer 3
+ CONFIG_PIC32MX_T4 - Timer 4
+ CONFIG_PIC32MX_T5 - Timer 5
+ CONFIG_PIC32MX_IC1 - Input Capture 1
+ CONFIG_PIC32MX_IC2 - Input Capture 2
+ CONFIG_PIC32MX_IC3 - Input Capture 3
+ CONFIG_PIC32MX_IC4 - Input Capture 4
+ CONFIG_PIC32MX_IC5 - Input Capture 5
+ CONFIG_PIC32MX_OC1 - Output Compare 1
+ CONFIG_PIC32MX_OC2 - Output Compare 2
+ CONFIG_PIC32MX_OC3 - Output Compare 3
+ CONFIG_PIC32MX_OC4 - Output Compare 4
+ CONFIG_PIC32MX_OC5 - Output Compare 5
+ CONFIG_PIC32MX_I2C1 - I2C 1
+ CONFIG_PIC32MX_I2C2 - I2C 2
+ CONFIG_PIC32MX_SPI1 - SPI 1
+ CONFIG_PIC32MX_SPI2 - SPI 2
+ CONFIG_PIC32MX_UART1 - UART 1
+ CONFIG_PIC32MX_UART2 - UART 2
+ CONFIG_PIC32MX_ADC - ADC 1
+ CONFIG_PIC32MX_PMP - Parallel Master Port
+ CONFIG_PIC32MX_CM1 - Comparator 1
+ CONFIG_PIC32MX_CM2 - Comparator 2
+ CONFIG_PIC32MX_RTCC - Real-Time Clock and Calendar
+ CONFIG_PIC32MX_DMA - DMA
+ CONFIG_PIC32MX_FLASH - FLASH
+ CONFIG_PIC32MX_USB - USB
The priority of interrupts may be specified. The value ranage of
priority is 4-31. The default (16) will be used if these any of these
are undefined.
- CONFIG_PIC32MX_WDTPRIO
- CONFIG_PIC32MX_RTCCPRIO
- CONFIG_PIC32MX_T1PRIO /* System timer priority */
- CONFIG_PIC32MX_T2PRIO
- CONFIG_PIC32MX_T3PRIO
- CONFIG_PIC32MX_T4PRIO
- CONFIG_PIC32MX_T5PRIO
- CONFIG_PIC32MX_IC1PRIO
- CONFIG_PIC32MX_IC2PRIO
- CONFIG_PIC32MX_IC3PRIO
- CONFIG_PIC32MX_IC4PRIO
- CONFIG_PIC32MX_IC5PRIO
- CONFIG_PIC32MX_OC1PRIO
- CONFIG_PIC32MX_OC2PRIO
- CONFIG_PIC32MX_OC3PRIO
- CONFIG_PIC32MX_OC4PRIO
- CONFIG_PIC32MX_OC5PRIO
- CONFIG_PIC32MX_I2C1PRIO
- CONFIG_PIC32MX_I2C2PRIO
- CONFIG_PIC32MX_SPI1PRIO
- CONFIG_PIC32MX_SPI2PRIO
- CONFIG_PIC32MX_UART1PRIO
- CONFIG_PIC32MX_UART2PRIO
- CONFIG_PIC32MX_PMPPRIO
- CONFIG_PIC32MX_ADCPRIO
- CONFIG_PIC32MX_CVRPRIO
- CONFIG_PIC32MX_CM1PRIO
- CONFIG_PIC32MX_CM2PRIO
- CONFIG_PIC32MX_OSCPRIO
- CONFIG_PIC32MX_DDPPRIO
- CONFIG_PIC32MX_FLASHPRIO
- CONFIG_PIC32MX_BMXPRIO
- CONFIG_PIC32MX_DMAPRIO
- CONFIG_PIC32MX_CHEPRIO
- CONFIG_PIC32MX_USBPRIO
- CONFIG_PIC32MX_IOPORTAPRIO
- CONFIG_PIC32MX_IOPORTBPRIO
- CONFIG_PIC32MX_IOPORTCPRIO
- CONFIG_PIC32MX_IOPORTDPRIO
- CONFIG_PIC32MX_IOPORTEPRIO
- CONFIG_PIC32MX_IOPORTFPRIO
- CONFIG_PIC32MX_IOPORTGPRIO
+ CONFIG_PIC32MX_CTPRIO - Core Timer Interrupt
+ CONFIG_PIC32MX_CS0PRIO - Core Software Interrupt 0
+ CONFIG_PIC32MX_CS1PRIO - Core Software Interrupt 1
+ CONFIG_PIC32MX_INT0PRIO - External Interrupt 0
+ CONFIG_PIC32MX_INT1PRIO - External Interrupt 1
+ CONFIG_PIC32MX_INT2PRIO - External Interrupt 2
+ CONFIG_PIC32MX_INT3PRIO - External Interrupt 3
+ CONFIG_PIC32MX_INT4PRIO - External Interrupt 4
+ CONFIG_PIC32MX_FSCMPRIO - Fail-Safe Clock Monitor
+ CONFIG_PIC32MX_T1PRIO - Timer 1 (System timer) priority
+ CONFIG_PIC32MX_T2PRIO - Timer 2 priority
+ CONFIG_PIC32MX_T3PRIO - Timer 3 priority
+ CONFIG_PIC32MX_T4PRIO - Timer 4 priority
+ CONFIG_PIC32MX_T5PRIO - Timer 5 priority
+ CONFIG_PIC32MX_IC1PRIO - Input Capture 1
+ CONFIG_PIC32MX_IC2PRIO - Input Capture 2
+ CONFIG_PIC32MX_IC3PRIO - Input Capture 3
+ CONFIG_PIC32MX_IC4PRIO - Input Capture 4
+ CONFIG_PIC32MX_IC5PRIO - Input Capture 5
+ CONFIG_PIC32MX_OC1PRIO - Output Compare 1
+ CONFIG_PIC32MX_OC2PRIO - Output Compare 2
+ CONFIG_PIC32MX_OC3PRIO - Output Compare 3
+ CONFIG_PIC32MX_OC4PRIO - Output Compare 4
+ CONFIG_PIC32MX_OC5PRIO - Output Compare 5
+ CONFIG_PIC32MX_I2C1PRIO - I2C 1
+ CONFIG_PIC32MX_I2C2PRIO - I2C 2
+ CONFIG_PIC32MX_SPI1PRIO - SPI 1
+ CONFIG_PIC32MX_SPI2PRIO - SPI 2
+ CONFIG_PIC32MX_UART1PRIO - UART 1
+ CONFIG_PIC32MX_UART2PRIO - UART 2
+ CONFIG_PIC32MX_CN - Input Change Interrupt
+ CONFIG_PIC32MX_ADCPRIO - ADC1 Convert Done
+ CONFIG_PIC32MX_PMPPRIO - Parallel Master Port
+ CONFIG_PIC32MX_CM1PRIO - Comparator 1
+ CONFIG_PIC32MX_CM2PRIO - Comparator 2
+ CONFIG_PIC32MX_FSCMPRIO - Fail-Safe Clock Monitor
+ CONFIG_PIC32MX_RTCCPRIO - Real-Time Clock and Calendar
+ CONFIG_PIC32MX_DMA0PRIO - DMA Channel 0
+ CONFIG_PIC32MX_DMA1PRIO - DMA Channel 1
+ CONFIG_PIC32MX_DMA2PRIO - DMA Channel 2
+ CONFIG_PIC32MX_DMA3PRIO - DMA Channel 3
+ CONFIG_PIC32MX_FCEPRIO - Flash Control Event
+ CONFIG_PIC32MX_USBPRIO - USB
PIC32MXx specific device driver settings
diff --git a/nuttx/configs/pcblogic-pic32mx/include/board.h b/nuttx/configs/pcblogic-pic32mx/include/board.h
index b70bbb80e..8d4c24460 100755
--- a/nuttx/configs/pcblogic-pic32mx/include/board.h
+++ b/nuttx/configs/pcblogic-pic32mx/include/board.h
@@ -51,8 +51,8 @@
/* Clocking *****************************************************************/
/* Crystal frequencies */
-#define BOARD_POSC_XTAL 8000000 /* Primary OSC XTAL frequency (8MHz) */
-#define BOARD_SOSC_XTAL 32768 /* Secondary OSC XTAL frequency (32.768KHz) */
+#define BOARD_POSC_FREQ 8000000 /* Primary OSC XTAL frequency (8MHz) */
+#define BOARD_SOSC_FREQ 32768 /* Secondary OSC XTAL frequency (32.768KHz) */
/* PLL configuration and resulting CPU clock.
* CPU_CLOCK = ((POSC_XTAL / IDIV) * MULT) / ODIV