Add support for PIC32 MX1 and MX2 families

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4851 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-06-19 19:09:14 +00:00
parent 4bb2e9dea6
commit bd7bf04393
28 changed files with 3814 additions and 1942 deletions

View File

@ -2910,3 +2910,5 @@
particular.
* Documentation/NfsHowTo.html: Add a How-To document for the new NFS
client feature.
* arch/mips/include/pic32mx and arch/mips/src/pic32mx: Add support for the
PIC32MX1 and PIC32MX2 families.

View File

@ -35,7 +35,7 @@
<li><a href="NuttXNxFlat.html" target="main">NXFLAT</a></li>
<li><a href="NXGraphicsSubsystem.html" target="main">NX Graphics</a></li>
<li><a href="NxWidgets.html" target="main">NxWidgets</a></li>
<li><a href="NfsHowTo.html" target="main">NFS How-To</a></li>
<li><a href="NfsHowto.html" target="main">NFS How-To</a></li>
<li><a href="NuttXDemandPaging.html" target="main">Demand Paging</a></li>
<li><a href="UsbTrace.html" target="main">USB Trace</a></li>
<li><a href="README.html" target="main">README Files</a></li>

0
nuttx/arch/mips/include/mips32/cp0.h Executable file → Normal file
View File

0
nuttx/arch/mips/include/mips32/irq.h Executable file → Normal file
View File

0
nuttx/arch/mips/include/mips32/registers.h Executable file → Normal file
View File

File diff suppressed because it is too large Load Diff

0
nuttx/arch/mips/include/pic32mx/cp0.h Executable file → Normal file
View File

6
nuttx/arch/mips/include/pic32mx/irq.h Executable file → Normal file
View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/include/pic32mx/irq.h
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -45,7 +45,9 @@
****************************************************************************/
#include <arch/pic32mx/chip.h>
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# include <arch/pic32mx/irq_1xx2xx.h>
#elif defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# include <arch/pic32mx/irq_3xx4xx.h>
#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# include <arch/pic32mx/irq_5xx6xx7xx.h>

View File

@ -0,0 +1,215 @@
/****************************************************************************
* arch/mips/include/pic32mx/irq_1xx2xx.h
*
* Copyright (C) 2012 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.
*
****************************************************************************/
/* This file should never be included directed but, rather, only indirectly
* through nuttx/irq.h
*/
#ifndef __ARCH_MIPS_INCLUDE_PIC32MX_IRQ_1XX2XX_H
#define __ARCH_MIPS_INCLUDE_PIC32MX_IRQ_1XX2XX_H
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Interrupt vector numbers. These should be used to attach to interrupts
* and to change interrupt priorities.
*/
#define PIC32MX_IRQ_CT 0 /* Vector: 0, Core Timer Interrupt */
#define PIC32MX_IRQ_CS0 1 /* Vector: 1, Core Software Interrupt 0 */
#define PIC32MX_IRQ_CS1 2 /* Vector: 2, Core Software Interrupt 1 */
#define PIC32MX_IRQ_INT0 3 /* Vector: 3, External Interrupt 0 */
#define PIC32MX_IRQ_T1 4 /* Vector: 4, Timer 1 */
#define PIC32MX_IRQ_IC1 5 /* Vector: 5, Input Capture 1 */
#define PIC32MX_IRQ_OC1 6 /* Vector: 6, Output Compare 1 */
#define PIC32MX_IRQ_INT1 7 /* Vector: 7, External Interrupt 1 */
#define PIC32MX_IRQ_T2 8 /* Vector: 8, Timer 2 */
#define PIC32MX_IRQ_IC2 9 /* Vector: 9, Input Capture 2 */
#define PIC32MX_IRQ_OC2 10 /* Vector: 10, Output Compare 2 */
#define PIC32MX_IRQ_INT2 11 /* Vector: 11, External Interrupt 2 */
#define PIC32MX_IRQ_T3 12 /* Vector: 12, Timer 3 */
#define PIC32MX_IRQ_IC3 13 /* Vector: 13, Input Capture 3 */
#define PIC32MX_IRQ_OC3 14 /* Vector: 14, Output Compare 3 */
#define PIC32MX_IRQ_INT3 15 /* Vector: 15, External Interrupt 3 */
#define PIC32MX_IRQ_T4 16 /* Vector: 16, Timer 4 */
#define PIC32MX_IRQ_IC4 17 /* Vector: 17, Input Capture 4 */
#define PIC32MX_IRQ_OC4 18 /* Vector: 18, Output Compare 4 */
#define PIC32MX_IRQ_INT4 19 /* Vector: 19, External Interrupt 4 */
#define PIC32MX_IRQ_T5 20 /* Vector: 20, Timer 5 */
#define PIC32MX_IRQ_IC5 21 /* Vector: 21, Input Capture 5 */
#define PIC32MX_IRQ_OC5 22 /* Vector: 22, Output Compare 5 */
#define PIC32MX_IRQ_AD1 23 /* Vector: 23, ADC1 Convert Done */
#define PIC32MX_IRQ_FSCM 24 /* Vector: 24, Fail-Safe Clock Monitor */
#define PIC32MX_IRQ_RTCC 25 /* Vector: 25, Real-Time Clock and Calendar */
#define PIC32MX_IRQ_FCE 26 /* Vector: 26, Flash Control Event */
#define PIC32MX_IRQ_CMP1 27 /* Vector: 27, Comparator 1 */
#define PIC32MX_IRQ_CMP2 28 /* Vector: 28, Comparator 2 */
#define PIC32MX_IRQ_CMP3 29 /* Vector: 29, Comparator 3 */
#define PIC32MX_IRQ_USB 30 /* Vector: 30, USB */
#define PIC32MX_IRQ_SPI1 31 /* Vector: 31, SPI1 */
#define PIC32MX_IRQ_U1 32 /* Vector: 32, UART1 */
#define PIC32MX_IRQ_I2C1 33 /* Vector: 33, I2C1 */
#define PIC32MX_IRQ_CN 34 /* Vector: 34, Input Change */
#define PIC32MX_IRQ_PMP 35 /* Vector: 35, Parallel Master Port */
#define PIC32MX_IRQ_SPI2 36 /* Vector: 36, SPI2 */
#define PIC32MX_IRQ_U2 37 /* Vector: 37, UART2 */
#define PIC32MX_IRQ_I2C2 38 /* Vector: 38, I2C2 */
#define PIC32MX_IRQ_CTMU 39 /* Vector: 39, CTMU */
#define PIC32MX_IRQ_DMA0 40 /* Vector: 40, DMA Channel 0 */
#define PIC32MX_IRQ_DMA1 41 /* Vector: 41, DMA Channel 1 */
#define PIC32MX_IRQ_DMA2 42 /* Vector: 42, DMA Channel 2 */
#define PIC32MX_IRQ_DMA3 43 /* Vector: 43, DMA Channel 3 */
#define PIC32MX_IRQ_BAD 44 /* Not a real IRQ number */
#define NR_IRQS 44
/* Interrupt numbers. These should be used for enabling and disabling
* interrupt sources. Note that there are more interrupt sources than
* interrupt vectors and interrupt priorities. An offset of 128 is
* used so that there is no overlap with the IRQ numbers and to avoid
* errors due to misuse.
*/
#define PIC32MX_IRQSRC0_FIRST (128+0)
#define PIC32MX_IRQSRC_CT (128+0) /* Vector: 0, Core Timer Interrupt */
#define PIC32MX_IRQSRC_CS0 (128+1) /* Vector: 1, Core Software Interrupt 0 */
#define PIC32MX_IRQSRC_CS1 (128+2) /* Vector: 2, Core Software Interrupt 1 */
#define PIC32MX_IRQSRC_INT0 (128+3) /* Vector: 3, External Interrupt 0 */
#define PIC32MX_IRQSRC_T1 (128+4) /* Vector: 4, Timer 1 */
#define PIC32MX_IRQSRC_IC1E (128+5) /* Vector: 5, Input Capture 1 Error */
#define PIC32MX_IRQSRC_IC1 (128+6) /* Vector: 5, Input Capture 1 */
#define PIC32MX_IRQSRC_OC1 (128+7) /* Vector: 6, Output Compare 1 */
#define PIC32MX_IRQSRC_INT1 (128+8) /* Vector: 7, External Interrupt 1 */
#define PIC32MX_IRQSRC_T2 (128+9) /* Vector: 8, Timer 2 */
#define PIC32MX_IRQSRC_IC2E (128+10) /* Vector: 9, Input Capture 2 Error */
#define PIC32MX_IRQSRC_IC2 (128+11) /* Vector: 9, Input Capture 2 */
#define PIC32MX_IRQSRC_OC2 (128+12) /* Vector: 10, Output Compare 2 */
#define PIC32MX_IRQSRC_INT2 (128+13) /* Vector: 11, External Interrupt 2 */
#define PIC32MX_IRQSRC_T3 (128+14) /* Vector: 12, Timer 3 */
#define PIC32MX_IRQSRC_IC3E (128+15) /* Vector: 13, Input Capture 3 Error */
#define PIC32MX_IRQSRC_IC3 (128+16) /* Vector: 13, Input Capture 3 */
#define PIC32MX_IRQSRC_OC3 (128+17) /* Vector: 14, Output Compare 3 */
#define PIC32MX_IRQSRC_INT3 (128+18) /* Vector: 15, External Interrupt 3 */
#define PIC32MX_IRQSRC_T4 (128+19) /* Vector: 16, Timer 4 */
#define PIC32MX_IRQSRC_IC4E (128+20) /* Vector: 17, Input Capture 4 Error */
#define PIC32MX_IRQSRC_IC4 (128+21) /* Vector: 17, Input Capture 4 */
#define PIC32MX_IRQSRC_OC4 (128+22) /* Vector: 18, Output Compare 4 */
#define PIC32MX_IRQSRC_INT4 (128+23) /* Vector: 19, External Interrupt 4 */
#define PIC32MX_IRQSRC_T5 (128+24) /* Vector: 20, Timer 5 */
#define PIC32MX_IRQSRC_IC5E (128+25) /* Vector: 21, Input Capture 5 Error */
#define PIC32MX_IRQSRC_IC5 (128+26) /* Vector: 21, Input Capture 5 */
#define PIC32MX_IRQSRC_OC5 (128+27) /* Vector: 22, Output Compare 5 */
#define PIC32MX_IRQSRC_AD1 (128+28) /* Vector: 23, ADC1 Convert Done */
#define PIC32MX_IRQSRC_FSCM (128+29) /* Vector: 24, Fail-Safe Clock Monitor */
#define PIC32MX_IRQSRC_RTCC (128+30) /* Vector: 25, Real-Time Clock and Calendar */
#define PIC32MX_IRQSRC_FCE (128+31) /* Vector: 26, Flash Control Event */
#define PIC32MX_IRQSRC0_LAST (128+31)
#define PIC32MX_IRQSRC1_FIRST (128+32)
#define PIC32MX_IRQSRC_CMP1 (128+32) /* Vector: 27, Comparator 1 Interrupt */
#define PIC32MX_IRQSRC_CMP2 (128+33) /* Vector: 28, Comparator 2 Interrupt */
#define PIC32MX_IRQSRC_CMP2 (128+34) /* Vector: 29, Comparator 3 Interrupt */
#define PIC32MX_IRQSRC_USB (128+35) /* Vector: 30, USB */
#define PIC32MX_IRQSRC_SPI1E (128+36) /* Vector: 31, SPI1 */
#define PIC32MX_IRQSRC_SPI1TX (128+37) /* Vector: 31, " " */
#define PIC32MX_IRQSRC_SPI1RX (128+38) /* Vector: 31, " " */
#define PIC32MX_IRQSRC_U1E (128+39) /* Vector: 32, UART1 */
#define PIC32MX_IRQSRC_U1RX (128+40) /* Vector: 32, " " */
#define PIC32MX_IRQSRC_U1TX (128+41) /* Vector: 32, " " */
#define PIC32MX_IRQSRC_I2C1B (128+42) /* Vector: 33, I2C1 */
#define PIC32MX_IRQSRC_I2C1S (128+43) /* Vector: 33, " " */
#define PIC32MX_IRQSRC_I2C1M (128+44) /* Vector: 33, " " */
#define PIC32MX_IRQSRC_CNA (128+45) /* Vector: 34, Input Change Interrupt */
#define PIC32MX_IRQSRC_CNB (128+46) /* Vector: 34, Input Change Interrupt */
#define PIC32MX_IRQSRC_CNC (128+47) /* Vector: 34, Input Change Interrupt */
#define PIC32MX_IRQSRC_PMP (128+48) /* Vector: 35, Parallel Master Port */
#define PIC32MX_IRQSRC_PMPE (128+49) /* Vector: 35, Parallel Master Port */
#define PIC32MX_IRQSRC_SPI2E (128+50) /* Vector: 36, SPI2 */
#define PIC32MX_IRQSRC_SPI2TX (128+51) /* Vector: 36, " " */
#define PIC32MX_IRQSRC_SPI2RX (128+52) /* Vector: 36, " " */
#define PIC32MX_IRQSRC_U2E (128+53) /* Vector: 37, UART2 */
#define PIC32MX_IRQSRC_U2RX (128+54) /* Vector: 37, " " */
#define PIC32MX_IRQSRC_U2TX (128+55) /* Vector: 37, " " */
#define PIC32MX_IRQSRC_I2C2B (128+56) /* Vector: 38, I2C2 */
#define PIC32MX_IRQSRC_I2C2S (128+57) /* Vector: 38, " " */
#define PIC32MX_IRQSRC_I2C2M (128+58) /* Vector: 38, " " */
#define PIC32MX_IRQSRC_CTMU (128+59) /* Vector: 39, CTMU */
#define PIC32MX_IRQSRC_DMA0 (128+60) /* Vector: 40, DMA Channel 0 */
#define PIC32MX_IRQSRC_DMA1 (128+61) /* Vector: 41, DMA Channel 1 */
#define PIC32MX_IRQSRC_DMA2 (128+62) /* Vector: 42, DMA Channel 2 */
#define PIC32MX_IRQSRC_DMA3 (128+63) /* Vector: 43, DMA Channel 3 */
#define PIC32MX_IRQSRC1_LAST (128+63)
#define PIC32MX_IRQSRC_FIRST PIC32MX_IRQSRC0_FIRST
#define PIC32MX_IRQSRC_LAST PIC32MX_IRQSRC1_LAST
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Inline functions
****************************************************************************/
/****************************************************************************
* Public Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_MIPS_INCLUDE_PIC32MX_IRQ_1XX2XX_H */

