summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-16 18:59:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-16 18:59:30 +0000
commitf460cb60146bd6b2458dd1ef558e5a2e5a02d2cf (patch)
tree7c7cfdee3d4fe31b41f6ea0f7153c3ab79fb1735 /nuttx
parent3119f7b909d6c8938ae92e45b1e92dc1bcba0c0b (diff)
downloadpx4-nuttx-f460cb60146bd6b2458dd1ef558e5a2e5a02d2cf.tar.gz
px4-nuttx-f460cb60146bd6b2458dd1ef558e5a2e5a02d2cf.tar.bz2
px4-nuttx-f460cb60146bd6b2458dd1ef558e5a2e5a02d2cf.zip
Completes all PIC32 header files
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3618 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog3
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-adc.h243
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-reset.h30
-rwxr-xr-xnuttx/arch/mips/src/pic32mx/pic32mx-usbotg.h309
4 files changed, 570 insertions, 15 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index dce9ecdae..998a0acfa 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1761,3 +1761,6 @@
behavior that people expect for printf.
6.4 2011-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+
+ * lib/drivers/cc1101: Add initial, functional CC1101 wireless driver
+ (contributed by Uros Platise)
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-adc.h b/nuttx/arch/mips/src/pic32mx/pic32mx-adc.h
new file mode 100755
index 000000000..e5ebc97fb
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-adc.h
@@ -0,0 +1,243 @@
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-adc.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_ADc_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_ADc_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "pic32mx-memorymap.h"
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_ADC_CON1_OFFSET 0x0000 /* ADC control register 1 */
+#define PIC32MX_ADC_CON1CLR_OFFSET 0x0004 /* ADC control clear register 1 */
+#define PIC32MX_ADC_CON1SET_OFFSET 0x0008 /* ADC control set register 1 */
+#define PIC32MX_ADC_CON1INV_OFFSET 0x000c /* ADC control invert register 1 */
+#define PIC32MX_ADC_CON2_OFFSET 0x0010 /* ADC control register 2 */
+#define PIC32MX_ADC_CON2CLR_OFFSET 0x0014 /* ADC control clear register 2 */
+#define PIC32MX_ADC_CON2SET_OFFSET 0x0018 /* ADC control set register 2 */
+#define PIC32MX_ADC_CON2INV_OFFSET 0x001c /* ADC control invert register 2 */
+#define PIC32MX_ADC_CON3_OFFSET 0x0020 /* ADC control register 3 */
+#define PIC32MX_ADC_CON3CLR_OFFSET 0x0024 /* ADC control clear register 3 */
+#define PIC32MX_ADC_CON3SET_OFFSET 0x0028 /* ADC control set register 3 */
+#define PIC32MX_ADC_CON3INV_OFFSET 0x002c /* ADC control invert register 3 */
+#define PIC32MX_ADC_CHS_OFFSET 0x0040 /* ADC input pin selection register */
+#define PIC32MX_ADC_CHSCLR_OFFSET 0x0044 /* ADC input pin selection clear register */
+#define PIC32MX_ADC_CHSSET_OFFSET 0x0048 /* ADC input pin selection set register */
+#define PIC32MX_ADC_CHSINV_OFFSET 0x004c /* ADC input pin selection invert register */
+#define PIC32MX_ADC_CSSL_OFFSET 0x0050 /* ADC sequentially scanned input register */
+#define PIC32MX_ADC_CSSLCLR_OFFSET 0x0054 /* ADC sequentially scanned input clear register */
+#define PIC32MX_ADC_CSSLSET_OFFSET 0x0058 /* ADC sequentially scanned input set register */
+#define PIC32MX_ADC_CSSLINV_OFFSET 0x005c /* ADC sequentially scanned input invert register */
+#define PIC32MX_ADC_CFG_OFFSET 0x0060 /* ADC input pin configuration register */
+#define PIC32MX_ADC_CFGCLR_OFFSET 0x0064 /* ADC input pin configuration clear register */
+#define PIC32MX_ADC_CFGSET_OFFSET 0x0068 /* ADC input pin configuration set register */
+#define PIC32MX_ADC_CFGINV_OFFSET 0x006c /* ADC input pin configuration invert register */
+
+#define PIC32MX_ADC_BUF_OFFSET(n) (0x0070 + ((n) << 4))
+#define PIC32MX_ADC_BUF0_OFFSET 0x0070 /* ADC result word 0 */
+#define PIC32MX_ADC_BUF1_OFFSET 0x0080 /* ADC result word 1 */
+#define PIC32MX_ADC_BUF2_OFFSET 0x0090 /* ADC result word 2 */
+#define PIC32MX_ADC_BUF3_OFFSET 0x00a0 /* ADC result word 3 */
+#define PIC32MX_ADC_BUF4_OFFSET 0x00b0 /* ADC result word 4 */
+#define PIC32MX_ADC_BUF5_OFFSET 0x00c0 /* ADC result word 5 */
+#define PIC32MX_ADC_BUF6_OFFSET 0x00d0 /* ADC result word 6 */
+#define PIC32MX_ADC_BUF7_OFFSET 0x00e0 /* ADC result word 7 */
+#define PIC32MX_ADC_BUF8_OFFSET 0x00f0 /* ADC result word 8 */
+#define PIC32MX_ADC_BUF9_OFFSET 0x0100 /* ADC result word 9 */
+#define PIC32MX_ADC_BUF10_OFFSET 0x0110 /* ADC result word 10 */
+#define PIC32MX_ADC_BUF11_OFFSET 0x0120 /* ADC result word 11 */
+#define PIC32MX_ADC_BUF12_OFFSET 0x0130 /* ADC result word 12 */
+#define PIC32MX_ADC_BUF13_OFFSET 0x0140 /* ADC result word 13 */
+#define PIC32MX_ADC_BUF14_OFFSET 0x0150 /* ADC result word 14 */
+#define PIC32MX_ADC_BUF15_OFFSET 0x0160 /* ADC result word 15 */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_ADC_CON1 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON1_OFFSET)
+#define PIC32MX_ADC_CON1CLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON1CLR_OFFSET)
+#define PIC32MX_ADC_CON1SET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON1SET_OFFSET)
+#define PIC32MX_ADC_CON1INV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON1INV_OFFSET)
+#define PIC32MX_ADC_CON2 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON2_OFFSET)
+#define PIC32MX_ADC_CON2CLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON2CLR_OFFSET)
+#define PIC32MX_ADC_CON2SET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON2SET_OFFSET)
+#define PIC32MX_ADC_CON2INV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON2INV_OFFSET)
+#define PIC32MX_ADC_CON3 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON3_OFFSET)
+#define PIC32MX_ADC_CON3CLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON3CLR_OFFSET)
+#define PIC32MX_ADC_CON3SET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON3SET_OFFSET)
+#define PIC32MX_ADC_CON3INV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CON3INV_OFFSET)
+#define PIC32MX_ADC_CHS (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CHS_OFFSET)
+#define PIC32MX_ADC_CHSCLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CHSCLR_OFFSET)
+#define PIC32MX_ADC_CHSSET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CHSSET_OFFSET)
+#define PIC32MX_ADC_CHSINV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CHSINV_OFFSET)
+#define PIC32MX_ADC_CSSL (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CSSL_OFFSET)
+#define PIC32MX_ADC_CSSLCLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CSSLCLR_OFFSET)
+#define PIC32MX_ADC_CSSLSET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CSSLSET_OFFSET)
+#define PIC32MX_ADC_CSSLINV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CSSLINV_OFFSET)
+#define PIC32MX_ADC_CFG (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CFG_OFFSET)
+#define PIC32MX_ADC_CFGCLR (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CFGCLR_OFFSET)
+#define PIC32MX_ADC_CFGSET (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CFGSET_OFFSET)
+#define PIC32MX_ADC_CFGINV (PIC32MX_ADC_K1BASE+PIC32MX_ADC_CFGINV_OFFSET)
+
+#define PIC32MX_ADC_BUF(n) (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF_OFFSET(n))
+#define PIC32MX_ADC_BUF0 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF0_OFFSET)
+#define PIC32MX_ADC_BUF1 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF1_OFFSET)
+#define PIC32MX_ADC_BUF2 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF2_OFFSET)
+#define PIC32MX_ADC_BUF3 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF3_OFFSET)
+#define PIC32MX_ADC_BUF4 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF4_OFFSET)
+#define PIC32MX_ADC_BUF5 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF5_OFFSET)
+#define PIC32MX_ADC_BUF6 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF6_OFFSET)
+#define PIC32MX_ADC_BUF7 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF7_OFFSET)
+#define PIC32MX_ADC_BUF8 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF8_OFFSET)
+#define PIC32MX_ADC_BUF9 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF9_OFFSET)
+#define PIC32MX_ADC_BUF10 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF10_OFFSET)
+#define PIC32MX_ADC_BUF11 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF11_OFFSET)
+#define PIC32MX_ADC_BUF12 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF12_OFFSET)
+#define PIC32MX_ADC_BUF13 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF13_OFFSET)
+#define PIC32MX_ADC_BUF14 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF14_OFFSET)
+#define PIC32MX_ADC_BUF15 (PIC32MX_ADC_K1BASE+PIC32MX_ADC_BUF15_OFFSET)
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* ADC control register 1 */
+
+#define ADC_CON1_DONE (1 << 0) /* Bit 0: A/D conversion status */
+#define ADC_CON1_SAMP (1 << 1) /* Bit 1: ADC sample enable */
+#define ADC_CON1_ASAM (1 << 2) /* Bit 2: ADC sample auto start */
+#define ADC_CON1_CLRASAM (1 << 4) /* Bit 4: Stop conversion sequence */
+#define ADC_CON1_SSRC_SHIFT (5) /* Bits 5-7: Conversion trigger source select */
+#define ADC_CON1_SSRC_MASK (7 << ADC_CON1_SSRC_SHIFT)
+# define ADC_CON1_SSRC_SAMP (0 << ADC_CON1_SSRC_SHIFT) /* Clearing SAMP starts */
+# define ADC_CON1_SSRC_INT0 (1 << ADC_CON1_SSRC_SHIFT) /* INT0 transition starts */
+# define ADC_CON1_SSRC_TIMER3 (2 << ADC_CON1_SSRC_SHIFT) /* Timer3 match starts */
+# define ADC_CON1_SSRC_COUNT (7 << ADC_CON1_SSRC_SHIFT) /* Internal counter starts */
+#define ADC_CON1_FORM_SHIFT (8) /* Bits 8-10: Data output format */
+#define ADC_CON1_FORM_MASK (7 << ADC_CON1_FORM_SHIFT)
+# define ADC_CON1_FORM_UINT16 (0 << ADC_CON1_FORM_SHIFT) /* Integer 16-bit */
+# define ADC_CON1_FORM_SINT16 (1 << ADC_CON1_FORM_SHIFT) /* Signed integer 16-bit */
+# define ADC_CON1_FORM_FRAC16 (2 << ADC_CON1_FORM_SHIFT) /* Fractional 16-bit */
+# define ADC_CON1_FORM_SFRAC16 (3 << ADC_CON1_FORM_SHIFT) /* Signed fractional 16-bit */
+# define ADC_CON1_FORM_UINT32 (4 << ADC_CON1_FORM_SHIFT) /* Integer 32-bit */
+# define ADC_CON1_FORM_SINT32 (5 << ADC_CON1_FORM_SHIFT) /* Signed integer 32-bit */
+# define ADC_CON1_FORM_FRAC32 (6 << ADC_CON1_FORM_SHIFT) /* Fractional 32-bit */
+# define ADC_CON1_FORM_SFRAC32 (7 << ADC_CON1_FORM_SHIFT) /* Signed fractional 32-bit */
+#define ADC_CON1_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
+#define ADC_CON1_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode */
+#define ADC_CON1_ON (1 << 15) /* Bit 14: ADC operating mode */
+
+/* ADC control register 2 */
+
+#define ADC_CON2_ALTS (1 << 0) /* Bit 0: Alternate input sample mode select */
+#define ADC_CON2_BUFM (1 << 1) /* Bit 1: ADC result buffer mode select */
+#define ADC_CON2_SMPI_SHIFT (2) /* Bits 2-5: Sample/sequences per interrupt */
+#define ADC_CON2_SMPI_MASK (15 << ADC_CON2_SMPI_SHIFT)
+# define ADC_CON2_SMPI(n) ((n-1) << ADC_CON2_SMPI_SHIFT) /* Interrupt after nth conversion */
+#define ADC_CON2_BUFS (1 << 7) /* Bit 7: Buffer fill status */
+#define ADC_CON2_CSCNA (1 << 10) /* Bit 10: Scan input selections */
+#define ADC_CON2_OFFCAL (1 << 12) /* Bit 12: Input offset calibration mode select */
+#define ADC_CON2_VCFG_SHIFT (13) /* Bits 13-15: Voltage reference configuation */
+#define ADC_CON2_VCFG_MASK (15 << ADC_CON2_VCFG_SHIFT)
+# define ADC_CON2_VCFG_AVDDAVSS (0 << ADC_CON2_VCFG_SHIFT) /* VR+=AVdd VR-=AVss */
+# define ADC_CON2_VCFG_VREFAVSS (1 << ADC_CON2_VCFG_SHIFT) /* VR+=VREF+ VR-=AVss */
+# define ADC_CON2_VCFG_AVDDVREF (2 << ADC_CON2_VCFG_SHIFT) /* VR+=AVdd VR-=VREF- */
+# define ADC_CON2_VCFG_VREFVREF (3 << ADC_CON2_VCFG_SHIFT) /* VR+=VREF+ VR-=VREF- */
+
+/* ADC control register 3 */
+
+#define ADC_CON3_ADCS_SHIFT (0) /* Bits 0-7: ADC conversion clock select */
+#define ADC_CON3_ADCS_MASK (0xff << ADC_CON3_ADCS_SHIFT)
+# define ADC_CON3_ADCS(n) ((((n)>>1)-1) << ADC_CON3_ADCS_SHIFT) /* n*Tpb = Tad, n=2,4,..,512 */
+#define ADC_CON3_SAMC_SHIFT (8) /* Bits 8-12: Auto-sample time bits */
+#define ADC_CON3_SAMC_MASK (31 << ADC_CON3_SAMC_SHIFT)
+# define ADC_CON3_SAMC(n) ((n) << ADC_CON3_SAMC_SHIFT) /* Tad = n, n=1..15 */
+#define ADC_CON3_ADRC (1 << 15) /* Bit 15: ADC conversion clock source */
+
+/* ADC input pin selection register */
+
+#define ADC_CHS_CH0SA_SHIFT (16) /* Bits 16-19: MUX A positive input select */
+#define ADC_CHS_CH0SA_MASK (15 << ADC_CHS_CH0SA_SHIFT)
+# define ADC_CHS_CH0SA(n) ((n) << ADC_CHS_CH0SA_SHIFT) /* Channel 0 positive input ANn, n=0..15 */
+#define ADC_CHS_CH0NA (1 << 23) /* Bit 23: MUX A negative input select */
+#define ADC_CHS_CH0SB_SHIFT (24) /* Bits 24-27: MUX B positive input select */
+#define ADC_CHS_CH0SB_MASK (15 << ADC_CHS_CH0SB_SHIFT)
+# define ADC_CHS_CH0SB(n) ((n) << ADC_CHS_CH0SB_SHIFT) /* Channel 0 positive input ANn, n=0..15 */
+#define ADC_CHS_CH0NB (1 << 31) /* Bit 31: MUX B negative input select */
+
+/* ADC sequentially scanned input register */
+
+#define ADC_CSSL(n) (1 << (n)) /* Bit n: xx n, n=0..15 */
+
+/* ADC input pin configuration register */
+
+#define ADC_CFG(n) (1 << (n)) /* Bit n: xx n, n=0..15 */
+
+/* ADC result word 0-15 -- 32-bits of ADC result data */
+
+/************************************************************************************
+ * 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_ADc_H */
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-reset.h b/nuttx/arch/mips/src/pic32mx/pic32mx-reset.h
index 1ba54be68..5e1721796 100755
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-reset.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-reset.h
@@ -1,4 +1,4 @@
-/****************************************************************************
+/************************************************************************************
* arch/mips/src/pic32mx/pic32mx-reset.h
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
@@ -31,23 +31,23 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ****************************************************************************/
+ ************************************************************************************/
#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_RESET_H
#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_RESET_H
-/****************************************************************************
+/************************************************************************************
* Included Files
- ****************************************************************************/
+ ************************************************************************************/
#include <nuttx/config.h>
#include "pic32mx-memorymap.h"
-/****************************************************************************
+/************************************************************************************
* Pre-Processor Definitions
- ****************************************************************************/
-/* Register Offsets *********************************************************/
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
#define PIC32MX_RESET_RCON_OFFSET 0x0000 /* Reset control register */
#define PIC32MX_RESET_RCONCLR_OFFSET 0x0004 /* RCON clear register */
@@ -58,7 +58,7 @@
#define PIC32MX_RESET_RSWRSTSET_OFFSET 0x0018 /* RSWRST set register */
#define PIC32MX_RESET_RSWRSTINV_OFFSET 0x001c /* RSWRST invert register */
-/* Register Addresses *******************************************************/
+/* Register Addresses ***************************************************************/
#define PIC32MX_RESET_RCON (PIC32MX_RESET_K1BASE+PIC32MX_RCON_OFFSET)
#define PIC32MX_RESET_RCONCLR (PIC32MX_RESET_K1BASE+PIC32MX_RCONCLR_OFFSET)
@@ -69,7 +69,7 @@
#define PIC32MX_RESET_RSWRSTSET (PIC32MX_RESET_K1BASE+PIC32MX_RSWRSTSET_OFFSET)
#define PIC32MX_RESET_RSWRSTINV (PIC32MX_RESET_K1BASE+PIC32MX_RSWRSTINV_OFFSET)
-/* Register Bit-Field Definitions *******************************************/
+/* Register Bit-Field Definitions ***************************************************/
/* Reset control register */
@@ -87,19 +87,19 @@
#define RESET_RSWRST_TRIGGER (1 << 0) /* Bit 0: Software reset trigger */
-/****************************************************************************
+/************************************************************************************
* Public Types
- ****************************************************************************/
+ ************************************************************************************/
#ifndef __ASSEMBLY__
-/****************************************************************************
+/************************************************************************************
* Inline Functions
- ****************************************************************************/
+ ************************************************************************************/
-/****************************************************************************
+/************************************************************************************
* Public Function Prototypes
- ****************************************************************************/
+ ************************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-usbotg.h b/nuttx/arch/mips/src/pic32mx/pic32mx-usbotg.h
new file mode 100755
index 000000000..022e931ed
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-usbotg.h
@@ -0,0 +1,309 @@
+/************************************************************************************
+ * arch/mips/src/pic32mx/pic32mx-usbotg.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_USBOTG_H
+#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_USBOTG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "pic32mx-memorymap.h"
+
+/************************************************************************************
+ * Pre-Processor Definitions
+ ************************************************************************************/
+/* Register Offsets *****************************************************************/
+
+#define PIC32MX_USBOTG_IR_OFFSET 0x0040 /* USB OTG Interrupt Flags Register */
+#define PIC32MX_USBOTG_IE_OFFSET 0x0050 /* USB OTG Interrupt Enable Register */
+#define PIC32MX_USBOTG_STAT_OFFSET 0x0060 /* USB Comparator and Pin Status Register */
+#define PIC32MX_USBOTG_CON_OFFSET 0x0070 /* USB Resistor and Pin Control Register */
+#define PIC32MX_USB_PWRC_OFFSET 0x0080 /* USB Power Control Register */
+#define PIC32MX_USB_IR_OFFSET 0x0200 /* USB Pending Interrupt Register */
+#define PIC32MX_USB_IE_OFFSET 0x0210 /* USB Interrupt Enable Register */
+#define PIC32MX_USB_EIR_OFFSET 0x0220 /* USB Pending Error Interrupt Register */
+#define PIC32MX_USB_EIE_OFFSET 0x0230 /* USB Interrupt Error Enable Register */
+#define PIC32MX_USB_STAT_OFFSET 0x0240 /* USB Status FIFO Register */
+#define PIC32MX_USB_CON_OFFSET 0x0250 /* USB Module Control Register */
+#define PIC32MX_USB_ADDR_OFFSET 0x0260 /* USB Address Register */
+#define PIC32MX_USB_FRMH_OFFSET 0x0290 /* USB Frame Counter Register (high) */
+#define PIC32MX_USB_FRML_OFFSET 0x0280 /* USB Frame Counter Register (low) */
+#define PIC32MX_USB_TOK_OFFSET 0x02a0 /* USB Host Control Register */
+#define PIC32MX_USB_SOF_OFFSET 0x02b0 /* USB SOF Counter Register */
+#define PIC32MX_USB_BDTP1_OFFSET 0x0270 /* USB Buffer Descriptor Table Pointer Register 1 */
+#define PIC32MX_USB_BDTP2_OFFSET 0x02c0 /* USB Buffer Descriptor Table Pointer Register 2 */
+#define PIC32MX_USB_BDTP3_OFFSET 0x02d0 /* USB Buffer Descriptor Table Pointer Register 3 */
+#define PIC32MX_USB_CNFG1_OFFSET 0x02e0 /* USB Debug and Idle Register */
+
+#define PIC32MX_USB_EP_OFFSET(n) 0x0300 /* USB Endpoint n Control Register */
+#define PIC32MX_USB_EP0_OFFSET 0x0300 /* USB Endpoint 0 Control Register */
+#define PIC32MX_USB_EP1_OFFSET 0x0310 /* USB Endpoint 1 Control Register */
+#define PIC32MX_USB_EP2_OFFSET 0x0320 /* USB Endpoint 2 Control Register */
+#define PIC32MX_USB_EP3_OFFSET 0x0330 /* USB Endpoint 3 Control Register */
+#define PIC32MX_USB_EP4_OFFSET 0x0340 /* USB Endpoint 4 Control Register */
+#define PIC32MX_USB_EP5_OFFSET 0x0350 /* USB Endpoint 5 Control Register */
+#define PIC32MX_USB_EP6_OFFSET 0x0360 /* USB Endpoint 6 Control Register */
+#define PIC32MX_USB_EP7_OFFSET 0x0370 /* USB Endpoint 7 Control Register */
+#define PIC32MX_USB_EP8_OFFSET 0x0380 /* USB Endpoint 8 Control Register */
+#define PIC32MX_USB_EP9_OFFSET 0x0390 /* USB Endpoint 9 Control Register */
+#define PIC32MX_USB_EP10_OFFSET 0x03a0 /* USB Endpoint 10 Control Register */
+#define PIC32MX_USB_EP11_OFFSET 0x03b0 /* USB Endpoint 11 Control Register */
+#define PIC32MX_USB_EP12_OFFSET 0x03c0 /* USB Endpoint 12 Control Register */
+#define PIC32MX_USB_EP13_OFFSET 0x03d0 /* USB Endpoint 13 Control Register */
+#define PIC32MX_USB_EP14_OFFSET 0x03e0 /* USB Endpoint 14 Control Register */
+#define PIC32MX_USB_EP15_OFFSET 0x03f0 /* USB Endpoint 15 Control Register */
+
+/* Register Addresses ***************************************************************/
+
+#define PIC32MX_USBOTG_IR (PIC32MX_USB_K1BASE+PIC32MX_USBOTG_IR_OFFSET)
+#define PIC32MX_USBOTG_IE (PIC32MX_USB_K1BASE+PIC32MX_USBOTG_IE_OFFSET)
+#define PIC32MX_USBOTG_STAT (PIC32MX_USB_K1BASE+PIC32MX_USBOTG_STAT_OFFSET)
+#define PIC32MX_USBOTG_CON (PIC32MX_USB_K1BASE+PIC32MX_USBOTG_CON_OFFSET)
+#define PIC32MX_USB_PWRC (PIC32MX_USB_K1BASE+PIC32MX_USB_PWRC_OFFSET)
+#define PIC32MX_USB_IR (PIC32MX_USB_K1BASE+PIC32MX_USB_IR_OFFSET)
+#define PIC32MX_USB_IE (PIC32MX_USB_K1BASE+PIC32MX_USB_IE_OFFSET)
+#define PIC32MX_USB_EIR (PIC32MX_USB_K1BASE+PIC32MX_USB_EIR_OFFSET)
+#define PIC32MX_USB_EIE (PIC32MX_USB_K1BASE+PIC32MX_USB_EIE_OFFSET)
+#define PIC32MX_USB_STAT (PIC32MX_USB_K1BASE+PIC32MX_USB_STAT_OFFSET)
+#define PIC32MX_USB_CON (PIC32MX_USB_K1BASE+PIC32MX_USB_CON_OFFSET)
+#define PIC32MX_USB_ADDR (PIC32MX_USB_K1BASE+PIC32MX_USB_ADDR_OFFSET)
+#define PIC32MX_USB_FRMH (PIC32MX_USB_K1BASE+PIC32MX_USB_FRMH_OFFSET)
+#define PIC32MX_USB_FRML (PIC32MX_USB_K1BASE+PIC32MX_USB_FRML_OFFSET)
+#define PIC32MX_USB_TOK (PIC32MX_USB_K1BASE+PIC32MX_USB_TOK_OFFSET)
+#define PIC32MX_USB_SOF (PIC32MX_USB_K1BASE+PIC32MX_USB_SOF_OFFSET)
+#define PIC32MX_USB_BDTP1 (PIC32MX_USB_K1BASE+PIC32MX_USB_BDTP1_OFFSET)
+#define PIC32MX_USB_BDTP2 (PIC32MX_USB_K1BASE+PIC32MX_USB_BDTP2_OFFSET)
+#define PIC32MX_USB_BDTP3 (PIC32MX_USB_K1BASE+PIC32MX_USB_BDTP3_OFFSET)
+#define PIC32MX_USB_CNFG1 (PIC32MX_USB_K1BASE+PIC32MX_USB_CNFG1_OFFSET)
+
+#define PIC32MX_USB_EP(n) (PIC32MX_USB_K1BASE+PIC32MX_USB_EP_OFFSET(n))
+#define PIC32MX_USB_EP0 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP0_OFFSET)
+#define PIC32MX_USB_EP1 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP1_OFFSET)
+#define PIC32MX_USB_EP2 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP2_OFFSET)
+#define PIC32MX_USB_EP3 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP3_OFFSET)
+#define PIC32MX_USB_EP4 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP4_OFFSET)
+#define PIC32MX_USB_EP5 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP5_OFFSET)
+#define PIC32MX_USB_EP6 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP6_OFFSET)
+#define PIC32MX_USB_EP7 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP7_OFFSET)
+#define PIC32MX_USB_EP8 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP8_OFFSET)
+#define PIC32MX_USB_EP9 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP9_OFFSET)
+#define PIC32MX_USB_EP10 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP10_OFFSET)
+#define PIC32MX_USB_EP11 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP11_OFFSET)
+#define PIC32MX_USB_EP12 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP12_OFFSET)
+#define PIC32MX_USB_EP13 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP13_OFFSET)
+#define PIC32MX_USB_EP14 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP14_OFFSET)
+#define PIC32MX_USB_EP15 (PIC32MX_USB_K1BASE+PIC32MX_USB_EP15_OFFSET)
+
+/* Register Bit-Field Definitions ***************************************************/
+
+/* USB OTG Interrupt Flags Register */
+/* USB OTG Interrupt Enable Register */
+
+#define USBOTG_INT_VBUSVD (1 << 0) /* Bit 0: A-Device VBUS Change Indicator */
+#define USBOTG_INT_SESEND (1 << 2) /* Bit 2: B-Device VBUS Change Indicator */
+#define USBOTG_INT_ACTV (1 << 4) /* Bit 4: Bus Activity Indicator */
+#define USBOTG_INT_SESVD (1 << 3) /* Bit 3: Session Valid Change Indicator */
+#define USBOTG_INT_LSTATE (1 << 5) /* Bit 5: Line State Stable Indicator */
+#define USBOTG_INT_T1MSEC (1 << 6) /* Bit 6: 1 Millisecond Timer */
+#define USBOTG_INT_ID (1 << 7) /* Bit 7: ID State Change Indicator */
+
+/* USB Comparator and Pin Status Register */
+
+#define USBOTG_STAT_VBUSVD (1 << 0) /* Bit 0: A-VBUS Valid Indicator */
+#define USBOTG_STAT_SESEND (1 << 2) /* Bit 2: B-Session End Indicator */
+#define USBOTG_STAT_SESVD (1 << 3) /* Bit 3: Session Valid Indicator */
+#define USBOTG_STAT_LSTATE (1 << 5) /* Bit 5: Line State Stable Indicator */
+#define USBOTG_STAT_ID (1 << 7) /* Bit 7: ID Pin State Indicator */
+
+/* USB Resistor and Pin Control Register */
+
+#define USBOTG_CON_VBUSDIS (1 << 0) /* Bit 0: VBUS Discharge Enable */
+#define USBOTG_CON_VBUSCHG (1 << 1) /* Bit 1: VBUS Charge Enable */
+#define USBOTG_CON_OTGEN (1 << 2) /* Bit 2: OTG Functionality Enable */
+#define USBOTG_CON_VBUSON (1 << 3) /* Bit 3: VBUS Power-on */
+#define USBOTG_CON_DMPULDWN (1 << 4) /* Bit 4: D- Pull-Down Enable */
+#define USBOTG_CON_DPPULDWN (1 << 5) /* Bit 5: D+ Pull-Down Enable */
+#define USBOTG_CON_DMPULUP (1 << 6) /* Bit 6: D- Pull-Up Enable */
+#define USBOTG_CON_DPPULUP (1 << 7) /* Bit 7: D+ Pull-Up Enable */
+
+/* USB Power Control Register */
+
+#define USB_PWRC_USBPWR (1 << 0) /* Bit 0: USB Operation Enable */
+#define USB_PWRC_USUSPEND (1 << 1) /* Bit 1: USB Suspend Mode */
+#define USB_PWRC_USBBUSY (1 << 3) /* Bit 3: USB Module Busy */
+#define USB_PWRC_USLPGRD (1 << 4) /* Bit 4: USB Sleep Entry Guard */
+#define USB_PWRC_UACTPND (1 << 7) /* Bit 7: USB Activity Pending */
+
+/* USB Pending Interrupt Register */
+/* USB Interrupt Enable Register */
+
+#define USB_INT_URST (1 << 0) /* Bit 0: USB Reset Interrupt (Device mode) */
+#define USB_INT_DETACH (1 << 0) /* Bit 0: USB Detach Interrupt (Host mode) */
+#define USB_INT_UERR (1 << 1) /* Bit 1: USB Error Condition Interrupt */
+#define USB_INT_SOF (1 << 2) /* Bit 2: SOF Token Interrupt */
+#define USB_INT_TRN (1 << 3) /* Bit 3: Token Processing Complete Interrupt */
+#define USB_INT_IDLE (1 << 4) /* Bit 4 : Idle Detect Interrupt */
+#define USB_INT_RESUME (1 << 5) /* Bit 5: Resume Interrupt */
+#define USB_INT_ATTACH (1 << 6) /* Bit 6: Peripheral Attach Interrupt */
+#define USB_INT_STALL (1 << 7) /* Bit 7: STALL Handshake Interrupt */
+
+/* USB Pending Error Interrupt Register */
+/* USB Interrupt Error Enable Register */
+
+#define USB_EINT_PID (1 << 0) /* Bit 0: PID Check Failure Flag */
+#define USB_EINT_CRC5 (1 << 1) /* Bit 1: CRC5 Host Error Flag */
+#define USB_EINT_EOF (1 << 1) /* Bit 1: EOF Error Flag */
+#define USB_EINT_CRC16 (1 << 2) /* Bit 2: CRC16 Failure Flag */
+#define USB_EINT_DFN8 (1 << 3) /* Bit 3: Data Field Size Error Flag */
+#define USB_EINT_BTO (1 << 4) /* Bit 4: Bus Turnaround Time-Out Error Flag */
+#define USB_EINT_DMA (1 << 5) /* Bit 5: DMA Error Flag */
+#define USB_EINT_BMX (1 << 6) /* Bit 6: Bus Matrix Error Flag */
+#define USB_EINT_BTS (1 << 7) /* Bit 7: Bit Stuff Error Flag */
+
+/* USB Status FIFO Register */
+
+#define USB_STAT_PPBI (1 << 2) /* Bit 2: Ping-Pong BD Pointer Indicator */
+#define USB_STAT_DIR (1 << 3) /* Bit 3: Last BD Direction Indicator */
+#define USB_STAT_ENDPT_SHIFT (4) /* Bits 4-7: Encoded Endpoint Activity */
+#define USB_STAT_ENDPT_MASK (15 << USB_STAT_ENDPT_SHIFT)
+# define USB_STAT_ENDPT(n) ((n) << USB_STAT_ENDPT_SHIFT) /* Endpoint n, n=0..15 */
+
+/* USB Module Control Register */
+
+#define USB_CON_USBEN (1 << 0) /* Bit 0: USB Module Enable */
+#define USB_CON_SOFEN (1 << 0) /* Bit 0: SOF Enable */
+#define USB_CON_PPBRST (1 << 1) /* Bit 1: Ping-Pong Buffers Reset */
+#define USB_CON_RESUME (1 << 2) /* Bit 2: RESUME Signaling Enable */
+#define USB_CON_HOSTEN (1 << 3) /* Bit 3: Host Mode Enable */
+#define USB_CON_USBRST (1 << 4) /* Bit 4: Module Reset */
+#define USB_CON_PKTDIS (1 << 5) /* Bit 5: Packet Transfer Disable */
+#define USB_CON_TOKBUSY (1 << 5) /* Bit 5: Token Busy Indicator */
+#define USB_CON_SE0 (1 << 6) /* Bit 6: Live Single-Ended Zero flag */
+#define USB_CON_JSTATE (1 << 7) /* Bit 7: Live Differential Receiver JSTATE flag */
+
+/* USB Address Register */
+
+#define USB_ADDR_DEVADDR_SHIFT (0) /* Bit 0-6: 7-bit USB Device Address */
+#define USB_ADDR_DEVADDR_MASK (0x7f << USB_ADDR_DEVADDR_SHIFT)
+#define USB_ADDR_LSPDEN (1 << 7) /* Bit 7: Low Speed Enable Indicator */
+
+/* USB Frame Counter Register (high) */
+
+#define USB_FRMH_MASK 0x07 /* Bits 0-2: 11-bit frame number upper 3 bits */
+
+/* USB Frame Counter Register (low) */
+
+#define USB_FRML_MASK 0xff /* Bits 0-7: 11-bit frame number lower 8 bits */
+
+/* USB Host Control Register */
+
+#define USB_TOK_PID_SHIFT (4) /* Bits 4-7: Token Type Indicator */
+#define USB_TOK_PID_MASK (15 << USB_TOK_PID_SHIFT)
+# define USB_TOK_PID_OUT (1 << USB_TOK_PID_SHIFT) /* OUT (TX) token type transaction */
+# define USB_TOK_PID_IN (9 << USB_TOK_PID_SHIFT) /* IN (RX) token type transaction */
+# define USB_TOK_PID_SETUP (13 << USB_TOK_PID_SHIFT) /* SETUP (TX) token type transaction */
+#define USB_TOK_EP_SHIFT (0) /* Bits 0-3: Token Command Endpoint Address */
+#define USB_TOK_EP_MASK (15 << USB_TOK_EP_SHIFT)
+
+/* USB SOF Counter Register */
+
+#define USB_SOF_SHIFT (0) /* Bits 0-7: SOF Threshold Value */
+#define USB_SOF_MASK (0xff << USB_SOF_SHIFT)
+# define USB_SOF_8BTYE (0x12 << USB_SOF_SHIFT) /* 8-byte packet */
+# define USB_SOF_16BTYE (0x1a << USB_SOF_SHIFT) /* 16-byte packet */
+# define USB_SOF_32BTYE (0x2a << USB_SOF_SHIFT) /* 32-byte packet */
+# define USB_SOF_64BTYE (0x4a << USB_SOF_SHIFT) /* 64-byte packet */
+
+/* USB Buffer Descriptor Table Pointer Register 1 */
+
+#define USB_BDTP1_MASK 0x7e /* Bits 1-7: BDT Base Address bits 9-15 */
+
+/* USB Buffer Descriptor Table Pointer Register 2 */
+
+#define USB_BDTP2_MASK 0xff /* Bits 0-7: BDT Base Address bits 16-23 */
+
+/* USB Buffer Descriptor Table Pointer Register 3 */
+
+#define USB_BDTP3_MASK 0xff /* Bits 0-7: BDT Base Address bits 24-31 */
+
+/* USB Debug and Idle Register */
+
+#define USB_CNFG1_UASUSPND (1 << 0) /* Bit 0: Automatic Suspend Enable */
+#define USB_CNFG1_USBSIDL (1 << 4) /* Bit 4: Stop in Idle Mode */
+#define USB_CNFG1_USBFRZ (1 << 5) /* Bit 5: Freeze in Debug Mode */
+#define USB_CNFG1_UOEMON (1 << 6) /* Bit 6: USB OE Monitor Enable */
+#define USB_CNFG1_UTEYE (1 << 7) /* Bit 7: USB Eye-Pattern Test Enable */
+
+/* USB Endpoint Control Register */
+
+#define USB_EP_EPHSHK (1 << 0) /* Bit 0: Endpoint Handshake Enable */
+#define USB_EP_EPSTALL (1 << 1) /* Bit 1: Endpoint Stall Status */
+#define USB_EP_EPRXEN (1 << 3) /* Bit 3: Endpoint Receive Enable */
+#define USB_EP_EPTXEN (1 << 2) /* Bit 2: Endpoint Transmit Enable */
+#define USB_EP_EPCONDIS (1 << 4) /* Bit 4: Bidirectional Endpoint Control */
+#define USB_EP_RETRYDIS (1 << 6) /* Bit 6: Retry Disable (Host mode and U1EP0 only) */
+#define USB_EP_LSPD (1 << 7) /* Bit 7: Low-Speed Direct Connection Enable */
+
+/************************************************************************************
+ * 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_USBOTG_H */