summaryrefslogtreecommitdiff
path: root/nuttx/arch/mips/src
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/src
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/src')
-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
13 files changed, 731 insertions, 731 deletions
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 */