0
nuttx/arch/mips/include/pic32mx/irq_3xx4xx.h Executable file → Normal file
View File

0
nuttx/arch/mips/include/pic32mx/irq_5xx6xx7xx.h Executable file → Normal file
View File

0
nuttx/arch/mips/src/common/up_etherstub.c Executable file → Normal file
View File

0
nuttx/arch/mips/src/common/up_internal.h Executable file → Normal file
View File

0
nuttx/arch/mips/src/mips32/mips32-memorymap.h Executable file → Normal file
View File

0
nuttx/arch/mips/src/mips32/up_blocktask.c Executable file → Normal file
View File

0
nuttx/arch/mips/src/mips32/up_releasepending.c Executable file → Normal file
View File

0
nuttx/arch/mips/src/mips32/up_reprioritizertr.c Executable file → Normal file
View File

0
nuttx/arch/mips/src/mips32/up_unblocktask.c Executable file → Normal file
View File

View File

@ -9,6 +9,126 @@ choice
prompt "PIC32MX chip selection"
default ARCH_CHIP_PIC32MX460F512L
config ARCH_CHIP_PIC32MX110F016B
bool "PIC32MX110F016B"
---help---
Microchip PIC32MX110F016B (MIPS32)
config ARCH_CHIP_PIC32MX110F016C
bool "PIC32MX110F016C"
---help---
Microchip PIC32MX110F016C (MIPS32)
config ARCH_CHIP_PIC32MX110F016D
bool "PIC32MX110F016D"
---help---
Microchip PIC32MX110F016D (MIPS32)
config ARCH_CHIP_PIC32MX120F032B
bool "PIC32MX120F032B"
---help---
Microchip PIC32MX120F032B (MIPS32)
config ARCH_CHIP_PIC32MX120F032C
bool "PIC32MX120F032C"
---help---
Microchip PIC32MX120F032C (MIPS32)
config ARCH_CHIP_PIC32MX120F032D
bool "PIC32MX120F032D"
---help---
Microchip PIC32MX120F032D (MIPS32)
config ARCH_CHIP_PIC32MX130F064B
bool "PIC32MX130F064B"
---help---
Microchip PIC32MX130F064B (MIPS32)
config ARCH_CHIP_PIC32MX130F064C
bool "PIC32MX130F064C"
---help---
Microchip PIC32MX130F064C (MIPS32)
config ARCH_CHIP_PIC32MX130F064D
bool "PIC32MX130F064D"
---help---
Microchip PIC32MX130F064D (MIPS32)
config ARCH_CHIP_PIC32MX150F128B
bool "PIC32MX150F128B"
---help---
Microchip PIC32MX150F128B (MIPS32)
config ARCH_CHIP_PIC32MX150F128C
bool "PIC32MX150F128C"
---help---
Microchip PIC32MX150F128C (MIPS32)
config ARCH_CHIP_PIC32MX150F128D
bool "PIC32MX150F128D"
---help---
Microchip PIC32MX150F128D (MIPS32)
config ARCH_CHIP_PIC32MX210F016B
bool "PIC32MX210F016B"
---help---
Microchip PIC32MX210F016B (MIPS32)
config ARCH_CHIP_PIC32MX210F016C
bool "PIC32MX210F016C"
---help---
Microchip PIC32MX210F016C (MIPS32)
config ARCH_CHIP_PIC32MX210F016D
bool "PIC32MX210F016D"
---help---
Microchip PIC32MX210F016D (MIPS32)
config ARCH_CHIP_PIC32MX220F032B
bool "PIC32MX220F032B"
---help---
Microchip PIC32MX220F032B (MIPS32)
config ARCH_CHIP_PIC32MX220F032C
bool "PIC32MX220F032C"
---help---
Microchip PIC32MX220F032C (MIPS32)
config ARCH_CHIP_PIC32MX220F032D
bool "PIC32MX220F032D"
---help---
Microchip PIC32MX220F032D (MIPS32)
config ARCH_CHIP_PIC32MX230F064B
bool "PIC32MX230F064B"
---help---
Microchip PIC32MX230F064B (MIPS32)
config ARCH_CHIP_PIC32MX230F064C
bool "PIC32MX230F064C"
---help---
Microchip PIC32MX230F064C (MIPS32)
config ARCH_CHIP_PIC32MX230F064D
bool "PIC32MX230F064D"
---help---
Microchip PIC32MX230F064D (MIPS32)
config ARCH_CHIP_PIC32MX250F128B
bool "PIC32MX250F128B"
---help---
Microchip PIC32MX250F128B (MIPS32)
config ARCH_CHIP_PIC32MX250F128C
bool "PIC32MX250F128C"
---help---
Microchip PIC32MX250F128C (MIPS32)
config ARCH_CHIP_PIC32MX250F128D
bool "PIC32MX250F128D"
---help---
Microchip PIC32MX250F128D (MIPS32)
config ARCH_CHIP_PIC32MX320F032H
bool "PIC32MX320F032H"
---help---
@ -236,10 +356,18 @@ config ARCH_CHIP_PIC32MX795F512L
endchoice
config ARCH_CHIP_PIC322MX1
bool
default y if ARCH_CHIP_PIC32MX110F016B || ARCH_CHIP_PIC32MX110F016C || ARCH_CHIP_PIC32MX110F016D || ARCH_CHIP_PIC32MX120F032B || ARCH_CHIP_PIC32MX120F032C || ARCH_CHIP_PIC32MX120F032D || ARCH_CHIP_PIC32MX130F064B || ARCH_CHIP_PIC32MX130F064C || ARCH_CHIP_PIC32MX130F064D || ARCH_CHIP_PIC32MX150F128B || ARCH_CHIP_PIC32MX150F128C || ARCH_CHIP_PIC32MX150F128D
config ARCH_CHIP_PIC322MX2
bool
default y if ARCH_CHIP_PIC32MX210F016B || ARCH_CHIP_PIC32MX210F016C || ARCH_CHIP_PIC32MX210F016D || ARCH_CHIP_PIC32MX220F032B || ARCH_CHIP_PIC32MX220F032C || ARCH_CHIP_PIC32MX220F032D || ARCH_CHIP_PIC32MX230F064B || ARCH_CHIP_PIC32MX230F064C || ARCH_CHIP_PIC32MX230F064D || ARCH_CHIP_PIC32MX250F128B || ARCH_CHIP_PIC32MX250F128C || ARCH_CHIP_PIC32MX250F128D
config ARCH_CHIP_PIC322MX3
bool
default y if ARCH_CHIP_PIC32MX320F032H || ARCH_CHIP_PIC32MX320F064H || ARCH_CHIP_PIC32MX320F128H || ARCH_CHIP_PIC32MX320F128L || ARCH_CHIP_PIC32MX340F128H || ARCH_CHIP_PIC32MX340F256H || ARCH_CHIP_PIC32MX340F512H || ARCH_CHIP_PIC32MX340F128L || ARCH_CHIP_PIC32MX360F256L || ARCH_CHIP_PIC32MX360F512L
config ARCH_CHIP_PIC322MX4
bool
default y if ARCH_CHIP_PIC32MX420F032H || ARCH_CHIP_PIC32MX440F128H || ARCH_CHIP_PIC32MX440F128L || ARCH_CHIP_PIC32MX440F256H || ARCH_CHIP_PIC32MX440F512H || ARCH_CHIP_PIC32MX460F256L || ARCH_CHIP_PIC32MX460F512L
@ -434,6 +562,10 @@ config PIC32MX_ETHERNET
bool "Ethernet"
default n
config PIC32MX_CTMU
bool "Charge Time Measurement Unit (CMTU)"
default n
endmenu
menu "PIC32MX Peripheral Interrupt Priorities"

View File

