summaryrefslogtreecommitdiff
path: root/nuttx/arch/mips
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-01-24 14:28:49 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-01-24 14:28:49 -0600
commitce7d02b55783779750eb4da036ad2185e7f7cf44 (patch)
tree8d1eebba9a1bb5c7942bcf89c617fff85df96045 /nuttx/arch/mips
parentcafcbeb3a0d16b13048d14fa8ef75cce2a87f738 (diff)
downloadpx4-nuttx-ce7d02b55783779750eb4da036ad2185e7f7cf44.tar.gz
px4-nuttx-ce7d02b55783779750eb4da036ad2185e7f7cf44.tar.bz2
px4-nuttx-ce7d02b55783779750eb4da036ad2185e7f7cf44.zip
rename up_led*() functions to board_led_*()
Diffstat (limited to 'nuttx/arch/mips')
-rw-r--r--nuttx/arch/mips/include/pic32mx/cp0.h792
-rw-r--r--nuttx/arch/mips/src/common/up_allocateheap.c2
-rw-r--r--nuttx/arch/mips/src/common/up_createstack.c2
-rw-r--r--nuttx/arch/mips/src/common/up_initialize.c2
-rw-r--r--nuttx/arch/mips/src/common/up_internal.h10
-rw-r--r--nuttx/arch/mips/src/mips32/up_assert.c6
-rw-r--r--nuttx/arch/mips/src/mips32/up_doirq.c4
-rw-r--r--nuttx/arch/mips/src/mips32/up_sigdeliver.c4
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-cvr.h226
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c6
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-exception.c2
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ic.h332
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-oc.h422
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-timer.h444
14 files changed, 1127 insertions, 1127 deletions
diff --git a/nuttx/arch/mips/include/pic32mx/cp0.h b/nuttx/arch/mips/include/pic32mx/cp0.h
index 67ced8a2c..9d70e2c76 100644
--- a/nuttx/arch/mips/include/pic32mx/cp0.h
+++ b/nuttx/arch/mips/include/pic32mx/cp0.h
@@ -1,396 +1,396 @@
-/****************************************************************************
- * arch/mips/include/pic32mx/cp0.h
- *
- * Copyright (C) 2011 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.
- *
- ****************************************************************************/
-
-#ifndef __ARCH_MIPS_INCLUDE_PIC32MX_CP0_H
-#define __ARCH_MIPS_INCLUDE_PIC32MX_CP0_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <arch/mips32/cp0.h>
-
-/****************************************************************************
- * 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 */
-# define PIC32MX_CP0_DEBUG $23,3 /* Debug control and exception status */
-# define PIC32MX_CP0_DEPC $24,3 /* Program counter at last debug exception */
-# define PIC32MX_CP0_ERREPC $30,3 /* Program counter at last error */
-# define PIC32MX_CP0_DESAVE $31,3 /* Debug handler scratchpad register */
-#endif
-
-/* CP0 Registers ************************************************************/
-
-/* Register Number: 0-6: Reserved
- * Compliance Level: Required for TLB-based MMU; Optional otherwise.
- */
-
-/* Register Number: 7 Sel: 0 Name: HWREna
- * Function: Enables access via the RDHWR instruction to selected hardware
- * registers in non-privileged mode.
- * Compliance Level: (Reserved for future extensions)
- */
-
-#define CP0_HWRENA_SHIFT (0) /* Bits 0-3: Enable access to a hardware resource */
-#define CP0_HWRENA_MASK (15 << CP0_HWRENA_SHIFT)
-# define CP0_HWRENA_BIT0 (1 << CP0_HWRENA_SHIFT)
-# define CP0_HWRENA_BIT1 (2 << CP0_HWRENA_SHIFT)
-# define CP0_HWRENA_BIT2 (4 << CP0_HWRENA_SHIFT)
-# define CP0_HWRENA_BIT3 (8 << CP0_HWRENA_SHIFT)
-
-/* Register Number: 8 Sel: 0 Name: BadVAddr
- * Function: Reports the address for the most recent address-related
- * exception
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- *
- * Register Number: 9 Sel: 0 Name: Count
- * Function: Processor cycle count
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- *
- * Register Number: 10 Reserved.
- * Compliance Level: Required for TLB-based MMU; Optional otherwise.
- *
- * Register Number: 11 Sel: 0 Name: Compare
- * Function: Timer interrupt control
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- */
-
-/* Register Number: 12 Sel: 0 Name: Status
- * Function: Processor status and control
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- * NOTES:
- * 1. The following are reserved bits in the PIC32:
- * CP0_STATUS_UX Bit 5: Enables 64-bit user address space (Not MIPS32)
- * CP0_STATUS_SX Bit 6: Enables 64-bit supervisor address space (Not MIPS32)
- * CP0_STATUS_KX Bit 7: Enables 64-bit kernel address space (Not MIPS32)
- * CP0_STATUS_IMPL Bits 16-17: Implementation dependent
- * CP0_STATUS_TS Bit 21: TLB detected match on multiple entries
- * CP0_STATUS_PX Bit 23: Enables 64-bit operations (Not MIPS32)
- * CP0_STATUS_MX Bit 24: Enables MDMX™ (Not MIPS32)
- */
-
-#undef CP0_STATUS_UX
-#undef CP0_STATUS_SX
-#undef CP0_STATUS_KX
-#undef CP0_STATUS_IMPL
-#undef CP0_STATUS_IMPL_SHIFT
-#undef CP0_STATUS_IMPL_MASK
-#undef CP0_STATUS_TS
-#undef CP0_STATUS_PX
-#undef CP0_STATUS_MX
-
-/* 2. The following field is of a different width. Apparently, it
- * excludes the software interrupt bits.
- *
- * CP0_STATUS_IM Bits 8-15: Interrupt Mask
- * Vs.
- * CP0_STATUS_IPL Bits 10-15: Interrupt priority level
- * Bitss 8-9 reserved
- */
-
-#define CP0_STATUS_IPL_SHIFT (10) /* Bits 10-15: Interrupt priority level */
-#define CP0_STATUS_IPL_MASK (0x3f << CP0_STATUS_IPL_SHIFT)
-
-/* 3. Supervisor mode not supported
- * CP0_STATUS_KSU Bits 3-4: Operating mode (with supervisor mode)
- */
-
-#undef CP0_STATUS_KSU_SHIFT
-#undef CP0_STATUS_KSU_MASK
-#undef CP0_STATUS_KSU_KERNEL
-#undef CP0_STATUS_KSU_SUPER
-#undef CP0_STATUS_KSU_USER
-
-/* Register Number: 12 Sel: 1 Name: IntCtl */
-
-#define CP0_INTCTL_VS_SHIFT (5) /* Bits 5-9: Vector spacing bits */
-#define CP0_INTCTL_VS_MASK (0x1f << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_0BYTES (0x00 << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_32BYTES (0x01 << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_64BYTES (0x02 << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_128BYTES (0x04 << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_256BYTES (0x08 << CP0_INTCTL_VS_SHIFT)
-# define CP0_INTCTL_VS_512BYTES (0x10 << CP0_INTCTL_VS_SHIFT)
-
-/* 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)
-#define CP0_SRSCTL_PSS_SHIFT (6) /* Bits 6-9: Previous shadow set */
-#define CP0_SRSCTL_PSS_MASK (15 << CP0_SRSCTL_PSS_SHIFT)
-#define CP0_SRSCTL_ESS_SHIFT (12) /* Bits 12-15: Exception shadow sets */
-#define CP0_SRSCTL_ESS_MASK (15 << CP0_SRSCTL_ESS_SHIFT)
-#define CP0_SRSCTL_EICSS_SHIFT (18) /* Bits 18-21: External interrupt controller shadow sets */
-#define CP0_SRSCTL_EICSS_MASK (15 << CP0_SRSCTL_EICSS_SHIFT)
-#define CP0_SRSCTL_HSS_SHIFT (26) /* Bits 26-29: High shadow sets */
-#define CP0_SRSCTL_HSS_MASK (15 << CP0_SRSCTL_HSS_SHIFT)
-# define CP0_SRSCTL_HSS_1SET (0 << CP0_SRSCTL_HSS_SHIFT) /* One shadow set (normal GPR set) */
-# 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: 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)
-#define CP0_SRSMAP_SSV1_SHIFT (4) /* Bits 4-7: Shadow set vector 1 */
-#define CP0_SRSMAP_SSV1_MASK (15 << CP0_SRSMAP_SSV1_SHIFT)
-#define CP0_SRSMAP_SSV2_SHIFT (8) /* Bits 8-11: Shadow set vector 2 */
-#define CP0_SRSMAP_SSV2_MASK (15 << CP0_SRSMAP_SSV2_SHIFT)
-#define CP0_SRSMAP_SSV3_SHIFT (12) /* Bits 12-15: Shadow set vector 3 */
-#define CP0_SRSMAP_SSV3_MASK (15 << CP0_SRSMAP_SSV3_SHIFT)
-#define CP0_SRSMAP_SSV4_SHIFT (16) /* Bits 16-19: Shadow set vector 4 */
-#define CP0_SRSMAP_SSV4_MASK (15 << CP0_SRSMAP_SSV4_SHIFT)
-#define CP0_SRSMAP_SSV5_SHIFT (20) /* Bits 20-23: Shadow set vector 5 */
-#define CP0_SRSMAP_SSV5_MASK (15 << CP0_SRSMAP_SSV5_SHIFT)
-#define CP0_SRSMAP_SSV6_SHIFT (24) /* Bits 24-27: Shadow set vector 6 */
-#define CP0_SRSMAP_SSV6_MASK (15 << CP0_SRSMAP_SSV6_SHIFT)
-#define CP0_SRSMAP_SSV7_SHIFT (28) /* Bits 28-31: Shadow set vector 7 */
-#define CP0_SRSMAP_SSV7_MASK (15 << CP0_SRSMAP_SSV7_SHIFT)
-
-/* Register Number: 13 Sel: 0 Name: Cause
- * Function: Cause of last general exception
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- * NOTES: The following bits are added in the PIC32:
- */
-
-#define CP0_CAUSE_R (1 << 26) /* Bit 26: R bit */
-#define CP0_CAUSE_DC (1 << 27) /* Bit 27: Disable count */
-#define CP0_CAUSE_TI (1 << 30) /* Bit 30: Timer interrupt bit *.
-
-/* Register Number: 14 Sel: 0 Name: EPC
- * Function: Program counter at last exception
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- */
-
-/* Register Number: 15 Sel: 0 Name: PRId
- * Function: Processor identification and revision
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- * NOTE: Slightly different bit interpretations of some fields:
- */
-
-#define CP0_PRID_PATCH_SHIFT (5) /* Bits 0-1: Patch level */
-#define CP0_PRID_PATCH_MASK (3 << CP0_PRID_PATCH_SHIFT)
-#define CP0_PRID_MINOR_SHIFT (2) /* Bits 2-4: Minor revision number */
-#define CP0_PRID_MINOR_MASK (7 << CP0_PRID_MINOR_SHIFT)
-#define CP0_PRID_MAJOR_SHIFT (5) /* Bits 5-7: Major revision number */
-#define CP0_PRID_MAJOR_MASK (7 << CP0_PRID_MAJOR_SHIFT)
-
-#undef CP0_PRID_OPTIONS_SHIFT
-#undef CP0_PRID_OPTIONS_MASK
-
-/* 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)
-#define CP_EBASE_SHIFT (12) /* Bits 30-31=10, Bits 12-29: Exception base */
-#define CP_EBASE_MASK (0x3ffff << CP_EBASE_SHIFT)
-
-/* Register Number: 16 Sel: 0 Name: Config
- * Function: Configuration register
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- * 1. PIC32MX is always little-endian.
- * 2. Implementation specific bits defined.
- */
-
-#undef CP0_CONFIG_IMPL_SHIFT
-#undef CP0_CONFIG_IMPL_MASK
-
-#define CP0_CONFIG_K23_SHIFT (0) /* Bits 28-30: KSEG2 and KSEG3 cacheability */
-#define CP0_CONFIG_K23_MASK (7 << CP0_CONFIG_K23_SHIFT)
-# define CP0_CONFIG_K23_UNCACHED (2 << CP0_CONFIG_K23_SHIFT)
-# define CP0_CONFIG_K23_CACHEABLE (3 << CP0_CONFIG_K23_SHIFT)
-#define CP0_CONFIG_KU_SHIFT (0) /* Bits 0-2: KUSEG and USEG cacheability */
-#define CP0_CONFIG_KU_MASK (7 << CP0_CONFIG_KU_SHIFT)
-# define CP0_CONFIG_KU_UNCACHED (2 << CP0_CONFIG_KU_SHIFT)
-# define CP0_CONFIG_KU_CACHEABLE (3 << CP0_CONFIG_KU_SHIFT)
-#define CP0_CONFIG_UDI (1 << 22) /* Bit 22: User defined bit */
-#define CP0_CONFIG_SB (1 << 21) /* Bit 32: Simple BE bus mode bit */
-#define CP0_CONFIG_MDU (1 << 20) /* Multipley/Divide unit bit */
-#define CP0_CONFIG_DS (1 << 16) /* Dual SRAM bit */
-
-/* Register Number: 16 Sel: 1 Name: Config1
- * Function: Configuration register 1
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- *
- * Register Number: 16 Sel: 2 Name: Config2
- * Function: Configuration register 2
- * Compliance Level: Optional.
- *
- * See arch/mips/include/mips32/cp0.h
- */
-
-#undef CP0_CONFIG2_TBS_SHIFT
-#undef CP0_CONFIG2_TBS_MASK
-
-/* Register Number: 16 Sel: 3 Name: Config3
- * Function: Configuration register 3
- * Compliance Level: Optional.
- *
- * See arch/mips/include/mips32/cp0.h
- */
-
-#define CP0_CONFIG3_SP (1 << 4) /* Bit 4: Support page bit */
-#define CP0_CONFIG3_VINT (1 << 5) /* Bit 5: Vector interrupt bit */
-#define CP0_CONFIG3_VEIC (1 << 6) /* Bit 6: External interrupt controller supported */
-
-/* Register Number: 17-22 Reserved
- * Compliance Level: Optional.
- */
-
-/* Register Number: 23 Sel: 0 Name: Debug
- * Function: EJTAG Debug register
- * Compliance Level: Optional.
- */
-
-#define CP0_DEBUG_DSS (1 << 0) /* Bit 0: Debug single-step exception */
-#define CP0_DEBUG_DBP (1 << 1) /* Bit 1: Debug software breakpoint exception */
-#define CP0_DEBUG_DDBL (1 << 2) /* Bit 2: Debug data break exception on load */
-#define CP0_DEBUG_DDBS (1 << 3) /* Bit 3: Debug data break exception on store */
-#define CP0_DEBUG_DIB (1 << 4) /* Bit 4: Debug instruction break exception */
-#define CP0_DEBUG_DINT (1 << 5) /* Bit 5: Debug interrupt exception */
-#define CP0_DEBUG_SST (1 << 8) /* Bit 6: Enable debug single step exception */
-#define CP0_DEBUG_NOSST (1 << 9) /* Bit 7: No single step feature available */
-#define CP0_DEBUG_DEXCCODE_SHIFT (10) /* Bits 10-14: Cause of latest exception in DEBUG mode */
-#define CP0_DEBUG_DEXCCODE_MASK (31 << CP0_DEBUG_DEXCCODE_SHIFT)
-#define CP0_DEBUG_VER_SHIFT (15) /* Bits 15-17: EJTAG version */
-#define CP0_DEBUG_VER_MASK (7 << CP0_DEBUG_VER_SHIFT)
-#define CP0_DEBUG_DDBLIMPR (1 << 18) /* Bit 18: Imprecise debug data break load instruction */
-#define CP0_DEBUG_DDBSIMPR (1 << 19) /* Bit 19: Imprecise debug data break store instruction */
-#define CP0_DEBUG_IEXI (1 << 20) /* Bit 20: Imprecise error exception inhibit */
-#define CP0_DEBUG_DBUSEP (1 << 21) /* Bit 21: Data access bus error exception pending */
-#define CP0_DEBUG_CACHEEP (1 << 22) /* Bit 22: Imprecise cache error exception is pending */
-#define CP0_DEBUG_MCHECKP (1 << 23) /* Bit 23: Imprecise machine check exception is pending */
-#define CP0_DEBUG_IBUSEP (1 << 24) /* Bit 24: Bus error exception pending */
-#define CP0_DEBUG_COUNTDM (1 << 25) /* Bit 25: Count register behavior (1=running) */
-#define CP0_DEBUG_HALT (1 << 26) /* Bit 26: Internal system bus clock stopped */
-#define CP0_DEBUG_DOZE (1 << 27) /* Bit 27: Processor in low power mode */
-#define CP0_DEBUG_LSNM (1 << 28) /* Bit 28: Load/store in DSEG goes to main memory */
-#define CP0_DEBUG_NODCR (1 << 29) /* Bit 29: No DSEG preset */
-#define CP0_DEBUG_DM (1 << 30) /* Bit 30: Processor is operating in DEBUG mode */
-#define CP0_DEBUG_DBD (1 << 31) /* Bit 31: Last debug exception occurred in a dely slot */
-
-/* Register Number: 23 Sel: ? Name: Debug2
- * Is this documented anywhere?
- */
-
-/* Register Number: 24 Sel: 0 Name: DEPC
- * Function: Program counter at last EJTAG debug exception
- * Compliance Level: Optional.
- *
- * See arch/mips/include/mips32/cp0.h
- *
- * Register Number: 25-29 Reserved
- * Compliance Level: Recommended/Optional.
- *
- * Register Number: 30 Sel: 0 Name: ErrorEPC
- * Function: Program counter at last error
- * Compliance Level: Required.
- *
- * See arch/mips/include/mips32/cp0.h
- *
- * Register Number: 31 Sel: 0 Name: DeSAVE
- * Function: EJTAG debug exception save register
- * Compliance Level: Optional.
- *
- * See arch/mips/include/mips32/cp0.h
- */
-
-/****************************************************************************
- * 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_INCLUDE_PIC32MX_CP0_H */
+/****************************************************************************
+ * arch/mips/include/pic32mx/cp0.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_MIPS_INCLUDE_PIC32MX_CP0_H
+#define __ARCH_MIPS_INCLUDE_PIC32MX_CP0_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <arch/mips32/cp0.h>
+
+/****************************************************************************
+ * 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 */
+# define PIC32MX_CP0_DEBUG $23,3 /* Debug control and exception status */
+# define PIC32MX_CP0_DEPC $24,3 /* Program counter at last debug exception */
+# define PIC32MX_CP0_ERREPC $30,3 /* Program counter at last error */
+# define PIC32MX_CP0_DESAVE $31,3 /* Debug handler scratchpad register */
+#endif
+
+/* CP0 Registers ************************************************************/
+
+/* Register Number: 0-6: Reserved
+ * Compliance Level: Required for TLB-based MMU; Optional otherwise.
+ */
+
+/* Register Number: 7 Sel: 0 Name: HWREna
+ * Function: Enables access via the RDHWR instruction to selected hardware
+ * registers in non-privileged mode.
+ * Compliance Level: (Reserved for future extensions)
+ */
+
+#define CP0_HWRENA_SHIFT (0) /* Bits 0-3: Enable access to a hardware resource */
+#define CP0_HWRENA_MASK (15 << CP0_HWRENA_SHIFT)
+# define CP0_HWRENA_BIT0 (1 << CP0_HWRENA_SHIFT)
+# define CP0_HWRENA_BIT1 (2 << CP0_HWRENA_SHIFT)
+# define CP0_HWRENA_BIT2 (4 << CP0_HWRENA_SHIFT)
+# define CP0_HWRENA_BIT3 (8 << CP0_HWRENA_SHIFT)
+
+/* Register Number: 8 Sel: 0 Name: BadVAddr
+ * Function: Reports the address for the most recent address-related
+ * exception
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ *
+ * Register Number: 9 Sel: 0 Name: Count
+ * Function: Processor cycle count
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ *
+ * Register Number: 10 Reserved.
+ * Compliance Level: Required for TLB-based MMU; Optional otherwise.
+ *
+ * Register Number: 11 Sel: 0 Name: Compare
+ * Function: Timer interrupt control
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ */
+
+/* Register Number: 12 Sel: 0 Name: Status
+ * Function: Processor status and control
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ * NOTES:
+ * 1. The following are reserved bits in the PIC32:
+ * CP0_STATUS_UX Bit 5: Enables 64-bit user address space (Not MIPS32)
+ * CP0_STATUS_SX Bit 6: Enables 64-bit supervisor address space (Not MIPS32)
+ * CP0_STATUS_KX Bit 7: Enables 64-bit kernel address space (Not MIPS32)
+ * CP0_STATUS_IMPL Bits 16-17: Implementation dependent
+ * CP0_STATUS_TS Bit 21: TLB detected match on multiple entries
+ * CP0_STATUS_PX Bit 23: Enables 64-bit operations (Not MIPS32)
+ * CP0_STATUS_MX Bit 24: Enables MDMX™ (Not MIPS32)
+ */
+
+#undef CP0_STATUS_UX
+#undef CP0_STATUS_SX
+#undef CP0_STATUS_KX
+#undef CP0_STATUS_IMPL
+#undef CP0_STATUS_IMPL_SHIFT
+#undef CP0_STATUS_IMPL_MASK
+#undef CP0_STATUS_TS
+#undef CP0_STATUS_PX
+#undef CP0_STATUS_MX
+
+/* 2. The following field is of a different width. Apparently, it
+ * excludes the software interrupt bits.
+ *
+ * CP0_STATUS_IM Bits 8-15: Interrupt Mask
+ * Vs.
+ * CP0_STATUS_IPL Bits 10-15: Interrupt priority level
+ * Bitss 8-9 reserved
+ */
+
+#define CP0_STATUS_IPL_SHIFT (10) /* Bits 10-15: Interrupt priority level */
+#define CP0_STATUS_IPL_MASK (0x3f << CP0_STATUS_IPL_SHIFT)
+
+/* 3. Supervisor mode not supported
+ * CP0_STATUS_KSU Bits 3-4: Operating mode (with supervisor mode)
+ */
+
+#undef CP0_STATUS_KSU_SHIFT
+#undef CP0_STATUS_KSU_MASK
+#undef CP0_STATUS_KSU_KERNEL
+#undef CP0_STATUS_KSU_SUPER
+#undef CP0_STATUS_KSU_USER
+
+/* Register Number: 12 Sel: 1 Name: IntCtl */
+
+#define CP0_INTCTL_VS_SHIFT (5) /* Bits 5-9: Vector spacing bits */
+#define CP0_INTCTL_VS_MASK (0x1f << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_0BYTES (0x00 << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_32BYTES (0x01 << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_64BYTES (0x02 << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_128BYTES (0x04 << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_256BYTES (0x08 << CP0_INTCTL_VS_SHIFT)
+# define CP0_INTCTL_VS_512BYTES (0x10 << CP0_INTCTL_VS_SHIFT)
+
+/* 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)
+#define CP0_SRSCTL_PSS_SHIFT (6) /* Bits 6-9: Previous shadow set */
+#define CP0_SRSCTL_PSS_MASK (15 << CP0_SRSCTL_PSS_SHIFT)
+#define CP0_SRSCTL_ESS_SHIFT (12) /* Bits 12-15: Exception shadow sets */
+#define CP0_SRSCTL_ESS_MASK (15 << CP0_SRSCTL_ESS_SHIFT)
+#define CP0_SRSCTL_EICSS_SHIFT (18) /* Bits 18-21: External interrupt controller shadow sets */
+#define CP0_SRSCTL_EICSS_MASK (15 << CP0_SRSCTL_EICSS_SHIFT)
+#define CP0_SRSCTL_HSS_SHIFT (26) /* Bits 26-29: High shadow sets */
+#define CP0_SRSCTL_HSS_MASK (15 << CP0_SRSCTL_HSS_SHIFT)
+# define CP0_SRSCTL_HSS_1SET (0 << CP0_SRSCTL_HSS_SHIFT) /* One shadow set (normal GPR set) */
+# 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: 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)
+#define CP0_SRSMAP_SSV1_SHIFT (4) /* Bits 4-7: Shadow set vector 1 */
+#define CP0_SRSMAP_SSV1_MASK (15 << CP0_SRSMAP_SSV1_SHIFT)
+#define CP0_SRSMAP_SSV2_SHIFT (8) /* Bits 8-11: Shadow set vector 2 */
+#define CP0_SRSMAP_SSV2_MASK (15 << CP0_SRSMAP_SSV2_SHIFT)
+#define CP0_SRSMAP_SSV3_SHIFT (12) /* Bits 12-15: Shadow set vector 3 */
+#define CP0_SRSMAP_SSV3_MASK (15 << CP0_SRSMAP_SSV3_SHIFT)
+#define CP0_SRSMAP_SSV4_SHIFT (16) /* Bits 16-19: Shadow set vector 4 */
+#define CP0_SRSMAP_SSV4_MASK (15 << CP0_SRSMAP_SSV4_SHIFT)
+#define CP0_SRSMAP_SSV5_SHIFT (20) /* Bits 20-23: Shadow set vector 5 */
+#define CP0_SRSMAP_SSV5_MASK (15 << CP0_SRSMAP_SSV5_SHIFT)
+#define CP0_SRSMAP_SSV6_SHIFT (24) /* Bits 24-27: Shadow set vector 6 */
+#define CP0_SRSMAP_SSV6_MASK (15 << CP0_SRSMAP_SSV6_SHIFT)
+#define CP0_SRSMAP_SSV7_SHIFT (28) /* Bits 28-31: Shadow set vector 7 */
+#define CP0_SRSMAP_SSV7_MASK (15 << CP0_SRSMAP_SSV7_SHIFT)
+
+/* Register Number: 13 Sel: 0 Name: Cause
+ * Function: Cause of last general exception
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ * NOTES: The following bits are added in the PIC32:
+ */
+
+#define CP0_CAUSE_R (1 << 26) /* Bit 26: R bit */
+#define CP0_CAUSE_DC (1 << 27) /* Bit 27: Disable count */
+#define CP0_CAUSE_TI (1 << 30) /* Bit 30: Timer interrupt bit *.
+
+/* Register Number: 14 Sel: 0 Name: EPC
+ * Function: Program counter at last exception
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ */
+
+/* Register Number: 15 Sel: 0 Name: PRId
+ * Function: Processor identification and revision
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ * NOTE: Slightly different bit interpretations of some fields:
+ */
+
+#define CP0_PRID_PATCH_SHIFT (5) /* Bits 0-1: Patch level */
+#define CP0_PRID_PATCH_MASK (3 << CP0_PRID_PATCH_SHIFT)
+#define CP0_PRID_MINOR_SHIFT (2) /* Bits 2-4: Minor revision number */
+#define CP0_PRID_MINOR_MASK (7 << CP0_PRID_MINOR_SHIFT)
+#define CP0_PRID_MAJOR_SHIFT (5) /* Bits 5-7: Major revision number */
+#define CP0_PRID_MAJOR_MASK (7 << CP0_PRID_MAJOR_SHIFT)
+
+#undef CP0_PRID_OPTIONS_SHIFT
+#undef CP0_PRID_OPTIONS_MASK
+
+/* 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)
+#define CP_EBASE_SHIFT (12) /* Bits 30-31=10, Bits 12-29: Exception base */
+#define CP_EBASE_MASK (0x3ffff << CP_EBASE_SHIFT)
+
+/* Register Number: 16 Sel: 0 Name: Config
+ * Function: Configuration register
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ * 1. PIC32MX is always little-endian.
+ * 2. Implementation specific bits defined.
+ */
+
+#undef CP0_CONFIG_IMPL_SHIFT
+#undef CP0_CONFIG_IMPL_MASK
+
+#define CP0_CONFIG_K23_SHIFT (0) /* Bits 28-30: KSEG2 and KSEG3 cacheability */
+#define CP0_CONFIG_K23_MASK (7 << CP0_CONFIG_K23_SHIFT)
+# define CP0_CONFIG_K23_UNCACHED (2 << CP0_CONFIG_K23_SHIFT)
+# define CP0_CONFIG_K23_CACHEABLE (3 << CP0_CONFIG_K23_SHIFT)
+#define CP0_CONFIG_KU_SHIFT (0) /* Bits 0-2: KUSEG and USEG cacheability */
+#define CP0_CONFIG_KU_MASK (7 << CP0_CONFIG_KU_SHIFT)
+# define CP0_CONFIG_KU_UNCACHED (2 << CP0_CONFIG_KU_SHIFT)
+# define CP0_CONFIG_KU_CACHEABLE (3 << CP0_CONFIG_KU_SHIFT)
+#define CP0_CONFIG_UDI (1 << 22) /* Bit 22: User defined bit */
+#define CP0_CONFIG_SB (1 << 21) /* Bit 32: Simple BE bus mode bit */
+#define CP0_CONFIG_MDU (1 << 20) /* Multipley/Divide unit bit */
+#define CP0_CONFIG_DS (1 << 16) /* Dual SRAM bit */
+
+/* Register Number: 16 Sel: 1 Name: Config1
+ * Function: Configuration register 1
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ *
+ * Register Number: 16 Sel: 2 Name: Config2
+ * Function: Configuration register 2
+ * Compliance Level: Optional.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ */
+
+#undef CP0_CONFIG2_TBS_SHIFT
+#undef CP0_CONFIG2_TBS_MASK
+
+/* Register Number: 16 Sel: 3 Name: Config3
+ * Function: Configuration register 3
+ * Compliance Level: Optional.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ */
+
+#define CP0_CONFIG3_SP (1 << 4) /* Bit 4: Support page bit */
+#define CP0_CONFIG3_VINT (1 << 5) /* Bit 5: Vector interrupt bit */
+#define CP0_CONFIG3_VEIC (1 << 6) /* Bit 6: External interrupt controller supported */
+
+/* Register Number: 17-22 Reserved
+ * Compliance Level: Optional.
+ */
+
+/* Register Number: 23 Sel: 0 Name: Debug
+ * Function: EJTAG Debug register
+ * Compliance Level: Optional.
+ */
+
+#define CP0_DEBUG_DSS (1 << 0) /* Bit 0: Debug single-step exception */
+#define CP0_DEBUG_DBP (1 << 1) /* Bit 1: Debug software breakpoint exception */
+#define CP0_DEBUG_DDBL (1 << 2) /* Bit 2: Debug data break exception on load */
+#define CP0_DEBUG_DDBS (1 << 3) /* Bit 3: Debug data break exception on store */
+#define CP0_DEBUG_DIB (1 << 4) /* Bit 4: Debug instruction break exception */
+#define CP0_DEBUG_DINT (1 << 5) /* Bit 5: Debug interrupt exception */
+#define CP0_DEBUG_SST (1 << 8) /* Bit 6: Enable debug single step exception */
+#define CP0_DEBUG_NOSST (1 << 9) /* Bit 7: No single step feature available */
+#define CP0_DEBUG_DEXCCODE_SHIFT (10) /* Bits 10-14: Cause of latest exception in DEBUG mode */
+#define CP0_DEBUG_DEXCCODE_MASK (31 << CP0_DEBUG_DEXCCODE_SHIFT)
+#define CP0_DEBUG_VER_SHIFT (15) /* Bits 15-17: EJTAG version */
+#define CP0_DEBUG_VER_MASK (7 << CP0_DEBUG_VER_SHIFT)
+#define CP0_DEBUG_DDBLIMPR (1 << 18) /* Bit 18: Imprecise debug data break load instruction */
+#define CP0_DEBUG_DDBSIMPR (1 << 19) /* Bit 19: Imprecise debug data break store instruction */
+#define CP0_DEBUG_IEXI (1 << 20) /* Bit 20: Imprecise error exception inhibit */
+#define CP0_DEBUG_DBUSEP (1 << 21) /* Bit 21: Data access bus error exception pending */
+#define CP0_DEBUG_CACHEEP (1 << 22) /* Bit 22: Imprecise cache error exception is pending */
+#define CP0_DEBUG_MCHECKP (1 << 23) /* Bit 23: Imprecise machine check exception is pending */
+#define CP0_DEBUG_IBUSEP (1 << 24) /* Bit 24: Bus error exception pending */
+#define CP0_DEBUG_COUNTDM (1 << 25) /* Bit 25: Count register behavior (1=running) */
+#define CP0_DEBUG_HALT (1 << 26) /* Bit 26: Internal system bus clock stopped */
+#define CP0_DEBUG_DOZE (1 << 27) /* Bit 27: Processor in low power mode */
+#define CP0_DEBUG_LSNM (1 << 28) /* Bit 28: Load/store in DSEG goes to main memory */
+#define CP0_DEBUG_NODCR (1 << 29) /* Bit 29: No DSEG preset */
+#define CP0_DEBUG_DM (1 << 30) /* Bit 30: Processor is operating in DEBUG mode */
+#define CP0_DEBUG_DBD (1 << 31) /* Bit 31: Last debug exception occurred in a dely slot */
+
+/* Register Number: 23 Sel: ? Name: Debug2
+ * Is this documented anywhere?
+ */
+
+/* Register Number: 24 Sel: 0 Name: DEPC
+ * Function: Program counter at last EJTAG debug exception
+ * Compliance Level: Optional.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ *
+ * Register Number: 25-29 Reserved
+ * Compliance Level: Recommended/Optional.
+ *
+ * Register Number: 30 Sel: 0 Name: ErrorEPC
+ * Function: Program counter at last error
+ * Compliance Level: Required.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ *
+ * Register Number: 31 Sel: 0 Name: DeSAVE
+ * Function: EJTAG debug exception save register
+ * Compliance Level: Optional.
+ *
+ * See arch/mips/include/mips32/cp0.h
+ */
+
+/****************************************************************************
+ * 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_INCLUDE_PIC32MX_CP0_H */
diff --git a/nuttx/arch/mips/src/common/up_allocateheap.c b/nuttx/arch/mips/src/common/up_allocateheap.c
index 0e83c4c63..c334290dd 100644
--- a/nuttx/arch/mips/src/common/up_allocateheap.c
+++ b/nuttx/arch/mips/src/common/up_allocateheap.c
@@ -81,7 +81,7 @@
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
- up_ledon(LED_HEAPALLOCATE);
+ board_led_on(LED_HEAPALLOCATE);
*heap_start = (FAR void*)g_idle_topstack;
*heap_size = CONFIG_RAM_END - g_idle_topstack;
}
diff --git a/nuttx/arch/mips/src/common/up_createstack.c b/nuttx/arch/mips/src/common/up_createstack.c
index e2a73fc7d..7961ef3d9 100644
--- a/nuttx/arch/mips/src/common/up_createstack.c
+++ b/nuttx/arch/mips/src/common/up_createstack.c
@@ -213,7 +213,7 @@ int up_create_stack(FAR struct tcb_s *tcb, size_t stack_size, uint8_t ttype)
tcb->adj_stack_ptr = (uint32_t*)top_of_stack;
tcb->adj_stack_size = size_of_stack;
- up_ledon(LED_STACKCREATED);
+ board_led_on(LED_STACKCREATED);
return OK;
}
diff --git a/nuttx/arch/mips/src/common/up_initialize.c b/nuttx/arch/mips/src/common/up_initialize.c
index eb03cf931..a6e3e5577 100644
--- a/nuttx/arch/mips/src/common/up_initialize.c
+++ b/nuttx/arch/mips/src/common/up_initialize.c
@@ -191,5 +191,5 @@ void up_initialize(void)
/* Initialize USB -- device and/or host */
up_usbinitialize();
- up_ledon(LED_IRQSENABLED);
+ board_led_on(LED_IRQSENABLED);
}
diff --git a/nuttx/arch/mips/src/common/up_internal.h b/nuttx/arch/mips/src/common/up_internal.h
index 0e7960c0f..3e9da3e2c 100644
--- a/nuttx/arch/mips/src/common/up_internal.h
+++ b/nuttx/arch/mips/src/common/up_internal.h
@@ -290,12 +290,12 @@ extern void up_usbuninitialize(void);
/* LEDs */
#ifdef CONFIG_ARCH_LEDS
-extern void up_ledon(int led);
-extern void up_ledoff(int led);
+extern void board_led_on(int led);
+extern void board_led_off(int led);
#else
-# define up_ledinit()
-# define up_ledon(led)
-# define up_ledoff(led)
+# define board_led_initialize()
+# define board_led_on(led)
+# define board_led_off(led)
#endif
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/arch/mips/src/mips32/up_assert.c b/nuttx/arch/mips/src/mips32/up_assert.c
index 36414d71c..bd59bbc2c 100644
--- a/nuttx/arch/mips/src/mips32/up_assert.c
+++ b/nuttx/arch/mips/src/mips32/up_assert.c
@@ -101,9 +101,9 @@ static void _up_assert(int errorcode)
for(;;)
{
#ifdef CONFIG_ARCH_LEDS
- up_ledon(LED_PANIC);
+ board_led_on(LED_PANIC);
up_mdelay(250);
- up_ledoff(LED_PANIC);
+ board_led_off(LED_PANIC);
up_mdelay(250);
#endif
}
@@ -128,7 +128,7 @@ void up_assert(const uint8_t *filename, int lineno)
struct tcb_s *rtcb = (struct tcb_s*)g_readytorun.head;
#endif
- up_ledon(LED_ASSERTION);
+ board_led_on(LED_ASSERTION);
#ifdef CONFIG_PRINT_TASKNAME
lldbg("Assertion failed at file:%s line: %d task: %s\n",
diff --git a/nuttx/arch/mips/src/mips32/up_doirq.c b/nuttx/arch/mips/src/mips32/up_doirq.c
index bf1a19727..090fdbae5 100644
--- a/nuttx/arch/mips/src/mips32/up_doirq.c
+++ b/nuttx/arch/mips/src/mips32/up_doirq.c
@@ -72,7 +72,7 @@
uint32_t *up_doirq(int irq, uint32_t *regs)
{
- up_ledon(LED_INIRQ);
+ board_led_on(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC();
#else
@@ -122,6 +122,6 @@ uint32_t *up_doirq(int irq, uint32_t *regs)
up_enable_irq(irq);
#endif
- up_ledoff(LED_INIRQ);
+ board_led_off(LED_INIRQ);
return regs;
}
diff --git a/nuttx/arch/mips/src/mips32/up_sigdeliver.c b/nuttx/arch/mips/src/mips32/up_sigdeliver.c
index defa6bd10..7ad80f733 100644
--- a/nuttx/arch/mips/src/mips32/up_sigdeliver.c
+++ b/nuttx/arch/mips/src/mips32/up_sigdeliver.c
@@ -93,7 +93,7 @@ void up_sigdeliver(void)
int saved_errno = rtcb->pterrno;
- up_ledon(LED_SIGNAL);
+ board_led_on(LED_SIGNAL);
sdbg("rtcb=%p sigdeliver=%p sigpendactionq.head=%p\n",
rtcb, rtcb->xcp.sigdeliver, rtcb->sigpendactionq.head);
@@ -135,7 +135,7 @@ void up_sigdeliver(void)
* execution.
*/
- up_ledoff(LED_SIGNAL);
+ board_led_off(LED_SIGNAL);
up_fullcontextrestore(regs);
/* up_fullcontextrestore() should not return but could if the software
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-cvr.h b/nuttx/arch/mips/src/pic32mx/pic32mx-cvr.h
index f41ea89fb..ab865c0a6 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-cvr.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-cvr.h
@@ -1,113 +1,113 @@
-/************************************************************************************
- * arch/mips/src/pic32mx/pic32mx-cvr.h
- *
- * Copyright (C) 2011 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.
- *
- ************************************************************************************/
-
-#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CVR_H
-#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CVR_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "pic32mx-memorymap.h"
-
-/************************************************************************************
- * Pre-Processor Definitions
- ************************************************************************************/
-/* Register Offsets *****************************************************************/
-
-#define PIC32MX_CVR_CON_OFFSET 0x0000 /* Comparator voltage reference control register */
-#define PIC32MX_CVR_CONCLR_OFFSET 0x0004 /* Comparator voltage reference control clear register */
-#define PIC32MX_CVR_CONSET_OFFSET 0x0008 /* Comparator voltage reference control set register */
-#define PIC32MX_CVR_CONINV_OFFSET 0x000c /* Comparator voltage reference control invert register */
-
-/* Register Addresses ***************************************************************/
-
-#define PIC32MX_CVR_CON (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CON_OFFSET)
-#define PIC32MX_CVR_CONCLR (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONCLR_OFFSET)
-#define PIC32MX_CVR_CONSET (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONSET_OFFSET)
-#define PIC32MX_CVR_CONINV (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONINV_OFFSET)
-
-/* Register Bit-Field Definitions ***************************************************/
-
-/* Comparator voltage reference control register */
-
-#define CVR_CON_CVR_SHIFT (0) /* Bits 0-3: CVREF value selection */
-#define CVR_CON_CVR_MASK (15 << CVR_CON_CVR_SHIFT)
-# define CVR_CON_CVR(n) ((n) << CVR_CON_CVR_SHIFT)
-#define CVR_CON_CVRSS (1 << 4) /* Bit 4: CVREF source selection */
-#define CVR_CON_CVRR (1 << 5) /* Bit 5: CVREF range selection */
-#define CVR_CON_CVROE (1 << 6) /* Bit 6: CVREFOUT enable */
-#ifdef CHIP_VRFSEL
-# define CVR_CON_BGSEL_SHIFT (8) /* Bits 8-9: Band gap reference source */
-# define CVR_CON_BGSEL_MASK (3 << CVR_CON_CVR_SHIFT)
-# define CVR_CON_BGSEL_1p2V (0 << CVR_CON_CVR_SHIFT) /* IVREF = 1.2V (nominal) */
-# define CVR_CON_BGSEL_0p6V (1 << CVR_CON_CVR_SHIFT) /* IVREF = 0.6V (nominal) */
-# define CVR_CON_BGSEL_0p2V (2 << CVR_CON_CVR_SHIFT) /* IVREF = 0.2V (nominal) */
-# define CVR_CON_BGSEL_VREF (3 << CVR_CON_CVR_SHIFT) /* VREF = VREF+ */
-# define CVR_CON_VREFSEL (1 << 10) /* Bit 10: Voltage reference select */
-#endif
-#define CVR_CON_ON (1 << 15) /* Bit 15: Comparator voltage reference on */
-
-/************************************************************************************
- * 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_CVR_H */
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-cvr.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CVR_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_CVR_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "pic32mx-memorymap.h"
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_CVR_CON_OFFSET 0x0000 /* Comparator voltage reference control register */
+#define PIC32MX_CVR_CONCLR_OFFSET 0x0004 /* Comparator voltage reference control clear register */
+#define PIC32MX_CVR_CONSET_OFFSET 0x0008 /* Comparator voltage reference control set register */
+#define PIC32MX_CVR_CONINV_OFFSET 0x000c /* Comparator voltage reference control invert register */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_CVR_CON (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CON_OFFSET)
+#define PIC32MX_CVR_CONCLR (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONCLR_OFFSET)
+#define PIC32MX_CVR_CONSET (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONSET_OFFSET)
+#define PIC32MX_CVR_CONINV (PIC32MX_CVR_K1BASE+PIC32MX_CVR_CONINV_OFFSET)
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* Comparator voltage reference control register */
+
+#define CVR_CON_CVR_SHIFT (0) /* Bits 0-3: CVREF value selection */
+#define CVR_CON_CVR_MASK (15 << CVR_CON_CVR_SHIFT)
+# define CVR_CON_CVR(n) ((n) << CVR_CON_CVR_SHIFT)
+#define CVR_CON_CVRSS (1 << 4) /* Bit 4: CVREF source selection */
+#define CVR_CON_CVRR (1 << 5) /* Bit 5: CVREF range selection */
+#define CVR_CON_CVROE (1 << 6) /* Bit 6: CVREFOUT enable */
+#ifdef CHIP_VRFSEL
+# define CVR_CON_BGSEL_SHIFT (8) /* Bits 8-9: Band gap reference source */
+# define CVR_CON_BGSEL_MASK (3 << CVR_CON_CVR_SHIFT)
+# define CVR_CON_BGSEL_1p2V (0 << CVR_CON_CVR_SHIFT) /* IVREF = 1.2V (nominal) */
+# define CVR_CON_BGSEL_0p6V (1 << CVR_CON_CVR_SHIFT) /* IVREF = 0.6V (nominal) */
+# define CVR_CON_BGSEL_0p2V (2 << CVR_CON_CVR_SHIFT) /* IVREF = 0.2V (nominal) */
+# define CVR_CON_BGSEL_VREF (3 << CVR_CON_CVR_SHIFT) /* VREF = VREF+ */
+# define CVR_CON_VREFSEL (1 << 10) /* Bit 10: Voltage reference select */
+#endif
+#define CVR_CON_ON (1 << 15) /* Bit 15: Comparator voltage reference on */
+
+/************************************************************************************
+ * 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_CVR_H */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c b/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c
index 3f5126cfc..3c38610bd 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-decodeirq.c
@@ -95,7 +95,7 @@ uint32_t *pic32mx_decodeirq(uint32_t *regs)
* processing an interrupt.
*/
- up_ledon(LED_INIRQ);
+ board_led_on(LED_INIRQ);
/* Save the current value of current_regs (to support nested interrupt
* handling). Then set current_regs to regs, indicating that this is
@@ -161,11 +161,11 @@ uint32_t *pic32mx_decodeirq(uint32_t *regs)
current_regs = savestate;
if (current_regs == NULL)
{
- up_ledoff(LED_INIRQ);
+ board_led_off(LED_INIRQ);
}
#else
current_regs = NULL;
- up_ledoff(LED_INIRQ);
+ board_led_off(LED_INIRQ);
#endif
return regs;
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c b/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
index cf0813e5f..125bbbf88 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
@@ -94,7 +94,7 @@ uint32_t *pic32mx_exception(uint32_t *regs)
* processing an interrupt.
*/
- up_ledon(LED_INIRQ);
+ board_led_on(LED_INIRQ);
#ifdef CONFIG_DEBUG
/* Get the cause of the exception from the CAUSE register */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ic.h b/nuttx/arch/mips/src/pic32mx/pic32mx-ic.h
index a553f1f71..87703818a 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ic.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ic.h
@@ -1,166 +1,166 @@
-/************************************************************************************
- * arch/mips/src/pic32mx/pic32mx-ic.h
- *
- * Copyright (C) 2011 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.
- *
- ************************************************************************************/
-
-#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H
-#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "pic32mx-memorymap.h"
-
-#if CHIP_NIC > 0
-
-/************************************************************************************
- * Pre-Processor Definitions
- ************************************************************************************/
-/* Register Offsets *****************************************************************/
-
-#define PIC32MX_IC_CON_OFFSET 0x0000 /* Input Capture X Control Register */
-#define PIC32MX_IC_CONCLR_OFFSET 0x0004 /* Input Capture X Control Set Register */
-#define PIC32MX_IC_CONSET_OFFSET 0x0008 /* Input Capture X Control Clear Register */
-#define PIC32MX_IC_CONINV_OFFSET 0x000c /* Input Capture X Control Invert Register */
-#define PIC32MX_IC_BUF_OFFSET 0x0010 /* Input Capture X Buffer Register */
-
-/* Register Addresses ***************************************************************/
-
-#define PIC32MX_IC_CON(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CON_OFFSET)
-#define PIC32MX_IC_CONCLR(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONCLR_OFFSET)
-#define PIC32MX_IC_CONSET(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONSET_OFFSET)
-#define PIC32MX_IC_CONINV(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONINV_OFFSET)
-#define PIC32MX_IC_BUF(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_BUF_OFFSET)
-
-#define PIC32MX_IC1_CON (PIC32MX_IC1_K1BASE+PIC32MX_IC_CON_OFFSET)
-#define PIC32MX_IC1_CONCLR (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
-#define PIC32MX_IC1_CONSET (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONSET_OFFSET)
-#define PIC32MX_IC1_CONINV (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONINV_OFFSET)
-#define PIC32MX_IC1_BUF (PIC32MX_IC1_K1BASE+PIC32MX_IC_BUF_OFFSET)
-
-#if CHIP_NIC > 1
-# define PIC32MX_IC2_CON (PIC32MX_IC2_K1BASE+PIC32MX_IC_CON_OFFSET)
-# define PIC32MX_IC2_CONCLR (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
-# define PIC32MX_IC2_CONSET (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONSET_OFFSET)
-# define PIC32MX_IC2_CONINV (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONINV_OFFSET)
-# define PIC32MX_IC2_BUF (PIC32MX_IC2_K1BASE+PIC32MX_IC_BUF_OFFSET)
-#endif
-
-#if CHIP_NIC > 2
-# define PIC32MX_IC3_CON (PIC32MX_IC3_K1BASE+PIC32MX_IC_CON_OFFSET)
-# define PIC32MX_IC3_CONCLR (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
-# define PIC32MX_IC3_CONSET (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONSET_OFFSET)
-# define PIC32MX_IC3_CONINV (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONINV_OFFSET)
-# define PIC32MX_IC3_BUF (PIC32MX_IC3_K1BASE+PIC32MX_IC_BUF_OFFSET)
-#endif
-
-#if CHIP_NIC > 3
-# define PIC32MX_IC4_CON (PIC32MX_IC4_K1BASE+PIC32MX_IC_CON_OFFSET)
-# define PIC32MX_IC4_CONCLR (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
-# define PIC32MX_IC4_CONSET (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONSET_OFFSET)
-# define PIC32MX_IC4_CONINV (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONINV_OFFSET)
-# define PIC32MX_IC4_BUF (PIC32MX_IC4_K1BASE+PIC32MX_IC_BUF_OFFSET)
-#endif
-
-#if CHIP_NIC > 4
-# define PIC32MX_IC5_CON (PIC32MX_IC5_K1BASE+PIC32MX_IC_CON_OFFSET)
-# define PIC32MX_IC5_CONCLR (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
-# define PIC32MX_IC5_CONSET (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONSET_OFFSET)
-# define PIC32MX_IC5_CONINV (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONINV_OFFSET)
-# define PIC32MX_IC5_BUF (PIC32MX_IC5_K1BASE+PIC32MX_IC_BUF_OFFSET)
-#endif
-
-/* Register Bit-Field Definitions ***************************************************/
-
-/* Input Capture X Control Register */
-
-#define IC_CON_ICM_SHIFT (0) /* Bits 0-2: Input Capture Mode Select */
-#define IC_CON_ICM_MASK (7 << IC_CON_ICM_SHIFT)
-# define IC_CON_ICM_DISABLE (0 << IC_CON_ICM_SHIFT) /* Capture disable mode */
-# define IC_CON_ICM_EDGE (1 << IC_CON_ICM_SHIFT) /* Edge detect mode */
-# define IC_CON_ICM_FALLING (2 << IC_CON_ICM_SHIFT) /* Every falling edge */
-# define IC_CON_ICM_RISING (3 << IC_CON_ICM_SHIFT) /* Every rising edge */
-# define IC_CON_ICM_4th (4 << IC_CON_ICM_SHIFT) /* Every fourth rising edge */
-# define IC_CON_ICM_16th (5 << IC_CON_ICM_SHIFT) /* Every sixteenth rising edge */
-# define IC_CON_ICM_TRIGGER (6 << IC_CON_ICM_SHIFT) /* Specified edge first and every edge thereafter */
-# define IC_CON_ICM_INTERRUPT (7 << IC_CON_ICM_SHIFT) /* Interrupt-only mode */
-#define IC_CON_ICBNE (1 << 3) /* Bit 3: Input Capture Buffer Not Empty Status */
-#define IC_CON_ICOV (1 << 4) /* Bit 4: Input Capture */
-#define IC_CON_ICI_SHIFT (5) /* Bits 5-6: Interrupt Control */
-#define IC_CON_ICI_MASK (3 << IC_CON_ICI_SHIFT)
-# define IC_CON_ICI_EVERY (0 << IC_CON_ICI_SHIFT) /* Interrupt every capture event */
-# define IC_CON_ICI_2ND (1 << IC_CON_ICI_SHIFT) /* Interrupt every 2nd capture event */
-# define IC_CON_ICI_3RD (2 << IC_CON_ICI_SHIFT) /* Interrupt every 3rd capture event */
-# define IC_CON_ICI_4TH (3 << IC_CON_ICI_SHIFT) /* Interrupt every 4th capture event */
-#define IC_CON_ICTMR (1 << 7) /* Bit 7: Timer Select */
-#define IC_CON_C32 (1 << 8) /* Bit 8: 32-bit Capture Select */
-#define IC_CON_FEDGE (1 << 9) /* Bit 9: First Capture Edge Select */
-#define IC_CON_SIDL (1 << 13) /* Bit 13: Stop in Idle Control */
-#define IC_CON_FRZ (1 << 14) /* Bit 14: Freeze in Debug Mode Control */
-#define IC_CON_ON (1 << 15) /* Bit 15: Input Capture Module Enable */
-
-/* Input Capture X Buffer Register -- 32-bit capture 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 /* CHIP_NIC > 0 */
-#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H */
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-ic.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "pic32mx-memorymap.h"
+
+#if CHIP_NIC > 0
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_IC_CON_OFFSET 0x0000 /* Input Capture X Control Register */
+#define PIC32MX_IC_CONCLR_OFFSET 0x0004 /* Input Capture X Control Set Register */
+#define PIC32MX_IC_CONSET_OFFSET 0x0008 /* Input Capture X Control Clear Register */
+#define PIC32MX_IC_CONINV_OFFSET 0x000c /* Input Capture X Control Invert Register */
+#define PIC32MX_IC_BUF_OFFSET 0x0010 /* Input Capture X Buffer Register */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_IC_CON(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CON_OFFSET)
+#define PIC32MX_IC_CONCLR(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONCLR_OFFSET)
+#define PIC32MX_IC_CONSET(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONSET_OFFSET)
+#define PIC32MX_IC_CONINV(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_CONINV_OFFSET)
+#define PIC32MX_IC_BUF(n) (PIC32MX_IC_K1BASE(n)+PIC32MX_IC_BUF_OFFSET)
+
+#define PIC32MX_IC1_CON (PIC32MX_IC1_K1BASE+PIC32MX_IC_CON_OFFSET)
+#define PIC32MX_IC1_CONCLR (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
+#define PIC32MX_IC1_CONSET (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONSET_OFFSET)
+#define PIC32MX_IC1_CONINV (PIC32MX_IC1_K1BASE+PIC32MX_IC_CONINV_OFFSET)
+#define PIC32MX_IC1_BUF (PIC32MX_IC1_K1BASE+PIC32MX_IC_BUF_OFFSET)
+
+#if CHIP_NIC > 1
+# define PIC32MX_IC2_CON (PIC32MX_IC2_K1BASE+PIC32MX_IC_CON_OFFSET)
+# define PIC32MX_IC2_CONCLR (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
+# define PIC32MX_IC2_CONSET (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONSET_OFFSET)
+# define PIC32MX_IC2_CONINV (PIC32MX_IC2_K1BASE+PIC32MX_IC_CONINV_OFFSET)
+# define PIC32MX_IC2_BUF (PIC32MX_IC2_K1BASE+PIC32MX_IC_BUF_OFFSET)
+#endif
+
+#if CHIP_NIC > 2
+# define PIC32MX_IC3_CON (PIC32MX_IC3_K1BASE+PIC32MX_IC_CON_OFFSET)
+# define PIC32MX_IC3_CONCLR (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
+# define PIC32MX_IC3_CONSET (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONSET_OFFSET)
+# define PIC32MX_IC3_CONINV (PIC32MX_IC3_K1BASE+PIC32MX_IC_CONINV_OFFSET)
+# define PIC32MX_IC3_BUF (PIC32MX_IC3_K1BASE+PIC32MX_IC_BUF_OFFSET)
+#endif
+
+#if CHIP_NIC > 3
+# define PIC32MX_IC4_CON (PIC32MX_IC4_K1BASE+PIC32MX_IC_CON_OFFSET)
+# define PIC32MX_IC4_CONCLR (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
+# define PIC32MX_IC4_CONSET (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONSET_OFFSET)
+# define PIC32MX_IC4_CONINV (PIC32MX_IC4_K1BASE+PIC32MX_IC_CONINV_OFFSET)
+# define PIC32MX_IC4_BUF (PIC32MX_IC4_K1BASE+PIC32MX_IC_BUF_OFFSET)
+#endif
+
+#if CHIP_NIC > 4
+# define PIC32MX_IC5_CON (PIC32MX_IC5_K1BASE+PIC32MX_IC_CON_OFFSET)
+# define PIC32MX_IC5_CONCLR (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONCLR_OFFSET)
+# define PIC32MX_IC5_CONSET (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONSET_OFFSET)
+# define PIC32MX_IC5_CONINV (PIC32MX_IC5_K1BASE+PIC32MX_IC_CONINV_OFFSET)
+# define PIC32MX_IC5_BUF (PIC32MX_IC5_K1BASE+PIC32MX_IC_BUF_OFFSET)
+#endif
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* Input Capture X Control Register */
+
+#define IC_CON_ICM_SHIFT (0) /* Bits 0-2: Input Capture Mode Select */
+#define IC_CON_ICM_MASK (7 << IC_CON_ICM_SHIFT)
+# define IC_CON_ICM_DISABLE (0 << IC_CON_ICM_SHIFT) /* Capture disable mode */
+# define IC_CON_ICM_EDGE (1 << IC_CON_ICM_SHIFT) /* Edge detect mode */
+# define IC_CON_ICM_FALLING (2 << IC_CON_ICM_SHIFT) /* Every falling edge */
+# define IC_CON_ICM_RISING (3 << IC_CON_ICM_SHIFT) /* Every rising edge */
+# define IC_CON_ICM_4th (4 << IC_CON_ICM_SHIFT) /* Every fourth rising edge */
+# define IC_CON_ICM_16th (5 << IC_CON_ICM_SHIFT) /* Every sixteenth rising edge */
+# define IC_CON_ICM_TRIGGER (6 << IC_CON_ICM_SHIFT) /* Specified edge first and every edge thereafter */
+# define IC_CON_ICM_INTERRUPT (7 << IC_CON_ICM_SHIFT) /* Interrupt-only mode */
+#define IC_CON_ICBNE (1 << 3) /* Bit 3: Input Capture Buffer Not Empty Status */
+#define IC_CON_ICOV (1 << 4) /* Bit 4: Input Capture */
+#define IC_CON_ICI_SHIFT (5) /* Bits 5-6: Interrupt Control */
+#define IC_CON_ICI_MASK (3 << IC_CON_ICI_SHIFT)
+# define IC_CON_ICI_EVERY (0 << IC_CON_ICI_SHIFT) /* Interrupt every capture event */
+# define IC_CON_ICI_2ND (1 << IC_CON_ICI_SHIFT) /* Interrupt every 2nd capture event */
+# define IC_CON_ICI_3RD (2 << IC_CON_ICI_SHIFT) /* Interrupt every 3rd capture event */
+# define IC_CON_ICI_4TH (3 << IC_CON_ICI_SHIFT) /* Interrupt every 4th capture event */
+#define IC_CON_ICTMR (1 << 7) /* Bit 7: Timer Select */
+#define IC_CON_C32 (1 << 8) /* Bit 8: 32-bit Capture Select */
+#define IC_CON_FEDGE (1 << 9) /* Bit 9: First Capture Edge Select */
+#define IC_CON_SIDL (1 << 13) /* Bit 13: Stop in Idle Control */
+#define IC_CON_FRZ (1 << 14) /* Bit 14: Freeze in Debug Mode Control */
+#define IC_CON_ON (1 << 15) /* Bit 15: Input Capture Module Enable */
+
+/* Input Capture X Buffer Register -- 32-bit capture 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 /* CHIP_NIC > 0 */
+#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_IC_H */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-oc.h b/nuttx/arch/mips/src/pic32mx/pic32mx-oc.h
index 488970533..dc3486295 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-oc.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-oc.h
@@ -1,211 +1,211 @@
-/************************************************************************************
- * arch/mips/src/pic32mx/pic32mx-oc.h
- *
- * Copyright (C) 2011 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.
- *
- ************************************************************************************/
-
-#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H
-#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "pic32mx-memorymap.h"
-
-#if CHIP_NOC > 0
-
-/************************************************************************************
- * Pre-Processor Definitions
- ************************************************************************************/
-/* Register Offsets *****************************************************************/
-
-#define PIC32MX_OC_CON_OFFSET 0x0000 /* Output compare control register */
-#define PIC32MX_OC_CONCLR_OFFSET 0x0004 /* Output compare control clear register */
-#define PIC32MX_OC_CONSET_OFFSET 0x0008 /* Output compare control set register */
-#define PIC32MX_OC_CONINV_OFFSET 0x000c /* Output compare control invert register */
-#define PIC32MX_OC_R_OFFSET 0x0010 /* Output compare data register */
-#define PIC32MX_OC_RCLR_OFFSET 0x0014 /* Output compare data clear register */
-#define PIC32MX_OC_RSET_OFFSET 0x0018 /* Output compare data set register */
-#define PIC32MX_OC_RINV_OFFSET 0x001c /* Output compare data invert register */
-#define PIC32MX_OC_RS_OFFSET 0x0020 /* Output compare secondary data register */
-#define PIC32MX_OC_RSCLR_OFFSET 0x0024 /* Output compare secondary data clear register */
-#define PIC32MX_OC_RSSET_OFFSET 0x0028 /* Output compare secondary data set register */
-#define PIC32MX_OC_RSINV_OFFSET 0x002c /* Output compare secondary data invert register */
-
-/* See also TIMER2 and TIMER3 registers */
-
-/* Register Addresses ***************************************************************/
-
-#define PIC32MX_OC_CON(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CON_OFFSET)
-#define PIC32MX_OC_CONCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONCLR_OFFSET)
-#define PIC32MX_OC_CONSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONSET_OFFSET)
-#define PIC32MX_OC_CONINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONINV_OFFSET)
-#define PIC32MX_OC_R(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_R_OFFSET)
-#define PIC32MX_OC_RCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RCLR_OFFSET)
-#define PIC32MX_OC_RSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSET_OFFSET)
-#define PIC32MX_OC_RINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RINV_OFFSET)
-#define PIC32MX_OC_RS(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RS_OFFSET)
-#define PIC32MX_OC_RSCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSCLR_OFFSET)
-#define PIC32MX_OC_RSSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSSET_OFFSET)
-#define PIC32MX_OC_RSINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSINV_OFFSET)
-
-#define PIC32MX_OC1_CON (PIC32MX_OC1_K1BASE+PIC32MX_OC_CON_OFFSET)
-#define PIC32MX_OC1_CONCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
-#define PIC32MX_OC1_CONSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONSET_OFFSET)
-#define PIC32MX_OC1_CONINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONINV_OFFSET)
-#define PIC32MX_OC1_R (PIC32MX_OC1_K1BASE+PIC32MX_OC_R_OFFSET)
-#define PIC32MX_OC1_RCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_RCLR_OFFSET)
-#define PIC32MX_OC1_RSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSET_OFFSET)
-#define PIC32MX_OC1_RINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_RINV_OFFSET)
-#define PIC32MX_OC1_RS (PIC32MX_OC1_K1BASE+PIC32MX_OC_RS_OFFSET)
-#define PIC32MX_OC1_RSCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
-#define PIC32MX_OC1_RSSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSSET_OFFSET)
-#define PIC32MX_OC1_RSINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSINV_OFFSET)
-
-#if CHIP_NOC > 1
-# define PIC32MX_OC2_CON (PIC32MX_OC2_K1BASE+PIC32MX_OC_CON_OFFSET)
-# define PIC32MX_OC2_CONCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
-# define PIC32MX_OC2_CONSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONSET_OFFSET)
-# define PIC32MX_OC2_CONINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONINV_OFFSET)
-# define PIC32MX_OC2_R (PIC32MX_OC2_K1BASE+PIC32MX_OC_R_OFFSET)
-# define PIC32MX_OC2_RCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_RCLR_OFFSET)
-# define PIC32MX_OC2_RSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSET_OFFSET)
-# define PIC32MX_OC2_RINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_RINV_OFFSET)
-# define PIC32MX_OC2_RS (PIC32MX_OC2_K1BASE+PIC32MX_OC_RS_OFFSET)
-# define PIC32MX_OC2_RSCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
-# define PIC32MX_OC2_RSSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSSET_OFFSET)
-# define PIC32MX_OC2_RSINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSINV_OFFSET)
-#endif
-
-#if CHIP_NOC > 2
-# define PIC32MX_OC3_CON (PIC32MX_OC3_K1BASE+PIC32MX_OC_CON_OFFSET)
-# define PIC32MX_OC3_CONCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
-# define PIC32MX_OC3_CONSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONSET_OFFSET)
-# define PIC32MX_OC3_CONINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONINV_OFFSET)
-# define PIC32MX_OC3_R (PIC32MX_OC3_K1BASE+PIC32MX_OC_R_OFFSET)
-# define PIC32MX_OC3_RCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_RCLR_OFFSET)
-# define PIC32MX_OC3_RSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSET_OFFSET)
-# define PIC32MX_OC3_RINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_RINV_OFFSET)
-# define PIC32MX_OC3_RS (PIC32MX_OC3_K1BASE+PIC32MX_OC_RS_OFFSET)
-# define PIC32MX_OC3_RSCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
-# define PIC32MX_OC3_RSSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSSET_OFFSET)
-# define PIC32MX_OC3_RSINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSINV_OFFSET)
-#endif
-
-#if CHIP_NOC > 3
-# define PIC32MX_OC4_CON (PIC32MX_OC4_K1BASE+PIC32MX_OC_CON_OFFSET)
-# define PIC32MX_OC4_CONCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
-# define PIC32MX_OC4_CONSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONSET_OFFSET)
-# define PIC32MX_OC4_CONINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONINV_OFFSET)
-# define PIC32MX_OC4_R (PIC32MX_OC4_K1BASE+PIC32MX_OC_R_OFFSET)
-# define PIC32MX_OC4_RCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_RCLR_OFFSET)
-# define PIC32MX_OC4_RSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSET_OFFSET)
-# define PIC32MX_OC4_RINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_RINV_OFFSET)
-# define PIC32MX_OC4_RS (PIC32MX_OC4_K1BASE+PIC32MX_OC_RS_OFFSET)
-# define PIC32MX_OC4_RSCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
-# define PIC32MX_OC4_RSSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSSET_OFFSET)
-# define PIC32MX_OC4_RSINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSINV_OFFSET)
-#endif
-
-#if CHIP_NOC > 4
-# define PIC32MX_OC5_CON (PIC32MX_OC5_K1BASE+PIC32MX_OC_CON_OFFSET)
-# define PIC32MX_OC5_CONCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
-# define PIC32MX_OC5_CONSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONSET_OFFSET)
-# define PIC32MX_OC5_CONINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONINV_OFFSET)
-# define PIC32MX_OC5_R (PIC32MX_OC5_K1BASE+PIC32MX_OC_R_OFFSET)
-# define PIC32MX_OC5_RCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_RCLR_OFFSET)
-# define PIC32MX_OC5_RSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSET_OFFSET)
-# define PIC32MX_OC5_RINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_RINV_OFFSET)
-# define PIC32MX_OC5_RS (PIC32MX_OC5_K1BASE+PIC32MX_OC_RS_OFFSET)
-# define PIC32MX_OC5_RSCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
-# define PIC32MX_OC5_RSSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSSET_OFFSET)
-# define PIC32MX_OC5_RSINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSINV_OFFSET)
-#endif
-
-/* Register Bit-Field Definitions ***************************************************/
-
-/* Output compare control register */
-
-#define OC_CON_OCM_SHIFT (0) /* Bits 0-2: Output compare mode select */
-#define OC_CON_OCM_MASK (7 << OC_CON_OCM_SHIFT)
-# define OC_CON_OCM_DISABLE (0 << OC_CON_OCM_SHIFT) /* Output compare peripheral disabled */
-# define OC_CON_OCM_LOW2HI (1 << OC_CON_OCM_SHIFT) /* OCx low; compare forces high */
-# define OC_CON_OCM_HITOLOW (2 << OC_CON_OCM_SHIFT) /* OCx high; compare forces low */
-# define OC_CON_OCM_TOGGLE (3 << OC_CON_OCM_SHIFT) /* Compare event toggles OCx */
-# define OC_CON_OCM_LOWPULSE (4 << OC_CON_OCM_SHIFT) /* OCx low; output pulse on OCx*/
-# define OC_CON_OCM_HIPULSE (5 << OC_CON_OCM_SHIFT) /* OCx high; output pulse on OCx */
-# define OC_CON_OCM_PWM (6 << OC_CON_OCM_SHIFT) /* PWM mode on OCx; fault disabled */
-# define OC_CON_OCM_PWMFAULT (7 << OC_CON_OCM_SHIFT) /* PWM mode on OCx; fault enabled */
-#define OC_CON_OCTSEL (1 << 3) /* Bit 3: Output compare timer select */
-#define OC_CON_OCFLT (1 << 4) /* Bit 4: PWM fault condition status */
-#define OC_CON_OC32 (1 << 5) /* Bit 5: 32-bit compare more */
-#define OC_CON_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
-#define OC_CON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode */
-#define OC_CON_ON (1 << 15) /* Bit 15: Output compare periperal on */
-
-/* Output compare data register -- 32-bit data register */
-
-/* Output compare secondary data register -- 32-bit data register */
-
-/************************************************************************************
- * 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 /* CHIP_NOC > 0 */
-#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H */
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-oc.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "pic32mx-memorymap.h"
+
+#if CHIP_NOC > 0
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_OC_CON_OFFSET 0x0000 /* Output compare control register */
+#define PIC32MX_OC_CONCLR_OFFSET 0x0004 /* Output compare control clear register */
+#define PIC32MX_OC_CONSET_OFFSET 0x0008 /* Output compare control set register */
+#define PIC32MX_OC_CONINV_OFFSET 0x000c /* Output compare control invert register */
+#define PIC32MX_OC_R_OFFSET 0x0010 /* Output compare data register */
+#define PIC32MX_OC_RCLR_OFFSET 0x0014 /* Output compare data clear register */
+#define PIC32MX_OC_RSET_OFFSET 0x0018 /* Output compare data set register */
+#define PIC32MX_OC_RINV_OFFSET 0x001c /* Output compare data invert register */
+#define PIC32MX_OC_RS_OFFSET 0x0020 /* Output compare secondary data register */
+#define PIC32MX_OC_RSCLR_OFFSET 0x0024 /* Output compare secondary data clear register */
+#define PIC32MX_OC_RSSET_OFFSET 0x0028 /* Output compare secondary data set register */
+#define PIC32MX_OC_RSINV_OFFSET 0x002c /* Output compare secondary data invert register */
+
+/* See also TIMER2 and TIMER3 registers */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_OC_CON(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CON_OFFSET)
+#define PIC32MX_OC_CONCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONCLR_OFFSET)
+#define PIC32MX_OC_CONSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONSET_OFFSET)
+#define PIC32MX_OC_CONINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_CONINV_OFFSET)
+#define PIC32MX_OC_R(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_R_OFFSET)
+#define PIC32MX_OC_RCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RCLR_OFFSET)
+#define PIC32MX_OC_RSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSET_OFFSET)
+#define PIC32MX_OC_RINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RINV_OFFSET)
+#define PIC32MX_OC_RS(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RS_OFFSET)
+#define PIC32MX_OC_RSCLR(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSCLR_OFFSET)
+#define PIC32MX_OC_RSSET(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSSET_OFFSET)
+#define PIC32MX_OC_RSINV(n) (PIC32MX_OC_K1BASE(n)+PIC32MX_OC_RSINV_OFFSET)
+
+#define PIC32MX_OC1_CON (PIC32MX_OC1_K1BASE+PIC32MX_OC_CON_OFFSET)
+#define PIC32MX_OC1_CONCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
+#define PIC32MX_OC1_CONSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONSET_OFFSET)
+#define PIC32MX_OC1_CONINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_CONINV_OFFSET)
+#define PIC32MX_OC1_R (PIC32MX_OC1_K1BASE+PIC32MX_OC_R_OFFSET)
+#define PIC32MX_OC1_RCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_RCLR_OFFSET)
+#define PIC32MX_OC1_RSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSET_OFFSET)
+#define PIC32MX_OC1_RINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_RINV_OFFSET)
+#define PIC32MX_OC1_RS (PIC32MX_OC1_K1BASE+PIC32MX_OC_RS_OFFSET)
+#define PIC32MX_OC1_RSCLR (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
+#define PIC32MX_OC1_RSSET (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSSET_OFFSET)
+#define PIC32MX_OC1_RSINV (PIC32MX_OC1_K1BASE+PIC32MX_OC_RSINV_OFFSET)
+
+#if CHIP_NOC > 1
+# define PIC32MX_OC2_CON (PIC32MX_OC2_K1BASE+PIC32MX_OC_CON_OFFSET)
+# define PIC32MX_OC2_CONCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
+# define PIC32MX_OC2_CONSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONSET_OFFSET)
+# define PIC32MX_OC2_CONINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_CONINV_OFFSET)
+# define PIC32MX_OC2_R (PIC32MX_OC2_K1BASE+PIC32MX_OC_R_OFFSET)
+# define PIC32MX_OC2_RCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_RCLR_OFFSET)
+# define PIC32MX_OC2_RSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSET_OFFSET)
+# define PIC32MX_OC2_RINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_RINV_OFFSET)
+# define PIC32MX_OC2_RS (PIC32MX_OC2_K1BASE+PIC32MX_OC_RS_OFFSET)
+# define PIC32MX_OC2_RSCLR (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
+# define PIC32MX_OC2_RSSET (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSSET_OFFSET)
+# define PIC32MX_OC2_RSINV (PIC32MX_OC2_K1BASE+PIC32MX_OC_RSINV_OFFSET)
+#endif
+
+#if CHIP_NOC > 2
+# define PIC32MX_OC3_CON (PIC32MX_OC3_K1BASE+PIC32MX_OC_CON_OFFSET)
+# define PIC32MX_OC3_CONCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
+# define PIC32MX_OC3_CONSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONSET_OFFSET)
+# define PIC32MX_OC3_CONINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_CONINV_OFFSET)
+# define PIC32MX_OC3_R (PIC32MX_OC3_K1BASE+PIC32MX_OC_R_OFFSET)
+# define PIC32MX_OC3_RCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_RCLR_OFFSET)
+# define PIC32MX_OC3_RSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSET_OFFSET)
+# define PIC32MX_OC3_RINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_RINV_OFFSET)
+# define PIC32MX_OC3_RS (PIC32MX_OC3_K1BASE+PIC32MX_OC_RS_OFFSET)
+# define PIC32MX_OC3_RSCLR (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
+# define PIC32MX_OC3_RSSET (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSSET_OFFSET)
+# define PIC32MX_OC3_RSINV (PIC32MX_OC3_K1BASE+PIC32MX_OC_RSINV_OFFSET)
+#endif
+
+#if CHIP_NOC > 3
+# define PIC32MX_OC4_CON (PIC32MX_OC4_K1BASE+PIC32MX_OC_CON_OFFSET)
+# define PIC32MX_OC4_CONCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
+# define PIC32MX_OC4_CONSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONSET_OFFSET)
+# define PIC32MX_OC4_CONINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_CONINV_OFFSET)
+# define PIC32MX_OC4_R (PIC32MX_OC4_K1BASE+PIC32MX_OC_R_OFFSET)
+# define PIC32MX_OC4_RCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_RCLR_OFFSET)
+# define PIC32MX_OC4_RSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSET_OFFSET)
+# define PIC32MX_OC4_RINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_RINV_OFFSET)
+# define PIC32MX_OC4_RS (PIC32MX_OC4_K1BASE+PIC32MX_OC_RS_OFFSET)
+# define PIC32MX_OC4_RSCLR (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
+# define PIC32MX_OC4_RSSET (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSSET_OFFSET)
+# define PIC32MX_OC4_RSINV (PIC32MX_OC4_K1BASE+PIC32MX_OC_RSINV_OFFSET)
+#endif
+
+#if CHIP_NOC > 4
+# define PIC32MX_OC5_CON (PIC32MX_OC5_K1BASE+PIC32MX_OC_CON_OFFSET)
+# define PIC32MX_OC5_CONCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONCLR_OFFSET)
+# define PIC32MX_OC5_CONSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONSET_OFFSET)
+# define PIC32MX_OC5_CONINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_CONINV_OFFSET)
+# define PIC32MX_OC5_R (PIC32MX_OC5_K1BASE+PIC32MX_OC_R_OFFSET)
+# define PIC32MX_OC5_RCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_RCLR_OFFSET)
+# define PIC32MX_OC5_RSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSET_OFFSET)
+# define PIC32MX_OC5_RINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_RINV_OFFSET)
+# define PIC32MX_OC5_RS (PIC32MX_OC5_K1BASE+PIC32MX_OC_RS_OFFSET)
+# define PIC32MX_OC5_RSCLR (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSCLR_OFFSET)
+# define PIC32MX_OC5_RSSET (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSSET_OFFSET)
+# define PIC32MX_OC5_RSINV (PIC32MX_OC5_K1BASE+PIC32MX_OC_RSINV_OFFSET)
+#endif
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* Output compare control register */
+
+#define OC_CON_OCM_SHIFT (0) /* Bits 0-2: Output compare mode select */
+#define OC_CON_OCM_MASK (7 << OC_CON_OCM_SHIFT)
+# define OC_CON_OCM_DISABLE (0 << OC_CON_OCM_SHIFT) /* Output compare peripheral disabled */
+# define OC_CON_OCM_LOW2HI (1 << OC_CON_OCM_SHIFT) /* OCx low; compare forces high */
+# define OC_CON_OCM_HITOLOW (2 << OC_CON_OCM_SHIFT) /* OCx high; compare forces low */
+# define OC_CON_OCM_TOGGLE (3 << OC_CON_OCM_SHIFT) /* Compare event toggles OCx */
+# define OC_CON_OCM_LOWPULSE (4 << OC_CON_OCM_SHIFT) /* OCx low; output pulse on OCx*/
+# define OC_CON_OCM_HIPULSE (5 << OC_CON_OCM_SHIFT) /* OCx high; output pulse on OCx */
+# define OC_CON_OCM_PWM (6 << OC_CON_OCM_SHIFT) /* PWM mode on OCx; fault disabled */
+# define OC_CON_OCM_PWMFAULT (7 << OC_CON_OCM_SHIFT) /* PWM mode on OCx; fault enabled */
+#define OC_CON_OCTSEL (1 << 3) /* Bit 3: Output compare timer select */
+#define OC_CON_OCFLT (1 << 4) /* Bit 4: PWM fault condition status */
+#define OC_CON_OC32 (1 << 5) /* Bit 5: 32-bit compare more */
+#define OC_CON_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
+#define OC_CON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode */
+#define OC_CON_ON (1 << 15) /* Bit 15: Output compare periperal on */
+
+/* Output compare data register -- 32-bit data register */
+
+/* Output compare secondary data register -- 32-bit data register */
+
+/************************************************************************************
+ * 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 /* CHIP_NOC > 0 */
+#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_OC_H */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-timer.h b/nuttx/arch/mips/src/pic32mx/pic32mx-timer.h
index 6f359b5b6..ecaa05457 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-timer.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-timer.h
@@ -1,222 +1,222 @@
-/************************************************************************************
- * arch/mips/src/pic32mx/pic32mx-timer.h
- *
- * Copyright (C) 2011 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.
- *
- ************************************************************************************/
-
-#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H
-#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include "chip.h"
-#include "pic32mx-memorymap.h"
-
-#if CHIP_NTIMERS > 0
-
-/************************************************************************************
- * Pre-Processor Definitions
- ************************************************************************************/
-/* Register Offsets *****************************************************************/
-
-#define PIC32MX_TIMER_CON_OFFSET 0x0000 /* Timer control register */
-#define PIC32MX_TIMER_CONCLR_OFFSET 0x0004 /* Timer control clear register */
-#define PIC32MX_TIMER_CONSET_OFFSET 0x0008 /* Timer control set register */
-#define PIC32MX_TIMER_CONINV_OFFSET 0x000c /* Timer control invert register */
-#define PIC32MX_TIMER_CNT_OFFSET 0x0010 /* Timer count register */
-#define PIC32MX_TIMER_CNTCLR_OFFSET 0x0014 /* Timer count clear register */
-#define PIC32MX_TIMER_CNTSET_OFFSET 0x0018 /* Timer count set register */
-#define PIC32MX_TIMER_CNTINV_OFFSET 0x001c /* Timer count invert register */
-#define PIC32MX_TIMER_PR_OFFSET 0x0020 /* Timer period register */
-#define PIC32MX_TIMER_PRCLR_OFFSET 0x0024 /* Timer period clear register */
-#define PIC32MX_TIMER_PRSET_OFFSET 0x0028 /* Timer period set register */
-#define PIC32MX_TIMER_PRINV_OFFSET 0x002c /* Timer period invert register */
-
-/* Register Addresses ***************************************************************/
-
-#define PIC32MX_TIMER_CON(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CON_OFFSET)
-#define PIC32MX_TIMER_CONCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONCLR_OFFSET)
-#define PIC32MX_TIMER_CONSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONSET_OFFSET)
-#define PIC32MX_TIMER_CONINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONINV_OFFSET)
-#define PIC32MX_TIMER_CNT(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNT_OFFSET)
-#define PIC32MX_TIMER_CNTCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTCLR_OFFSET)
-#define PIC32MX_TIMER_CNTSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTSET_OFFSET)
-#define PIC32MX_TIMER_CNTINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTINV_OFFSET)
-#define PIC32MX_TIMER_PR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PR_OFFSET)
-#define PIC32MX_TIMER_PRCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRCLR_OFFSET)
-#define PIC32MX_TIMER_PRSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRSET_OFFSET)
-#define PIC32MX_TIMER_PRINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRINV_OFFSET)
-
-#define PIC32MX_TIMER1_CON (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CON_OFFSET)
-#define PIC32MX_TIMER1_CONCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
-#define PIC32MX_TIMER1_CONSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
-#define PIC32MX_TIMER1_CONINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
-#define PIC32MX_TIMER1_CNT (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
-#define PIC32MX_TIMER1_CNTCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
-#define PIC32MX_TIMER1_CNTSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
-#define PIC32MX_TIMER1_CNTINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
-#define PIC32MX_TIMER1_PR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PR_OFFSET)
-#define PIC32MX_TIMER1_PRCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
-#define PIC32MX_TIMER1_PRSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
-#define PIC32MX_TIMER1_PRINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
-
-#if CHIP_NTIMERS > 1
-# define PIC32MX_TIMER2_CON (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CON_OFFSET)
-# define PIC32MX_TIMER2_CONCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
-# define PIC32MX_TIMER2_CONSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
-# define PIC32MX_TIMER2_CONINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
-# define PIC32MX_TIMER2_CNT (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
-# define PIC32MX_TIMER2_CNTCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
-# define PIC32MX_TIMER2_CNTSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
-# define PIC32MX_TIMER2_CNTINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
-# define PIC32MX_TIMER2_PR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PR_OFFSET)
-# define PIC32MX_TIMER2_PRCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
-# define PIC32MX_TIMER2_PRSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
-# define PIC32MX_TIMER2_PRINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
-#endif
-
-#if CHIP_NTIMERS > 2
-# define PIC32MX_TIMER3_CON (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CON_OFFSET)
-# define PIC32MX_TIMER3_CONCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
-# define PIC32MX_TIMER3_CONSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
-# define PIC32MX_TIMER3_CONINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
-# define PIC32MX_TIMER3_CNT (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
-# define PIC32MX_TIMER3_CNTCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
-# define PIC32MX_TIMER3_CNTSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
-# define PIC32MX_TIMER3_CNTINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
-# define PIC32MX_TIMER3_PR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PR_OFFSET)
-# define PIC32MX_TIMER3_PRCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
-# define PIC32MX_TIMER3_PRSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
-# define PIC32MX_TIMER3_PRINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
-#endif
-
-#if CHIP_NTIMERS > 3
-# define PIC32MX_TIMER4_CON (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CON_OFFSET)
-# define PIC32MX_TIMER4_CONCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
-# define PIC32MX_TIMER4_CONSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
-# define PIC32MX_TIMER4_CONINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
-# define PIC32MX_TIMER4_CNT (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
-# define PIC32MX_TIMER4_CNTCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
-# define PIC32MX_TIMER4_CNTSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
-# define PIC32MX_TIMER4_CNTINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
-# define PIC32MX_TIMER4_PR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PR_OFFSET)
-# define PIC32MX_TIMER4_PRCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
-# define PIC32MX_TIMER4_PRSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
-# define PIC32MX_TIMER4_PRINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
-#endif
-
-#if CHIP_NTIMERS > 4
-# define PIC32MX_TIMER5_CON (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CON_OFFSET)
-# define PIC32MX_TIMER5_CONCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
-# define PIC32MX_TIMER5_CONSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
-# define PIC32MX_TIMER5_CONINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
-# define PIC32MX_TIMER5_CNT (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
-# define PIC32MX_TIMER5_CNTCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
-# define PIC32MX_TIMER5_CNTSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
-# define PIC32MX_TIMER5_CNTINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
-# define PIC32MX_TIMER5_PR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PR_OFFSET)
-# define PIC32MX_TIMER5_PRCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
-# define PIC32MX_TIMER5_PRSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
-# define PIC32MX_TIMER5_PRINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
-#endif
-
-/* Register Bit-Field Definitions ***************************************************/
-
-/* Timer control register */
-
-#define TIMER_CON_TCS (1 << 1) /* Bit 1: Timer clock source select (all) */
-#define TIMER1_CON_TSYNC (1 << 2) /* Bit 2: Timer external clock input synchronization selection (timer 1 only) */
-#define TIMER_CON_T32 (1 << 3) /* Bit 2: 32-bit timer mode select (even timers only) */
-#define TIMER_CON_TCKPS_SHIFT (4) /* Bits 4-6: Timer input clock prescale select (all except timer 1) */
-#define TIMER_CON_TCKPS_MASK (7 << TIMER_CON_TCKPS_SHIFT)
-# define TIMER_CON_TCKPS_1 (0 << TIMER_CON_TCKPS_SHIFT) /* 1:1 prescale value */
-# define TIMER_CON_TCKPS_2 (1 << TIMER_CON_TCKPS_SHIFT) /* 1:2 prescale value */
-# define TIMER_CON_TCKPS_4 (2 << TIMER_CON_TCKPS_SHIFT) /* 1:4 prescale value */
-# define TIMER_CON_TCKPS_8 (3 << TIMER_CON_TCKPS_SHIFT) /* 1:8 prescale value */
-# define TIMER_CON_TCKPS_16 (4 << TIMER_CON_TCKPS_SHIFT) /* 1:16 prescale value */
-# define TIMER_CON_TCKPS_32 (5 << TIMER_CON_TCKPS_SHIFT) /* 1:32 prescale value */
-# define TIMER_CON_TCKPS_64 (6 << TIMER_CON_TCKPS_SHIFT) /* 1:64 prescale value */
-# define TIMER_CON_TCKPS_256 (7 << TIMER_CON_TCKPS_SHIFT) /* 1:256 prescale value */
-#define TIMER1_CON_TCKPS_SHIFT (4) /* Bits 4-5: Timer input clock prescale select (timer 1 only) */
-#define TIMER1_CON_TCKPS_MASK (3 << TIMER1_CON_TCKPS_SHIFT)
-# define TIMER1_CON_TCKPS_1 (0 << TIMER1_CON_TCKPS_SHIFT) /* 1:1 prescale value */
-# define TIMER1_CON_TCKPS_8 (1 << TIMER1_CON_TCKPS_SHIFT) /* 1:8 prescale value */
-# define TIMER1_CON_TCKPS_64 (2 << TIMER1_CON_TCKPS_SHIFT) /* 1:64 prescale value */
-# define TIMER1_CON_TCKPS_256 (3 << TIMER1_CON_TCKPS_SHIFT) /* 1:256 prescale value */
-#define TIMER_CON_TGATE (1 << 7) /* Bit 7: Timer gated time accumulation enable (all) */
-#define TIMER1_CON_TWIP (1 << 11) /* Bit 11: Asynchronous timer write in progress (timer 1 only) */
-#define TIMER1_CON_TWDIS (1 << 12) /* Bit 12: Asynchronous timer write disable (timer 1 only) */
-#define TIMER_CON_SIDL (1 << 13) /* Bit 13: Stop in idle mode (all) */
-#define TIMER_CON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode (all) */
-#define TIMER_CON_ON (1 << 15) /* Bit 15: Timer on (all) */
-
-/* Timer count register */
-
-#define TIMER_CNT_MASK 0xffff /* 16-bit timer counter value */
-
-/* Timer period register */
-
-#define TIMER_PR_MASK 0xffff /* 16-bit timer period 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 /* CHIP_NTIMERS > 0 */
-#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H */
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-timer.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "pic32mx-memorymap.h"
+
+#if CHIP_NTIMERS > 0
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_TIMER_CON_OFFSET 0x0000 /* Timer control register */
+#define PIC32MX_TIMER_CONCLR_OFFSET 0x0004 /* Timer control clear register */
+#define PIC32MX_TIMER_CONSET_OFFSET 0x0008 /* Timer control set register */
+#define PIC32MX_TIMER_CONINV_OFFSET 0x000c /* Timer control invert register */
+#define PIC32MX_TIMER_CNT_OFFSET 0x0010 /* Timer count register */
+#define PIC32MX_TIMER_CNTCLR_OFFSET 0x0014 /* Timer count clear register */
+#define PIC32MX_TIMER_CNTSET_OFFSET 0x0018 /* Timer count set register */
+#define PIC32MX_TIMER_CNTINV_OFFSET 0x001c /* Timer count invert register */
+#define PIC32MX_TIMER_PR_OFFSET 0x0020 /* Timer period register */
+#define PIC32MX_TIMER_PRCLR_OFFSET 0x0024 /* Timer period clear register */
+#define PIC32MX_TIMER_PRSET_OFFSET 0x0028 /* Timer period set register */
+#define PIC32MX_TIMER_PRINV_OFFSET 0x002c /* Timer period invert register */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_TIMER_CON(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CON_OFFSET)
+#define PIC32MX_TIMER_CONCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONCLR_OFFSET)
+#define PIC32MX_TIMER_CONSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONSET_OFFSET)
+#define PIC32MX_TIMER_CONINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CONINV_OFFSET)
+#define PIC32MX_TIMER_CNT(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNT_OFFSET)
+#define PIC32MX_TIMER_CNTCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTCLR_OFFSET)
+#define PIC32MX_TIMER_CNTSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTSET_OFFSET)
+#define PIC32MX_TIMER_CNTINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_CNTINV_OFFSET)
+#define PIC32MX_TIMER_PR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PR_OFFSET)
+#define PIC32MX_TIMER_PRCLR(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRCLR_OFFSET)
+#define PIC32MX_TIMER_PRSET(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRSET_OFFSET)
+#define PIC32MX_TIMER_PRINV(n) (PIC32MX_TIMER_K1BASE(n)+PIC32MX_TIMER_PRINV_OFFSET)
+
+#define PIC32MX_TIMER1_CON (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CON_OFFSET)
+#define PIC32MX_TIMER1_CONCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
+#define PIC32MX_TIMER1_CONSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
+#define PIC32MX_TIMER1_CONINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
+#define PIC32MX_TIMER1_CNT (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
+#define PIC32MX_TIMER1_CNTCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
+#define PIC32MX_TIMER1_CNTSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
+#define PIC32MX_TIMER1_CNTINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
+#define PIC32MX_TIMER1_PR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PR_OFFSET)
+#define PIC32MX_TIMER1_PRCLR (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
+#define PIC32MX_TIMER1_PRSET (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
+#define PIC32MX_TIMER1_PRINV (PIC32MX_TIMER1_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
+
+#if CHIP_NTIMERS > 1
+# define PIC32MX_TIMER2_CON (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CON_OFFSET)
+# define PIC32MX_TIMER2_CONCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
+# define PIC32MX_TIMER2_CONSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
+# define PIC32MX_TIMER2_CONINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
+# define PIC32MX_TIMER2_CNT (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
+# define PIC32MX_TIMER2_CNTCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
+# define PIC32MX_TIMER2_CNTSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
+# define PIC32MX_TIMER2_CNTINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
+# define PIC32MX_TIMER2_PR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PR_OFFSET)
+# define PIC32MX_TIMER2_PRCLR (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
+# define PIC32MX_TIMER2_PRSET (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
+# define PIC32MX_TIMER2_PRINV (PIC32MX_TIMER2_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
+#endif
+
+#if CHIP_NTIMERS > 2
+# define PIC32MX_TIMER3_CON (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CON_OFFSET)
+# define PIC32MX_TIMER3_CONCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
+# define PIC32MX_TIMER3_CONSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
+# define PIC32MX_TIMER3_CONINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
+# define PIC32MX_TIMER3_CNT (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
+# define PIC32MX_TIMER3_CNTCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
+# define PIC32MX_TIMER3_CNTSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
+# define PIC32MX_TIMER3_CNTINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
+# define PIC32MX_TIMER3_PR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PR_OFFSET)
+# define PIC32MX_TIMER3_PRCLR (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
+# define PIC32MX_TIMER3_PRSET (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
+# define PIC32MX_TIMER3_PRINV (PIC32MX_TIMER3_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
+#endif
+
+#if CHIP_NTIMERS > 3
+# define PIC32MX_TIMER4_CON (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CON_OFFSET)
+# define PIC32MX_TIMER4_CONCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
+# define PIC32MX_TIMER4_CONSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
+# define PIC32MX_TIMER4_CONINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
+# define PIC32MX_TIMER4_CNT (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
+# define PIC32MX_TIMER4_CNTCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
+# define PIC32MX_TIMER4_CNTSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
+# define PIC32MX_TIMER4_CNTINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
+# define PIC32MX_TIMER4_PR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PR_OFFSET)
+# define PIC32MX_TIMER4_PRCLR (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
+# define PIC32MX_TIMER4_PRSET (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
+# define PIC32MX_TIMER4_PRINV (PIC32MX_TIMER4_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
+#endif
+
+#if CHIP_NTIMERS > 4
+# define PIC32MX_TIMER5_CON (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CON_OFFSET)
+# define PIC32MX_TIMER5_CONCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONCLR_OFFSET)
+# define PIC32MX_TIMER5_CONSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONSET_OFFSET)
+# define PIC32MX_TIMER5_CONINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CONINV_OFFSET)
+# define PIC32MX_TIMER5_CNT (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNT_OFFSET)
+# define PIC32MX_TIMER5_CNTCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTCLR_OFFSET)
+# define PIC32MX_TIMER5_CNTSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTSET_OFFSET)
+# define PIC32MX_TIMER5_CNTINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_CNTINV_OFFSET)
+# define PIC32MX_TIMER5_PR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PR_OFFSET)
+# define PIC32MX_TIMER5_PRCLR (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRCLR_OFFSET)
+# define PIC32MX_TIMER5_PRSET (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRSET_OFFSET)
+# define PIC32MX_TIMER5_PRINV (PIC32MX_TIMER5_K1BASE+PIC32MX_TIMER_PRINV_OFFSET)
+#endif
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* Timer control register */
+
+#define TIMER_CON_TCS (1 << 1) /* Bit 1: Timer clock source select (all) */
+#define TIMER1_CON_TSYNC (1 << 2) /* Bit 2: Timer external clock input synchronization selection (timer 1 only) */
+#define TIMER_CON_T32 (1 << 3) /* Bit 2: 32-bit timer mode select (even timers only) */
+#define TIMER_CON_TCKPS_SHIFT (4) /* Bits 4-6: Timer input clock prescale select (all except timer 1) */
+#define TIMER_CON_TCKPS_MASK (7 << TIMER_CON_TCKPS_SHIFT)
+# define TIMER_CON_TCKPS_1 (0 << TIMER_CON_TCKPS_SHIFT) /* 1:1 prescale value */
+# define TIMER_CON_TCKPS_2 (1 << TIMER_CON_TCKPS_SHIFT) /* 1:2 prescale value */
+# define TIMER_CON_TCKPS_4 (2 << TIMER_CON_TCKPS_SHIFT) /* 1:4 prescale value */
+# define TIMER_CON_TCKPS_8 (3 << TIMER_CON_TCKPS_SHIFT) /* 1:8 prescale value */
+# define TIMER_CON_TCKPS_16 (4 << TIMER_CON_TCKPS_SHIFT) /* 1:16 prescale value */
+# define TIMER_CON_TCKPS_32 (5 << TIMER_CON_TCKPS_SHIFT) /* 1:32 prescale value */
+# define TIMER_CON_TCKPS_64 (6 << TIMER_CON_TCKPS_SHIFT) /* 1:64 prescale value */
+# define TIMER_CON_TCKPS_256 (7 << TIMER_CON_TCKPS_SHIFT) /* 1:256 prescale value */
+#define TIMER1_CON_TCKPS_SHIFT (4) /* Bits 4-5: Timer input clock prescale select (timer 1 only) */
+#define TIMER1_CON_TCKPS_MASK (3 << TIMER1_CON_TCKPS_SHIFT)
+# define TIMER1_CON_TCKPS_1 (0 << TIMER1_CON_TCKPS_SHIFT) /* 1:1 prescale value */
+# define TIMER1_CON_TCKPS_8 (1 << TIMER1_CON_TCKPS_SHIFT) /* 1:8 prescale value */
+# define TIMER1_CON_TCKPS_64 (2 << TIMER1_CON_TCKPS_SHIFT) /* 1:64 prescale value */
+# define TIMER1_CON_TCKPS_256 (3 << TIMER1_CON_TCKPS_SHIFT) /* 1:256 prescale value */
+#define TIMER_CON_TGATE (1 << 7) /* Bit 7: Timer gated time accumulation enable (all) */
+#define TIMER1_CON_TWIP (1 << 11) /* Bit 11: Asynchronous timer write in progress (timer 1 only) */
+#define TIMER1_CON_TWDIS (1 << 12) /* Bit 12: Asynchronous timer write disable (timer 1 only) */
+#define TIMER_CON_SIDL (1 << 13) /* Bit 13: Stop in idle mode (all) */
+#define TIMER_CON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode (all) */
+#define TIMER_CON_ON (1 << 15) /* Bit 15: Timer on (all) */
+
+/* Timer count register */
+
+#define TIMER_CNT_MASK 0xffff /* 16-bit timer counter value */
+
+/* Timer period register */
+
+#define TIMER_PR_MASK 0xffff /* 16-bit timer period 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 /* CHIP_NTIMERS > 0 */
+#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_TIMER_H */