@ -55,7 +55,7 @@
/* Interrupt Priorities *************************************************************/
#ifndef CONFIG_PIC32MX_CTPRIO /* Core Timer Interrupt */
# define CONFIG_PIC32MX_CTPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CTPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CTPRIO < 4
# error "CONFIG_PIC32MX_CTPRIO is too small"
@ -65,7 +65,7 @@
#endif
#ifndef CONFIG_PIC32MX_CS0PRIO /* Core Software Interrupt 0 */
# define CONFIG_PIC32MX_CS0PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CS0PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CS0PRIO < 4
# error "CONFIG_PIC32MX_CS0PRIO is too small"
@ -75,7 +75,7 @@
#endif
#ifndef CONFIG_PIC32MX_CS1PRIO /* Core Software Interrupt 1 */
# define CONFIG_PIC32MX_CS1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CS1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CS1PRIO < 4
# error "CONFIG_PIC32MX_CS1PRIO is too small"
@ -85,7 +85,7 @@
#endif
#ifndef CONFIG_PIC32MX_INT0PRIO /* External interrupt 0 */
# define CONFIG_PIC32MX_INT0PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_INT0PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_INT0PRIO < 4
# error "CONFIG_PIC32MX_INT0PRIO is too small"
@ -95,7 +95,7 @@
#endif
#ifndef CONFIG_PIC32MX_INT1PRIO /* External interrupt 1 */
# define CONFIG_PIC32MX_INT1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_INT1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_INT1PRIO < 4
# error "CONFIG_PIC32MX_INT1PRIO is too small"
@ -105,7 +105,7 @@
#endif
#ifndef CONFIG_PIC32MX_INT2PRIO /* External interrupt 2 */
# define CONFIG_PIC32MX_INT2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_INT2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_INT2PRIO < 4
# error "CONFIG_PIC32MX_INT2PRIO is too small"
@ -115,7 +115,7 @@
#endif
#ifndef CONFIG_PIC32MX_INT3PRIO /* External interrupt 3 */
# define CONFIG_PIC32MX_INT3PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_INT3PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_INT3PRIO < 4
# error "CONFIG_PIC32MX_INT3PRIO is too small"
@ -125,7 +125,7 @@
#endif
#ifndef CONFIG_PIC32MX_INT4PRIO /* External interrupt 4 */
# define CONFIG_PIC32MX_INT4PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_INT4PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_INT4PRIO < 4
# error "CONFIG_PIC32MX_INT4PRIO is too small"
@ -135,7 +135,7 @@
#endif
#ifndef CONFIG_PIC32MX_FSCMPRIO /* Fail-Safe Clock Monitor */
# define CONFIG_PIC32MX_FSCMPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_FSCMPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_FSCMPRIO < 4
# error "CONFIG_PIC32MX_FSCMPRIO is too small"
@ -145,7 +145,7 @@
#endif
#ifndef CONFIG_PIC32MX_T1PRIO /* Timer 1 (System timer) priority */
# define CONFIG_PIC32MX_T1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_T1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T1PRIO < 4
# error "CONFIG_PIC32MX_T1PRIO is too small"
@ -155,7 +155,7 @@
#endif
#ifndef CONFIG_PIC32MX_T2PRIO /* Timer 2 priority */
# define CONFIG_PIC32MX_T2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_T2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T2PRIO < 4
# error "CONFIG_PIC32MX_T2PRIO is too small"
@ -165,7 +165,7 @@
#endif
#ifndef CONFIG_PIC32MX_T3PRIO /* Timer 3 priority */
# define CONFIG_PIC32MX_T3PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_T3PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T3PRIO < 4
# error "CONFIG_PIC32MX_T3PRIO is too small"
@ -175,7 +175,7 @@
#endif
#ifndef CONFIG_PIC32MX_T4PRIO /* Timer 4 priority */
# define CONFIG_PIC32MX_T4PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_T4PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T4PRIO < 4
# error "CONFIG_PIC32MX_T4PRIO is too small"
@ -185,7 +185,7 @@
#endif
#ifndef CONFIG_PIC32MX_T5PRIO /* Timer 5 priority */
# define CONFIG_PIC32MX_T5PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_T5PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_T5PRIO < 4
# error "CONFIG_PIC32MX_T5PRIO is too small"
@ -195,7 +195,7 @@
#endif
#ifndef CONFIG_PIC32MX_IC1PRIO /* Input Capture 1 */
# define CONFIG_PIC32MX_IC1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_IC1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC1PRIO < 4
# error "CONFIG_PIC32MX_IC1PRIO is too small"
@ -205,7 +205,7 @@
#endif
#ifndef CONFIG_PIC32MX_IC2PRIO /* Input Capture 2 */
# define CONFIG_PIC32MX_IC2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_IC2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC2PRIO < 4
# error "CONFIG_PIC32MX_IC2PRIO is too small"
@ -215,7 +215,7 @@
#endif
#ifndef CONFIG_PIC32MX_IC3PRIO /* Input Capture 3 */
# define CONFIG_PIC32MX_IC3PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_IC3PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC3PRIO < 4
# error "CONFIG_PIC32MX_IC3PRIO is too small"
@ -225,7 +225,7 @@
#endif
#ifndef CONFIG_PIC32MX_IC4PRIO /* Input Capture 4 */
# define CONFIG_PIC32MX_IC4PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_IC4PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC4PRIO < 4
# error "CONFIG_PIC32MX_IC4PRIO is too small"
@ -235,7 +235,7 @@
#endif
#ifndef CONFIG_PIC32MX_IC5PRIO /* Input Capture 5 */
# define CONFIG_PIC32MX_IC5PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_IC5PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_IC5PRIO < 4
# error "CONFIG_PIC32MX_IC5PRIO is too small"
@ -245,7 +245,7 @@
#endif
#ifndef CONFIG_PIC32MX_OC1PRIO /* Output Compare 1 */
# define CONFIG_PIC32MX_OC1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_OC1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC1PRIO < 4
# error "CONFIG_PIC32MX_OC1PRIO is too small"
@ -255,7 +255,7 @@
#endif
#ifndef CONFIG_PIC32MX_OC2PRIO /* Output Compare 2 */
# define CONFIG_PIC32MX_OC2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_OC2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC2PRIO < 4
# error "CONFIG_PIC32MX_OC2PRIO is too small"
@ -265,7 +265,7 @@
#endif
#ifndef CONFIG_PIC32MX_OC3PRIO /* Output Compare 3 */
# define CONFIG_PIC32MX_OC3PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_OC3PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC3PRIO < 4
# error "CONFIG_PIC32MX_OC3PRIO is too small"
@ -275,7 +275,7 @@
#endif
#ifndef CONFIG_PIC32MX_OC4PRIO /* Output Compare 4 */
# define CONFIG_PIC32MX_OC4PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_OC4PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC4PRIO < 4
# error "CONFIG_PIC32MX_OC4PRIO is too small"
@ -285,7 +285,7 @@
#endif
#ifndef CONFIG_PIC32MX_OC5PRIO /* Output Compare 5 */
# define CONFIG_PIC32MX_OC5PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_OC5PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_OC5PRIO < 4
# error "CONFIG_PIC32MX_OC5PRIO is too small"
@ -295,7 +295,7 @@
#endif
#ifndef CONFIG_PIC32MX_I2C1PRIO /* I2C 1 */
# define CONFIG_PIC32MX_I2C1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_I2C1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_I2C1PRIO < 4
# error "CONFIG_PIC32MX_I2C1PRIO is too small"
@ -305,7 +305,7 @@
#endif
#ifndef CONFIG_PIC32MX_I2C2PRIO /* I2C 2 */
# define CONFIG_PIC32MX_I2C2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_I2C2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_I2C2PRIO < 4
# error "CONFIG_PIC32MX_I2C2PRIO is too small"
@ -315,7 +315,7 @@
#endif
#ifndef CONFIG_PIC32MX_SPI1PRIO /* SPI 1 */
# define CONFIG_PIC32MX_SPI1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_SPI1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_SPI1PRIO < 4
# error "CONFIG_PIC32MX_SPI1PRIO is too small"
@ -325,7 +325,7 @@
#endif
#ifndef CONFIG_PIC32MX_SPI2PRIO /* SPI 2 */
# define CONFIG_PIC32MX_SPI2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_SPI2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_SPI2PRIO < 4
# error "CONFIG_PIC32MX_SPI2PRIO is too small"
@ -335,7 +335,7 @@
#endif
#ifndef CONFIG_PIC32MX_UART1PRIO /* UART 1 */
# define CONFIG_PIC32MX_UART1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_UART1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_UART1PRIO < 4
# error "CONFIG_PIC32MX_UART1PRIO is too small"
@ -345,7 +345,7 @@
#endif
#ifndef CONFIG_PIC32MX_UART2PRIO /* UART 2 */
# define CONFIG_PIC32MX_UART2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_UART2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_UART2PRIO < 4
# error "CONFIG_PIC32MX_UART2PRIO is too small"
@ -355,7 +355,7 @@
#endif
#ifndef CONFIG_PIC32MX_CNPRIO /* Input Change Interrupt */
# define CONFIG_PIC32MX_CNPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CNPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CNPRIO < 4
# error "CONFIG_PIC32MX_CNPRIO is too small"
@ -365,7 +365,7 @@
#endif
#ifndef CONFIG_PIC32MX_ADCPRIO /* ADC1 Convert Done */
# define CONFIG_PIC32MX_ADCPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_ADCPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_ADCPRIO < 4
# error "CONFIG_PIC32MX_ADCPRIO is too small"
@ -375,7 +375,7 @@
#endif
#ifndef CONFIG_PIC32MX_PMPPRIO /* Parallel Master Port */
# define CONFIG_PIC32MX_PMPPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_PMPPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_PMPPRIO < 4
# error "CONFIG_PIC32MX_PMPPRIO is too small"
@ -385,7 +385,7 @@
#endif
#ifndef CONFIG_PIC32MX_CM1PRIO /* Comparator 1 */
# define CONFIG_PIC32MX_CM1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CM1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CM1PRIO < 4
# error "CONFIG_PIC32MX_CM1PRIO is too small"
@ -395,7 +395,7 @@
#endif
#ifndef CONFIG_PIC32MX_CM2PRIO /* Comparator 2 */
# define CONFIG_PIC32MX_CM2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_CM2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_CM2PRIO < 4
# error "CONFIG_PIC32MX_CM2PRIO is too small"
@ -405,7 +405,7 @@
#endif
#ifndef CONFIG_PIC32MX_FSCMPRIO /* Fail-Safe Clock Monitor */
# define CONFIG_PIC32MX_FSCMPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_FSCMPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_FSCMPRIO < 4
# error "CONFIG_PIC32MX_FSCMPRIO is too small"
@ -415,7 +415,7 @@
#endif
#ifndef CONFIG_PIC32MX_RTCCPRIO /* Real-Time Clock and Calendar */
# define CONFIG_PIC32MX_RTCCPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_RTCCPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_RTCCPRIO < 4
# error "CONFIG_PIC32MX_RTCCPRIO is too small"
@ -425,7 +425,7 @@
#endif
#ifndef CONFIG_PIC32MX_DMA0PRIO /* DMA Channel 0 */
# define CONFIG_PIC32MX_DMA0PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_DMA0PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_DMA0PRIO < 4
# error "CONFIG_PIC32MX_DMA0PRIO is too small"
@ -435,7 +435,7 @@
#endif
#ifndef CONFIG_PIC32MX_DMA1PRIO /* DMA Channel 1 */
# define CONFIG_PIC32MX_DMA1PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_DMA1PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_DMA1PRIO < 4
# error "CONFIG_PIC32MX_DMA1PRIO is too small"
@ -445,7 +445,7 @@
#endif
#ifndef CONFIG_PIC32MX_DMA2PRIO /* DMA Channel 2 */
# define CONFIG_PIC32MX_DMA2PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_DMA2PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_DMA2PRIO < 4
# error "CONFIG_PIC32MX_DMA2PRIO is too small"
@ -455,7 +455,7 @@
#endif
#ifndef CONFIG_PIC32MX_DMA3PRIO /* DMA Channel 3 */
# define CONFIG_PIC32MX_DMA3PRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_DMA3PRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_DMA3PRIO < 4
# error "CONFIG_PIC32MX_DMA3PRIO is too small"
@ -465,7 +465,7 @@
#endif
#ifndef CONFIG_PIC32MX_FCEPRIO /* Flash Control Event */
# define CONFIG_PIC32MX_FCEPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_FCEPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_FCEPRIO < 4
# error "CONFIG_PIC32MX_FCEPRIO is too small"
@ -475,7 +475,7 @@
#endif
#ifndef CONFIG_PIC32MX_USBPRIO /* USB */
# define CONFIG_PIC32MX_USBPRIO (INT_ICP_MID_PRIORITY << 2)
# define CONFIG_PIC32MX_USBPRIO (INT_IPC_MID_PRIORITY << 2)
#endif
#if CONFIG_PIC32MX_USBPRIO < 4
# error "CONFIG_PIC32MX_USBPRIO is too small"
@ -602,7 +602,7 @@
#endif
#ifndef CONFIG_PIC32MX_SRSSEL /* Shadow register interrupt priority */
# define CONFIG_PIC32MX_SRSSEL INT_ICP_MIN_PRIORITY
# define CONFIG_PIC32MX_SRSSEL INT_IPC_MIN_PRIORITY
#endif
/* Unless overridden in the .config file, all pins are in the default setting */

View File

@ -1,237 +1,256 @@
/****************************************************************************
* arch/mips/src/pic32mx/pic32mx-devcfg.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_DEVCFG_H
#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_DEVCFG_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "pic32mx-memorymap.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Register Offsets *********************************************************/
#define PIC32MX_DEVCFG3_OFFSET 0x0000 /* Device configuration word 3 */
#define PIC32MX_DEVCFG2_OFFSET 0x0004 /* Device configuration word 2 */
#define PIC32MX_DEVCFG1_OFFSET 0x0008 /* Device configuration word 1 */
#define PIC32MX_DEVCFG0_OFFSET 0x000c /* Device configuration word 0 */
/* Register Addresses *******************************************************/
#define PIC32MX_DEVCFG3 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG3_OFFSET)
#define PIC32MX_DEVCFG2 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG2_OFFSET)
#define PIC32MX_DEVCFG1 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG1_OFFSET)
#define PIC32MX_DEVCFG0 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG0_OFFSET)
/* Register Bit-Field Definitions *******************************************/
/* Device configuration word 3 */
#define DEVCFG3_USERID_SHIFT (0) /* Bits 0-15: User-defined, readable via ICSP™ and JTAG */
#define DEVCFG3_USERID_MASK (0xffff << DEVCFG3_USERID_SHIFT)
#define DEVCFG3_FSRSSEL_SHIFT (16) /* Bits 16-18: SRS select */
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# define DEVCFG3_UNUSED 0xffff0000 /* Bits 16-31 */
#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define DEVCFG3_FSRSSEL_MASK (7 << DEVCFG3_FSRSSEL_SHIFT)
# define DEVCFG3_FMIIEN (1 << 24) /* Bit 24: Ethernet MII enable */
# define DEVCFG3_FETHIO (1 << 25) /* Bit 25: Ethernet I/O pin selection */
# define DEVCFG3_FCANIO (1 << 26) /* Bit 26: CAN I/O pin selection */
# define DEVCFG3_FSCM1IO (1 << 29) /* Bit 29: SCM1 pin C selection */
# define DEVCFG3_FUSBIDIO (1 << 30) /* Bit 30: USB USBID selection */
# define DEVCFG3_FVBUSIO (1 << 31) /* Bit 31: USB VBUSON selection */
# define DEVCFG3_UNUSED 0x18f80000 /* Bits 19-23, 27-28 */
#endif
/* Device configuration word 2 */
#define DEVCFG2_FPLLIDIV_SHIFT (0) /* Bits 0-2: PLL input divider value */
#define DEVCFG2_FPLLIDIV_MASK (7 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV1 (0 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV2 (1 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV3 (2 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV4 (3 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV5 (4 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV6 (5 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV10 (6 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV12 (7 << DEVCFG2_FPLLIDIV_SHIFT)
#define DEVCFG2_FPLLMULT_SHIFT (4) /* Bits 4-6: Initial PLL multiplier value */
#define DEVCFG2_FPLLMULT_MASK (7 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL15 (0 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL16 (1 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL17 (2 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL18 (3 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL19 (4 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL20 (5 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL21 (6 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL24 (7 << DEVCFG2_FPLLMULT_SHIFT)
#define DEVCFG2_FUPLLIDIV_SHIFT (8) /* Bits 8-10: PLL input divider */
#define DEVCFG2_FUPLLIDIV_MASK (7 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV1 (0 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV2 (1 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV3 (2 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV4 (3 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV5 (4 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV6 (5 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV10 (6 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV12 (7 << DEVCFG2_FUPLLIDIV_SHIFT)
#define DEVCFG2_FUPLLEN (1 << 15) /* Bit 15: USB PLL enable */
#define DEVCFG2_FPLLODIV_SHIFT (16) /* Bits 16-18: Default postscaler for PLL bits */
#define DEVCFG2_FPLLODIV_MASK (7 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV1 (0 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV2 (1 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV4 (2 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV8 (3 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV16 (4 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV32 (5 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV64 (6 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV256 (7 << DEVCFG2_FPLLODIV_SHIFT)
#define DEVCFG2_UNUSED 0xfff87888 /* Bits 3, 7, 11-14, 19-31 */
/* Device configuration word 1 */
#define DEVCFG1_FNOSC_SHIFT (0) /* Bits 0-2: Oscillator selection */
#define DEVCFG1_FNOSC_MASK (7 << DEVCFG1_FNOSC_SHIFT)
# define DEVCFG1_FNOSC_FRC (0 << DEVCFG1_FNOSC_SHIFT) /* FRC oscillator */
# define DEVCFG1_FNOSC_FRCPLL (1 << DEVCFG1_FNOSC_SHIFT) /* FRC w/PLL module */
# define DEVCFG1_FNOSC_POSC (2 << DEVCFG1_FNOSC_SHIFT) /* Primary oscillator */
# define DEVCFG1_FNOSC_POSCPLL (3 << DEVCFG1_FNOSC_SHIFT) /* Primary oscillator w/PLL */
# define DEVCFG1_FNOSC_SOSC (4 << DEVCFG1_FNOSC_SHIFT) /* Secondary oscillator */
# define DEVCFG1_FNOSC_LPRC (5 << DEVCFG1_FNOSC_SHIFT) /* Low power RC oscillator */
# define DEVCFG1_FNOSC_FRCDIV (7 << DEVCFG1_FNOSC_SHIFT) /* FRC oscillator with FRCDIV */
#define DEVCFG1_FSOSCEN (1 << 5) /* Bit 5: Secondary oscillator (sosc) enable bit */
#define DEVCFG1_IESO (1 << 7) /* Bit 7: Internal external switch over */
#define DEVCFG1_POSCMOD_SHIFT (8) /* Bits 8-9: Primary oscillator (posc) configuration */
#define DEVCFG1_POSCMOD_MASK (3 << DEVCFG1_POSCMOD_SHIFT)
# define DEVCFG1_POSCMOD_EC (0 << DEVCFG1_POSCMOD_SHIFT) /* EC mode */
# define DEVCFG1_POSCMOD_XT (1 << DEVCFG1_POSCMOD_SHIFT) /* XT mode */
# define DEVCFG1_POSCMOD_HS (2 << DEVCFG1_POSCMOD_SHIFT) /* HS mode */
# define DEVCFG1_POSCMOD_DIS (3 << DEVCFG1_POSCMOD_SHIFT) /* Primary Oscillator disabled */
#define DEVCFG1_OSCIOFNC (1 << 10) /* Bit 10: CLKO (clock-out) enable configuration */
#define DEVCFG1_FPBDIV_SHIFT (12) /* Bits 12-13: Peripheral bus clock divisor default value */
#define DEVCFG1_FPBDIV_MASK (3 << DEVCFG1_FPBDIV_SHIFT)
# define DEVCFG1_FPBDIV_DIV1 (0 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/1 */
# define DEVCFG1_FPBDIV_DIV2 (1 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/2 */
# define DEVCFG1_FPBDIV_DIV4 (2 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/4 */
# define DEVCFG1_FPBDIV_DIV8 (3 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK /8 */
#define DEVCFG1_FCKSM_SHIFT (14) /* Bits 14-15: Clock switching and monitor selection configuration */
#define DEVCFG1_FCKSM_MASK (3 << DEVCFG1_FCKSM_SHIFT)
# define DEVCFG1_FCKSM_BOTH (0 << DEVCFG1_FCKSM_SHIFT) /* Clock switching and FSCM are enabled */
# define DEVCFG1_FCKSM_CSONLY (1 << DEVCFG1_FCKSM_SHIFT) /* Clock switching is enabled, FSCM is disabled */
# define DEVCFG1_FCKSM_NONE (3 << DEVCFG1_FCKSM_SHIFT) /* Clock switching and FSCM are disabled */
#define DEVCFG1_WDTPS_SHIFT (16) /* Bits 16-20: WDT postscaler select */
#define DEVCFG1_WDTPS_MASK (31 << DEVCFG1_WDTPS_SHIFT)
# define DEVCFG1_WDTPS_1 (0 << DEVCFG1_WDTPS_SHIFT) /* 1:1 */
# define DEVCFG1_WDTPS_2 (1 << DEVCFG1_WDTPS_SHIFT) /* 1:2 */
# define DEVCFG1_WDTPS_4 (2 << DEVCFG1_WDTPS_SHIFT) /* 1:4 */
# define DEVCFG1_WDTPS_8 (3 << DEVCFG1_WDTPS_SHIFT) /* 1:8 */
# define DEVCFG1_WDTPS_16 (4 << DEVCFG1_WDTPS_SHIFT) /* 1:16 */
# define DEVCFG1_WDTPS_32 (5 << DEVCFG1_WDTPS_SHIFT) /* 1:32 */
# define DEVCFG1_WDTPS_64 (6 << DEVCFG1_WDTPS_SHIFT) /* 1:64 */
# define DEVCFG1_WDTPS_128 (7 << DEVCFG1_WDTPS_SHIFT) /* 1:128 */
# define DEVCFG1_WDTPS_256 (8 << DEVCFG1_WDTPS_SHIFT) /* 1:256 */
# define DEVCFG1_WDTPS_512 (9 << DEVCFG1_WDTPS_SHIFT) /* 1:512 */
# define DEVCFG1_WDTPS_1024 (10 << DEVCFG1_WDTPS_SHIFT) /* 1:1024 */
# define DEVCFG1_WDTPS_2048 (11 << DEVCFG1_WDTPS_SHIFT) /* 1:2048 */
# define DEVCFG1_WDTPS_4096 (12 << DEVCFG1_WDTPS_SHIFT) /* 1:4096 */
# define DEVCFG1_WDTPS_8192 (13 << DEVCFG1_WDTPS_SHIFT) /* 1:8192 */
# define DEVCFG1_WDTPS_16384 (14 << DEVCFG1_WDTPS_SHIFT) /* 1:16384 */
# define DEVCFG1_WDTPS_32768 (15 << DEVCFG1_WDTPS_SHIFT) /* 1:32768 */
# define DEVCFG1_WDTPS_65536 (16 << DEVCFG1_WDTPS_SHIFT) /* 1:65536 */
# define DEVCFG1_WDTPS_131072 (17 << DEVCFG1_WDTPS_SHIFT) /* 1:131072 */
# define DEVCFG1_WDTPS_262144 (18 << DEVCFG1_WDTPS_SHIFT) /* 1:262144 */
# define DEVCFG1_WDTPS_524288 (19 << DEVCFG1_WDTPS_SHIFT) /* 1:524288 */
# define DEVCFG1_WDTPS_1048576 (20 << DEVCFG1_WDTPS_SHIFT) /* 1:1048576 */
#define DEVCFG1_WINDIS (1 << 22) /* Bit 22: Windowed watchdog timer enable */
#define DEVCFG1_FWDTEN (1 << 23) /* Bit 23: WDT enable */
#define DEVCFG1_UNUSED 0xff200858 /* Bits 3-4, 6, 11, 21, 24-31 */
/* Device configuration word 0 */
#define PWP_CODE(a) (((~((a) >> 12)) - 1) & 0xff)
#define DEVCFG0_DEBUG_SHIFT (0) /* Bits 0-1: Background debugger enable */
#define DEVCFG0_DEBUG_MASK (3 << DEVCFG0_DEBUG_SHIFT)
# define DEVCFG0_DEBUG_ENABLED (2 << DEVCFG0_DEBUG_SHIFT)
# define DEVCFG0_DEBUG_DISABLED (3 << DEVCFG0_DEBUG_SHIFT)
#define DEVCFG0_ICESEL (1 << 3) /* Bit 3: ICE/debugger channel select */
#define DEVCFG0_PWP_SHIFT (12) /* Bits 12-19: Program flash write-protect */
#define DEVCFG0_PWP_MASK (0xff << DEVCFG0_PWP_SHIFT)
# define DEVCFG0_PWP_DISABLE (0xff << DEVCFG0_PWP_SHIFT)
# define DEVCFG0_PWP(code) ((code) << DEVCFG0_PWP_SHIFT) /* See PWP_CODE above */
#define DEVCFG0_BWP (1 << 24) /* Bit 24: Boot flash write-protect */
#define DEVCFG0_CP (1 << 28) /* Bit 28: Code-protect */
#define DEVCFG0_SIGN (1 << 31) /* Bit 31: Signature */
#define DEVCFG0_UNUSED 0x6ef00ff0 /* Bits 4-11, 20-23, 25-27, 29-30 */
/****************************************************************************
* 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_DEVCFG_H */
/****************************************************************************
* arch/mips/src/pic32mx/pic32mx-devcfg.h
*
* Copyright (C) 2011-2012 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_DEVCFG_H
#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_DEVCFG_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "pic32mx-memorymap.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Register Offsets *********************************************************/
#define PIC32MX_DEVCFG3_OFFSET 0x0000 /* Device configuration word 3 */
#define PIC32MX_DEVCFG2_OFFSET 0x0004 /* Device configuration word 2 */
#define PIC32MX_DEVCFG1_OFFSET 0x0008 /* Device configuration word 1 */
#define PIC32MX_DEVCFG0_OFFSET 0x000c /* Device configuration word 0 */
/* Register Addresses *******************************************************/
#define PIC32MX_DEVCFG3 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG3_OFFSET)
#define PIC32MX_DEVCFG2 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG2_OFFSET)
#define PIC32MX_DEVCFG1 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG1_OFFSET)
#define PIC32MX_DEVCFG0 (PIC32MX_DEVCFG_K1BASE+PIC32MX_DEVCFG0_OFFSET)
/* Register Bit-Field Definitions *******************************************/
/* Device configuration word 3 */
#define DEVCFG3_USERID_SHIFT (0) /* Bits 0-15: User-defined, readable via ICSP™ and JTAG */
#define DEVCFG3_USERID_MASK (0xffff << DEVCFG3_USERID_SHIFT)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define DEVCFG3_PMDL1WAY (1 << 28) /* Bit 28: Peripheral Module Disable Configuration */
# define DEVCFG3_IOL1WAY (1 << 29) /* Bit 29: Peripheral Pin Select Configuration */
# define DEVCFG3_FUSBIDIO (1 << 30) /* Bit 30: USB USBID selection */
# define DEVCFG3_FVBUSIO (1 << 31) /* Bit 31: USB VBUSON selection */
# define DEVCFG3_UNUSED 0x0fff0000 /* Bits 16-28 */
#elif defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# define DEVCFG3_UNUSED 0xffff0000 /* Bits 16-31 */
#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define DEVCFG3_FSRSSEL_SHIFT (16) /* Bits 16-18: SRS select */
# define DEVCFG3_FSRSSEL_MASK (7 << DEVCFG3_FSRSSEL_SHIFT)
# define DEVCFG3_FMIIEN (1 << 24) /* Bit 24: Ethernet MII enable */
# define DEVCFG3_FETHIO (1 << 25) /* Bit 25: Ethernet I/O pin selection */
# define DEVCFG3_FCANIO (1 << 26) /* Bit 26: CAN I/O pin selection */
# define DEVCFG3_FSCM1IO (1 << 29) /* Bit 29: SCM1 pin C selection */
# define DEVCFG3_FUSBIDIO (1 << 30) /* Bit 30: USB USBID selection */
# define DEVCFG3_FVBUSIO (1 << 31) /* Bit 31: USB VBUSON selection */
# define DEVCFG3_UNUSED 0x18f80000 /* Bits 19-23, 27-28 */
#endif
/* Device configuration word 2 */
#define DEVCFG2_FPLLIDIV_SHIFT (0) /* Bits 0-2: PLL input divider value */
#define DEVCFG2_FPLLIDIV_MASK (7 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV1 (0 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV2 (1 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV3 (2 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV4 (3 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV5 (4 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV6 (5 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV10 (6 << DEVCFG2_FPLLIDIV_SHIFT)
# define DEVCFG2_FPLLIDIV_DIV12 (7 << DEVCFG2_FPLLIDIV_SHIFT)
#define DEVCFG2_FPLLMULT_SHIFT (4) /* Bits 4-6: Initial PLL multiplier value */
#define DEVCFG2_FPLLMULT_MASK (7 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL15 (0 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL16 (1 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL17 (2 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL18 (3 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL19 (4 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL20 (5 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL21 (6 << DEVCFG2_FPLLMULT_SHIFT)
# define DEVCFG2_FPLLMULT_MUL24 (7 << DEVCFG2_FPLLMULT_SHIFT)
#define DEVCFG2_FUPLLIDIV_SHIFT (8) /* Bits 8-10: PLL input divider */
#define DEVCFG2_FUPLLIDIV_MASK (7 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV1 (0 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV2 (1 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV3 (2 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV4 (3 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV5 (4 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV6 (5 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV10 (6 << DEVCFG2_FUPLLIDIV_SHIFT)
# define DEVCFG2_FUPLLIDIV_DIV12 (7 << DEVCFG2_FUPLLIDIV_SHIFT)
#define DEVCFG2_FUPLLEN (1 << 15) /* Bit 15: USB PLL enable */
#define DEVCFG2_FPLLODIV_SHIFT (16) /* Bits 16-18: Default postscaler for PLL bits */
#define DEVCFG2_FPLLODIV_MASK (7 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV1 (0 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV2 (1 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV4 (2 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV8 (3 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV16 (4 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV32 (5 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV64 (6 << DEVCFG2_FPLLODIV_SHIFT)
# define DEVCFG2_FPLLODIV_DIV256 (7 << DEVCFG2_FPLLODIV_SHIFT)
#define DEVCFG2_UNUSED 0xfff87888 /* Bits 3, 7, 11-14, 19-31 */
/* Device configuration word 1 */
#define DEVCFG1_FNOSC_SHIFT (0) /* Bits 0-2: Oscillator selection */
#define DEVCFG1_FNOSC_MASK (7 << DEVCFG1_FNOSC_SHIFT)
# define DEVCFG1_FNOSC_FRC (0 << DEVCFG1_FNOSC_SHIFT) /* FRC oscillator */
# define DEVCFG1_FNOSC_FRCPLL (1 << DEVCFG1_FNOSC_SHIFT) /* FRC w/PLL module */
# define DEVCFG1_FNOSC_POSC (2 << DEVCFG1_FNOSC_SHIFT) /* Primary oscillator */
# define DEVCFG1_FNOSC_POSCPLL (3 << DEVCFG1_FNOSC_SHIFT) /* Primary oscillator w/PLL */
# define DEVCFG1_FNOSC_SOSC (4 << DEVCFG1_FNOSC_SHIFT) /* Secondary oscillator */
# define DEVCFG1_FNOSC_LPRC (5 << DEVCFG1_FNOSC_SHIFT) /* Low power RC oscillator */
# define DEVCFG1_FNOSC_FRCDIV (7 << DEVCFG1_FNOSC_SHIFT) /* FRC oscillator with FRCDIV */
#define DEVCFG1_FSOSCEN (1 << 5) /* Bit 5: Secondary oscillator (sosc) enable bit */
#define DEVCFG1_IESO (1 << 7) /* Bit 7: Internal external switch over */
#define DEVCFG1_POSCMOD_SHIFT (8) /* Bits 8-9: Primary oscillator (posc) configuration */
#define DEVCFG1_POSCMOD_MASK (3 << DEVCFG1_POSCMOD_SHIFT)
# define DEVCFG1_POSCMOD_EC (0 << DEVCFG1_POSCMOD_SHIFT) /* EC mode */
# define DEVCFG1_POSCMOD_XT (1 << DEVCFG1_POSCMOD_SHIFT) /* XT mode */
# define DEVCFG1_POSCMOD_HS (2 << DEVCFG1_POSCMOD_SHIFT) /* HS mode */
# define DEVCFG1_POSCMOD_DIS (3 << DEVCFG1_POSCMOD_SHIFT) /* Primary Oscillator disabled */
#define DEVCFG1_OSCIOFNC (1 << 10) /* Bit 10: CLKO (clock-out) enable configuration */
#define DEVCFG1_FPBDIV_SHIFT (12) /* Bits 12-13: Peripheral bus clock divisor default value */
#define DEVCFG1_FPBDIV_MASK (3 << DEVCFG1_FPBDIV_SHIFT)
# define DEVCFG1_FPBDIV_DIV1 (0 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/1 */
# define DEVCFG1_FPBDIV_DIV2 (1 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/2 */
# define DEVCFG1_FPBDIV_DIV4 (2 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK/4 */
# define DEVCFG1_FPBDIV_DIV8 (3 << DEVCFG1_FPBDIV_SHIFT) /* PBCLK is SYSCLK /8 */
#define DEVCFG1_FCKSM_SHIFT (14) /* Bits 14-15: Clock switching and monitor selection configuration */
#define DEVCFG1_FCKSM_MASK (3 << DEVCFG1_FCKSM_SHIFT)
# define DEVCFG1_FCKSM_BOTH (0 << DEVCFG1_FCKSM_SHIFT) /* Clock switching and FSCM are enabled */
# define DEVCFG1_FCKSM_CSONLY (1 << DEVCFG1_FCKSM_SHIFT) /* Clock switching is enabled, FSCM is disabled */
# define DEVCFG1_FCKSM_NONE (3 << DEVCFG1_FCKSM_SHIFT) /* Clock switching and FSCM are disabled */
#define DEVCFG1_WDTPS_SHIFT (16) /* Bits 16-20: WDT postscaler select */
#define DEVCFG1_WDTPS_MASK (31 << DEVCFG1_WDTPS_SHIFT)
# define DEVCFG1_WDTPS_1 (0 << DEVCFG1_WDTPS_SHIFT) /* 1:1 */
# define DEVCFG1_WDTPS_2 (1 << DEVCFG1_WDTPS_SHIFT) /* 1:2 */
# define DEVCFG1_WDTPS_4 (2 << DEVCFG1_WDTPS_SHIFT) /* 1:4 */
# define DEVCFG1_WDTPS_8 (3 << DEVCFG1_WDTPS_SHIFT) /* 1:8 */
# define DEVCFG1_WDTPS_16 (4 << DEVCFG1_WDTPS_SHIFT) /* 1:16 */
# define DEVCFG1_WDTPS_32 (5 << DEVCFG1_WDTPS_SHIFT) /* 1:32 */
# define DEVCFG1_WDTPS_64 (6 << DEVCFG1_WDTPS_SHIFT) /* 1:64 */
# define DEVCFG1_WDTPS_128 (7 << DEVCFG1_WDTPS_SHIFT) /* 1:128 */
# define DEVCFG1_WDTPS_256 (8 << DEVCFG1_WDTPS_SHIFT) /* 1:256 */
# define DEVCFG1_WDTPS_512 (9 << DEVCFG1_WDTPS_SHIFT) /* 1:512 */
# define DEVCFG1_WDTPS_1024 (10 << DEVCFG1_WDTPS_SHIFT) /* 1:1024 */
# define DEVCFG1_WDTPS_2048 (11 << DEVCFG1_WDTPS_SHIFT) /* 1:2048 */
# define DEVCFG1_WDTPS_4096 (12 << DEVCFG1_WDTPS_SHIFT) /* 1:4096 */
# define DEVCFG1_WDTPS_8192 (13 << DEVCFG1_WDTPS_SHIFT) /* 1:8192 */
# define DEVCFG1_WDTPS_16384 (14 << DEVCFG1_WDTPS_SHIFT) /* 1:16384 */
# define DEVCFG1_WDTPS_32768 (15 << DEVCFG1_WDTPS_SHIFT) /* 1:32768 */
# define DEVCFG1_WDTPS_65536 (16 << DEVCFG1_WDTPS_SHIFT) /* 1:65536 */
# define DEVCFG1_WDTPS_131072 (17 << DEVCFG1_WDTPS_SHIFT) /* 1:131072 */
# define DEVCFG1_WDTPS_262144 (18 << DEVCFG1_WDTPS_SHIFT) /* 1:262144 */
# define DEVCFG1_WDTPS_524288 (19 << DEVCFG1_WDTPS_SHIFT) /* 1:524288 */
# define DEVCFG1_WDTPS_1048576 (20 << DEVCFG1_WDTPS_SHIFT) /* 1:1048576 */
#define DEVCFG1_WINDIS (1 << 22) /* Bit 22: Windowed watchdog timer enable */
#define DEVCFG1_FWDTEN (1 << 23) /* Bit 23: WDT enable */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define DEVCFG1_FWDTWINSZ_SHIFT (24) /* Bits 24-25: Watchdog Timer Window Size bits */
# define DEVCFG1_FWDTWINSZ_MASK (3 << DEVCFG1_FWDTWINSZ_SHIFT)
# define DEVCFG1_FWDTWINSZ_25 (0 << DEVCFG1_FWDTWINSZ_SHIFT) /* 25% */
# define DEVCFG1_FWDTWINSZ_37p5 (1 << DEVCFG1_FWDTWINSZ_SHIFT) /* 37.5% */
# define DEVCFG1_FWDTWINSZ_50 (2 << DEVCFG1_FWDTWINSZ_SHIFT) /* 50% */
# define DEVCFG1_FWDTWINSZ_75 (3 << DEVCFG1_FWDTWINSZ_SHIFT) /* 75% */
# define DEVCFG1_UNUSED 0xfc200858 /* Bits 3-4, 6, 11, 21, 26-31 */
#else
# define DEVCFG1_UNUSED 0xff200858 /* Bits 3-4, 6, 11, 21, 24-31 */
#endif
/* Device configuration word 0 */
#define PWP_CODE(a) (((~((a) >> 12)) - 1) & 0xff)
#define DEVCFG0_DEBUG_SHIFT (0) /* Bits 0-1: Background debugger enable */
#define DEVCFG0_DEBUG_MASK (3 << DEVCFG0_DEBUG_SHIFT)
# define DEVCFG0_DEBUG_ENABLED (2 << DEVCFG0_DEBUG_SHIFT)
# define DEVCFG0_DEBUG_DISABLED (3 << DEVCFG0_DEBUG_SHIFT)
#define DEVCFG0_ICESEL (1 << 3) /* Bit 3: ICE/debugger channel select */
#define DEVCFG0_PWP_SHIFT (12) /* Bits 12-19: Program flash write-protect */
#define DEVCFG0_PWP_MASK (0xff << DEVCFG0_PWP_SHIFT)
# define DEVCFG0_PWP_DISABLE (0xff << DEVCFG0_PWP_SHIFT)
# define DEVCFG0_PWP(code) ((code) << DEVCFG0_PWP_SHIFT) /* See PWP_CODE above */
#define DEVCFG0_BWP (1 << 24) /* Bit 24: Boot flash write-protect */
#define DEVCFG0_CP (1 << 28) /* Bit 28: Code-protect */
#define DEVCFG0_SIGN (1 << 31) /* Bit 31: Signature */
#define DEVCFG0_UNUSED 0x6ef00ff0 /* Bits 4-11, 20-23, 25-27, 29-30 */
/****************************************************************************
* 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_DEVCFG_H */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -59,7 +59,7 @@
/* GPIO settings used in the configport, readport, writeport, etc.
*
* General encoding:
* MMxV IIxx RRRx PPPP
* MMxV IIDx RRRx PPPP
*/
#define GPIO_MODE_SHIFT (14) /* Bits 14-15: I/O mode */
@ -72,12 +72,20 @@
# define GPIO_VALUE_ONE (1 << 12)
# define GPIO_VALUE_ZERO (0)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define GPIO_PULLUP (1 << 11) /* Bit 11: Change notification pull-up */
#endif
#define GPIO_INT_SHIFT (10) /* Bits 10-11: Interrupt mode */
#define GPIO_INT_MASK (3 << GPIO_INT_SHIFT)
# define GPIO_INT_NONE (0 << GPIO_INT_SHIFT) /* Bit 00: No interrupt */
# define GPIO_INT (1 << GPIO_INT_SHIFT) /* Bit 01: Change notification enable */
# define GPIO_PUINT (3 << GPIO_INT_SHIFT) /* Bit 11: Pulled-up interrupt input */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define GPIO_PULLDOWN (1 << 9) /* Bit 11: Change notification pull-down */
#endif
#define GPIO_PORT_SHIFT (5) /* Bits 5-7: Port number */
#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
# define GPIO_PORTA (0 << GPIO_PORT_SHIFT)

View File

@ -49,42 +49,92 @@
* Pre-Processor Definitions
********************************************************************************************/
/* Register Offsets *************************************************************************/
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
/* Offsets relative to PIC32MX_IOPORTn_K1BASE */
#define PIC32MX_IOPORT_TRIS_OFFSET 0x0000 /* Tri-state register */
#define PIC32MX_IOPORT_TRISCLR_OFFSET 0x0004 /* Tri-state clear register */
#define PIC32MX_IOPORT_TRISSET_OFFSET 0x0008 /* Tri-state set register */
#define PIC32MX_IOPORT_TRISINV_OFFSET 0x000c /* Tri-state invert register */
#define PIC32MX_IOPORT_PORT_OFFSET 0x0010 /* Port register */
#define PIC32MX_IOPORT_PORTCLR_OFFSET 0x0014 /* Port clear register */
#define PIC32MX_IOPORT_PORTSET_OFFSET 0x0018 /* Port set register */
#define PIC32MX_IOPORT_PORTINV_OFFSET 0x001c /* Port invert register */
#define PIC32MX_IOPORT_LAT_OFFSET 0x0020 /* Port data latch register */
#define PIC32MX_IOPORT_LATCLR_OFFSET 0x0024 /* Port data latch clear register */
#define PIC32MX_IOPORT_LATSET_OFFSET 0x0028 /* Port data latch set register */
#define PIC32MX_IOPORT_LATINV_OFFSET 0x002c /* Port data latch invert register */
#define PIC32MX_IOPORT_ODC_OFFSET 0x0030 /* Open drain control register */
#define PIC32MX_IOPORT_ODCCLR_OFFSET 0x0034 /* Open drain control clear register */
#define PIC32MX_IOPORT_ODCSET_OFFSET 0x0038 /* Open drain control set register */
#define PIC32MX_IOPORT_ODCINV_OFFSET 0x003c /* Open drain control invert register */
# define PIC32MX_IOPORT_ANSEL_OFFSET 0x0000 /* Analog select register */
# define PIC32MX_IOPORT_ANSELCLR_OFFSET 0x0004 /* Analog select clear register */
# define PIC32MX_IOPORT_ANSELSET_OFFSET 0x0008 /* Analog select set register */
# define PIC32MX_IOPORT_ANSELINV_OFFSET 0x000c /* Analog select invert register */
# define PIC32MX_IOPORT_TRIS_OFFSET 0x0010 /* Tri-state register */
# define PIC32MX_IOPORT_TRISCLR_OFFSET 0x0014 /* Tri-state clear register */
# define PIC32MX_IOPORT_TRISSET_OFFSET 0x0018 /* Tri-state set register */
# define PIC32MX_IOPORT_TRISINV_OFFSET 0x001c /* Tri-state invert register */
# define PIC32MX_IOPORT_PORT_OFFSET 0x0020 /* Port register */
# define PIC32MX_IOPORT_PORTCLR_OFFSET 0x0024 /* Port clear register */
# define PIC32MX_IOPORT_PORTSET_OFFSET 0x0028 /* Port set register */
# define PIC32MX_IOPORT_PORTINV_OFFSET 0x002c /* Port invert register */
# define PIC32MX_IOPORT_LAT_OFFSET 0x0030 /* Port data latch register */
# define PIC32MX_IOPORT_LATCLR_OFFSET 0x0034 /* Port data latch clear register */
# define PIC32MX_IOPORT_LATSET_OFFSET 0x0038 /* Port data latch set register */
# define PIC32MX_IOPORT_LATINV_OFFSET 0x003c /* Port data latch invert register */
# define PIC32MX_IOPORT_ODC_OFFSET 0x0040 /* Open drain control register */
# define PIC32MX_IOPORT_ODCCLR_OFFSET 0x0044 /* Open drain control clear register */
# define PIC32MX_IOPORT_ODCSET_OFFSET 0x0048 /* Open drain control set register */
# define PIC32MX_IOPORT_ODCINV_OFFSET 0x004c /* Open drain control invert register */
# define PIC32MX_IOPORT_CNPU_OFFSET 0x0050 /* Change Notification Pull-up register */
# define PIC32MX_IOPORT_CNPUCLR_OFFSET 0x0054 /* Change Notification Pull-up clear register */
# define PIC32MX_IOPORT_CNPUSET_OFFSET 0x0058 /* Change Notification Pull-up set register */
# define PIC32MX_IOPORT_CNPUINV_OFFSET 0x005c /* Change Notification Pull-up invert register */
# define PIC32MX_IOPORT_CNPD_OFFSET 0x0060 /* Change Notification Pull-down register */
# define PIC32MX_IOPORT_CNPDCLR_OFFSET 0x0064 /* Change Notification Pull-down clear register */
# define PIC32MX_IOPORT_CNPDSET_OFFSET 0x0068 /* Change Notification Pull-down set register */
# define PIC32MX_IOPORT_CNPDINV_OFFSET 0x006c /* Change Notification Pull-down invert register */
# define PIC32MX_IOPORT_CNCON_OFFSET 0x0070 /* Change Notification Control register */
# define PIC32MX_IOPORT_CNCONCLR_OFFSET 0x0074 /* Change Notification Control clear register */
# define PIC32MX_IOPORT_CNCONSET_OFFSET 0x0078 /* Change Notification Control set register */
# define PIC32MX_IOPORT_CNCONINV_OFFSET 0x007c /* Change Notification Control invert register */
# define PIC32MX_IOPORT_CNEN_OFFSET 0x0080 /* Change Notification Interrupt Enable register */
# define PIC32MX_IOPORT_CNENCLR_OFFSET 0x0084 /* Change Notification Interrupt Enable clear register */
# define PIC32MX_IOPORT_CNENSET_OFFSET 0x0088 /* Change Notification Interrupt Enable set register */
# define PIC32MX_IOPORT_CNENINV_OFFSET 0x008c /* Change Notification Interrupt Enable *invert register */
#else
/* Offsets relative to PIC32MX_IOPORTn_K1BASE */
# define PIC32MX_IOPORT_TRIS_OFFSET 0x0000 /* Tri-state register */
# define PIC32MX_IOPORT_TRISCLR_OFFSET 0x0004 /* Tri-state clear register */
# define PIC32MX_IOPORT_TRISSET_OFFSET 0x0008 /* Tri-state set register */
# define PIC32MX_IOPORT_TRISINV_OFFSET 0x000c /* Tri-state invert register */
# define PIC32MX_IOPORT_PORT_OFFSET 0x0010 /* Port register */
# define PIC32MX_IOPORT_PORTCLR_OFFSET 0x0014 /* Port clear register */
# define PIC32MX_IOPORT_PORTSET_OFFSET 0x0018 /* Port set register */
# define PIC32MX_IOPORT_PORTINV_OFFSET 0x001c /* Port invert register */
# define PIC32MX_IOPORT_LAT_OFFSET 0x0020 /* Port data latch register */
# define PIC32MX_IOPORT_LATCLR_OFFSET 0x0024 /* Port data latch clear register */
# define PIC32MX_IOPORT_LATSET_OFFSET 0x0028 /* Port data latch set register */
# define PIC32MX_IOPORT_LATINV_OFFSET 0x002c /* Port data latch invert register */
# define PIC32MX_IOPORT_ODC_OFFSET 0x0030 /* Open drain control register */
# define PIC32MX_IOPORT_ODCCLR_OFFSET 0x0034 /* Open drain control clear register */
# define PIC32MX_IOPORT_ODCSET_OFFSET 0x0038 /* Open drain control set register */
# define PIC32MX_IOPORT_ODCINV_OFFSET 0x003c /* Open drain control invert register */
/* Offsets relative to PIC32MX_IOPORTCN_K1BASE */
#define PIC32MX_IOPORT_CNCON_OFFSET 0x0000 /* Interrupt-on-change control register */
#define PIC32MX_IOPORT_CNCONCLR_OFFSET 0x0004 /* Interrupt-on-change control clear register */
#define PIC32MX_IOPORT_CNCONSET_OFFSET 0x0008 /* Interrupt-on-change control set register */
#define PIC32MX_IOPORT_CNCONINV_OFFSET 0x000c /* Interrupt-on-change control invert register */
#define PIC32MX_IOPORT_CNEN_OFFSET 0x0010 /* Input change notification interrupt enable */
#define PIC32MX_IOPORT_CNENCLR_OFFSET 0x0014 /* Input change notification interrupt enable clear */
#define PIC32MX_IOPORT_CNENSET_OFFSET 0x0018 /* Input change notification interrupt enable set */
#define PIC32MX_IOPORT_CNENINV_OFFSET 0x001c /* Input change notification interrupt enable invert */
#define PIC32MX_IOPORT_CNPUE_OFFSET 0x0020 /* Input change notification pull-up enable */
#define PIC32MX_IOPORT_CNPUECLR_OFFSET 0x0024 /* Input change notification pull-up enable clear */
#define PIC32MX_IOPORT_CNPUESET_OFFSET 0x0028 /* Input change notification pull-up enable set */
#define PIC32MX_IOPORT_CNPUEINV_OFFSET 0x002c /* Input change notification pull-up enable invert */
# define PIC32MX_IOPORT_CNCON_OFFSET 0x0000 /* Interrupt-on-change control register */
# define PIC32MX_IOPORT_CNCONCLR_OFFSET 0x0004 /* Interrupt-on-change control clear register */
# define PIC32MX_IOPORT_CNCONSET_OFFSET 0x0008 /* Interrupt-on-change control set register */
# define PIC32MX_IOPORT_CNCONINV_OFFSET 0x000c /* Interrupt-on-change control invert register */
# define PIC32MX_IOPORT_CNEN_OFFSET 0x0010 /* Input change notification interrupt enable */
# define PIC32MX_IOPORT_CNENCLR_OFFSET 0x0014 /* Input change notification interrupt enable clear */
# define PIC32MX_IOPORT_CNENSET_OFFSET 0x0018 /* Input change notification interrupt enable set */
# define PIC32MX_IOPORT_CNENINV_OFFSET 0x001c /* Input change notification interrupt enable invert */
# define PIC32MX_IOPORT_CNPUE_OFFSET 0x0020 /* Input change notification pull-up enable */
# define PIC32MX_IOPORT_CNPUECLR_OFFSET 0x0024 /* Input change notification pull-up enable clear */
# define PIC32MX_IOPORT_CNPUESET_OFFSET 0x0028 /* Input change notification pull-up enable set */
# define PIC32MX_IOPORT_CNPUEINV_OFFSET 0x002c /* Input change notification pull-up enable invert */
#endif
/* Register Addresses ***********************************************************************/
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORT_ANSEL(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ANSEL_OFFSET)
# define PIC32MX_IOPORT_ANSELCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ANSELCLR_OFFSET)
# define PIC32MX_IOPORT_ANSELSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ANSELSET_OFFSET)
# define PIC32MX_IOPORT_ANSELINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ANSELINV_OFFSET)
#endif
#define PIC32MX_IOPORT_TRIS(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_TRIS_OFFSET)
#define PIC32MX_IOPORT_TRISCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_TRISCLR_OFFSET)
#define PIC32MX_IOPORT_TRISSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_TRISSET_OFFSET)
@ -102,6 +152,32 @@
#define PIC32MX_IOPORT_ODCSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ODCSET_OFFSET)
#define PIC32MX_IOPORT_ODCINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_ODCINV_OFFSET)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORT_CNPU(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPU_OFFSET)
# define PIC32MX_IOPORT_CNPUCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPUCLR_OFFSET)
# define PIC32MX_IOPORT_CNPUSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPUSET_OFFSET)
# define PIC32MX_IOPORT_CNPUINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPUINV_OFFSET)
# define PIC32MX_IOPORT_CNPD(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPD_OFFSET)
# define PIC32MX_IOPORT_CNPDCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPDCLR_OFFSET)
# define PIC32MX_IOPORT_CNPDSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPDSET_OFFSET)
# define PIC32MX_IOPORT_CNPDINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNPDINV_OFFSET)
# define PIC32MX_IOPORT_CNCON(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNCON_OFFSET)
# define PIC32MX_IOPORT_CNCONCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNCONCLR_OFFSET)
# define PIC32MX_IOPORT_CNCONSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNCONSET_OFFSET)
# define PIC32MX_IOPORT_CNCONINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNCONINV_OFFSET)
# define PIC32MX_IOPORT_CNEN(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNEN_OFFSET)
# define PIC32MX_IOPORT_CNENCLR(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNENCLR_OFFSET)
# define PIC32MX_IOPORT_CNENSET(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNENSET_OFFSET)
# define PIC32MX_IOPORT_CNENINV(n) (PIC32MX_IOPORT_K1BASE(n)+PIC32MX_IOPORT_CNENINV_OFFSET)
#endif
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTA_ANSEL (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ANSEL_OFFSET)
# define PIC32MX_IOPORTA_ANSELCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ANSELCLR_OFFSET)
# define PIC32MX_IOPORTA_ANSELSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ANSELSET_OFFSET)
# define PIC32MX_IOPORTA_ANSELINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ANSELINV_OFFSET)
#endif
#define PIC32MX_IOPORTA_TRIS (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_TRIS_OFFSET)
#define PIC32MX_IOPORTA_TRISCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_TRISCLR_OFFSET)
#define PIC32MX_IOPORTA_TRISSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_TRISSET_OFFSET)
@ -119,6 +195,32 @@
#define PIC32MX_IOPORTA_ODCSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ODCSET_OFFSET)
#define PIC32MX_IOPORTA_ODCINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_ODCINV_OFFSET)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTA_CNPU (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPU_OFFSET)
# define PIC32MX_IOPORTA_CNPUCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPUCLR_OFFSET)
# define PIC32MX_IOPORTA_CNPUSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPUSET_OFFSET)
# define PIC32MX_IOPORTA_CNPUINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPUINV_OFFSET)
# define PIC32MX_IOPORTA_CNPD (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPD_OFFSET)
# define PIC32MX_IOPORTA_CNPDCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPDCLR_OFFSET)
# define PIC32MX_IOPORTA_CNPDSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPDSET_OFFSET)
# define PIC32MX_IOPORTA_CNPDINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNPDINV_OFFSET)
# define PIC32MX_IOPORTA_CNCON (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNCON_OFFSET)
# define PIC32MX_IOPORTA_CNCONCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNCONCLR_OFFSET)
# define PIC32MX_IOPORTA_CNCONSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNCONSET_OFFSET)
# define PIC32MX_IOPORTA_CNCONINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNCONINV_OFFSET)
# define PIC32MX_IOPORTA_CNEN (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNEN_OFFSET)
# define PIC32MX_IOPORTA_CNENCLR (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNENCLR_OFFSET)
# define PIC32MX_IOPORTA_CNENSET (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNENSET_OFFSET)
# define PIC32MX_IOPORTA_CNENINV (PIC32MX_IOPORTA_K1BASE+PIC32MX_IOPORT_CNENINV_OFFSET)
#endif
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTB_ANSEL (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ANSEL_OFFSET)
# define PIC32MX_IOPORTB_ANSELCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ANSELCLR_OFFSET)
# define PIC32MX_IOPORTB_ANSELSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ANSELSET_OFFSET)
# define PIC32MX_IOPORTB_ANSELINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ANSELINV_OFFSET)
#endif
#define PIC32MX_IOPORTB_TRIS (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_TRIS_OFFSET)
#define PIC32MX_IOPORTB_TRISCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_TRISCLR_OFFSET)
#define PIC32MX_IOPORTB_TRISSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_TRISSET_OFFSET)
@ -136,6 +238,32 @@
#define PIC32MX_IOPORTB_ODCSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ODCSET_OFFSET)
#define PIC32MX_IOPORTB_ODCINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_ODCINV_OFFSET)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTB_CNPU (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPU_OFFSET)
# define PIC32MX_IOPORTB_CNPUCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPUCLR_OFFSET)
# define PIC32MX_IOPORTB_CNPUSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPUSET_OFFSET)
# define PIC32MX_IOPORTB_CNPUINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPUINV_OFFSET)
# define PIC32MX_IOPORTB_CNPD (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPD_OFFSET)
# define PIC32MX_IOPORTB_CNPDCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPDCLR_OFFSET)
# define PIC32MX_IOPORTB_CNPDSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPDSET_OFFSET)
# define PIC32MX_IOPORTB_CNPDINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNPDINV_OFFSET)
# define PIC32MX_IOPORTB_CNCON (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNCON_OFFSET)
# define PIC32MX_IOPORTB_CNCONCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNCONCLR_OFFSET)
# define PIC32MX_IOPORTB_CNCONSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNCONSET_OFFSET)
# define PIC32MX_IOPORTB_CNCONINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNCONINV_OFFSET)
# define PIC32MX_IOPORTB_CNEN (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNEN_OFFSET)
# define PIC32MX_IOPORTB_CNENCLR (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNENCLR_OFFSET)
# define PIC32MX_IOPORTB_CNENSET (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNENSET_OFFSET)
# define PIC32MX_IOPORTB_CNENINV (PIC32MX_IOPORTB_K1BASE+PIC32MX_IOPORT_CNENINV_OFFSET)
#endif
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTC_ANSEL (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ANSEL_OFFSET)
# define PIC32MX_IOPORTC_ANSELCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ANSELCLR_OFFSET)
# define PIC32MX_IOPORTC_ANSELSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ANSELSET_OFFSET)
# define PIC32MX_IOPORTC_ANSELINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ANSELINV_OFFSET)
#endif
#define PIC32MX_IOPORTC_TRIS (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_TRIS_OFFSET)
#define PIC32MX_IOPORTC_TRISCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_TRISCLR_OFFSET)
#define PIC32MX_IOPORTC_TRISSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_TRISSET_OFFSET)
@ -153,6 +281,25 @@
#define PIC32MX_IOPORTC_ODCSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ODCSET_OFFSET)
#define PIC32MX_IOPORTC_ODCINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_ODCINV_OFFSET)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORTC_CNPU (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPU_OFFSET)
# define PIC32MX_IOPORTC_CNPUCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPUCLR_OFFSET)
# define PIC32MX_IOPORTC_CNPUSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPUSET_OFFSET)
# define PIC32MX_IOPORTC_CNPUINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPUINV_OFFSET)
# define PIC32MX_IOPORTC_CNPD (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPD_OFFSET)
# define PIC32MX_IOPORTC_CNPDCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPDCLR_OFFSET)
# define PIC32MX_IOPORTC_CNPDSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPDSET_OFFSET)
# define PIC32MX_IOPORTC_CNPDINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNPDINV_OFFSET)
# define PIC32MX_IOPORTC_CNCON (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNCON_OFFSET)
# define PIC32MX_IOPORTC_CNCONCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNCONCLR_OFFSET)
# define PIC32MX_IOPORTC_CNCONSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNCONSET_OFFSET)
# define PIC32MX_IOPORTC_CNCONINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNCONINV_OFFSET)
# define PIC32MX_IOPORTC_CNEN (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNEN_OFFSET)
# define PIC32MX_IOPORTC_CNENCLR (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNENCLR_OFFSET)
# define PIC32MX_IOPORTC_CNENSET (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNENSET_OFFSET)
# define PIC32MX_IOPORTC_CNENINV (PIC32MX_IOPORTC_K1BASE+PIC32MX_IOPORT_CNENINV_OFFSET)
#endif
#define PIC32MX_IOPORTD_TRIS (PIC32MX_IOPORTD_K1BASE+PIC32MX_IOPORT_TRIS_OFFSET)
#define PIC32MX_IOPORTD_TRISCLR (PIC32MX_IOPORTD_K1BASE+PIC32MX_IOPORT_TRISCLR_OFFSET)
#define PIC32MX_IOPORTD_TRISSET (PIC32MX_IOPORTD_K1BASE+PIC32MX_IOPORT_TRISSET_OFFSET)
@ -221,21 +368,29 @@
#define PIC32MX_IOPORTG_ODCSET (PIC32MX_IOPORTG_K1BASE+PIC32MX_IOPORT_ODCSET_OFFSET)
#define PIC32MX_IOPORTG_ODCINV (PIC32MX_IOPORTG_K1BASE+PIC32MX_IOPORT_ODCINV_OFFSET)
#define PIC32MX_IOPORT_CNCON (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCON_OFFSET)
#define PIC32MX_IOPORT_CNCONCLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONCLR_OFFSET)
#define PIC32MX_IOPORT_CNCONSET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONSET_OFFSET)
#define PIC32MX_IOPORT_CNCONINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONINV_OFFSET)
#define PIC32MX_IOPORT_CNEN (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNEN_OFFSET)
#define PIC32MX_IOPORT_CNENCLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENCLR_OFFSET)
#define PIC32MX_IOPORT_CNENSET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENSET_OFFSET)
#define PIC32MX_IOPORT_CNENINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENINV_OFFSET)
#define PIC32MX_IOPORT_CNPUE (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUE_OFFSET)
#define PIC32MX_IOPORT_CNPUECLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUECLR_OFFSET)
#define PIC32MX_IOPORT_CNPUESET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUESET_OFFSET)
#define PIC32MX_IOPORT_CNPUEINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUEINV_OFFSET)
#if !defined(CHIP_PIC32MX1) && !defined(CHIP_PIC32MX2)
# define PIC32MX_IOPORT_CNCON (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCON_OFFSET)
# define PIC32MX_IOPORT_CNCONCLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONCLR_OFFSET)
# define PIC32MX_IOPORT_CNCONSET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONSET_OFFSET)
# define PIC32MX_IOPORT_CNCONINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNCONINV_OFFSET)
# define PIC32MX_IOPORT_CNEN (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNEN_OFFSET)
# define PIC32MX_IOPORT_CNENCLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENCLR_OFFSET)
# define PIC32MX_IOPORT_CNENSET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENSET_OFFSET)
# define PIC32MX_IOPORT_CNENINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNENINV_OFFSET)
# define PIC32MX_IOPORT_CNPUE (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUE_OFFSET)
# define PIC32MX_IOPORT_CNPUECLR (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUECLR_OFFSET)
# define PIC32MX_IOPORT_CNPUESET (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUESET_OFFSET)
# define PIC32MX_IOPORT_CNPUEINV (PIC32MX_IOPORTCN_K1BASE+PIC32MX_IOPORT_CNPUEINV_OFFSET)
#endif
/* Register Bit-Field Definitions ***********************************************************/
/* Analog select register */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define IOPORT_ANSEL(n) (1 << (n)) /* Bits 0-15: Analog select */
#endif
/* Tri-state register */
#define IOPORT_TRIS(n) (1 << (n)) /* Bits 0-15: 1: Input 0: Output */
@ -252,26 +407,46 @@
#define IOPORT_ODC(n) (1 << (n)) /* Bits 0-15: 1: OD output enabled, 0: Disabled */
/* Interrupt-on-change control register */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
/* Change Notification Pull-up register */
#define IOPORT_CNCON_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
#define IOPORT_CNCON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode */
#define IOPORT_CNCON_ON (1 << 15) /* Bit 15: Change notice module enable */
# define IOPORT_CNPU(n) (1 << (n)) /* Bits 0:15: 1=Pull-up enabled */
/* Input change notification interrupt enable */
/* Change Notification Pull-down register */
#define IOPORT_CNEN(n) (1 << (n)) /* Bits 0-18/21: Port pin input change notice enabled */
# define IOPORT_CNPD(n) (1 << (n)) /* Bits 0:15: 1=Pull-down enabled */
/* Input change notification pull-up enable */
/* Change Notification Control register */
#define IOPORT_CNPUE(n) (1 << (n)) /* Bits 0-18/21: Port pin pull-up enabled */
# define IOPORT_CNCON_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
# define IOPORT_CNCON_ON (1 << 15) /* Bit 15: Change notice module enable */
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# define IOPORT_CN_ALL 0x0007ffff /* Bits 0-18 */
# define IOPORT_NUMCN 19
#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define IOPORT_CN_ALL 0x003fffff /* Bits 0-21 */
# define IOPORT_NUMCN 22
/* Change Notification Interrupt Enable register */
# define IOPORT_CNEN(n) (1 << (n)) /* Bits 0:15: 1=Interrupt enabled */
#else
/* Interrupt-on-change control register */
# define IOPORT_CNCON_SIDL (1 << 13) /* Bit 13: Stop in idle mode */
# define IOPORT_CNCON_FRZ (1 << 14) /* Bit 14: Freeze in debug exception mode */
# define IOPORT_CNCON_ON (1 << 15) /* Bit 15: Change notice module enable */
/* Input change notification interrupt enable */
# define IOPORT_CNEN(n) (1 << (n)) /* Bits 0-18/21: Port pin input change notice enabled */
/* Input change notification pull-up enable */
# define IOPORT_CNPUE(n) (1 << (n)) /* Bits 0-18/21: Port pin pull-up enabled */
# if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# define IOPORT_CN_ALL 0x0007ffff /* Bits 0-18 */
# define IOPORT_NUMCN 19
# elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define IOPORT_CN_ALL 0x003fffff /* Bits 0-21 */
# define IOPORT_NUMCN 22
# endif
#endif
/********************************************************************************************

View File

@ -105,7 +105,7 @@ void up_irqinitialize(void)
for (irq = 0; irq < NR_IRQS; irq++)
{
(void)up_prioritize_irq(irq, (INT_ICP_MID_PRIORITY << 2));
(void)up_prioritize_irq(irq, (INT_IPC_MID_PRIORITY << 2));
}
/* Set the BEV bit in the STATUS register */

View File

@ -48,41 +48,177 @@
/************************************************************************************
* Pre-Processor Definitions
************************************************************************************/
/* Physical Memory Map **************************************************************/
/* This top-level memory map is valid for the PIC32MX1xx/2xx families. */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_DATAMEM_PBASE 0x00000000 /* Size depends on CHIP_DATAMEM_KB */
# define PIC32MX_PROGFLASH_PBASE 0x1d000000 /* Size depends on CHIP_PROGFLASH_KB */
# define PIC32MX_SFR_PBASE 0x1f800000 /* Special function registers */
# define PIC32MX_BOOTFLASH_PBASE 0x1fc00000 /* Size depends on CHIP_BOOTFLASH_KB */
# define PIC32MX_DEVCFG_PBASE 0x1fc00bf0 /* Device configuration registers */
/* This top-level memory map is valid for the PIC32MX3xx/4xx as well as the
* PIC32MX5xx/6xx/7xx families.
*/
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4) || defined(CHIP_PIC32MX5) || \
#elif defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4) || defined(CHIP_PIC32MX5) || \
defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
/* Physical Memory Map **************************************************************/
# define PIC32MX_DATAMEM_PBASE 0x00000000 /* Size depends on CHIP_DATAMEM_KB */
# define PIC32MX_PROGFLASH_PBASE 0x1d000000 /* Size depends on CHIP_PROGFLASH_KB */
# define PIC32MX_SFR_PBASE 0x1f800000 /* Special function registers */
# define PIC32MX_BOOTFLASH_PBASE 0x1fc00000 /* Size depends on CHIP_BOOTFLASH_KB */
# define PIC32MX_DEVCFG_PBASE 0x1fc02ff0 /* Device configuration registers */
/* Virtual Memory Map ***************************************************************/
# define PIC32MX_DATAMEM_K0BASE (KSEG0_BASE + PIC32MX_DATAMEM_PBASE)
# define PIC32MX_PROGFLASH_K0BASE (KSEG0_BASE + PIC32MX_PROGFLASH_PBASE)
# define PIC32MX_BOOTFLASH_K0BASE (KSEG0_BASE + PIC32MX_BOOTFLASH_PBASE)
# define PIC32MX_DEVCFG_K0BASE (KSEG0_BASE + PIC32MX_DEVCFG_PBASE)
# define PIC32MX_DATAMEM_K1BASE (KSEG1_BASE + PIC32MX_DATAMEM_PBASE)
# define PIC32MX_PROGFLASH_K1BASE (KSEG1_BASE + PIC32MX_PROGFLASH_PBASE)
# define PIC32MX_SFR_K1BASE (KSEG1_BASE + PIC32MX_SFR_PBASE)
# define PIC32MX_BOOTFLASH_K1BASE (KSEG1_BASE + PIC32MX_BOOTFLASH_PBASE)
# define PIC32MX_DEVCFG_K1BASE (KSEG1_BASE + PIC32MX_DEVCFG_PBASE)
#else
# error "Memory map unknown for this PIC32 chip"
#endif
/* Virtual Memory Map ***************************************************************/
#define PIC32MX_DATAMEM_K0BASE (KSEG0_BASE + PIC32MX_DATAMEM_PBASE)
#define PIC32MX_PROGFLASH_K0BASE (KSEG0_BASE + PIC32MX_PROGFLASH_PBASE)
#define PIC32MX_BOOTFLASH_K0BASE (KSEG0_BASE + PIC32MX_BOOTFLASH_PBASE)
#define PIC32MX_DEVCFG_K0BASE (KSEG0_BASE + PIC32MX_DEVCFG_PBASE)
#define PIC32MX_DATAMEM_K1BASE (KSEG1_BASE + PIC32MX_DATAMEM_PBASE)
#define PIC32MX_PROGFLASH_K1BASE (KSEG1_BASE + PIC32MX_PROGFLASH_PBASE)
#define PIC32MX_SFR_K1BASE (KSEG1_BASE + PIC32MX_SFR_PBASE)
#define PIC32MX_BOOTFLASH_K1BASE (KSEG1_BASE + PIC32MX_BOOTFLASH_PBASE)
#define PIC32MX_DEVCFG_K1BASE (KSEG1_BASE + PIC32MX_DEVCFG_PBASE)
/* Register Base Addresses **********************************************************/
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
/* Watchdog Register Base Address */
# define PIC32MX_WDT_K1BASE (PIC32MX_SFR_K1BASE + 0x00000000)
/* RTCC Register Base Address */
# define PIC32MX_RTCC_K1BASE (PIC32MX_SFR_K1BASE + 0x00000200)
/* Timer 1-5 Register Base Addresses */
# define PIC32MX_TIMER_K1BASE(n) (PIC32MX_SFR_K1BASE + 0x00000600 + 0x200*(n-1))
# define PIC32MX_TIMER1_K1BASE (PIC32MX_SFR_K1BASE + 0x00000600)
# define PIC32MX_TIMER2_K1BASE (PIC32MX_SFR_K1BASE + 0x00000800)
# define PIC32MX_TIMER3_K1BASE (PIC32MX_SFR_K1BASE + 0x00000a00)
# define PIC32MX_TIMER4_K1BASE (PIC32MX_SFR_K1BASE + 0x00000c00)
# define PIC32MX_TIMER5_K1BASE (PIC32MX_SFR_K1BASE + 0x00000e00)
/* Input Capture 1-5 Register Base Addresses */
# define PIC32MX_IC_K1BASE(n) (PIC32MX_SFR_K1BASE + 0x00002000 + 0x200*(n-1))
# define PIC32MX_IC1_K1BASE (PIC32MX_SFR_K1BASE + 0x00002000)
# define PIC32MX_IC2_K1BASE (PIC32MX_SFR_K1BASE + 0x00002200)
# define PIC32MX_IC3_K1BASE (PIC32MX_SFR_K1BASE + 0x00002400)
# define PIC32MX_IC4_K1BASE (PIC32MX_SFR_K1BASE + 0x00002600)
# define PIC32MX_IC5_K1BASE (PIC32MX_SFR_K1BASE + 0x00002800)
/* Output Compare 1-5 Register Base Addresses */
# define PIC32MX_OC_K1BASE(n) (PIC32MX_SFR_K1BASE + 0x00003000 + 0x200*(n-1))
# define PIC32MX_OC1_K1BASE (PIC32MX_SFR_K1BASE + 0x00003000)
# define PIC32MX_OC2_K1BASE (PIC32MX_SFR_K1BASE + 0x00003200)
# define PIC32MX_OC3_K1BASE (PIC32MX_SFR_K1BASE + 0x00003400)
# define PIC32MX_OC4_K1BASE (PIC32MX_SFR_K1BASE + 0x00003600)
# define PIC32MX_OC5_K1BASE (PIC32MX_SFR_K1BASE + 0x00003800)
/* I2C 1-2 Register Base Addresses */
# define PIC32MX_I2C1_K1BASE (PIC32MX_SFR_K1BASE + 0x00005000)
# define PIC32MX_I2C2_K1BASE (PIC32MX_SFR_K1BASE + 0x00005100)
/* SPI 1-2 Register Base Addresses */
# define PIC32MX_SPI1_K1BASE (PIC32MX_SFR_K1BASE + 0x00005800)
# define PIC32MX_SPI2_K1BASE (PIC32MX_SFR_K1BASE + 0x00005a00)
/* UART 1-2 Register Base Addresses */
# define PIC32MX_UART1_K1BASE (PIC32MX_SFR_K1BASE + 0x00006000)
# define PIC32MX_UART2_K1BASE (PIC32MX_SFR_K1BASE + 0x00006200)
/* Parallel Master Register Base Address */
# define PIC32MX_PMP_K1BASE (PIC32MX_SFR_K1BASE + 0x00007000)
/* ADC Register Base Addresses */
# define PIC32MX_ADC_K1BASE (PIC32MX_SFR_K1BASE + 0x00009000)
/* Comparator Voltage Reference Register Base Addresses */
# define PIC32MX_CVR_K1BASE (PIC32MX_SFR_K1BASE + 0x00009800)
/* Comparator Register Base Addresses */
# define PIC32MX_CM_K1BASE (PIC32MX_SFR_K1BASE + 0x0000a000)
/* CTMU Register Base Addresses */
# define PIC32MX_CTMU_K1BASE (PIC32MX_SFR_K1BASE + 0x0000a200)
/* Oscillator Control Register Base Addresses */
# define PIC32MX_OSC_K1BASE (PIC32MX_SFR_K1BASE + 0x0000f000)
/* Configuration Control Register Base Addresses */
# define PIC32MX_CFG_K1BASE (PIC32MX_SFR_K1BASE + 0x0000f200)
/* FLASH Controller Register Base Addresses */
# define PIC32MX_FLASH_K1BASE (PIC32MX_SFR_K1BASE + 0x0000f400)
/* Reset Control Register Base Address */
# define PIC32MX_RESET_K1BASE (PIC32MX_SFR_K1BASE + 0x0000f600)
/* Peripheral Pin Select Input/Ouput Register Base Address */
# define PIC32MX_INSEL_K1BASE (PIC32MX_SFR_K1BASE + 0x0000fa00)
# define PIC32MX_OUTSEL_K1BASE (PIC32MX_SFR_K1BASE + 0x0000fb00)
/* Interrupt Register Base Address */
# define PIC32MX_INT_K1BASE (PIC32MX_SFR_K1BASE + 0x00081000)
/* Bus Matrix Register Base Address */
# define PIC32MX_BMX_K1BASE (PIC32MX_SFR_K1BASE + 0x00082000)
/* DMA Register Base Address */
# define PIC32MX_DMA_K1BASE (PIC32MX_SFR_K1BASE + 0x00083000)
# define PIC32MX_DMACH_K1BASE(n) (PIC32MX_SFR_K1BASE + 0x00083060 + 0xc0*(n))
# define PIC32MX_DMACH0_K1BASE (PIC32MX_SFR_K1BASE + 0x00083060)
# define PIC32MX_DMACH1_K1BASE (PIC32MX_SFR_K1BASE + 0x00083120)
# define PIC32MX_DMACH2_K1BASE (PIC32MX_SFR_K1BASE + 0x000831e0)
# define PIC32MX_DMACH3_K1BASE (PIC32MX_SFR_K1BASE + 0x000832a0)
/* USBOTG Register Base Addresses */
# define PIC32MX_USB_K1BASE (PIC32MX_SFR_K1BASE + 0x00085000)
/* Port Register Base Addresses */
# define PIC32MX_IOPORTA 0
# define PIC32MX_IOPORTB 1
# define PIC32MX_IOPORTC 2
# define PIC32MX_IOPORT_K1BASE(n) (PIC32MX_SFR_K1BASE + 0x00086000 + 0x100*(n))
# define PIC32MX_IOPORTA_K1BASE (PIC32MX_SFR_K1BASE + 0x00086000)
# define PIC32MX_IOPORTB_K1BASE (PIC32MX_SFR_K1BASE + 0x00086100)
# define PIC32MX_IOPORTC_K1BASE (PIC32MX_SFR_K1BASE + 0x00086200)
#elif defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
/* Watchdog Register Base Address */

View File

@ -62,6 +62,10 @@
#define PIC32MX_SPI_BRGSET_OFFSET 0x0038 /* SPI baud rate set register */
#define PIC32MX_SPI_BRGINV_OFFSET 0x003c /* SPI baud rate invert register */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
#define PIC32MX_SPI_CON2_OFFSET 0x0020 /* SPI control register 2*/
#endif
/* Register Addresses *******************************************************/
#ifdef PIC32MX_SPI1_K1BASE
@ -76,6 +80,9 @@
# define PIC32MX_SPI1_BRGCLR (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET)
# define PIC32MX_SPI1_BRGSET (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGSET_OFFSET)
# define PIC32MX_SPI1_BRGINV (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_BRGINV_OFFSET)
# if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_SPI1_CON2 (PIC32MX_SPI1_K1BASE+PIC32MX_SPI_CON2_OFFSET)
# endif
#endif
#ifdef PIC32MX_SPI2_K1BASE
@ -90,6 +97,9 @@
# define PIC32MX_SPI2_BRGCLR (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGCLR_OFFSET)
# define PIC32MX_SPI2_BRGSET (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGSET_OFFSET)
# define PIC32MX_SPI2_BRGINV (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_BRGINV_OFFSET)
# if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define PIC32MX_SPI2_CON2 (PIC32MX_SPI2_K1BASE+PIC32MX_SPI_CON2_OFFSET)
# endif
#endif
#ifdef PIC32MX_SPI3_K1BASE
@ -124,11 +134,12 @@
/* SPI control register */
#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2) || defined(CHIP_PIC32MX5) || \
defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define SPI_CON_RTXISEL_SHIFT (0) /* Bits 0-1: SPI Receive Buffer Full Interrupt Mode */
# define SPI_CON_RTXISEL_MASK (3 << SPI_CON_RTXISEL_SHIFT)
# define SPI_CON_RTXISEL_EMPTY (0 << SPI_CON_RTXISEL_SHIFT) /* Buffer empty*/
# define SPI_CON_RTXISEL_NEMPTY (1 << SPI_CON_RTXISEL_SHIFT) /* Buffer not empty*/
# define SPI_CON_RTXISEL_EMPTY (0 << SPI_CON_RTXISEL_SHIFT) /* Buffer empty */
# define SPI_CON_RTXISEL_NEMPTY (1 << SPI_CON_RTXISEL_SHIFT) /* Buffer not empty */
# define SPI_CON_RTXISEL_HALF (2 << SPI_CON_RTXISEL_SHIFT) /* Buffer half full or more */
# define SPI_CON_RTXISEL_FULL (3 << SPI_CON_RTXISEL_SHIFT) /* Buffer full */
# define SPI_CON_STXISEL_SHIFT (2) /* Bits 2-3: SPI Transmit Buffer Empty Interrupt Mode */
@ -138,7 +149,13 @@
# define SPI_CON_STXISEL_HALF (2 << SPI_CON_STXISEL_SHIFT) /* Buffer half empty or more */
# define SPI_CON_STXISEL_NFULL (3 << SPI_CON_STXISEL_SHIFT) /* Buffer not full */
#endif
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define SPI_CON_DISSDI (1 << 4) /* Bit 4: Disable SDI */
#else
/* Bit 4: Reserved */
#endif
#define SPI_CON_MSTEN (1 << 5) /* Bits 5: Master mode enable */
#define SPI_CON_CKP (1 << 6) /* Bits 6: Clock polarity select */
#define SPI_CON_SSEN (1 << 7) /* Bits 7: Slave select enable (slave mode) */
@ -148,15 +165,30 @@
#define SPI_CON_MODE_MASK (3 << SPI_CON_MODE_SHIFT)
# define SPI_CON_MODE_8BIT (0 << SPI_CON_MODE_SHIFT) /* 8-bit data width */
# define SPI_CON_MODE_16BIT (1 << SPI_CON_MODE_SHIFT) /* 16-bit data width */
# define SPI_CON_MODE_32BIT (2 << SPI_CON_MODE_SHIFT) /* 2-bit data width */
# define SPI_CON_MODE_32BIT (2 << SPI_CON_MODE_SHIFT) /* 32-bit data width */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
/* With AUDEN=1: */
# define SPI_CON_MODE_243232 (0 << SPI_CON_MODE_SHIFT) /* 24-bit data, 32-bit FIFO, 32-bit channel */
# define SPI_CON_MODE_323232 (0 << SPI_CON_MODE_SHIFT) /* 32-bit data, 32-bit FIFO, 32-bit channel */
# define SPI_CON_MODE_161632 (0 << SPI_CON_MODE_SHIFT) /* 16-bit data, 16-bit FIFO, 32-bit channel */
# define SPI_CON_MODE_161616 (0 << SPI_CON_MODE_SHIFT) /* 16-bit data, 16-bit FIFO, 16-bit channel */
#endif
#define SPI_CON_DISSDO (1 << 12) /* Bits 12: Disable SDOx pin */
#define SPI_CON_SIDL (1 << 13) /* Bits 13: Stop in idle mode */
#define SPI_CON_FRZ (1 << 14) /* Bits 14: Freeze in debug exception */
#if !defined(CHIP_PIC32MX1) && !defined(CHIP_PIC32MX2)
# define SPI_CON_FRZ (1 << 14) /* Bits 14: Freeze in debug exception */
#endif
#define SPI_CON_ON (1 << 15) /* Bits 15: SPI peripheral on */
#define SPI_CON_ENHBUF (1 << 16) /* Bits 16: Enhanced buffer enable */
#define SPI_CON_SPIFE (1 << 17) /* Bits 17: Frame sync pulse edge select */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
/* Bits 18-22: Reserved */
# define SPI_CON_MCLKSEL (1 << 18) /* Master clock enable */
#else
/* Bits 18-23: Reserved */
#if defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
#endif
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2) || defined(CHIP_PIC32MX5) || \
defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define SPI_CON_FRMCNT_SHIFT (24) /* Bits 24-26: Frame Sync Pulse Counter bits */
# define SPI_CON_FRMCNT_MASK (7 << SPI_CON_FRMCNT_SHIFT)
# define SPI_CON_FRMCNT_CHAR1 (0 << SPI_CON_FRMCNT_SHIFT) /* Frame sync pulse each char */
@ -172,22 +204,50 @@
#define SPI_CON_FRMSYNC (1 << 30) /* Bits 30: Frame sync pulse direction control on SSx pin */
#define SPI_CON_FRMEN (1 << 31) /* Bits 31: Framed SPI support */
/* SPI control register 2 */
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define SPI2_CON2_AUDMOD_SHIFT (0) /* Bits 0-1: Audio Protocol Mode */
# define SPI2_CON2_AUDMOD_MASK (3 << SPI2_CON2_AUDMOD_SHIFT)
# define SPI2_CON2_AUDMOD_I2S (0 << SPI2_CON2_AUDMOD_SHIFT) /* I2S mode */
# define SPI2_CON2_AUDMOD_LJ (1 << SPI2_CON2_AUDMOD_SHIFT) /* Left Justified mode */
# define SPI2_CON2_AUDMOD_RJ (2 << SPI2_CON2_AUDMOD_SHIFT) /* Right Justified mode */
# define SPI2_CON2_AUDMOD_PCM (3 << SPI2_CON2_AUDMOD_SHIFT) /* PCM/DSP mode */
/* Bit 2: Reserved */
# define SPI2_CON2_AUDMONO (1 << 6) /* Bit 3: Transmit Audio Data Format */
/* Bits 5-6: Reserved */
# define SPI2_CON2_AUDEN (1 << 7) /* Bit 7: Enable Audio CODEC Support */
# define SPI2_CON2_IGNTUR (1 << 8) /* Bit 8: Ignore Transmit Underrun bit */
# define SPI2_CON2_IGNROV (1 << 9) /* Bit 9: Ignore Receive Overflow */
# define SPI2_CON2_SPITUREN (1 << 10) /* Bit 10: Enable Interrupt Events via SPITUR */
# define SPI2_CON2_SPIROVEN (1 << 11) /* Bit 11: Enable Interrupt Events via SPIROV */
# define SPI2_CON2_FRMERREN (1 << 12) /* Bit 12: Enable Interrupt Events via FRMERR */
/* Bits 13-14: Reserved */
# define SPI2_CON2_SPISGNEXT (1 << 15) /* Bit 15 : Sign Extend Read Data from the RX FIFO */
/* Bits 16-31: Reserved */
#endif
/* SPI status register */
#if defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */
# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */
# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */
# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */
#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define SPI_STAT_SPIRBF (1 << 0) /* Bits 0: SPI receive buffer full status */
# define SPI_STAT_SPITBF (1 << 1) /* Bits 1: SPI transmit buffer full status */
# define SPI_STAT_SPITBE (1 << 3) /* Bits 3: SPI transmit buffer empty status */
# define SPI_STAT_SPIRBE (1 << 5) /* Bits 5: RX FIFO Empty */
# define SPI_STAT_SPIROV (1 << 6) /* Bits 6: Receive overflow flag */
# define SPI_STAT_SRMT (1 << 7) /* Bits 6: Shift Register Empty */
# define SPI_STAT_SPITUR (1 << 6) /* Bits 8: Transmit under run */
# define SPI_STAT_SPIBUSY (1 << 11) /* Bits 11: SPI activity status */
# define SPI_STAT_SPIRBF (1 << 0) /* Bit 0: SPI receive buffer full status */
# define SPI_STAT_SPITBE (1 << 3) /* Bit 3: SPI transmit buffer empty status */
# define SPI_STAT_SPIROV (1 << 6) /* Bit 6: Receive overflow flag */
# define SPI_STAT_SPIBUSY (1 << 11) /* Bit 11: SPI activity status */
#elif defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2) || defined(CHIP_PIC32MX5) || \
defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
# define SPI_STAT_SPIRBF (1 << 0) /* Bit 0: SPI receive buffer full status */
# define SPI_STAT_SPITBF (1 << 1) /* Bit 1: SPI transmit buffer full status */
# define SPI_STAT_SPITBE (1 << 3) /* Bit 3: SPI transmit buffer empty status */
# define SPI_STAT_SPIRBE (1 << 5) /* Bit 5: RX FIFO Empty */
# define SPI_STAT_SPIROV (1 << 6) /* Bit 6: Receive overflow flag */
# define SPI_STAT_SRMT (1 << 7) /* Bit 6: Shift Register Empty */
# define SPI_STAT_SPITUR (1 << 8) /* Bit 8: Transmit under run */
# define SPI_STAT_SPIBUSY (1 << 11) /* Bit 11: SPI activity status */
# if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
# define SPI_STAT_FRMERR (1 << 12) /* Bit 12: SPI Frame Error status */
# endif
# define SPI_STAT_TXBUFELM_SHIFT (16) /* Bits 16-20: Transmit Buffer Element Count bits */
# define SPI_STAT_TXBUFELM_MASK (31 << SPI_STAT_TXBUFELM_SHIFT)
# define SPI_STAT_RXBUFELM_SHIFT (24) /* Bits 24-28: Receive Buffer Element Count bits */