qemu-devel
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

[Qemu-devel] [PATCH pic32 6/7] Two new machine platforms: pic32mz7 and p


From: Serge Vakulenko
Subject: [Qemu-devel] [PATCH pic32 6/7] Two new machine platforms: pic32mz7 and pic32mz.
Date: Mon, 29 Jun 2015 22:06:01 -0700

Signed-off-by: Serge Vakulenko <address@hidden>
---
 hw/mips/Makefile.objs       |    3 +
 hw/mips/mips_pic32mx7.c     | 1589 +++++++++++++++++++++++++
 hw/mips/mips_pic32mz.c      | 2723 +++++++++++++++++++++++++++++++++++++++++++
 hw/mips/pic32_ethernet.c    |  535 +++++++++
 hw/mips/pic32_gpio.c        |   39 +
 hw/mips/pic32_load_hex.c    |  230 ++++
 hw/mips/pic32_peripherals.h |  176 +++
 hw/mips/pic32_sdcard.c      |  383 ++++++
 hw/mips/pic32_spi.c         |  121 ++
 hw/mips/pic32_uart.c        |  226 ++++
 hw/mips/pic32mx.h           | 1288 ++++++++++++++++++++
 hw/mips/pic32mz.h           | 2073 ++++++++++++++++++++++++++++++++
 12 files changed, 9386 insertions(+)
 create mode 100644 hw/mips/mips_pic32mx7.c
 create mode 100644 hw/mips/mips_pic32mz.c
 create mode 100644 hw/mips/pic32_ethernet.c
 create mode 100644 hw/mips/pic32_gpio.c
 create mode 100644 hw/mips/pic32_load_hex.c
 create mode 100644 hw/mips/pic32_peripherals.h
 create mode 100644 hw/mips/pic32_sdcard.c
 create mode 100644 hw/mips/pic32_spi.c
 create mode 100644 hw/mips/pic32_uart.c
 create mode 100644 hw/mips/pic32mx.h
 create mode 100644 hw/mips/pic32mz.h

diff --git a/hw/mips/Makefile.objs b/hw/mips/Makefile.objs
index 9633f3a..dcbaec9 100644
--- a/hw/mips/Makefile.objs
+++ b/hw/mips/Makefile.objs
@@ -3,3 +3,6 @@ obj-y += addr.o cputimer.o mips_int.o
 obj-$(CONFIG_JAZZ) += mips_jazz.o
 obj-$(CONFIG_FULONG) += mips_fulong2e.o
 obj-y += gt64xxx_pci.o
+obj-y += mips_pic32mz.o mips_pic32mx7.o
+obj-y += pic32_load_hex.o pic32_sdcard.o pic32_spi.o pic32_uart.o pic32_gpio.o
+obj-y += pic32_ethernet.o
diff --git a/hw/mips/mips_pic32mx7.c b/hw/mips/mips_pic32mx7.c
new file mode 100644
index 0000000..f246929
--- /dev/null
+++ b/hw/mips/mips_pic32mx7.c
@@ -0,0 +1,1589 @@
+/*
+ * QEMU support for Microchip PIC32MX7 microcontroller.
+ *
+ * Copyright (c) 2015 Serge Vakulenko
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the
"Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
+ * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/* Only 32-bit little endian mode supported. */
+#include "config.h"
+#if !defined TARGET_MIPS64 && !defined TARGET_WORDS_BIGENDIAN
+
+#include "hw/i386/pc.h"
+#include "hw/char/serial.h"
+#include "hw/mips/cpudevs.h"
+#include "sysemu/char.h"
+#include "hw/loader.h"
+#include "qemu/error-report.h"
+#include "hw/empty_slot.h"
+#include <termios.h>
+
+#define PIC32MX7
+#include "pic32mx.h"
+#include "pic32_peripherals.h"
+
+/* Hardware addresses */
+#define PROGRAM_FLASH_START 0x1d000000
+#define BOOT_FLASH_START    0x1fc00000
+#define DATA_MEM_START      0x00000000
+#define IO_MEM_START        0x1f800000
+
+#define PROGRAM_FLASH_SIZE  (512*1024)          // 512 kbytes
+#define BOOT_FLASH_SIZE     (12*1024)           // 12 kbytes
+#define DATA_MEM_SIZE       (128*1024)          // 128 kbytes
+#define USER_MEM_START      0xbf000000
+
+#define TYPE_MIPS_PIC32     "mips-pic32mx7"
+
+/*
+ * Board variants.
+ */
+enum {
+    BOARD_MAX32,            /* chipKIT Max32 board */
+    BOARD_MAXIMITE,         /* Geoff's Maximite board */
+    BOARD_EXPLORER16,       /* Microchip Explorer-16 board */
+};
+
+static const char *board_name[] = {
+    "chipKIT Max32",
+    "Geoff's Maximite Computer",
+    "Microchip Explorer16",
+};
+
+/*
+ * Pointers to Flash memory contents.
+ */
+static char *prog_ptr;
+static char *boot_ptr;
+
+#define BOOTMEM(addr) ((uint32_t*) boot_ptr) [(addr & 0xffff) >> 2]
+
+/*
+ * TODO: add option to enable tracing.
+ */
+#define TRACE   0
+
+/*
+ * PIC32MX7 specific table:
+ * translate IRQ number to interrupt vector.
+ */
+static const int irq_to_vector[] = {
+    PIC32_VECT_CT,      /* 0  - Core Timer Interrupt */
+    PIC32_VECT_CS0,     /* 1  - Core Software Interrupt 0 */
+    PIC32_VECT_CS1,     /* 2  - Core Software Interrupt 1 */
+    PIC32_VECT_INT0,    /* 3  - External Interrupt 0 */
+    PIC32_VECT_T1,      /* 4  - Timer1 */
+    PIC32_VECT_IC1,     /* 5  - Input Capture 1 */
+    PIC32_VECT_OC1,     /* 6  - Output Compare 1 */
+    PIC32_VECT_INT1,    /* 7  - External Interrupt 1 */
+    PIC32_VECT_T2,      /* 8  - Timer2 */
+    PIC32_VECT_IC2,     /* 9  - Input Capture 2 */
+    PIC32_VECT_OC2,     /* 10 - Output Compare 2 */
+    PIC32_VECT_INT2,    /* 11 - External Interrupt 2 */
+    PIC32_VECT_T3,      /* 12 - Timer3 */
+    PIC32_VECT_IC3,     /* 13 - Input Capture 3 */
+    PIC32_VECT_OC3,     /* 14 - Output Compare 3 */
+    PIC32_VECT_INT3,    /* 15 - External Interrupt 3 */
+    PIC32_VECT_T4,      /* 16 - Timer4 */
+    PIC32_VECT_IC4,     /* 17 - Input Capture 4 */
+    PIC32_VECT_OC4,     /* 18 - Output Compare 4 */
+    PIC32_VECT_INT4,    /* 19 - External Interrupt 4 */
+    PIC32_VECT_T5,      /* 20 - Timer5 */
+    PIC32_VECT_IC5,     /* 21 - Input Capture 5 */
+    PIC32_VECT_OC5,     /* 22 - Output Compare 5 */
+    PIC32_VECT_SPI1,    /* 23 - SPI1 Fault */
+    PIC32_VECT_SPI1,    /* 24 - SPI1 Transfer Done */
+    PIC32_VECT_SPI1,    /* 25 - SPI1 Receive Done */
+
+    PIC32_VECT_U1     | /* 26 - UART1 Error */
+    PIC32_VECT_SPI3   | /* 26 - SPI3 Fault */
+    PIC32_VECT_I2C3,    /* 26 - I2C3 Bus Collision Event */
+
+    PIC32_VECT_U1     | /* 27 - UART1 Receiver */
+    PIC32_VECT_SPI3   | /* 27 - SPI3 Transfer Done */
+    PIC32_VECT_I2C3,    /* 27 - I2C3 Slave Event */
+
+    PIC32_VECT_U1     | /* 28 - UART1 Transmitter */
+    PIC32_VECT_SPI3   | /* 28 - SPI3 Receive Done */
+    PIC32_VECT_I2C3,    /* 28 - I2C3 Master Event */
+
+    PIC32_VECT_I2C1,    /* 29 - I2C1 Bus Collision Event */
+    PIC32_VECT_I2C1,    /* 30 - I2C1 Slave Event */
+    PIC32_VECT_I2C1,    /* 31 - I2C1 Master Event */
+    PIC32_VECT_CN,      /* 32 - Input Change Interrupt */
+    PIC32_VECT_AD1,     /* 33 - ADC1 Convert Done */
+    PIC32_VECT_PMP,     /* 34 - Parallel Master Port */
+    PIC32_VECT_CMP1,    /* 35 - Comparator Interrupt */
+    PIC32_VECT_CMP2,    /* 36 - Comparator Interrupt */
+
+    PIC32_VECT_U3     | /* 37 - UART3 Error */
+    PIC32_VECT_SPI2   | /* 37 - SPI2 Fault */
+    PIC32_VECT_I2C4,    /* 37 - I2C4 Bus Collision Event */
+
+    PIC32_VECT_U3     | /* 38 - UART3 Receiver */
+    PIC32_VECT_SPI2   | /* 38 - SPI2 Transfer Done */
+    PIC32_VECT_I2C4,    /* 38 - I2C4 Slave Event */
+
+    PIC32_VECT_U3     | /* 39 - UART3 Transmitter */
+    PIC32_VECT_SPI2   | /* 39 - SPI2 Receive Done */
+    PIC32_VECT_I2C4,    /* 39 - I2C4 Master Event */
+
+    PIC32_VECT_U2     | /* 40 - UART2 Error */
+    PIC32_VECT_SPI4   | /* 40 - SPI4 Fault */
+    PIC32_VECT_I2C5,    /* 40 - I2C5 Bus Collision Event */
+
+    PIC32_VECT_U2     | /* 41 - UART2 Receiver */
+    PIC32_VECT_SPI4   | /* 41 - SPI4 Transfer Done */
+    PIC32_VECT_I2C5,    /* 41 - I2C5 Slave Event */
+
+    PIC32_VECT_U2     | /* 42 - UART2 Transmitter */
+    PIC32_VECT_SPI4   | /* 42 - SPI4 Receive Done */
+    PIC32_VECT_I2C5,    /* 42 - I2C5 Master Event */
+
+    PIC32_VECT_I2C2,    /* 43 - I2C2 Bus Collision Event */
+    PIC32_VECT_I2C2,    /* 44 - I2C2 Slave Event */
+    PIC32_VECT_I2C2,    /* 45 - I2C2 Master Event */
+    PIC32_VECT_FSCM,    /* 46 - Fail-Safe Clock Monitor */
+    PIC32_VECT_RTCC,    /* 47 - Real-Time Clock and Calendar */
+    PIC32_VECT_DMA0,    /* 48 - DMA Channel 0 */
+    PIC32_VECT_DMA1,    /* 49 - DMA Channel 1 */
+    PIC32_VECT_DMA2,    /* 50 - DMA Channel 2 */
+    PIC32_VECT_DMA3,    /* 51 - DMA Channel 3 */
+    PIC32_VECT_DMA4,    /* 52 - DMA Channel 4 */
+    PIC32_VECT_DMA5,    /* 53 - DMA Channel 5 */
+    PIC32_VECT_DMA6,    /* 54 - DMA Channel 6 */
+    PIC32_VECT_DMA7,    /* 55 - DMA Channel 7 */
+    PIC32_VECT_FCE,     /* 56 - Flash Control Event */
+    PIC32_VECT_USB,     /* 57 - USB */
+    PIC32_VECT_CAN1,    /* 58 - Control Area Network 1 */
+    PIC32_VECT_CAN2,    /* 59 - Control Area Network 2 */
+    PIC32_VECT_ETH,     /* 60 - Ethernet Interrupt */
+    PIC32_VECT_IC1,     /* 61 - Input Capture 1 Error */
+    PIC32_VECT_IC2,     /* 62 - Input Capture 2 Error */
+    PIC32_VECT_IC3,     /* 63 - Input Capture 3 Error */
+    PIC32_VECT_IC4,     /* 64 - Input Capture 4 Error */
+    PIC32_VECT_IC5,     /* 65 - Input Capture 5 Error */
+    PIC32_VECT_PMP,     /* 66 - Parallel Master Port Error */
+    PIC32_VECT_U4,      /* 67 - UART4 Error */
+    PIC32_VECT_U4,      /* 68 - UART4 Receiver */
+    PIC32_VECT_U4,      /* 69 - UART4 Transmitter */
+    PIC32_VECT_U6,      /* 70 - UART6 Error */
+    PIC32_VECT_U6,      /* 71 - UART6 Receiver */
+    PIC32_VECT_U6,      /* 72 - UART6 Transmitter */
+    PIC32_VECT_U5,      /* 73 - UART5 Error */
+    PIC32_VECT_U5,      /* 74 - UART5 Receiver */
+    PIC32_VECT_U5,      /* 75 - UART5 Transmitter */
+};
+
+static void update_irq_status(pic32_t *s)
+{
+    /* Assume no interrupts pending. */
+    int cause_ripl = 0;
+    int vector = 0;
+    CPUMIPSState *env = &s->cpu->env;
+    int current_ripl = (env->CP0_Cause >> (CP0Ca_IP + 2)) & 0x3f;
+
+    VALUE(INTSTAT) = 0;
+
+    if ((VALUE(IFS0) & VALUE(IEC0)) ||
+        (VALUE(IFS1) & VALUE(IEC1)) ||
+        (VALUE(IFS2) & VALUE(IEC2)))
+    {
+        /* Find the most prioritive pending interrupt,
+         * it's vector and level. */
+        int irq;
+        for (irq=0; irq<sizeof(irq_to_vector)/sizeof(int); irq++) {
+            int n = irq >> 5;
+
+            if (((VALUE(IFS(n)) & VALUE(IEC(n))) >> (irq & 31)) & 1) {
+                /* Interrupt is pending. */
+                int v = irq_to_vector [irq];
+                if (v < 0)
+                    continue;
+
+                int level = VALUE(IPC(v >> 2));
+                level >>= 2 + (v & 3) * 8;
+                level &= 7;
+                if (level > cause_ripl) {
+                    vector = v;
+                    cause_ripl = level;
+                }
+            }
+        }
+        VALUE(INTSTAT) = vector | (cause_ripl << 8);
+    }
+
+    if (cause_ripl == current_ripl)
+        return;
+
+    if (TRACE)
+        fprintf(qemu_logfile, "--- Priority level Cause.RIPL = %u\n",
+            cause_ripl);
+
+    /*
+     * Modify Cause.RIPL field and take EIC interrupt.
+     */
+    env->CP0_Cause &= ~(0x3f << (CP0Ca_IP + 2));
+    env->CP0_Cause |= cause_ripl << (CP0Ca_IP + 2);
+    cpu_interrupt(CPU(s->cpu), CPU_INTERRUPT_HARD);
+}
+
+/*
+ * Set interrupt flag status
+ */
+static void irq_raise(pic32_t *s, int irq)
+{
+    if (VALUE(IFS(irq >> 5)) & (1 << (irq & 31)))
+        return;
+
+    VALUE(IFS(irq >> 5)) |= 1 << (irq & 31);
+    update_irq_status(s);
+}
+
+/*
+ * Clear interrupt flag status
+ */
+static void irq_clear(pic32_t *s, int irq)
+{
+    if (! (VALUE(IFS(irq >> 5)) & (1 << (irq & 31))))
+        return;
+
+    VALUE(IFS(irq >> 5)) &= ~(1 << (irq & 31));
+    update_irq_status(s);
+}
+
+/*
+ * Timer interrupt.
+ */
+static void pic32_timer_irq(CPUMIPSState *env, int raise)
+{
+    pic32_t *s = env->eic_context;
+
+    if (raise) {
+        if (TRACE)
+            fprintf(qemu_logfile, "--- %08x: Timer interrupt\n",
+                env->active_tc.PC);
+        irq_raise(s, 0);
+    } else {
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Clear timer interrupt\n");
+        irq_clear(s, 0);
+    }
+}
+
+/*
+ * Software interrupt.
+ */
+static void pic32_soft_irq(CPUMIPSState *env, int num)
+{
+    pic32_t *s = env->eic_context;
+
+    if (TRACE)
+        fprintf(qemu_logfile, "--- %08x: Soft interrupt %u\n",
+            env->active_tc.PC, num);
+    irq_raise(s, num + 1);
+}
+
+/*
+ * Perform an assign/clear/set/invert operation.
+ */
+static inline unsigned write_op(int a, int b, int op)
+{
+    switch (op & 0xc) {
+    case 0x0: a = b;   break;   // Assign
+    case 0x4: a &= ~b; break;   // Clear
+    case 0x8: a |= b;  break;   // Set
+    case 0xc: a ^= b;  break;   // Invert
+    }
+    return a;
+}
+
+static void io_reset(pic32_t *s)
+{
+    int i;
+
+    /*
+     * Bus matrix control registers.
+     */
+    VALUE(BMXCON)    = 0x001f0041;      // Bus Matrix Control
+    VALUE(BMXDKPBA)  = 0;               // Data RAM kernel program base address
+    VALUE(BMXDUDBA)  = 0;               // Data RAM user data base address
+    VALUE(BMXDUPBA)  = 0;               // Data RAM user program base address
+    VALUE(BMXPUPBA)  = 0;               // Program Flash user program
base address
+    VALUE(BMXDRMSZ)  = 128 * 1024;      // Data RAM memory size
+    VALUE(BMXPFMSZ)  = 512 * 1024;      // Program Flash memory size
+    VALUE(BMXBOOTSZ) = 12 * 1024;       // Boot Flash size
+
+    /*
+     * Prefetch controller.
+     */
+    VALUE(CHECON) = 0x00000007;
+
+    /*
+     * System controller.
+     */
+    VALUE(OSCTUN) = 0;
+    VALUE(DDPCON) = 0;
+    VALUE(SYSKEY) = 0;
+    VALUE(RCON)   = 0;
+    VALUE(RSWRST) = 0;
+    s->syskey_unlock = 0;
+
+    /*
+     * Analog to digital converter.
+     */
+    VALUE(AD1CON1) = 0;                 // Control register 1
+    VALUE(AD1CON2) = 0;                 // Control register 2
+    VALUE(AD1CON3) = 0;                 // Control register 3
+    VALUE(AD1CHS)  = 0;                 // Channel select
+    VALUE(AD1CSSL) = 0;                 // Input scan selection
+    VALUE(AD1PCFG) = 0;                 // Port configuration
+
+    /*
+     * General purpose IO signals.
+     * All pins are inputs, high, open drains and pullups disabled.
+     * No interrupts on change.
+     */
+    VALUE(TRISA) = 0xFFFF;              // Port A: mask of inputs
+    VALUE(PORTA) = 0xFFFF;              // Port A: read inputs, write outputs
+    VALUE(LATA)  = 0xFFFF;              // Port A: read/write outputs
+    VALUE(ODCA)  = 0;                   // Port A: open drain configuration
+    VALUE(TRISB) = 0xFFFF;              // Port B: mask of inputs
+    VALUE(PORTB) = 0xFFFF;              // Port B: read inputs, write outputs
+    VALUE(LATB)  = 0xFFFF;              // Port B: read/write outputs
+    VALUE(ODCB)  = 0;                   // Port B: open drain configuration
+    VALUE(TRISC) = 0xFFFF;              // Port C: mask of inputs
+    VALUE(PORTC) = 0xFFFF;              // Port C: read inputs, write outputs
+    VALUE(LATC)  = 0xFFFF;              // Port C: read/write outputs
+    VALUE(ODCC)  = 0;                   // Port C: open drain configuration
+    VALUE(TRISD) = 0xFFFF;              // Port D: mask of inputs
+    VALUE(PORTD) = 0xFFFF;              // Port D: read inputs, write outputs
+    VALUE(LATD)  = 0xFFFF;              // Port D: read/write outputs
+    VALUE(ODCD)  = 0;                   // Port D: open drain configuration
+    VALUE(TRISE) = 0xFFFF;              // Port E: mask of inputs
+    VALUE(PORTE) = 0xFFFF;              // Port D: read inputs, write outputs
+    VALUE(LATE)  = 0xFFFF;              // Port E: read/write outputs
+    VALUE(ODCE)  = 0;                   // Port E: open drain configuration
+    VALUE(TRISF) = 0xFFFF;              // Port F: mask of inputs
+    VALUE(PORTF) = 0xFFFF;              // Port F: read inputs, write outputs
+    VALUE(LATF)  = 0xFFFF;              // Port F: read/write outputs
+    VALUE(ODCF)  = 0;                   // Port F: open drain configuration
+    VALUE(TRISG) = 0xFFFF;              // Port G: mask of inputs
+    VALUE(PORTG) = 0xFFFF;              // Port G: read inputs, write outputs
+    VALUE(LATG)  = 0xFFFF;              // Port G: read/write outputs
+    VALUE(ODCG)  = 0;                   // Port G: open drain configuration
+    VALUE(CNCON) = 0;                   // Interrupt-on-change control
+    VALUE(CNEN)  = 0;                   // Input change interrupt enable
+    VALUE(CNPUE) = 0;                   // Input pin pull-up enable
+
+    /*
+     * Reset UARTs.
+     */
+    VALUE(U1MODE)  = 0;
+    VALUE(U1STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U1TXREG) = 0;
+    VALUE(U1RXREG) = 0;
+    VALUE(U1BRG)   = 0;
+    VALUE(U2MODE)  = 0;
+    VALUE(U2STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U2TXREG) = 0;
+    VALUE(U2RXREG) = 0;
+    VALUE(U2BRG)   = 0;
+    VALUE(U3MODE)  = 0;
+    VALUE(U3STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U3TXREG) = 0;
+    VALUE(U3RXREG) = 0;
+    VALUE(U3BRG)   = 0;
+    VALUE(U4MODE)  = 0;
+    VALUE(U4STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U4TXREG) = 0;
+    VALUE(U4RXREG) = 0;
+    VALUE(U4BRG)   = 0;
+    VALUE(U5MODE)  = 0;
+    VALUE(U5STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U5TXREG) = 0;
+    VALUE(U5RXREG) = 0;
+    VALUE(U5BRG)   = 0;
+    VALUE(U6MODE)  = 0;
+    VALUE(U6STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U6TXREG) = 0;
+    VALUE(U6RXREG) = 0;
+    VALUE(U6BRG)   = 0;
+
+    /*
+     * Reset SPI.
+     */
+    VALUE(SPI1CON)  = 0;
+    VALUE(SPI1STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI1BRG)  = 0;
+
+    VALUE(SPI2CON)  = 0;
+    VALUE(SPI2STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI2BRG)  = 0;
+
+    VALUE(SPI3CON)  = 0;
+    VALUE(SPI3STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI3BRG)  = 0;
+
+    VALUE(SPI4CON)  = 0;
+    VALUE(SPI4STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI4BRG)  = 0;
+
+    for (i=0; i<NUM_SPI; i++) {
+        s->spi[i].rfifo = 0;
+        s->spi[i].wfifo = 0;
+    }
+}
+
+static unsigned io_read32(pic32_t *s, unsigned offset, const char **namep)
+{
+    unsigned *bufp = &VALUE(offset);
+
+    switch (offset) {
+    /*-------------------------------------------------------------------------
+     * Bus matrix control registers.
+     */
+    STORAGE(BMXCON); break;     // Bus Mmatrix Control
+    STORAGE(BMXDKPBA); break;   // Data RAM kernel program base address
+    STORAGE(BMXDUDBA); break;   // Data RAM user data base address
+    STORAGE(BMXDUPBA); break;   // Data RAM user program base address
+    STORAGE(BMXPUPBA); break;   // Program Flash user program base address
+    STORAGE(BMXDRMSZ); break;   // Data RAM memory size
+    STORAGE(BMXPFMSZ); break;   // Program Flash memory size
+    STORAGE(BMXBOOTSZ); break;  // Boot Flash size
+
+    /*-------------------------------------------------------------------------
+     * Interrupt controller registers.
+     */
+    STORAGE(INTCON); break;     // Interrupt Control
+    STORAGE(INTSTAT); break;    // Interrupt Status
+    STORAGE(IFS0); break;       // IFS(0..2) - Interrupt Flag Status
+    STORAGE(IFS1); break;
+    STORAGE(IFS2); break;
+    STORAGE(IEC0); break;       // IEC(0..2) - Interrupt Enable Control
+    STORAGE(IEC1); break;
+    STORAGE(IEC2); break;
+    STORAGE(IPC0); break;       // IPC(0..11) - Interrupt Priority Control
+    STORAGE(IPC1); break;
+    STORAGE(IPC2); break;
+    STORAGE(IPC3); break;
+    STORAGE(IPC4); break;
+    STORAGE(IPC5); break;
+    STORAGE(IPC6); break;
+    STORAGE(IPC7); break;
+    STORAGE(IPC8); break;
+    STORAGE(IPC9); break;
+    STORAGE(IPC10); break;
+    STORAGE(IPC11); break;
+    STORAGE(IPC12); break;
+
+    /*-------------------------------------------------------------------------
+     * Prefetch controller.
+     */
+    STORAGE(CHECON); break;     // Prefetch Control
+
+    /*-------------------------------------------------------------------------
+     * System controller.
+     */
+    STORAGE(OSCCON); break;     // Oscillator Control
+    STORAGE(OSCTUN); break;     // Oscillator Tuning
+    STORAGE(DDPCON); break;     // Debug Data Port Control
+    STORAGE(DEVID); break;      // Device Identifier
+    STORAGE(SYSKEY); break;     // System Key
+    STORAGE(RCON); break;       // Reset Control
+    STORAGE(RSWRST);            // Software Reset
+        if ((VALUE(RSWRST) & 1) && s->stop_on_reset) {
+            exit(0);
+        }
+        break;
+
+    /*-------------------------------------------------------------------------
+     * DMA controller.
+     */
+    STORAGE(DMACON); break;     // DMA Control
+    STORAGE(DMASTAT); break;    // DMA Status
+    STORAGE(DMAADDR); break;    // DMA Address
+
+    /*-------------------------------------------------------------------------
+     * Analog to digital converter.
+     */
+    STORAGE(AD1CON1); break;    // Control register 1
+    STORAGE(AD1CON2); break;    // Control register 2
+    STORAGE(AD1CON3); break;    // Control register 3
+    STORAGE(AD1CHS); break;     // Channel select
+    STORAGE(AD1CSSL); break;    // Input scan selection
+    STORAGE(AD1PCFG); break;    // Port configuration
+    STORAGE(ADC1BUF0); break;   // Result words
+    STORAGE(ADC1BUF1); break;
+    STORAGE(ADC1BUF2); break;
+    STORAGE(ADC1BUF3); break;
+    STORAGE(ADC1BUF4); break;
+    STORAGE(ADC1BUF5); break;
+    STORAGE(ADC1BUF6); break;
+    STORAGE(ADC1BUF7); break;
+    STORAGE(ADC1BUF8); break;
+    STORAGE(ADC1BUF9); break;
+    STORAGE(ADC1BUFA); break;
+    STORAGE(ADC1BUFB); break;
+    STORAGE(ADC1BUFC); break;
+    STORAGE(ADC1BUFD); break;
+    STORAGE(ADC1BUFE); break;
+    STORAGE(ADC1BUFF); break;
+
+    /*--------------------------------------
+     * USB registers.
+     */
+    STORAGE(U1OTGIR); break;    // OTG interrupt flags
+    STORAGE(U1OTGIE); break;    // OTG interrupt enable
+    STORAGE(U1OTGSTAT); break;  // Comparator and pin status
+    STORAGE(U1OTGCON); break;   // Resistor and pin control
+    STORAGE(U1PWRC); break;     // Power control
+    STORAGE(U1IR); break;       // Pending interrupt
+    STORAGE(U1IE); break;       // Interrupt enable
+    STORAGE(U1EIR); break;      // Pending error interrupt
+    STORAGE(U1EIE); break;      // Error interrupt enable
+    STORAGE(U1STAT); break;     // Status FIFO
+    STORAGE(U1CON); break;      // Control
+    STORAGE(U1ADDR); break;     // Address
+    STORAGE(U1BDTP1); break;    // Buffer descriptor table pointer 1
+    STORAGE(U1FRML); break;     // Frame counter low
+    STORAGE(U1FRMH); break;     // Frame counter high
+    STORAGE(U1TOK); break;      // Host control
+    STORAGE(U1SOF); break;      // SOF counter
+    STORAGE(U1BDTP2); break;    // Buffer descriptor table pointer 2
+    STORAGE(U1BDTP3); break;    // Buffer descriptor table pointer 3
+    STORAGE(U1CNFG1); break;    // Debug and idle
+    STORAGE(U1EP(0)); break;    // Endpoint control
+    STORAGE(U1EP(1)); break;
+    STORAGE(U1EP(2)); break;
+    STORAGE(U1EP(3)); break;
+    STORAGE(U1EP(4)); break;
+    STORAGE(U1EP(5)); break;
+    STORAGE(U1EP(6)); break;
+    STORAGE(U1EP(7)); break;
+    STORAGE(U1EP(8)); break;
+    STORAGE(U1EP(9)); break;
+    STORAGE(U1EP(10)); break;
+    STORAGE(U1EP(11)); break;
+    STORAGE(U1EP(12)); break;
+    STORAGE(U1EP(13)); break;
+    STORAGE(U1EP(14)); break;
+    STORAGE(U1EP(15)); break;
+
+    /*-------------------------------------------------------------------------
+     * General purpose IO signals.
+     */
+    STORAGE(TRISA); break;      // Port A: mask of inputs
+    STORAGE(PORTA); break;      // Port A: read inputs
+    STORAGE(LATA); break;       // Port A: read outputs
+    STORAGE(ODCA); break;       // Port A: open drain configuration
+    STORAGE(TRISB); break;      // Port B: mask of inputs
+    STORAGE(PORTB); break;      // Port B: read inputs
+    STORAGE(LATB); break;       // Port B: read outputs
+    STORAGE(ODCB); break;       // Port B: open drain configuration
+    STORAGE(TRISC); break;      // Port C: mask of inputs
+    STORAGE(PORTC); break;      // Port C: read inputs
+    STORAGE(LATC); break;       // Port C: read outputs
+    STORAGE(ODCC); break;       // Port C: open drain configuration
+    STORAGE(TRISD); break;      // Port D: mask of inputs
+    STORAGE(PORTD); break;      // Port D: read inputs
+    STORAGE(LATD); break;       // Port D: read outputs
+    STORAGE(ODCD); break;       // Port D: open drain configuration
+    STORAGE(TRISE); break;      // Port E: mask of inputs
+    STORAGE(PORTE); break;      // Port E: read inputs
+    STORAGE(LATE); break;       // Port E: read outputs
+    STORAGE(ODCE); break;       // Port E: open drain configuration
+    STORAGE(TRISF); break;      // Port F: mask of inputs
+    STORAGE(PORTF); break;      // Port F: read inputs
+    STORAGE(LATF); break;       // Port F: read outputs
+    STORAGE(ODCF); break;       // Port F: open drain configuration
+    STORAGE(TRISG); break;      // Port G: mask of inputs
+    STORAGE(PORTG); break;      // Port G: read inputs
+    STORAGE(LATG); break;       // Port G: read outputs
+    STORAGE(ODCG); break;       // Port G: open drain configuration
+    STORAGE(CNCON); break;      // Interrupt-on-change control
+    STORAGE(CNEN); break;       // Input change interrupt enable
+    STORAGE(CNPUE); break;      // Input pin pull-up enable
+
+    /*-------------------------------------------------------------------------
+     * UART 1.
+     */
+    STORAGE(U1RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 0);
+        break;
+    STORAGE(U1BRG); break;                      // Baud rate
+    STORAGE(U1MODE); break;                     // Mode
+    STORAGE(U1STA);                             // Status and control
+        pic32_uart_poll_status(s, 0);
+        break;
+    STORAGE(U1TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U1MODECLR); *bufp = 0; break;
+    STORAGE(U1MODESET); *bufp = 0; break;
+    STORAGE(U1MODEINV); *bufp = 0; break;
+    STORAGE(U1STACLR);  *bufp = 0; break;
+    STORAGE(U1STASET);  *bufp = 0; break;
+    STORAGE(U1STAINV);  *bufp = 0; break;
+    STORAGE(U1BRGCLR);  *bufp = 0; break;
+    STORAGE(U1BRGSET);  *bufp = 0; break;
+    STORAGE(U1BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 2.
+     */
+    STORAGE(U2RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 1);
+        break;
+    STORAGE(U2BRG); break;                      // Baud rate
+    STORAGE(U2MODE); break;                     // Mode
+    STORAGE(U2STA);                             // Status and control
+        pic32_uart_poll_status(s, 1);
+        break;
+    STORAGE(U2TXREG);   *bufp = 0; break;      // Transmit
+    STORAGE(U2MODECLR); *bufp = 0; break;
+    STORAGE(U2MODESET); *bufp = 0; break;
+    STORAGE(U2MODEINV); *bufp = 0; break;
+    STORAGE(U2STACLR);  *bufp = 0; break;
+    STORAGE(U2STASET);  *bufp = 0; break;
+    STORAGE(U2STAINV);  *bufp = 0; break;
+    STORAGE(U2BRGCLR);  *bufp = 0; break;
+    STORAGE(U2BRGSET);  *bufp = 0; break;
+    STORAGE(U2BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 3.
+     */
+    STORAGE(U3RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 2);
+        break;
+    STORAGE(U3BRG); break;                      // Baud rate
+    STORAGE(U3MODE); break;                     // Mode
+    STORAGE(U3STA);                             // Status and control
+        pic32_uart_poll_status(s, 2);
+        break;
+    STORAGE(U3TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U3MODECLR); *bufp = 0; break;
+    STORAGE(U3MODESET); *bufp = 0; break;
+    STORAGE(U3MODEINV); *bufp = 0; break;
+    STORAGE(U3STACLR);  *bufp = 0; break;
+    STORAGE(U3STASET);  *bufp = 0; break;
+    STORAGE(U3STAINV);  *bufp = 0; break;
+    STORAGE(U3BRGCLR);  *bufp = 0; break;
+    STORAGE(U3BRGSET);  *bufp = 0; break;
+    STORAGE(U3BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 4.
+     */
+    STORAGE(U4RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 3);
+        break;
+    STORAGE(U4BRG); break;                      // Baud rate
+    STORAGE(U4MODE); break;                     // Mode
+    STORAGE(U4STA);                             // Status and control
+        pic32_uart_poll_status(s, 3);
+        break;
+    STORAGE(U4TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U4MODECLR); *bufp = 0; break;
+    STORAGE(U4MODESET); *bufp = 0; break;
+    STORAGE(U4MODEINV); *bufp = 0; break;
+    STORAGE(U4STACLR);  *bufp = 0; break;
+    STORAGE(U4STASET);  *bufp = 0; break;
+    STORAGE(U4STAINV);  *bufp = 0; break;
+    STORAGE(U4BRGCLR);  *bufp = 0; break;
+    STORAGE(U4BRGSET);  *bufp = 0; break;
+    STORAGE(U4BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 5.
+     */
+    STORAGE(U5RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 4);
+        break;
+    STORAGE(U5BRG); break;                      // Baud rate
+    STORAGE(U5MODE); break;                     // Mode
+    STORAGE(U5STA);                             // Status and control
+        pic32_uart_poll_status(s, 4);
+        break;
+    STORAGE(U5TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U5MODECLR); *bufp = 0; break;
+    STORAGE(U5MODESET); *bufp = 0; break;
+    STORAGE(U5MODEINV); *bufp = 0; break;
+    STORAGE(U5STACLR);  *bufp = 0; break;
+    STORAGE(U5STASET);  *bufp = 0; break;
+    STORAGE(U5STAINV);  *bufp = 0; break;
+    STORAGE(U5BRGCLR);  *bufp = 0; break;
+    STORAGE(U5BRGSET);  *bufp = 0; break;
+    STORAGE(U5BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 6.
+     */
+    STORAGE(U6RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 5);
+        break;
+    STORAGE(U6BRG); break;                      // Baud rate
+    STORAGE(U6MODE); break;                     // Mode
+    STORAGE(U6STA);                             // Status and control
+        pic32_uart_poll_status(s, 5);
+        break;
+    STORAGE(U6TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U6MODECLR); *bufp = 0; break;
+    STORAGE(U6MODESET); *bufp = 0; break;
+    STORAGE(U6MODEINV); *bufp = 0; break;
+    STORAGE(U6STACLR);  *bufp = 0; break;
+    STORAGE(U6STASET);  *bufp = 0; break;
+    STORAGE(U6STAINV);  *bufp = 0; break;
+    STORAGE(U6BRGCLR);  *bufp = 0; break;
+    STORAGE(U6BRGSET);  *bufp = 0; break;
+    STORAGE(U6BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 1.
+     */
+    STORAGE(SPI1CON); break;                    // Control
+    STORAGE(SPI1CONCLR); *bufp = 0; break;
+    STORAGE(SPI1CONSET); *bufp = 0; break;
+    STORAGE(SPI1CONINV); *bufp = 0; break;
+    STORAGE(SPI1STAT); break;                   // Status
+    STORAGE(SPI1STATCLR); *bufp = 0; break;
+    STORAGE(SPI1STATSET); *bufp = 0; break;
+    STORAGE(SPI1STATINV); *bufp = 0; break;
+    STORAGE(SPI1BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 0);
+        break;
+    STORAGE(SPI1BRG); break;                    // Baud rate
+    STORAGE(SPI1BRGCLR); *bufp = 0; break;
+    STORAGE(SPI1BRGSET); *bufp = 0; break;
+    STORAGE(SPI1BRGINV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 2.
+     */
+    STORAGE(SPI2CON); break;                    // Control
+    STORAGE(SPI2CONCLR); *bufp = 0; break;
+    STORAGE(SPI2CONSET); *bufp = 0; break;
+    STORAGE(SPI2CONINV); *bufp = 0; break;
+    STORAGE(SPI2STAT); break;                   // Status
+    STORAGE(SPI2STATCLR); *bufp = 0; break;
+    STORAGE(SPI2STATSET); *bufp = 0; break;
+    STORAGE(SPI2STATINV); *bufp = 0; break;
+    STORAGE(SPI2BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 1);
+        break;
+    STORAGE(SPI2BRG); break;                    // Baud rate
+    STORAGE(SPI2BRGCLR); *bufp = 0; break;
+    STORAGE(SPI2BRGSET); *bufp = 0; break;
+    STORAGE(SPI2BRGINV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 3.
+     */
+    STORAGE(SPI3CON); break;                    // Control
+    STORAGE(SPI3CONCLR); *bufp = 0; break;
+    STORAGE(SPI3CONSET); *bufp = 0; break;
+    STORAGE(SPI3CONINV); *bufp = 0; break;
+    STORAGE(SPI3STAT); break;                   // Status
+    STORAGE(SPI3STATCLR); *bufp = 0; break;
+    STORAGE(SPI3STATSET); *bufp = 0; break;
+    STORAGE(SPI3STATINV); *bufp = 0; break;
+    STORAGE(SPI3BUF);                           // SPIx Buffer
+        *bufp = pic32_spi_readbuf(s, 2);
+        break;
+    STORAGE(SPI3BRG); break;                    // Baud rate
+    STORAGE(SPI3BRGCLR); *bufp = 0; break;
+    STORAGE(SPI3BRGSET); *bufp = 0; break;
+    STORAGE(SPI3BRGINV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 4.
+     */
+    STORAGE(SPI4CON); break;                    // Control
+    STORAGE(SPI4CONCLR); *bufp = 0; break;
+    STORAGE(SPI4CONSET); *bufp = 0; break;
+    STORAGE(SPI4CONINV); *bufp = 0; break;
+    STORAGE(SPI4STAT); break;                   // Status
+    STORAGE(SPI4STATCLR); *bufp = 0; break;
+    STORAGE(SPI4STATSET); *bufp = 0; break;
+    STORAGE(SPI4STATINV); *bufp = 0; break;
+    STORAGE(SPI4BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 3);
+        break;
+    STORAGE(SPI4BRG); break;                    // Baud rate
+    STORAGE(SPI4BRGCLR); *bufp = 0; break;
+    STORAGE(SPI4BRGSET); *bufp = 0; break;
+    STORAGE(SPI4BRGINV); *bufp = 0; break;
+
+    default:
+        printf("--- Read 1f8%05x: peripheral register not supported\n",
+            offset);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Read 1f8%05x: peripheral
register not supported\n",
+                offset);
+        exit(1);
+    }
+    return *bufp;
+}
+
+static void io_write32(pic32_t *s, unsigned offset, unsigned data,
const char **namep)
+{
+    unsigned *bufp = &VALUE(offset);
+
+    switch (offset) {
+    /*-------------------------------------------------------------------------
+     * Bus matrix control registers.
+     */
+    WRITEOP(BMXCON); return;    // Bus Matrix Control
+    STORAGE(BMXDKPBA); break;   // Data RAM kernel program base address
+    STORAGE(BMXDUDBA); break;   // Data RAM user data base address
+    STORAGE(BMXDUPBA); break;   // Data RAM user program base address
+    STORAGE(BMXPUPBA); break;   // Program Flash user program base address
+    READONLY(BMXDRMSZ);         // Data RAM memory size
+    READONLY(BMXPFMSZ);         // Program Flash memory size
+    READONLY(BMXBOOTSZ);        // Boot Flash size
+
+    /*-------------------------------------------------------------------------
+     * Interrupt controller registers.
+     */
+    WRITEOP(INTCON); return;    // Interrupt Control
+    READONLY(INTSTAT);          // Interrupt Status
+    WRITEOP(IPTMR);  return;    // Temporal Proximity Timer
+    WRITEOP(IFS0); goto irq;    // IFS(0..2) - Interrupt Flag Status
+    WRITEOP(IFS1); goto irq;
+    WRITEOP(IFS2); goto irq;
+    WRITEOP(IEC0); goto irq;    // IEC(0..2) - Interrupt Enable Control
+    WRITEOP(IEC1); goto irq;
+    WRITEOP(IEC2); goto irq;
+    WRITEOP(IPC0); goto irq;    // IPC(0..11) - Interrupt Priority Control
+    WRITEOP(IPC1); goto irq;
+    WRITEOP(IPC2); goto irq;
+    WRITEOP(IPC3); goto irq;
+    WRITEOP(IPC4); goto irq;
+    WRITEOP(IPC5); goto irq;
+    WRITEOP(IPC6); goto irq;
+    WRITEOP(IPC7); goto irq;
+    WRITEOP(IPC8); goto irq;
+    WRITEOP(IPC9); goto irq;
+    WRITEOP(IPC10); goto irq;
+    WRITEOP(IPC11); goto irq;
+    WRITEOP(IPC12);
+irq:    update_irq_status(s);
+        return;
+
+    /*-------------------------------------------------------------------------
+     * Prefetch controller.
+     */
+    WRITEOP(CHECON); return;    // Prefetch Control
+
+    /*-------------------------------------------------------------------------
+     * System controller.
+     */
+    WRITEOPR(OSCCON, PIC32_OSCCON_UNUSED); break; // Oscillator Control
+    WRITEOPR(OSCTUN, PIC32_OSCTUN_UNUSED); break; // Oscillator Tuning
+    STORAGE(DDPCON); break;     // Debug Data Port Control
+    READONLY(DEVID);            // Device Identifier
+    STORAGE(SYSKEY);            // System Key
+        /* Unlock state machine. */
+        if (s->syskey_unlock == 0 && VALUE(SYSKEY) == 0xaa996655)
+            s->syskey_unlock = 1;
+        if (s->syskey_unlock == 1 && VALUE(SYSKEY) == 0x556699aa)
+            s->syskey_unlock = 2;
+        else
+            s->syskey_unlock = 0;
+        break;
+    WRITEOPR(RCON, PIC32_RCON_UNUSED); break;       // Reset Control
+    WRITEOP(RSWRST);            // Software Reset
+        if (s->syskey_unlock == 2 && (VALUE(RSWRST) & 1)) {
+            /* Reset CPU. */
+            qemu_system_reset_request();
+
+            /* Reset all devices */
+            io_reset(s);
+            pic32_sdcard_reset(s);
+        }
+        break;
+
+    /*-------------------------------------------------------------------------
+     * DMA controller.
+     */
+    WRITEOP(DMACON); return;    // DMA Control
+    STORAGE(DMASTAT); break;    // DMA Status
+    STORAGE(DMAADDR); break;    // DMA Address
+
+    /*-------------------------------------------------------------------------
+     * Analog to digital converter.
+     */
+    WRITEOP(AD1CON1); return;   // Control register 1
+    WRITEOP(AD1CON2); return;   // Control register 2
+    WRITEOP(AD1CON3); return;   // Control register 3
+    WRITEOP(AD1CHS); return;    // Channel select
+    WRITEOP(AD1CSSL); return;   // Input scan selection
+    WRITEOP(AD1PCFG); return;   // Port configuration
+    READONLY(ADC1BUF0);         // Result words
+    READONLY(ADC1BUF1);
+    READONLY(ADC1BUF2);
+    READONLY(ADC1BUF3);
+    READONLY(ADC1BUF4);
+    READONLY(ADC1BUF5);
+    READONLY(ADC1BUF6);
+    READONLY(ADC1BUF7);
+    READONLY(ADC1BUF8);
+    READONLY(ADC1BUF9);
+    READONLY(ADC1BUFA);
+    READONLY(ADC1BUFB);
+    READONLY(ADC1BUFC);
+    READONLY(ADC1BUFD);
+    READONLY(ADC1BUFE);
+    READONLY(ADC1BUFF);
+
+    /*--------------------------------------
+     * USB registers.
+     */
+    STORAGE(U1OTGIR);           // OTG interrupt flags
+        VALUE(U1OTGIR) = 0;
+        return;
+    STORAGE(U1OTGIE); break;    // OTG interrupt enable
+    READONLY(U1OTGSTAT);        // Comparator and pin status
+    STORAGE(U1OTGCON); break;   // Resistor and pin control
+    STORAGE(U1PWRC); break;     // Power control
+    STORAGE(U1IR);              // Pending interrupt
+        VALUE(U1IR) = 0;
+        return;
+    STORAGE(U1IE); break;       // Interrupt enable
+    STORAGE(U1EIR);             // Pending error interrupt
+        VALUE(U1EIR) = 0;
+        return;
+    STORAGE(U1EIE); break;      // Error interrupt enable
+    READONLY(U1STAT);           // Status FIFO
+    STORAGE(U1CON); break;      // Control
+    STORAGE(U1ADDR); break;     // Address
+    STORAGE(U1BDTP1); break;    // Buffer descriptor table pointer 1
+    READONLY(U1FRML);           // Frame counter low
+    READONLY(U1FRMH);           // Frame counter high
+    STORAGE(U1TOK); break;      // Host control
+    STORAGE(U1SOF); break;      // SOF counter
+    STORAGE(U1BDTP2); break;    // Buffer descriptor table pointer 2
+    STORAGE(U1BDTP3); break;    // Buffer descriptor table pointer 3
+    STORAGE(U1CNFG1); break;    // Debug and idle
+    STORAGE(U1EP(0)); break;    // Endpoint control
+    STORAGE(U1EP(1)); break;
+    STORAGE(U1EP(2)); break;
+    STORAGE(U1EP(3)); break;
+    STORAGE(U1EP(4)); break;
+    STORAGE(U1EP(5)); break;
+    STORAGE(U1EP(6)); break;
+    STORAGE(U1EP(7)); break;
+    STORAGE(U1EP(8)); break;
+    STORAGE(U1EP(9)); break;
+    STORAGE(U1EP(10)); break;
+    STORAGE(U1EP(11)); break;
+    STORAGE(U1EP(12)); break;
+    STORAGE(U1EP(13)); break;
+    STORAGE(U1EP(14)); break;
+    STORAGE(U1EP(15)); break;
+
+    /*-------------------------------------------------------------------------
+     * General purpose IO signals.
+     */
+    WRITEOP(TRISA); return;         // Port A: mask of inputs
+    WRITEOPX(PORTA, LATA);          // Port A: write outputs
+    WRITEOP(LATA);                  // Port A: write outputs
+        pic32_gpio_write(s, 0, VALUE(LATA));
+        return;
+    WRITEOP(ODCA); return;          // Port A: open drain configuration
+    WRITEOP(TRISB); return;         // Port B: mask of inputs
+    WRITEOPX(PORTB, LATB);          // Port B: write outputs
+    WRITEOP(LATB);                  // Port B: write outputs
+        pic32_gpio_write(s, 1, VALUE(LATB));
+        return;
+    WRITEOP(ODCB); return;          // Port B: open drain configuration
+    WRITEOP(TRISC); return;         // Port C: mask of inputs
+    WRITEOPX(PORTC, LATC);          // Port C: write outputs
+    WRITEOP(LATC);                  // Port C: write outputs
+        pic32_gpio_write(s, 2, VALUE(LATC));
+        return;
+    WRITEOP(ODCC); return;          // Port C: open drain configuration
+    WRITEOP(TRISD); return;         // Port D: mask of inputs
+    WRITEOPX(PORTD, LATD);          // Port D: write outputs
+    WRITEOP(LATD);                  // Port D: write outputs
+        pic32_gpio_write(s, 3, VALUE(LATD));
+        return;
+    WRITEOP(ODCD); return;          // Port D: open drain configuration
+    WRITEOP(TRISE); return;         // Port E: mask of inputs
+    WRITEOPX(PORTE, LATE);          // Port E: write outputs
+    WRITEOP(LATE);                  // Port E: write outputs
+        pic32_gpio_write(s, 4, VALUE(LATE));
+        return;
+    WRITEOP(ODCE); return;          // Port E: open drain configuration
+    WRITEOP(TRISF); return;         // Port F: mask of inputs
+    WRITEOPX(PORTF, LATF);          // Port F: write outputs
+    WRITEOP(LATF);                  // Port F: write outputs
+        pic32_gpio_write(s, 5, VALUE(LATF));
+        return;
+    WRITEOP(ODCF); return;          // Port F: open drain configuration
+    WRITEOP(TRISG); return;         // Port G: mask of inputs
+    WRITEOPX(PORTG, LATG);          // Port G: write outputs
+    WRITEOP(LATG);                  // Port G: write outputs
+        pic32_gpio_write(s, 6, VALUE(LATG));
+        return;
+    WRITEOP(ODCG); return;          // Port G: open drain configuration
+    WRITEOP(CNCON); return;         // Interrupt-on-change control
+    WRITEOP(CNEN); return;          // Input change interrupt enable
+    WRITEOP(CNPUE); return;         // Input pin pull-up enable
+
+    /*-------------------------------------------------------------------------
+     * UART 1.
+     */
+    STORAGE(U1TXREG);                               // Transmit
+        pic32_uart_put_char(s, 0, data);
+        break;
+    WRITEOP(U1MODE);                                // Mode
+        pic32_uart_update_mode(s, 0);
+        return;
+    WRITEOPR(U1STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 0);
+        return;
+    WRITEOP(U1BRG); return;                         // Baud rate
+    READONLY(U1RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 2.
+     */
+    STORAGE(U2TXREG);                               // Transmit
+        pic32_uart_put_char(s, 1, data);
+        break;
+    WRITEOP(U2MODE);                                // Mode
+        pic32_uart_update_mode(s, 1);
+        return;
+    WRITEOPR(U2STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 1);
+        return;
+    WRITEOP(U2BRG); return;                         // Baud rate
+    READONLY(U2RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 3.
+     */
+    STORAGE(U3TXREG);                               // Transmit
+        pic32_uart_put_char(s, 2, data);
+        break;
+    WRITEOP(U3MODE);                                // Mode
+        pic32_uart_update_mode(s, 2);
+        return;
+    WRITEOPR(U3STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 2);
+        return;
+    WRITEOP(U3BRG); return;                         // Baud rate
+    READONLY(U3RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 4.
+     */
+    STORAGE(U4TXREG);                               // Transmit
+        pic32_uart_put_char(s, 3, data);
+        break;
+    WRITEOP(U4MODE);                                // Mode
+        pic32_uart_update_mode(s, 3);
+        return;
+    WRITEOPR(U4STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 3);
+        return;
+    WRITEOP(U4BRG); return;                         // Baud rate
+    READONLY(U4RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 5.
+     */
+    STORAGE(U5TXREG);                               // Transmit
+        pic32_uart_put_char(s, 4, data);
+        break;
+    WRITEOP(U5MODE);                                // Mode
+        pic32_uart_update_mode(s, 4);
+        return;
+    WRITEOPR(U5STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 4);
+        return;
+    WRITEOP(U5BRG); return;                         // Baud rate
+    READONLY(U5RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 6.
+     */
+    STORAGE(U6TXREG);                               // Transmit
+        pic32_uart_put_char(s, 5, data);
+        break;
+    WRITEOP(U6MODE);                                // Mode
+        pic32_uart_update_mode(s, 5);
+        return;
+    WRITEOPR(U6STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 5);
+        return;
+    WRITEOP(U6BRG); return;                         // Baud rate
+    READONLY(U6RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * SPI.
+     */
+    WRITEOP(SPI1CON);                               // Control
+        pic32_spi_control(s, 0);
+        return;
+    WRITEOPR(SPI1STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI1BUF);                               // Buffer
+        pic32_spi_writebuf(s, 0, data);
+        return;
+    WRITEOP(SPI1BRG); return;                       // Baud rate
+    WRITEOP(SPI2CON);                               // Control
+        pic32_spi_control(s, 1);
+        return;
+    WRITEOPR(SPI2STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI2BUF);                               // Buffer
+        pic32_spi_writebuf(s, 1, data);
+        return;
+    WRITEOP(SPI2BRG); return;                       // Baud rate
+    WRITEOP(SPI3CON);                               // Control
+        pic32_spi_control(s, 2);
+        return;
+    WRITEOPR(SPI3STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI3BUF);                               // Buffer
+        pic32_spi_writebuf(s, 2, data);
+        return;
+    WRITEOP(SPI3BRG); return;                       // Baud rate
+    WRITEOP(SPI4CON);                               // Control
+        pic32_spi_control(s, 3);
+        return;
+    WRITEOPR(SPI4STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI4BUF);                               // Buffer
+        pic32_spi_writebuf(s, 3, data);
+        return;
+    WRITEOP(SPI4BRG); return;                       // Baud rate
+
+    default:
+        printf("--- Write %08x to 1f8%05x: peripheral register not
supported\n",
+            data, offset);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Write %08x to 1f8%05x:
peripheral register not supported\n",
+                data, offset);
+        exit(1);
+readonly:
+        printf("--- Write %08x to %s: readonly register\n",
+            data, *namep);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Write %08x to %s: readonly register\n",
+                data, *namep);
+        *namep = 0;
+        return;
+    }
+    *bufp = data;
+}
+
+static uint64_t pic32_io_read(void *opaque, hwaddr addr, unsigned bytes)
+{
+    pic32_t *s = opaque;
+    uint32_t offset = addr & 0xfffff;
+    const char *name = "???";
+    uint32_t data = 0;
+
+    data = io_read32(s, offset & ~3, &name);
+    switch (bytes) {
+    case 1:
+        if ((offset &= 3) != 0) {
+            // Unaligned read.
+            data >>= offset * 8;
+        }
+        data = (uint8_t) data;
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %02x from %s\n", data, name);
+        }
+        break;
+    case 2:
+        if (offset & 2) {
+            // Unaligned read.
+            data >>= 16;
+        }
+        data = (uint16_t) data;
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %04x from %s\n", data, name);
+        }
+        break;
+    default:
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %08x from %s\n", data, name);
+        }
+        break;
+    }
+    return data;
+}
+
+static void pic32_io_write(void *opaque, hwaddr addr, uint64_t data,
unsigned bytes)
+{
+    pic32_t *s = opaque;
+    uint32_t offset = addr & 0xfffff;
+    const char *name = "???";
+
+    // Fetch data and align to word format.
+    switch (bytes) {
+    case 1:
+        data = (uint8_t) data;
+        data <<= (offset & 3) * 8;
+        break;
+    case 2:
+        data = (uint16_t) data;
+        data <<= (offset & 2) * 8;
+        break;
+    }
+    io_write32(s, offset & ~3, data, &name);
+
+    if (TRACE && name != 0) {
+        fprintf(qemu_logfile, "--- I/O Write %08x to %s\n",
+            (uint32_t) data, name);
+    }
+}
+
+static const MemoryRegionOps pic32_io_ops = {
+    .read       = pic32_io_read,
+    .write      = pic32_io_write,
+    .endianness = DEVICE_NATIVE_ENDIAN,
+};
+
+static void main_cpu_reset(void *opaque)
+{
+    MIPSCPU *cpu = opaque;
+    CPUMIPSState *env = &cpu->env;
+    int i;
+
+    cpu_reset(CPU(cpu));
+
+    /* Adjust the initial configuration for M4K core. */
+    env->CP0_IntCtl = 0;
+    env->CP0_Debug = (1 << CP0DB_CNT) | (3 << CP0DB_VER);
+    for (i=0; i<7; i++)
+        env->CP0_WatchHi[i] = 0;
+}
+
+static void store_byte(unsigned address, unsigned char byte)
+{
+    if (address >= PROGRAM_FLASH_START &&
+        address < PROGRAM_FLASH_START + PROGRAM_FLASH_SIZE)
+    {
+        //printf("Store %02x to program memory %08x\n", byte, address);
+        prog_ptr[address & 0xfffff] = byte;
+    }
+    else if (address >= BOOT_FLASH_START &&
+             address < BOOT_FLASH_START + BOOT_FLASH_SIZE)
+    {
+        //printf("Store %02x to boot memory %08x\n", byte, address);
+        boot_ptr[address & 0xffff] = byte;
+    }
+    else {
+        printf("Bad hex file: incorrect address %08X, must be
%08X-%08X or %08X-%08X\n",
+            address, PROGRAM_FLASH_START,
+            PROGRAM_FLASH_START + PROGRAM_FLASH_SIZE - 1,
+            BOOT_FLASH_START, BOOT_FLASH_START + BOOT_FLASH_SIZE - 1);
+        exit(1);
+    }
+}
+
+/*
+ * Ignore ^C and ^\ signals and pass these characters to the target.
+ */
+static void pic32_pass_signal_chars(void)
+{
+    struct termios tty;
+
+    tcgetattr(0, &tty);
+    tty.c_lflag &= ~ISIG;
+    tcsetattr(0, TCSANOW, &tty);
+}
+
+static void pic32_init(MachineState *machine, int board_type)
+{
+    const char *cpu_model = machine->cpu_model;
+    unsigned ram_size = DATA_MEM_SIZE;
+    MemoryRegion *system_memory = get_system_memory();
+    MemoryRegion *ram_main = g_new(MemoryRegion, 1);
+    MemoryRegion *prog_mem = g_new(MemoryRegion, 1);
+    MemoryRegion *boot_mem = g_new(MemoryRegion, 1);
+    MemoryRegion *io_mem = g_new(MemoryRegion, 1);
+    MIPSCPU *cpu;
+    CPUMIPSState *env;
+
+    DeviceState *dev = qdev_create(NULL, TYPE_MIPS_PIC32);
+    pic32_t *s = OBJECT_CHECK(pic32_t, dev, TYPE_MIPS_PIC32);
+    s->board_type = board_type;
+    s->stop_on_reset = 1;               /* halt simulation on soft reset */
+    s->iomem = g_malloc0(IO_MEM_SIZE);  /* backing storage for I/O area */
+
+    qdev_init_nofail(dev);
+
+    /* Init CPU. */
+    if (! cpu_model) {
+        cpu_model = "M4K";
+    }
+    printf("Board: %s\n", board_name[board_type]);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Board: %s\n", board_name[board_type]);
+
+    printf("Processor: %s\n", cpu_model);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Processor: %s\n", cpu_model);
+
+    cpu = cpu_mips_init(cpu_model);
+    if (! cpu) {
+        fprintf(stderr, "Unable to find CPU definition\n");
+        exit(1);
+    }
+    s->cpu = cpu;
+    env = &cpu->env;
+
+    /* Register RAM */
+    printf("RAM size: %u kbytes\n", ram_size / 1024);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "RAM size: %u kbytes\n", ram_size / 1024);
+
+    memory_region_init_ram(ram_main, NULL, "kernel.ram",
+        ram_size, &error_abort);
+    vmstate_register_ram_global(ram_main);
+    memory_region_add_subregion(system_memory, DATA_MEM_START, ram_main);
+
+    /* Alias for user space 96 kbytes.
+     * For MX family only. */
+    MemoryRegion *ram_user = g_new(MemoryRegion, 1);
+    memory_region_init_alias(ram_user, NULL, "user.ram",
+        ram_main, 0x8000, ram_size - 0x8000);
+    memory_region_add_subregion(system_memory, USER_MEM_START +
0x8000, ram_user);
+
+    /* Special function registers. */
+    memory_region_init_io(io_mem, NULL, &pic32_io_ops, s,
+                          "io", IO_MEM_SIZE);
+    memory_region_add_subregion(system_memory, IO_MEM_START, io_mem);
+
+    /*
+     * Map the flash memory.
+     */
+    memory_region_init_ram(boot_mem, NULL, "boot.flash",
BOOT_FLASH_SIZE, &error_abort);
+    memory_region_init_ram(prog_mem, NULL, "prog.flash",
PROGRAM_FLASH_SIZE, &error_abort);
+
+    /* Load a Flash memory image. */
+    if (! machine->kernel_filename) {
+        error_report("No -kernel argument was specified.");
+        exit(1);
+    }
+    prog_ptr = memory_region_get_ram_ptr(prog_mem);
+    boot_ptr = memory_region_get_ram_ptr(boot_mem);
+    if (bios_name)
+        pic32_load_hex_file(bios_name, store_byte);
+    pic32_load_hex_file(machine->kernel_filename, store_byte);
+
+    memory_region_set_readonly(boot_mem, true);
+    memory_region_set_readonly(prog_mem, true);
+    memory_region_add_subregion(system_memory, BOOT_FLASH_START, boot_mem);
+    memory_region_add_subregion(system_memory, PROGRAM_FLASH_START, prog_mem);
+
+    /* Init internal devices */
+    s->irq_raise = irq_raise;
+    s->irq_clear = irq_clear;
+    qemu_register_reset(main_cpu_reset, cpu);
+
+    /* Setup interrupt controller in EIC mode. */
+    env->CP0_Config3 |= 1 << CP0C3_VEIC;
+    cpu_mips_irq_init_cpu(env);
+    env->eic_timer_irq = pic32_timer_irq;
+    env->eic_soft_irq = pic32_soft_irq;
+    env->eic_context = s;
+
+    /* CPU runs at 80MHz.
+     * Count register increases at half this rate. */
+    cpu_mips_clock_init(env, 40*1000*1000);
+
+    /*
+     * Initialize board-specific parameters.
+     */
+    int cs0_port, cs0_pin, cs1_port, cs1_pin;
+    switch (board_type) {
+    default:
+    case BOARD_MAX32:
+        BOOTMEM(DEVCFG0) = 0xffffff7f;      // Max32 board
+        BOOTMEM(DEVCFG1) = 0x5bfd6aff;      // console on UART1
+        BOOTMEM(DEVCFG2) = 0xd979f8f9;
+        BOOTMEM(DEVCFG3) = 0xffff0722;
+        VALUE(DEVID)     = 0x04307053;      // MX795F512L
+        VALUE(OSCCON)    = 0x01453320;      // external oscillator 8MHz
+        s->sdcard_spi_port = 1;             // SD card at SPI2,
+        cs0_port = 2;  cs0_pin = 14;        // select0 at C14,
+        cs1_port = 3;  cs1_pin = 1;         // select1 at D1
+        break;
+    case BOARD_MAXIMITE:
+        BOOTMEM(DEVCFG0) = 0xffffff7f;      // TODO: get real data
from Maximite board
+        BOOTMEM(DEVCFG1) = 0x5bfd6aff;      // console on UART1
+        BOOTMEM(DEVCFG2) = 0xd979f8f9;
+        BOOTMEM(DEVCFG3) = 0xffff0722;
+        VALUE(DEVID)     = 0x04307053;      // MX795F512L
+        VALUE(OSCCON)    = 0x01453320;      // external oscillator 8MHz
+        s->sdcard_spi_port = 3;             // SD card at SPI4,
+        cs0_port = 4;  cs0_pin = 0;         // select0 at E0,
+        cs1_port = -1; cs1_pin = -1;        // select1 not available
+        break;
+    case BOARD_EXPLORER16:
+        BOOTMEM(DEVCFG0) = 0xffffff7f;      // TODO: get real data
from Explorer16 board
+        BOOTMEM(DEVCFG1) = 0x5bfd6aff;      // console on UART2
+        BOOTMEM(DEVCFG2) = 0xd979f8f9;
+        BOOTMEM(DEVCFG3) = 0xffff0722;
+        VALUE(DEVID)     = 0x04307053;      // MX795F512L
+        VALUE(OSCCON)    = 0x01453320;      // external oscillator 8MHz
+        s->sdcard_spi_port = 0;             // SD card at SPI1,
+        cs0_port = 1;  cs0_pin = 1;         // select0 at B1,
+        cs1_port = 1;  cs1_pin = 2;         // select1 at B2
+        break;
+    }
+
+    /* UARTs */
+    pic32_uart_init(s, 0, PIC32_IRQ_U1E, U1STA, U1MODE);
+    pic32_uart_init(s, 1, PIC32_IRQ_U2E, U2STA, U2MODE);
+    pic32_uart_init(s, 2, PIC32_IRQ_U3E, U3STA, U3MODE);
+    pic32_uart_init(s, 3, PIC32_IRQ_U4E, U4STA, U4MODE);
+    pic32_uart_init(s, 4, PIC32_IRQ_U5E, U5STA, U5MODE);
+    pic32_uart_init(s, 5, PIC32_IRQ_U6E, U6STA, U6MODE);
+
+    /* SPIs */
+    pic32_spi_init(s, 0, PIC32_IRQ_SPI1E, SPI1CON, SPI1STAT);
+    pic32_spi_init(s, 1, PIC32_IRQ_SPI2E, SPI2CON, SPI2STAT);
+    pic32_spi_init(s, 2, PIC32_IRQ_SPI3E, SPI3CON, SPI3STAT);
+    pic32_spi_init(s, 3, PIC32_IRQ_SPI4E, SPI4CON, SPI4STAT);
+
+    /*
+     * Load SD card images.
+     * Use options:
+     *      -sd filename
+     * or   -hda filename
+     * and  -hdb filename
+     */
+    const char *sd0_file = 0, *sd1_file = 0;
+    DriveInfo *dinfo = drive_get(IF_IDE, 0, 0);
+    if (dinfo) {
+        sd0_file = qemu_opt_get(dinfo->opts, "file");
+        dinfo->is_default = 1;
+
+        dinfo = drive_get(IF_IDE, 0, 1);
+        if (dinfo) {
+            sd1_file = qemu_opt_get(dinfo->opts, "file");
+            dinfo->is_default = 1;
+        }
+    }
+    if (! sd0_file) {
+        dinfo = drive_get(IF_SD, 0, 0);
+        if (dinfo) {
+            sd0_file = qemu_opt_get(dinfo->opts, "file");
+            dinfo->is_default = 1;
+        }
+    }
+    pic32_sdcard_init(s, 0, "sd0", sd0_file, cs0_port, cs0_pin);
+    pic32_sdcard_init(s, 1, "sd1", sd1_file, cs1_port, cs1_pin);
+
+    io_reset(s);
+    pic32_sdcard_reset(s);
+    pic32_pass_signal_chars();
+}
+
+static void pic32_init_max32(MachineState *machine)
+{
+    pic32_init(machine, BOARD_MAX32);
+}
+
+static void pic32_init_maximite(MachineState *machine)
+{
+    pic32_init(machine, BOARD_MAXIMITE);
+}
+
+static void pic32_init_explorer16(MachineState *machine)
+{
+    pic32_init(machine, BOARD_EXPLORER16);
+}
+
+static int pic32_sysbus_device_init(SysBusDevice *sysbusdev)
+{
+    return 0;
+}
+
+static void pic32_class_init(ObjectClass *klass, void *data)
+{
+    SysBusDeviceClass *k = SYS_BUS_DEVICE_CLASS(klass);
+
+    k->init = pic32_sysbus_device_init;
+}
+
+static const TypeInfo pic32_device = {
+    .name          = TYPE_MIPS_PIC32,
+    .parent        = TYPE_SYS_BUS_DEVICE,
+    .instance_size = sizeof(pic32_t),
+    .class_init    = pic32_class_init,
+};
+
+static void pic32_register_types(void)
+{
+    type_register_static(&pic32_device);
+}
+
+static QEMUMachine pic32_board[3] = {
+    {
+        .name       = "pic32mx7-max32",
+        .desc       = "PIC32MX7 microcontroller on chipKIT Max32 board",
+        .init       = pic32_init_max32,
+        .max_cpus   = 1,
+    },
+    {
+        .name       = "pic32mx7-maximite",
+        .desc       = "PIC32MX7 microcontroller on Geoff's Maximite board",
+        .init       = pic32_init_maximite,
+        .max_cpus   = 1,
+    },
+    {
+        .name       = "pic32mx7-explorer16",
+        .desc       = "PIC32MX7 microcontroller on Microchip
Explorer-16 board",
+        .init       = pic32_init_explorer16,
+        .max_cpus   = 1,
+    },
+};
+
+static void pic32_machine_init(void)
+{
+    qemu_register_machine(&pic32_board[0]);
+    qemu_register_machine(&pic32_board[1]);
+    qemu_register_machine(&pic32_board[2]);
+}
+
+type_init(pic32_register_types)
+machine_init(pic32_machine_init);
+
+#endif /* !TARGET_MIPS64 && !TARGET_WORDS_BIGENDIAN */
diff --git a/hw/mips/mips_pic32mz.c b/hw/mips/mips_pic32mz.c
new file mode 100644
index 0000000..7b621fd
--- /dev/null
+++ b/hw/mips/mips_pic32mz.c
@@ -0,0 +1,2723 @@
+/*
+ * QEMU support for Microchip PIC32MZ microcontroller.
+ *
+ * Copyright (c) 2015 Serge Vakulenko
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the
"Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
+ * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+/* Only 32-bit little endian mode supported. */
+#include "config.h"
+#if !defined TARGET_MIPS64 && !defined TARGET_WORDS_BIGENDIAN
+
+#include "hw/i386/pc.h"
+#include "hw/char/serial.h"
+#include "hw/mips/cpudevs.h"
+#include "sysemu/char.h"
+#include "hw/loader.h"
+#include "qemu/error-report.h"
+#include "hw/empty_slot.h"
+#include <termios.h>
+
+#include "pic32mz.h"
+#include "pic32_peripherals.h"
+
+/* Hardware addresses */
+#define PROGRAM_FLASH_START 0x1d000000
+#define BOOT_FLASH_START    0x1fc00000
+#define DATA_MEM_START      0x00000000
+#define IO_MEM_START        0x1f800000
+
+#define PROGRAM_FLASH_SIZE  (2*1024*1024)       // 2 Mbytes
+#define BOOT_FLASH_SIZE     (64*1024)           // 64 kbytes
+#define DATA_MEM_SIZE       (512*1024)          // 512 kbytes
+
+#define TYPE_MIPS_PIC32     "mips-pic32mz"
+
+/*
+ * Board variants.
+ */
+enum {
+    BOARD_WIFIRE,           /* chipKIT WiFire board */
+    BOARD_MEBII,            /* Microchip MEB-II board */
+    BOARD_EXPLORER16,       /* Microchip Explorer-16 board */
+};
+
+static const char *board_name[] = {
+    "chipKIT WiFire",
+    "Microchip MEB-II",
+    "Microchip Explorer16",
+};
+
+/*
+ * Pointers to Flash memory contents.
+ */
+static char *prog_ptr;
+static char *boot_ptr;
+
+#define BOOTMEM(addr) ((uint32_t*) boot_ptr) [(addr & 0xffff) >> 2]
+
+/*
+ * TODO: add option to enable tracing.
+ */
+#define TRACE   0
+
+static void update_irq_status(pic32_t *s)
+{
+    /* Assume no interrupts pending. */
+    int cause_ripl = 0;
+    int vector = 0;
+    CPUMIPSState *env = &s->cpu->env;
+    int current_ripl = (env->CP0_Cause >> (CP0Ca_IP + 2)) & 0x3f;
+
+    VALUE(INTSTAT) = 0;
+
+    if ((VALUE(IFS0) & VALUE(IEC0)) ||
+        (VALUE(IFS1) & VALUE(IEC1)) ||
+        (VALUE(IFS2) & VALUE(IEC2)) ||
+        (VALUE(IFS3) & VALUE(IEC3)) ||
+        (VALUE(IFS4) & VALUE(IEC4)) ||
+        (VALUE(IFS5) & VALUE(IEC5)))
+    {
+        /* Find the most prioritive pending interrupt,
+         * it's vector and level. */
+        int irq;
+        for (irq=0; irq<=PIC32_IRQ_LAST; irq++) {
+            int n = irq >> 5;
+
+            if (((VALUE(IFS(n)) & VALUE(IEC(n))) >> (irq & 31)) & 1) {
+                /* Interrupt is pending. */
+                int level = VALUE(IPC(irq >> 2));
+                level >>= 2 + (irq & 3) * 8;
+                level &= 7;
+                if (level > cause_ripl) {
+                    vector = irq;
+                    cause_ripl = level;
+                }
+            }
+        }
+        VALUE(INTSTAT) = vector | (cause_ripl << 8);
+    }
+
+    if (cause_ripl == current_ripl)
+        return;
+
+    if (TRACE)
+        fprintf(qemu_logfile, "--- Priority level Cause.RIPL = %u\n",
+            cause_ripl);
+
+    /*
+     * Modify Cause.RIPL field and take EIC interrupt.
+     */
+    env->CP0_Cause &= ~(0x3f << (CP0Ca_IP + 2));
+    env->CP0_Cause |= cause_ripl << (CP0Ca_IP + 2);
+    cpu_interrupt(CPU(s->cpu), CPU_INTERRUPT_HARD);
+}
+
+/*
+ * Set interrupt flag status
+ */
+static void irq_raise(pic32_t *s, int irq)
+{
+    if (VALUE(IFS(irq >> 5)) & (1 << (irq & 31)))
+        return;
+
+    VALUE(IFS(irq >> 5)) |= 1 << (irq & 31);
+    update_irq_status(s);
+}
+
+/*
+ * Clear interrupt flag status
+ */
+static void irq_clear(pic32_t *s, int irq)
+{
+    if (! (VALUE(IFS(irq >> 5)) & (1 << (irq & 31))))
+        return;
+
+    VALUE(IFS(irq >> 5)) &= ~(1 << (irq & 31));
+    update_irq_status(s);
+}
+
+/*
+ * Timer interrupt.
+ */
+static void pic32_timer_irq(CPUMIPSState *env, int raise)
+{
+    pic32_t *s = env->eic_context;
+
+    if (raise) {
+        if (TRACE)
+            fprintf(qemu_logfile, "--- %08x: Timer interrupt\n",
+                env->active_tc.PC);
+        irq_raise(s, 0);
+    } else {
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Clear timer interrupt\n");
+        irq_clear(s, 0);
+    }
+}
+
+/*
+ * Software interrupt.
+ */
+static void pic32_soft_irq(CPUMIPSState *env, int num)
+{
+    pic32_t *s = env->eic_context;
+
+    if (TRACE)
+        fprintf(qemu_logfile, "--- %08x: Soft interrupt %u\n",
+            env->active_tc.PC, num);
+    irq_raise(s, num + 1);
+}
+
+/*
+ * Perform an assign/clear/set/invert operation.
+ */
+static inline unsigned write_op(int a, int b, int op)
+{
+    switch (op & 0xc) {
+    case 0x0: a = b;   break;   // Assign
+    case 0x4: a &= ~b; break;   // Clear
+    case 0x8: a |= b;  break;   // Set
+    case 0xc: a ^= b;  break;   // Invert
+    }
+    return a;
+}
+
+static void io_reset(pic32_t *s)
+{
+    int i;
+
+    /*
+     * Prefetch controller.
+     */
+    VALUE(PRECON) = 0x00000007;
+
+    /*
+     * System controller.
+     */
+    s->syskey_unlock = 0;
+    VALUE(CFGCON) = PIC32_CFGCON_ECC_DISWR | PIC32_CFGCON_TDOEN;
+    VALUE(SYSKEY) = 0;
+    VALUE(RCON)   = 0;
+    VALUE(RSWRST) = 0;
+    VALUE(OSCTUN) = 0;
+    VALUE(SPLLCON)= 0x01310201;
+    VALUE(PB1DIV) = 0x00008801;
+    VALUE(PB2DIV) = 0x00008801;
+    VALUE(PB3DIV) = 0x00008801;
+    VALUE(PB4DIV) = 0x00008801;
+    VALUE(PB5DIV) = 0x00008801;
+    VALUE(PB7DIV) = 0x00008800;
+    VALUE(PB8DIV) = 0x00008801;
+
+    /*
+     * General purpose IO signals.
+     * All pins are inputs, high, open drains and pullups disabled.
+     * No interrupts on change.
+     */
+    VALUE(ANSELA) = 0xFFFF;             // Port A: analog select
+    VALUE(TRISA) = 0xFFFF;              // Port A: mask of inputs
+    VALUE(PORTA) = 0xFFCF;              // Port A: read inputs, write outputs
+    VALUE(LATA)  = 0xFFFF;              // Port A: read/write outputs
+    VALUE(ODCA)  = 0;                   // Port A: open drain configuration
+    VALUE(CNPUA) = 0;                   // Input pin pull-up
+    VALUE(CNPDA) = 0;                   // Input pin pull-down
+    VALUE(CNCONA) = 0;                  // Interrupt-on-change control
+    VALUE(CNENA) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATA) = 0;                 // Input change status
+
+    VALUE(ANSELB) = 0xFFFF;             // Port B: analog select
+    VALUE(TRISB) = 0xFFFF;              // Port B: mask of inputs
+    VALUE(PORTB) = 0xFFFF;              // Port B: read inputs, write outputs
+    if (s->board_type == BOARD_MEBII)
+        VALUE(PORTB) ^= 1 << 12;        // Disable pin RB12 - button 1
+    VALUE(LATB)  = 0xFFFF;              // Port B: read/write outputs
+    VALUE(ODCB)  = 0;                   // Port B: open drain configuration
+    VALUE(CNPUB) = 0;                   // Input pin pull-up
+    VALUE(CNPDB) = 0;                   // Input pin pull-down
+    VALUE(CNCONB) = 0;                  // Interrupt-on-change control
+    VALUE(CNENB) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATB) = 0;                 // Input change status
+
+    VALUE(ANSELC) = 0xFFFF;             // Port C: analog select
+    VALUE(TRISC) = 0xFFFF;              // Port C: mask of inputs
+    VALUE(PORTC) = 0xFFFF;              // Port C: read inputs, write outputs
+    VALUE(LATC)  = 0xFFFF;              // Port C: read/write outputs
+    if (s->board_type == BOARD_WIFIRE)
+        VALUE(LATC) ^= 0x1000;          // Disable latc[15] for the
chipKIT bootloader
+    VALUE(ODCC)  = 0;                   // Port C: open drain configuration
+    VALUE(CNPUC) = 0;                   // Input pin pull-up
+    VALUE(CNPDC) = 0;                   // Input pin pull-down
+    VALUE(CNCONC) = 0;                  // Interrupt-on-change control
+    VALUE(CNENC) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATC) = 0;                 // Input change status
+
+    VALUE(ANSELD) = 0xFFFF;             // Port D: analog select
+    VALUE(TRISD) = 0xFFFF;              // Port D: mask of inputs
+    VALUE(PORTD) = 0xFFFF;              // Port D: read inputs, write outputs
+    VALUE(LATD)  = 0xFFFF;              // Port D: read/write outputs
+    VALUE(ODCD)  = 0;                   // Port D: open drain configuration
+    VALUE(CNPUD) = 0;                   // Input pin pull-up
+    VALUE(CNPDD) = 0;                   // Input pin pull-down
+    VALUE(CNCOND) = 0;                  // Interrupt-on-change control
+    VALUE(CNEND) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATD) = 0;                 // Input change status
+
+    VALUE(ANSELE) = 0xFFFF;             // Port E: analog select
+    VALUE(TRISE) = 0xFFFF;              // Port E: mask of inputs
+    VALUE(PORTE) = 0xFFFF;              // Port E: read inputs, write outputs
+    VALUE(LATE)  = 0xFFFF;              // Port E: read/write outputs
+    VALUE(ODCE)  = 0;                   // Port E: open drain configuration
+    VALUE(CNPUE) = 0;                   // Input pin pull-up
+    VALUE(CNPDE) = 0;                   // Input pin pull-down
+    VALUE(CNCONE) = 0;                  // Interrupt-on-change control
+    VALUE(CNENE) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATE) = 0;                 // Input change status
+
+    VALUE(ANSELF) = 0xFFFF;             // Port F: analog select
+    VALUE(TRISF) = 0xFFFF;              // Port F: mask of inputs
+    VALUE(PORTF) = 0xFFFF;              // Port F: read inputs, write outputs
+    VALUE(LATF)  = 0xFFFF;              // Port F: read/write outputs
+    VALUE(ODCF)  = 0;                   // Port F: open drain configuration
+    VALUE(CNPUF) = 0;                   // Input pin pull-up
+    VALUE(CNPDF) = 0;                   // Input pin pull-down
+    VALUE(CNCONF) = 0;                  // Interrupt-on-change control
+    VALUE(CNENF) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATF) = 0;                 // Input change status
+
+    VALUE(ANSELG) = 0xFFFF;             // Port G: analog select
+    VALUE(TRISG) = 0xFFFF;              // Port G: mask of inputs
+    VALUE(PORTG) = 0xFFFF;              // Port G: read inputs, write outputs
+    VALUE(LATG)  = 0xFFFF;              // Port G: read/write outputs
+    VALUE(ODCG)  = 0;                   // Port G: open drain configuration
+    VALUE(CNPUG) = 0;                   // Input pin pull-up
+    VALUE(CNPDG) = 0;                   // Input pin pull-down
+    VALUE(CNCONG) = 0;                  // Interrupt-on-change control
+    VALUE(CNENG) = 0;                   // Input change interrupt enable
+    VALUE(CNSTATG) = 0;                 // Input change status
+
+    /*
+     * Reset UARTs.
+     */
+    VALUE(U1MODE)  = 0;
+    VALUE(U1STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U1TXREG) = 0;
+    VALUE(U1RXREG) = 0;
+    VALUE(U1BRG)   = 0;
+    VALUE(U2MODE)  = 0;
+    VALUE(U2STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U2TXREG) = 0;
+    VALUE(U2RXREG) = 0;
+    VALUE(U2BRG)   = 0;
+    VALUE(U3MODE)  = 0;
+    VALUE(U3STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U3TXREG) = 0;
+    VALUE(U3RXREG) = 0;
+    VALUE(U3BRG)   = 0;
+    VALUE(U4MODE)  = 0;
+    VALUE(U4STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U4TXREG) = 0;
+    VALUE(U4RXREG) = 0;
+    VALUE(U4BRG)   = 0;
+    VALUE(U5MODE)  = 0;
+    VALUE(U5STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U5TXREG) = 0;
+    VALUE(U5RXREG) = 0;
+    VALUE(U5BRG)   = 0;
+    VALUE(U6MODE)  = 0;
+    VALUE(U6STA)   = PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    VALUE(U6TXREG) = 0;
+    VALUE(U6RXREG) = 0;
+    VALUE(U6BRG)   = 0;
+
+    /*
+     * Reset SPI.
+     */
+    VALUE(SPI1CON)  = 0;
+    VALUE(SPI1STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI1BRG)  = 0;
+
+    VALUE(SPI2CON)  = 0;
+    VALUE(SPI2STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI2BRG)  = 0;
+
+    VALUE(SPI3CON)  = 0;
+    VALUE(SPI3STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI3BRG)  = 0;
+
+    VALUE(SPI4CON)  = 0;
+    VALUE(SPI4STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI4BRG)  = 0;
+
+    VALUE(SPI5CON)  = 0;
+    VALUE(SPI5STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI5BRG)  = 0;
+
+    VALUE(SPI6CON)  = 0;
+    VALUE(SPI6STAT) = PIC32_SPISTAT_SPITBE;     // Transmit buffer is empty
+    VALUE(SPI6BRG)  = 0;
+
+    VALUE(SPI1CON2) = 0;
+    VALUE(SPI2CON2) = 0;
+    VALUE(SPI3CON2) = 0;
+    VALUE(SPI4CON2) = 0;
+    VALUE(SPI5CON2) = 0;
+    VALUE(SPI6CON2) = 0;
+
+    for (i=0; i<NUM_SPI; i++) {
+        s->spi[i].rfifo = 0;
+        s->spi[i].wfifo = 0;
+    }
+
+    /*
+     * Reset timers.
+     */
+    VALUE(T1CON)    = 0;
+    VALUE(TMR1)     = 0;
+    VALUE(PR1)      = 0xffff;
+    VALUE(T2CON)    = 0;
+    VALUE(TMR2)     = 0;
+    VALUE(PR2)      = 0xffff;
+    VALUE(T3CON)    = 0;
+    VALUE(TMR3)     = 0;
+    VALUE(PR3)      = 0xffff;
+    VALUE(T4CON)    = 0;
+    VALUE(TMR4)     = 0;
+    VALUE(PR4)      = 0xffff;
+    VALUE(T5CON)    = 0;
+    VALUE(TMR5)     = 0;
+    VALUE(PR5)      = 0xffff;
+    VALUE(T6CON)    = 0;
+    VALUE(TMR6)     = 0;
+    VALUE(PR6)      = 0xffff;
+    VALUE(T7CON)    = 0;
+    VALUE(TMR7)     = 0;
+    VALUE(PR7)      = 0xffff;
+    VALUE(T8CON)    = 0;
+    VALUE(TMR8)     = 0;
+    VALUE(PR8)      = 0xffff;
+    VALUE(T9CON)    = 0;
+    VALUE(TMR9)     = 0;
+    VALUE(PR9)      = 0xffff;
+
+    /*
+     * Reset Ethernet.
+     */
+    VALUE(ETHCON1)      = 0;        // Control 1
+    VALUE(ETHCON2)      = 0;        // Control 2: RX data buffer size
+    VALUE(ETHTXST)      = 0;        // Tx descriptor start address
+    VALUE(ETHRXST)      = 0;        // Rx descriptor start address
+    VALUE(ETHHT0)       = 0;        // Hash tasble 0
+    VALUE(ETHHT1)       = 0;        // Hash tasble 1
+    VALUE(ETHPMM0)      = 0;        // Pattern match mask 0
+    VALUE(ETHPMM1)      = 0;        // Pattern match mask 1
+    VALUE(ETHPMCS)      = 0;        // Pattern match checksum
+    VALUE(ETHPMO)       = 0;        // Pattern match offset
+    VALUE(ETHRXFC)      = 0;        // Receive filter configuration
+    VALUE(ETHRXWM)      = 0;        // Receive watermarks
+    VALUE(ETHIEN)       = 0;        // Interrupt enable
+    VALUE(ETHIRQ)       = 0;        // Interrupt request
+    VALUE(ETHSTAT)      = 0;        // Status
+    VALUE(ETHRXOVFLOW)  = 0;        // Receive overflow statistics
+    VALUE(ETHFRMTXOK)   = 0;        // Frames transmitted OK statistics
+    VALUE(ETHSCOLFRM)   = 0;        // Single collision frames statistics
+    VALUE(ETHMCOLFRM)   = 0;        // Multiple collision frames statistics
+    VALUE(ETHFRMRXOK)   = 0;        // Frames received OK statistics
+    VALUE(ETHFCSERR)    = 0;        // Frame check sequence error statistics
+    VALUE(ETHALGNERR)   = 0;        // Alignment errors statistics
+    VALUE(EMAC1CFG1)    = 0x800d;   // MAC configuration 1
+    VALUE(EMAC1CFG2)    = 0x4082;   // MAC configuration 2
+    VALUE(EMAC1IPGT)    = 0x0012;   // MAC back-to-back interpacket gap
+    VALUE(EMAC1IPGR)    = 0x0c12;   // MAC non-back-to-back interpacket gap
+    VALUE(EMAC1CLRT)    = 0x370f;   // MAC collision window/retry limit
+    VALUE(EMAC1MAXF)    = 0x05ee;   // MAC maximum frame length
+    VALUE(EMAC1SUPP)    = 0x1000;   // MAC PHY support
+    VALUE(EMAC1TEST)    = 0;        // MAC test
+    VALUE(EMAC1MCFG)    = 0x0020;   // MII configuration
+    VALUE(EMAC1MCMD)    = 0;        // MII command
+    VALUE(EMAC1MADR)    = 0x0100;   // MII address
+    VALUE(EMAC1MWTD)    = 0;        // MII write data
+    VALUE(EMAC1MRDD)    = 0;        // MII read data
+    VALUE(EMAC1MIND)    = 0;        // MII indicators
+    VALUE(EMAC1SA0)     = 0x79c1;   // MAC station address 0
+    VALUE(EMAC1SA1)     = 0xcbc0;   // MAC station address 1
+    VALUE(EMAC1SA2)     = 0x1e00;   // MAC station address 2
+
+    /*
+     * Reset USB.
+     */
+    VALUE(USBCSR0)      = 0x2000;
+    VALUE(USBCSR1)      = 0x00ff0000;
+    VALUE(USBCSR2)      = 0x060000fe;
+    VALUE(USBCSR3)      = 0;
+    VALUE(USBIENCSR0)   = 0;
+    VALUE(USBIENCSR1)   = 0;
+    VALUE(USBIENCSR2)   = 0;
+    VALUE(USBIENCSR3)   = 0;
+    VALUE(USBFIFO0)     = 0;
+    VALUE(USBFIFO1)     = 0;
+    VALUE(USBFIFO2)     = 0;
+    VALUE(USBFIFO3)     = 0;
+    VALUE(USBFIFO4)     = 0;
+    VALUE(USBFIFO5)     = 0;
+    VALUE(USBFIFO6)     = 0;
+    VALUE(USBFIFO7)     = 0;
+    VALUE(USBOTG)       = 0x0080;
+    VALUE(USBFIFOA)     = 0;
+    VALUE(USBHWVER)     = 0x0800;
+    VALUE(USBINFO)      = 0x3C5C8C77;
+    VALUE(USBEOFRST)    = 0x00727780;
+    VALUE(USBE0TXA)     = 0;
+    VALUE(USBE0RXA)     = 0;
+    VALUE(USBE1TXA)     = 0;
+    VALUE(USBE1RXA)     = 0;
+    VALUE(USBE2TXA)     = 0;
+    VALUE(USBE2RXA)     = 0;
+    VALUE(USBE3TXA)     = 0;
+    VALUE(USBE3RXA)     = 0;
+    VALUE(USBE4TXA)     = 0;
+    VALUE(USBE4RXA)     = 0;
+    VALUE(USBE5TXA)     = 0;
+    VALUE(USBE5RXA)     = 0;
+    VALUE(USBE6TXA)     = 0;
+    VALUE(USBE6RXA)     = 0;
+    VALUE(USBE7TXA)     = 0;
+    VALUE(USBE7RXA)     = 0;
+    VALUE(USBE0CSR0)    = 0;
+    VALUE(USBE0CSR2)    = 0;
+    VALUE(USBE0CSR3)    = 0;
+    VALUE(USBE1CSR0)    = 0;
+    VALUE(USBE1CSR1)    = 0;
+    VALUE(USBE1CSR2)    = 0;
+    VALUE(USBE1CSR3)    = 0;
+    VALUE(USBE2CSR0)    = 0;
+    VALUE(USBE2CSR1)    = 0;
+    VALUE(USBE2CSR2)    = 0;
+    VALUE(USBE2CSR3)    = 0;
+    VALUE(USBE3CSR0)    = 0;
+    VALUE(USBE3CSR1)    = 0;
+    VALUE(USBE3CSR2)    = 0;
+    VALUE(USBE3CSR3)    = 0;
+    VALUE(USBE4CSR0)    = 0;
+    VALUE(USBE4CSR1)    = 0;
+    VALUE(USBE4CSR2)    = 0;
+    VALUE(USBE4CSR3)    = 0;
+    VALUE(USBE5CSR0)    = 0;
+    VALUE(USBE5CSR1)    = 0;
+    VALUE(USBE5CSR2)    = 0;
+    VALUE(USBE5CSR3)    = 0;
+    VALUE(USBE6CSR0)    = 0;
+    VALUE(USBE6CSR1)    = 0;
+    VALUE(USBE6CSR2)    = 0;
+    VALUE(USBE6CSR3)    = 0;
+    VALUE(USBE7CSR0)    = 0;
+    VALUE(USBE7CSR1)    = 0;
+    VALUE(USBE7CSR2)    = 0;
+    VALUE(USBE7CSR3)    = 0;
+    VALUE(USBDMAINT)    = 0;
+    VALUE(USBDMA1C)     = 0;
+    VALUE(USBDMA1A)     = 0;
+    VALUE(USBDMA1N)     = 0;
+    VALUE(USBDMA2C)     = 0;
+    VALUE(USBDMA2A)     = 0;
+    VALUE(USBDMA2N)     = 0;
+    VALUE(USBDMA3C)     = 0;
+    VALUE(USBDMA3A)     = 0;
+    VALUE(USBDMA3N)     = 0;
+    VALUE(USBDMA4C)     = 0;
+    VALUE(USBDMA4A)     = 0;
+    VALUE(USBDMA4N)     = 0;
+    VALUE(USBDMA5C)     = 0;
+    VALUE(USBDMA5A)     = 0;
+    VALUE(USBDMA5N)     = 0;
+    VALUE(USBDMA6C)     = 0;
+    VALUE(USBDMA6A)     = 0;
+    VALUE(USBDMA6N)     = 0;
+    VALUE(USBDMA7C)     = 0;
+    VALUE(USBDMA7A)     = 0;
+    VALUE(USBDMA7N)     = 0;
+    VALUE(USBDMA8C)     = 0;
+    VALUE(USBDMA8A)     = 0;
+    VALUE(USBDMA8N)     = 0;
+    VALUE(USBE1RPC)     = 0;
+    VALUE(USBE2RPC)     = 0;
+    VALUE(USBE3RPC)     = 0;
+    VALUE(USBE4RPC)     = 0;
+    VALUE(USBE5RPC)     = 0;
+    VALUE(USBE6RPC)     = 0;
+    VALUE(USBE7RPC)     = 0;
+    VALUE(USBDPBFD)     = 0;
+    VALUE(USBTMCON1)    = 0x05E64074;
+    VALUE(USBTMCON2)    = 0;
+    VALUE(USBLPMR1)     = 0;
+    VALUE(USBLMPR2)     = 0;
+}
+
+static unsigned io_read32(pic32_t *s, unsigned offset, const char **namep)
+{
+    unsigned *bufp = &VALUE(offset);
+
+    switch (offset) {
+    /*-------------------------------------------------------------------------
+     * Interrupt controller registers.
+     */
+    STORAGE(INTCON); break;     // Interrupt Control
+    STORAGE(INTSTAT); break;    // Interrupt Status
+    STORAGE(IFS0); break;       // IFS(0..2) - Interrupt Flag Status
+    STORAGE(IFS1); break;
+    STORAGE(IFS2); break;
+    STORAGE(IFS3); break;
+    STORAGE(IFS4); break;
+    STORAGE(IFS5); break;
+    STORAGE(IEC0); break;       // IEC(0..2) - Interrupt Enable Control
+    STORAGE(IEC1); break;
+    STORAGE(IEC2); break;
+    STORAGE(IEC3); break;
+    STORAGE(IEC4); break;
+    STORAGE(IEC5); break;
+
+    // IPC(0..11) - Interrupt Priority Control
+    STORAGE(IPC0); break;       STORAGE(IPC1); break;
+    STORAGE(IPC2); break;       STORAGE(IPC3); break;
+    STORAGE(IPC4); break;       STORAGE(IPC5); break;
+    STORAGE(IPC6); break;       STORAGE(IPC7); break;
+    STORAGE(IPC8); break;       STORAGE(IPC9); break;
+    STORAGE(IPC10); break;      STORAGE(IPC11); break;
+    STORAGE(IPC12); break;      STORAGE(IPC13); break;
+    STORAGE(IPC14); break;      STORAGE(IPC15); break;
+    STORAGE(IPC16); break;      STORAGE(IPC17); break;
+    STORAGE(IPC18); break;      STORAGE(IPC19); break;
+    STORAGE(IPC20); break;      STORAGE(IPC21); break;
+    STORAGE(IPC22); break;      STORAGE(IPC23); break;
+    STORAGE(IPC24); break;      STORAGE(IPC25); break;
+    STORAGE(IPC26); break;      STORAGE(IPC27); break;
+    STORAGE(IPC28); break;      STORAGE(IPC29); break;
+    STORAGE(IPC30); break;      STORAGE(IPC31); break;
+    STORAGE(IPC32); break;      STORAGE(IPC33); break;
+    STORAGE(IPC34); break;      STORAGE(IPC35); break;
+    STORAGE(IPC36); break;      STORAGE(IPC37); break;
+    STORAGE(IPC38); break;      STORAGE(IPC39); break;
+    STORAGE(IPC40); break;      STORAGE(IPC41); break;
+    STORAGE(IPC42); break;      STORAGE(IPC43); break;
+    STORAGE(IPC44); break;      STORAGE(IPC45); break;
+    STORAGE(IPC46); break;      STORAGE(IPC47); break;
+
+    // OFF000..OFF190 - Interrupt Vector Address Offset
+    STORAGE(OFF(0)); break;     STORAGE(OFF(1)); break;
+    STORAGE(OFF(2)); break;     STORAGE(OFF(3)); break;
+    STORAGE(OFF(4)); break;     STORAGE(OFF(5)); break;
+    STORAGE(OFF(6)); break;     STORAGE(OFF(7)); break;
+    STORAGE(OFF(8)); break;     STORAGE(OFF(9)); break;
+    STORAGE(OFF(10)); break;    STORAGE(OFF(11)); break;
+    STORAGE(OFF(12)); break;    STORAGE(OFF(13)); break;
+    STORAGE(OFF(14)); break;    STORAGE(OFF(15)); break;
+    STORAGE(OFF(16)); break;    STORAGE(OFF(17)); break;
+    STORAGE(OFF(18)); break;    STORAGE(OFF(19)); break;
+    STORAGE(OFF(20)); break;    STORAGE(OFF(21)); break;
+    STORAGE(OFF(22)); break;    STORAGE(OFF(23)); break;
+    STORAGE(OFF(24)); break;    STORAGE(OFF(25)); break;
+    STORAGE(OFF(26)); break;    STORAGE(OFF(27)); break;
+    STORAGE(OFF(28)); break;    STORAGE(OFF(29)); break;
+    STORAGE(OFF(30)); break;    STORAGE(OFF(31)); break;
+    STORAGE(OFF(32)); break;    STORAGE(OFF(33)); break;
+    STORAGE(OFF(34)); break;    STORAGE(OFF(35)); break;
+    STORAGE(OFF(36)); break;    STORAGE(OFF(37)); break;
+    STORAGE(OFF(38)); break;    STORAGE(OFF(39)); break;
+    STORAGE(OFF(40)); break;    STORAGE(OFF(41)); break;
+    STORAGE(OFF(42)); break;    STORAGE(OFF(43)); break;
+    STORAGE(OFF(44)); break;    STORAGE(OFF(45)); break;
+    STORAGE(OFF(46)); break;    STORAGE(OFF(47)); break;
+    STORAGE(OFF(48)); break;    STORAGE(OFF(49)); break;
+    STORAGE(OFF(50)); break;    STORAGE(OFF(51)); break;
+    STORAGE(OFF(52)); break;    STORAGE(OFF(53)); break;
+    STORAGE(OFF(54)); break;    STORAGE(OFF(55)); break;
+    STORAGE(OFF(56)); break;    STORAGE(OFF(57)); break;
+    STORAGE(OFF(58)); break;    STORAGE(OFF(59)); break;
+    STORAGE(OFF(60)); break;    STORAGE(OFF(61)); break;
+    STORAGE(OFF(62)); break;    STORAGE(OFF(63)); break;
+    STORAGE(OFF(64)); break;    STORAGE(OFF(65)); break;
+    STORAGE(OFF(66)); break;    STORAGE(OFF(67)); break;
+    STORAGE(OFF(68)); break;    STORAGE(OFF(69)); break;
+    STORAGE(OFF(70)); break;    STORAGE(OFF(71)); break;
+    STORAGE(OFF(72)); break;    STORAGE(OFF(73)); break;
+    STORAGE(OFF(74)); break;    STORAGE(OFF(75)); break;
+    STORAGE(OFF(76)); break;    STORAGE(OFF(77)); break;
+    STORAGE(OFF(78)); break;    STORAGE(OFF(79)); break;
+    STORAGE(OFF(80)); break;    STORAGE(OFF(81)); break;
+    STORAGE(OFF(82)); break;    STORAGE(OFF(83)); break;
+    STORAGE(OFF(84)); break;    STORAGE(OFF(85)); break;
+    STORAGE(OFF(86)); break;    STORAGE(OFF(87)); break;
+    STORAGE(OFF(88)); break;    STORAGE(OFF(89)); break;
+    STORAGE(OFF(90)); break;    STORAGE(OFF(91)); break;
+    STORAGE(OFF(92)); break;    STORAGE(OFF(93)); break;
+    STORAGE(OFF(94)); break;    STORAGE(OFF(95)); break;
+    STORAGE(OFF(96)); break;    STORAGE(OFF(97)); break;
+    STORAGE(OFF(98)); break;    STORAGE(OFF(99)); break;
+    STORAGE(OFF(100)); break;   STORAGE(OFF(101)); break;
+    STORAGE(OFF(102)); break;   STORAGE(OFF(103)); break;
+    STORAGE(OFF(104)); break;   STORAGE(OFF(105)); break;
+    STORAGE(OFF(106)); break;   STORAGE(OFF(107)); break;
+    STORAGE(OFF(108)); break;   STORAGE(OFF(109)); break;
+    STORAGE(OFF(110)); break;   STORAGE(OFF(111)); break;
+    STORAGE(OFF(112)); break;   STORAGE(OFF(113)); break;
+    STORAGE(OFF(114)); break;   STORAGE(OFF(115)); break;
+    STORAGE(OFF(116)); break;   STORAGE(OFF(117)); break;
+    STORAGE(OFF(118)); break;   STORAGE(OFF(119)); break;
+    STORAGE(OFF(120)); break;   STORAGE(OFF(121)); break;
+    STORAGE(OFF(122)); break;   STORAGE(OFF(123)); break;
+    STORAGE(OFF(124)); break;   STORAGE(OFF(125)); break;
+    STORAGE(OFF(126)); break;   STORAGE(OFF(127)); break;
+    STORAGE(OFF(128)); break;   STORAGE(OFF(129)); break;
+    STORAGE(OFF(130)); break;   STORAGE(OFF(131)); break;
+    STORAGE(OFF(132)); break;   STORAGE(OFF(133)); break;
+    STORAGE(OFF(134)); break;   STORAGE(OFF(135)); break;
+    STORAGE(OFF(136)); break;   STORAGE(OFF(137)); break;
+    STORAGE(OFF(138)); break;   STORAGE(OFF(139)); break;
+    STORAGE(OFF(140)); break;   STORAGE(OFF(141)); break;
+    STORAGE(OFF(142)); break;   STORAGE(OFF(143)); break;
+    STORAGE(OFF(144)); break;   STORAGE(OFF(145)); break;
+    STORAGE(OFF(146)); break;   STORAGE(OFF(147)); break;
+    STORAGE(OFF(148)); break;   STORAGE(OFF(149)); break;
+    STORAGE(OFF(150)); break;   STORAGE(OFF(151)); break;
+    STORAGE(OFF(152)); break;   STORAGE(OFF(153)); break;
+    STORAGE(OFF(154)); break;   STORAGE(OFF(155)); break;
+    STORAGE(OFF(156)); break;   STORAGE(OFF(157)); break;
+    STORAGE(OFF(158)); break;   STORAGE(OFF(159)); break;
+    STORAGE(OFF(160)); break;   STORAGE(OFF(161)); break;
+    STORAGE(OFF(162)); break;   STORAGE(OFF(163)); break;
+    STORAGE(OFF(164)); break;   STORAGE(OFF(165)); break;
+    STORAGE(OFF(166)); break;   STORAGE(OFF(167)); break;
+    STORAGE(OFF(168)); break;   STORAGE(OFF(169)); break;
+    STORAGE(OFF(170)); break;   STORAGE(OFF(171)); break;
+    STORAGE(OFF(172)); break;   STORAGE(OFF(173)); break;
+    STORAGE(OFF(174)); break;   STORAGE(OFF(175)); break;
+    STORAGE(OFF(176)); break;   STORAGE(OFF(177)); break;
+    STORAGE(OFF(178)); break;   STORAGE(OFF(179)); break;
+    STORAGE(OFF(180)); break;   STORAGE(OFF(181)); break;
+    STORAGE(OFF(182)); break;   STORAGE(OFF(183)); break;
+    STORAGE(OFF(184)); break;   STORAGE(OFF(185)); break;
+    STORAGE(OFF(186)); break;   STORAGE(OFF(187)); break;
+    STORAGE(OFF(188)); break;   STORAGE(OFF(189)); break;
+    STORAGE(OFF(190)); break;
+
+    /*-------------------------------------------------------------------------
+     * Prefetch controller.
+     */
+    STORAGE(PRECON); break;     // Prefetch Control
+    STORAGE(PRESTAT); break;    // Prefetch Status
+
+    /*-------------------------------------------------------------------------
+     * System controller.
+     */
+    STORAGE(CFGCON); break;     // Configuration Control
+    STORAGE(DEVID); break;      // Device Identifier
+    STORAGE(SYSKEY); break;     // System Key
+    STORAGE(RCON); break;       // Reset Control
+    STORAGE(RSWRST);            // Software Reset
+        if ((VALUE(RSWRST) & 1) && s->stop_on_reset) {
+            exit(0);
+        }
+        break;
+    STORAGE(OSCCON); break;     // Oscillator Control
+    STORAGE(OSCTUN); break;     // Oscillator Tuning
+    STORAGE(SPLLCON); break;    // System PLL Control
+    STORAGE(REFO1CON); break;
+    STORAGE(REFO1CONCLR); *bufp = 0; break;
+    STORAGE(REFO1CONSET); *bufp = 0; break;
+    STORAGE(REFO1CONINV); *bufp = 0; break;
+    STORAGE(REFO2CON); break;
+    STORAGE(REFO2CONCLR); *bufp = 0; break;
+    STORAGE(REFO2CONSET); *bufp = 0; break;
+    STORAGE(REFO2CONINV); *bufp = 0; break;
+    STORAGE(REFO3CON); break;
+    STORAGE(REFO3CONCLR); *bufp = 0; break;
+    STORAGE(REFO3CONSET); *bufp = 0; break;
+    STORAGE(REFO3CONINV); *bufp = 0; break;
+    STORAGE(REFO4CON); break;
+    STORAGE(REFO4CONCLR); *bufp = 0; break;
+    STORAGE(REFO4CONSET); *bufp = 0; break;
+    STORAGE(REFO4CONINV); *bufp = 0; break;
+    STORAGE(PB1DIV); break;     // Peripheral bus 1 divisor
+    STORAGE(PB1DIVCLR); *bufp = 0; break;
+    STORAGE(PB1DIVSET); *bufp = 0; break;
+    STORAGE(PB1DIVINV); *bufp = 0; break;
+    STORAGE(PB2DIV); break;     // Peripheral bus 2 divisor
+    STORAGE(PB2DIVCLR); *bufp = 0; break;
+    STORAGE(PB2DIVSET); *bufp = 0; break;
+    STORAGE(PB2DIVINV); *bufp = 0; break;
+    STORAGE(PB3DIV); break;     // Peripheral bus 3 divisor
+    STORAGE(PB3DIVCLR); *bufp = 0; break;
+    STORAGE(PB3DIVSET); *bufp = 0; break;
+    STORAGE(PB3DIVINV); *bufp = 0; break;
+    STORAGE(PB4DIV); break;     // Peripheral bus 4 divisor
+    STORAGE(PB4DIVCLR); *bufp = 0; break;
+    STORAGE(PB4DIVSET); *bufp = 0; break;
+    STORAGE(PB4DIVINV); *bufp = 0; break;
+    STORAGE(PB5DIV); break;     // Peripheral bus 5 divisor
+    STORAGE(PB5DIVCLR); *bufp = 0; break;
+    STORAGE(PB5DIVSET); *bufp = 0; break;
+    STORAGE(PB5DIVINV); *bufp = 0; break;
+    STORAGE(PB7DIV); break;     // Peripheral bus 7 divisor
+    STORAGE(PB7DIVCLR); *bufp = 0; break;
+    STORAGE(PB7DIVSET); *bufp = 0; break;
+    STORAGE(PB7DIVINV); *bufp = 0; break;
+    STORAGE(PB8DIV); break;     // Peripheral bus 8 divisor
+    STORAGE(PB8DIVCLR); *bufp = 0; break;
+    STORAGE(PB8DIVSET); *bufp = 0; break;
+    STORAGE(PB8DIVINV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * Peripheral port select registers: input.
+     */
+    STORAGE(INT1R); break;
+    STORAGE(INT2R); break;
+    STORAGE(INT3R); break;
+    STORAGE(INT4R); break;
+    STORAGE(T2CKR); break;
+    STORAGE(T3CKR); break;
+    STORAGE(T4CKR); break;
+    STORAGE(T5CKR); break;
+    STORAGE(T6CKR); break;
+    STORAGE(T7CKR); break;
+    STORAGE(T8CKR); break;
+    STORAGE(T9CKR); break;
+    STORAGE(IC1R); break;
+    STORAGE(IC2R); break;
+    STORAGE(IC3R); break;
+    STORAGE(IC4R); break;
+    STORAGE(IC5R); break;
+    STORAGE(IC6R); break;
+    STORAGE(IC7R); break;
+    STORAGE(IC8R); break;
+    STORAGE(IC9R); break;
+    STORAGE(OCFAR); break;
+    STORAGE(U1RXR); break;
+    STORAGE(U1CTSR); break;
+    STORAGE(U2RXR); break;
+    STORAGE(U2CTSR); break;
+    STORAGE(U3RXR); break;
+    STORAGE(U3CTSR); break;
+    STORAGE(U4RXR); break;
+    STORAGE(U4CTSR); break;
+    STORAGE(U5RXR); break;
+    STORAGE(U5CTSR); break;
+    STORAGE(U6RXR); break;
+    STORAGE(U6CTSR); break;
+    STORAGE(SDI1R); break;
+    STORAGE(SS1R); break;
+    STORAGE(SDI2R); break;
+    STORAGE(SS2R); break;
+    STORAGE(SDI3R); break;
+    STORAGE(SS3R); break;
+    STORAGE(SDI4R); break;
+    STORAGE(SS4R); break;
+    STORAGE(SDI5R); break;
+    STORAGE(SS5R); break;
+    STORAGE(SDI6R); break;
+    STORAGE(SS6R); break;
+    STORAGE(C1RXR); break;
+    STORAGE(C2RXR); break;
+    STORAGE(REFCLKI1R); break;
+    STORAGE(REFCLKI3R); break;
+    STORAGE(REFCLKI4R); break;
+
+    /*-------------------------------------------------------------------------
+     * Peripheral port select registers: output.
+     */
+    STORAGE(RPA14R); break;
+    STORAGE(RPA15R); break;
+    STORAGE(RPB0R); break;
+    STORAGE(RPB1R); break;
+    STORAGE(RPB2R); break;
+    STORAGE(RPB3R); break;
+    STORAGE(RPB5R); break;
+    STORAGE(RPB6R); break;
+    STORAGE(RPB7R); break;
+    STORAGE(RPB8R); break;
+    STORAGE(RPB9R); break;
+    STORAGE(RPB10R); break;
+    STORAGE(RPB14R); break;
+    STORAGE(RPB15R); break;
+    STORAGE(RPC1R); break;
+    STORAGE(RPC2R); break;
+    STORAGE(RPC3R); break;
+    STORAGE(RPC4R); break;
+    STORAGE(RPC13R); break;
+    STORAGE(RPC14R); break;
+    STORAGE(RPD0R); break;
+    STORAGE(RPD1R); break;
+    STORAGE(RPD2R); break;
+    STORAGE(RPD3R); break;
+    STORAGE(RPD4R); break;
+    STORAGE(RPD5R); break;
+    STORAGE(RPD6R); break;
+    STORAGE(RPD7R); break;
+    STORAGE(RPD9R); break;
+    STORAGE(RPD10R); break;
+    STORAGE(RPD11R); break;
+    STORAGE(RPD12R); break;
+    STORAGE(RPD14R); break;
+    STORAGE(RPD15R); break;
+    STORAGE(RPE3R); break;
+    STORAGE(RPE5R); break;
+    STORAGE(RPE8R); break;
+    STORAGE(RPE9R); break;
+    STORAGE(RPF0R); break;
+    STORAGE(RPF1R); break;
+    STORAGE(RPF2R); break;
+    STORAGE(RPF3R); break;
+    STORAGE(RPF4R); break;
+    STORAGE(RPF5R); break;
+    STORAGE(RPF8R); break;
+    STORAGE(RPF12R); break;
+    STORAGE(RPF13R); break;
+    STORAGE(RPG0R); break;
+    STORAGE(RPG1R); break;
+    STORAGE(RPG6R); break;
+    STORAGE(RPG7R); break;
+    STORAGE(RPG8R); break;
+    STORAGE(RPG9R); break;
+
+    /*-------------------------------------------------------------------------
+     * General purpose IO signals.
+     */
+    STORAGE(ANSELA); break;     // Port A: analog select
+    STORAGE(TRISA); break;      // Port A: mask of inputs
+    STORAGE(PORTA); break;      // Port A: read inputs
+    STORAGE(LATA); break;       // Port A: read outputs
+    STORAGE(ODCA); break;       // Port A: open drain configuration
+    STORAGE(CNPUA); break;      // Input pin pull-up
+    STORAGE(CNPDA); break;      // Input pin pull-down
+    STORAGE(CNCONA); break;     // Interrupt-on-change control
+    STORAGE(CNENA); break;      // Input change interrupt enable
+    STORAGE(CNSTATA); break;    // Input change status
+
+    STORAGE(ANSELB); break;     // Port B: analog select
+    STORAGE(TRISB); break;      // Port B: mask of inputs
+    STORAGE(PORTB); break;      // Port B: read inputs
+    STORAGE(LATB); break;       // Port B: read outputs
+    STORAGE(ODCB); break;       // Port B: open drain configuration
+    STORAGE(CNPUB); break;      // Input pin pull-up
+    STORAGE(CNPDB); break;      // Input pin pull-down
+    STORAGE(CNCONB); break;     // Interrupt-on-change control
+    STORAGE(CNENB); break;      // Input change interrupt enable
+    STORAGE(CNSTATB); break;    // Input change status
+
+    STORAGE(ANSELC); break;     // Port C: analog select
+    STORAGE(TRISC); break;      // Port C: mask of inputs
+    STORAGE(PORTC); break;      // Port C: read inputs
+    STORAGE(LATC); break;       // Port C: read outputs
+    STORAGE(ODCC); break;       // Port C: open drain configuration
+    STORAGE(CNPUC); break;      // Input pin pull-up
+    STORAGE(CNPDC); break;      // Input pin pull-down
+    STORAGE(CNCONC); break;     // Interrupt-on-change control
+    STORAGE(CNENC); break;      // Input change interrupt enable
+    STORAGE(CNSTATC); break;    // Input change status
+
+    STORAGE(ANSELD); break;     // Port D: analog select
+    STORAGE(TRISD); break;      // Port D: mask of inputs
+    STORAGE(PORTD); break;      // Port D: read inputs
+    STORAGE(LATD); break;       // Port D: read outputs
+    STORAGE(ODCD); break;       // Port D: open drain configuration
+    STORAGE(CNPUD); break;      // Input pin pull-up
+    STORAGE(CNPDD); break;      // Input pin pull-down
+    STORAGE(CNCOND); break;     // Interrupt-on-change control
+    STORAGE(CNEND); break;      // Input change interrupt enable
+    STORAGE(CNSTATD); break;    // Input change status
+
+    STORAGE(ANSELE); break;     // Port E: analog select
+    STORAGE(TRISE); break;      // Port E: mask of inputs
+    STORAGE(PORTE); break;      // Port E: read inputs
+    STORAGE(LATE); break;       // Port E: read outputs
+    STORAGE(ODCE); break;       // Port E: open drain configuration
+    STORAGE(CNPUE); break;      // Input pin pull-up
+    STORAGE(CNPDE); break;      // Input pin pull-down
+    STORAGE(CNCONE); break;     // Interrupt-on-change control
+    STORAGE(CNENE); break;      // Input change interrupt enable
+    STORAGE(CNSTATE); break;    // Input change status
+
+    STORAGE(ANSELF); break;     // Port F: analog select
+    STORAGE(TRISF); break;      // Port F: mask of inputs
+    STORAGE(PORTF); break;      // Port F: read inputs
+    STORAGE(LATF); break;       // Port F: read outputs
+    STORAGE(ODCF); break;       // Port F: open drain configuration
+    STORAGE(CNPUF); break;      // Input pin pull-up
+    STORAGE(CNPDF); break;      // Input pin pull-down
+    STORAGE(CNCONF); break;     // Interrupt-on-change control
+    STORAGE(CNENF); break;      // Input change interrupt enable
+    STORAGE(CNSTATF); break;    // Input change status
+
+    STORAGE(ANSELG); break;     // Port G: analog select
+    STORAGE(TRISG); break;      // Port G: mask of inputs
+    STORAGE(PORTG); break;      // Port G: read inputs
+    STORAGE(LATG); break;       // Port G: read outputs
+    STORAGE(ODCG); break;       // Port G: open drain configuration
+    STORAGE(CNPUG); break;      // Input pin pull-up
+    STORAGE(CNPDG); break;      // Input pin pull-down
+    STORAGE(CNCONG); break;     // Interrupt-on-change control
+    STORAGE(CNENG); break;      // Input change interrupt enable
+    STORAGE(CNSTATG); break;    // Input change status
+
+    /*-------------------------------------------------------------------------
+     * UART 1.
+     */
+    STORAGE(U1RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 0);
+        break;
+    STORAGE(U1BRG); break;                      // Baud rate
+    STORAGE(U1MODE); break;                     // Mode
+    STORAGE(U1STA);                             // Status and control
+        pic32_uart_poll_status(s, 0);
+        break;
+    STORAGE(U1TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U1MODECLR); *bufp = 0; break;
+    STORAGE(U1MODESET); *bufp = 0; break;
+    STORAGE(U1MODEINV); *bufp = 0; break;
+    STORAGE(U1STACLR);  *bufp = 0; break;
+    STORAGE(U1STASET);  *bufp = 0; break;
+    STORAGE(U1STAINV);  *bufp = 0; break;
+    STORAGE(U1BRGCLR);  *bufp = 0; break;
+    STORAGE(U1BRGSET);  *bufp = 0; break;
+    STORAGE(U1BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 2.
+     */
+    STORAGE(U2RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 1);
+        break;
+    STORAGE(U2BRG); break;                      // Baud rate
+    STORAGE(U2MODE); break;                     // Mode
+    STORAGE(U2STA);                             // Status and control
+        pic32_uart_poll_status(s, 1);
+        break;
+    STORAGE(U2TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U2MODECLR); *bufp = 0; break;
+    STORAGE(U2MODESET); *bufp = 0; break;
+    STORAGE(U2MODEINV); *bufp = 0; break;
+    STORAGE(U2STACLR);  *bufp = 0; break;
+    STORAGE(U2STASET);  *bufp = 0; break;
+    STORAGE(U2STAINV);  *bufp = 0; break;
+    STORAGE(U2BRGCLR);  *bufp = 0; break;
+    STORAGE(U2BRGSET);  *bufp = 0; break;
+    STORAGE(U2BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 3.
+     */
+    STORAGE(U3RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 2);
+        break;
+    STORAGE(U3BRG); break;                      // Baud rate
+    STORAGE(U3MODE); break;                     // Mode
+    STORAGE(U3STA);                             // Status and control
+        pic32_uart_poll_status(s, 2);
+        break;
+    STORAGE(U3TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U3MODECLR); *bufp = 0; break;
+    STORAGE(U3MODESET); *bufp = 0; break;
+    STORAGE(U3MODEINV); *bufp = 0; break;
+    STORAGE(U3STACLR);  *bufp = 0; break;
+    STORAGE(U3STASET);  *bufp = 0; break;
+    STORAGE(U3STAINV);  *bufp = 0; break;
+    STORAGE(U3BRGCLR);  *bufp = 0; break;
+    STORAGE(U3BRGSET);  *bufp = 0; break;
+    STORAGE(U3BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 4.
+     */
+    STORAGE(U4RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 3);
+        break;
+    STORAGE(U4BRG); break;                      // Baud rate
+    STORAGE(U4MODE); break;                     // Mode
+    STORAGE(U4STA);                             // Status and control
+        pic32_uart_poll_status(s, 3);
+        break;
+    STORAGE(U4TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U4MODECLR); *bufp = 0; break;
+    STORAGE(U4MODESET); *bufp = 0; break;
+    STORAGE(U4MODEINV); *bufp = 0; break;
+    STORAGE(U4STACLR);  *bufp = 0; break;
+    STORAGE(U4STASET);  *bufp = 0; break;
+    STORAGE(U4STAINV);  *bufp = 0; break;
+    STORAGE(U4BRGCLR);  *bufp = 0; break;
+    STORAGE(U4BRGSET);  *bufp = 0; break;
+    STORAGE(U4BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 5.
+     */
+    STORAGE(U5RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 4);
+        break;
+    STORAGE(U5BRG); break;                      // Baud rate
+    STORAGE(U5MODE); break;                     // Mode
+    STORAGE(U5STA);                             // Status and control
+        pic32_uart_poll_status(s, 4);
+        break;
+    STORAGE(U5TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U5MODECLR); *bufp = 0; break;
+    STORAGE(U5MODESET); *bufp = 0; break;
+    STORAGE(U5MODEINV); *bufp = 0; break;
+    STORAGE(U5STACLR);  *bufp = 0; break;
+    STORAGE(U5STASET);  *bufp = 0; break;
+    STORAGE(U5STAINV);  *bufp = 0; break;
+    STORAGE(U5BRGCLR);  *bufp = 0; break;
+    STORAGE(U5BRGSET);  *bufp = 0; break;
+    STORAGE(U5BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * UART 6.
+     */
+    STORAGE(U6RXREG);                           // Receive data
+        *bufp = pic32_uart_get_char(s, 5);
+        break;
+    STORAGE(U6BRG); break;                      // Baud rate
+    STORAGE(U6MODE); break;                     // Mode
+    STORAGE(U6STA);                             // Status and control
+        pic32_uart_poll_status(s, 5);
+        break;
+    STORAGE(U6TXREG);   *bufp = 0; break;       // Transmit
+    STORAGE(U6MODECLR); *bufp = 0; break;
+    STORAGE(U6MODESET); *bufp = 0; break;
+    STORAGE(U6MODEINV); *bufp = 0; break;
+    STORAGE(U6STACLR);  *bufp = 0; break;
+    STORAGE(U6STASET);  *bufp = 0; break;
+    STORAGE(U6STAINV);  *bufp = 0; break;
+    STORAGE(U6BRGCLR);  *bufp = 0; break;
+    STORAGE(U6BRGSET);  *bufp = 0; break;
+    STORAGE(U6BRGINV);  *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 1.
+     */
+    STORAGE(SPI1CON); break;                    // Control
+    STORAGE(SPI1CONCLR); *bufp = 0; break;
+    STORAGE(SPI1CONSET); *bufp = 0; break;
+    STORAGE(SPI1CONINV); *bufp = 0; break;
+    STORAGE(SPI1STAT); break;                   // Status
+    STORAGE(SPI1STATCLR); *bufp = 0; break;
+    STORAGE(SPI1STATSET); *bufp = 0; break;
+    STORAGE(SPI1STATINV); *bufp = 0; break;
+    STORAGE(SPI1BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 0);
+        break;
+    STORAGE(SPI1BRG); break;                    // Baud rate
+    STORAGE(SPI1BRGCLR); *bufp = 0; break;
+    STORAGE(SPI1BRGSET); *bufp = 0; break;
+    STORAGE(SPI1BRGINV); *bufp = 0; break;
+    STORAGE(SPI1CON2); break;                   // Control 2
+    STORAGE(SPI1CON2CLR); *bufp = 0; break;
+    STORAGE(SPI1CON2SET); *bufp = 0; break;
+    STORAGE(SPI1CON2INV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 2.
+     */
+    STORAGE(SPI2CON); break;                    // Control
+    STORAGE(SPI2CONCLR); *bufp = 0; break;
+    STORAGE(SPI2CONSET); *bufp = 0; break;
+    STORAGE(SPI2CONINV); *bufp = 0; break;
+    STORAGE(SPI2STAT); break;                   // Status
+    STORAGE(SPI2STATCLR); *bufp = 0; break;
+    STORAGE(SPI2STATSET); *bufp = 0; break;
+    STORAGE(SPI2STATINV); *bufp = 0; break;
+    STORAGE(SPI2BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 1);
+        break;
+    STORAGE(SPI2BRG); break;                    // Baud rate
+    STORAGE(SPI2BRGCLR); *bufp = 0; break;
+    STORAGE(SPI2BRGSET); *bufp = 0; break;
+    STORAGE(SPI2BRGINV); *bufp = 0; break;
+    STORAGE(SPI2CON2); break;                   // Control 2
+    STORAGE(SPI2CON2CLR); *bufp = 0; break;
+    STORAGE(SPI2CON2SET); *bufp = 0; break;
+    STORAGE(SPI2CON2INV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 3.
+     */
+    STORAGE(SPI3CON); break;                    // Control
+    STORAGE(SPI3CONCLR); *bufp = 0; break;
+    STORAGE(SPI3CONSET); *bufp = 0; break;
+    STORAGE(SPI3CONINV); *bufp = 0; break;
+    STORAGE(SPI3STAT); break;                   // Status
+    STORAGE(SPI3STATCLR); *bufp = 0; break;
+    STORAGE(SPI3STATSET); *bufp = 0; break;
+    STORAGE(SPI3STATINV); *bufp = 0; break;
+    STORAGE(SPI3BUF);                           // SPIx Buffer
+        *bufp = pic32_spi_readbuf(s, 2);
+        break;
+    STORAGE(SPI3BRG); break;                    // Baud rate
+    STORAGE(SPI3BRGCLR); *bufp = 0; break;
+    STORAGE(SPI3BRGSET); *bufp = 0; break;
+    STORAGE(SPI3BRGINV); *bufp = 0; break;
+    STORAGE(SPI3CON2); break;                   // Control 2
+    STORAGE(SPI3CON2CLR); *bufp = 0; break;
+    STORAGE(SPI3CON2SET); *bufp = 0; break;
+    STORAGE(SPI3CON2INV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * SPI 4.
+     */
+    STORAGE(SPI4CON); break;                    // Control
+    STORAGE(SPI4CONCLR); *bufp = 0; break;
+    STORAGE(SPI4CONSET); *bufp = 0; break;
+    STORAGE(SPI4CONINV); *bufp = 0; break;
+    STORAGE(SPI4STAT); break;                   // Status
+    STORAGE(SPI4STATCLR); *bufp = 0; break;
+    STORAGE(SPI4STATSET); *bufp = 0; break;
+    STORAGE(SPI4STATINV); *bufp = 0; break;
+    STORAGE(SPI4BUF);                           // Buffer
+        *bufp = pic32_spi_readbuf(s, 3);
+        break;
+    STORAGE(SPI4BRG); break;                    // Baud rate
+    STORAGE(SPI4BRGCLR); *bufp = 0; break;
+    STORAGE(SPI4BRGSET); *bufp = 0; break;
+    STORAGE(SPI4BRGINV); *bufp = 0; break;
+    STORAGE(SPI4CON2); break;                   // Control 2
+    STORAGE(SPI4CON2CLR); *bufp = 0; break;
+    STORAGE(SPI4CON2SET); *bufp = 0; break;
+    STORAGE(SPI4CON2INV); *bufp = 0; break;
+
+    /*-------------------------------------------------------------------------
+     * Timers.
+     */
+    STORAGE(T1CON); break;
+    STORAGE(TMR1); break;
+    STORAGE(PR1); break;
+    STORAGE(T2CON); break;
+    STORAGE(TMR2); break;
+    STORAGE(PR2); break;
+    STORAGE(T3CON); break;
+    STORAGE(TMR3); break;
+    STORAGE(PR3); break;
+    STORAGE(T4CON); break;
+    STORAGE(TMR4); break;
+    STORAGE(PR4); break;
+    STORAGE(T5CON); break;
+    STORAGE(TMR5); break;
+    STORAGE(PR5); break;
+    STORAGE(T6CON); break;
+    STORAGE(TMR6); break;
+    STORAGE(PR6); break;
+    STORAGE(T7CON); break;
+    STORAGE(TMR7); break;
+    STORAGE(PR7); break;
+    STORAGE(T8CON); break;
+    STORAGE(TMR8); break;
+    STORAGE(PR8); break;
+    STORAGE(T9CON); break;
+    STORAGE(TMR9); break;
+    STORAGE(PR9); break;
+
+    /*-------------------------------------------------------------------------
+     * Ethernet.
+     */
+    STORAGE(ETHCON1); break;            // Control 1
+    STORAGE(ETHCON2); break;            // Control 2: RX data buffer size
+    STORAGE(ETHTXST); break;            // Tx descriptor start address
+    STORAGE(ETHRXST); break;            // Rx descriptor start address
+    STORAGE(ETHHT0); break;             // Hash tasble 0
+    STORAGE(ETHHT1); break;             // Hash tasble 1
+    STORAGE(ETHPMM0); break;            // Pattern match mask 0
+    STORAGE(ETHPMM1); break;            // Pattern match mask 1
+    STORAGE(ETHPMCS); break;            // Pattern match checksum
+    STORAGE(ETHPMO); break;             // Pattern match offset
+    STORAGE(ETHRXFC); break;            // Receive filter configuration
+    STORAGE(ETHRXWM); break;            // Receive watermarks
+    STORAGE(ETHIEN); break;             // Interrupt enable
+    STORAGE(ETHIRQ); break;             // Interrupt request
+    STORAGE(ETHSTAT); break;            // Status
+    STORAGE(ETHRXOVFLOW); break;        // Receive overflow statistics
+    STORAGE(ETHFRMTXOK); break;         // Frames transmitted OK statistics
+    STORAGE(ETHSCOLFRM); break;         // Single collision frames statistics
+    STORAGE(ETHMCOLFRM); break;         // Multiple collision frames statistics
+    STORAGE(ETHFRMRXOK); break;         // Frames received OK statistics
+    STORAGE(ETHFCSERR); break;          // Frame check sequence error
statistics
+    STORAGE(ETHALGNERR); break;         // Alignment errors statistics
+    STORAGE(EMAC1CFG1); break;          // MAC configuration 1
+    STORAGE(EMAC1CFG2); break;          // MAC configuration 2
+    STORAGE(EMAC1IPGT); break;          // MAC back-to-back interpacket gap
+    STORAGE(EMAC1IPGR); break;          // MAC non-back-to-back interpacket gap
+    STORAGE(EMAC1CLRT); break;          // MAC collision window/retry limit
+    STORAGE(EMAC1MAXF); break;          // MAC maximum frame length
+    STORAGE(EMAC1SUPP); break;          // MAC PHY support
+    STORAGE(EMAC1TEST); break;          // MAC test
+    STORAGE(EMAC1MCFG); break;          // MII configuration
+    STORAGE(EMAC1MCMD); break;          // MII command
+    STORAGE(EMAC1MADR); break;          // MII address
+    STORAGE(EMAC1MWTD); break;          // MII write data
+    STORAGE(EMAC1MRDD); break;          // MII read data
+    STORAGE(EMAC1MIND); break;          // MII indicators
+    STORAGE(EMAC1SA0); break;           // MAC station address 0
+    STORAGE(EMAC1SA1); break;           // MAC station address 1
+    STORAGE(EMAC1SA2); break;           // MAC station address 2
+
+    /*-------------------------------------------------------------------------
+     * USB.
+     */
+    STORAGE(USBCSR0); break;
+    STORAGE(USBCSR1); break;
+    STORAGE(USBCSR2); break;
+    STORAGE(USBCSR3); break;
+    STORAGE(USBIENCSR0); break;
+    STORAGE(USBIENCSR1); break;
+    STORAGE(USBIENCSR2); break;
+    STORAGE(USBIENCSR3); break;
+    STORAGE(USBFIFO0); break;
+    STORAGE(USBFIFO1); break;
+    STORAGE(USBFIFO2); break;
+    STORAGE(USBFIFO3); break;
+    STORAGE(USBFIFO4); break;
+    STORAGE(USBFIFO5); break;
+    STORAGE(USBFIFO6); break;
+    STORAGE(USBFIFO7); break;
+    STORAGE(USBOTG); break;
+    STORAGE(USBFIFOA); break;
+    STORAGE(USBHWVER); break;
+    STORAGE(USBINFO); break;
+    STORAGE(USBEOFRST); break;
+    STORAGE(USBE0TXA); break;
+    STORAGE(USBE0RXA); break;
+    STORAGE(USBE1TXA); break;
+    STORAGE(USBE1RXA); break;
+    STORAGE(USBE2TXA); break;
+    STORAGE(USBE2RXA); break;
+    STORAGE(USBE3TXA); break;
+    STORAGE(USBE3RXA); break;
+    STORAGE(USBE4TXA); break;
+    STORAGE(USBE4RXA); break;
+    STORAGE(USBE5TXA); break;
+    STORAGE(USBE5RXA); break;
+    STORAGE(USBE6TXA); break;
+    STORAGE(USBE6RXA); break;
+    STORAGE(USBE7TXA); break;
+    STORAGE(USBE7RXA); break;
+    STORAGE(USBE0CSR0); break;
+    STORAGE(USBE0CSR2); break;
+    STORAGE(USBE0CSR3); break;
+    STORAGE(USBE1CSR0); break;
+    STORAGE(USBE1CSR1); break;
+    STORAGE(USBE1CSR2); break;
+    STORAGE(USBE1CSR3); break;
+    STORAGE(USBE2CSR0); break;
+    STORAGE(USBE2CSR1); break;
+    STORAGE(USBE2CSR2); break;
+    STORAGE(USBE2CSR3); break;
+    STORAGE(USBE3CSR0); break;
+    STORAGE(USBE3CSR1); break;
+    STORAGE(USBE3CSR2); break;
+    STORAGE(USBE3CSR3); break;
+    STORAGE(USBE4CSR0); break;
+    STORAGE(USBE4CSR1); break;
+    STORAGE(USBE4CSR2); break;
+    STORAGE(USBE4CSR3); break;
+    STORAGE(USBE5CSR0); break;
+    STORAGE(USBE5CSR1); break;
+    STORAGE(USBE5CSR2); break;
+    STORAGE(USBE5CSR3); break;
+    STORAGE(USBE6CSR0); break;
+    STORAGE(USBE6CSR1); break;
+    STORAGE(USBE6CSR2); break;
+    STORAGE(USBE6CSR3); break;
+    STORAGE(USBE7CSR0); break;
+    STORAGE(USBE7CSR1); break;
+    STORAGE(USBE7CSR2); break;
+    STORAGE(USBE7CSR3); break;
+    STORAGE(USBDMAINT); break;
+    STORAGE(USBDMA1C); break;
+    STORAGE(USBDMA1A); break;
+    STORAGE(USBDMA1N); break;
+    STORAGE(USBDMA2C); break;
+    STORAGE(USBDMA2A); break;
+    STORAGE(USBDMA2N); break;
+    STORAGE(USBDMA3C); break;
+    STORAGE(USBDMA3A); break;
+    STORAGE(USBDMA3N); break;
+    STORAGE(USBDMA4C); break;
+    STORAGE(USBDMA4A); break;
+    STORAGE(USBDMA4N); break;
+    STORAGE(USBDMA5C); break;
+    STORAGE(USBDMA5A); break;
+    STORAGE(USBDMA5N); break;
+    STORAGE(USBDMA6C); break;
+    STORAGE(USBDMA6A); break;
+    STORAGE(USBDMA6N); break;
+    STORAGE(USBDMA7C); break;
+    STORAGE(USBDMA7A); break;
+    STORAGE(USBDMA7N); break;
+    STORAGE(USBDMA8C); break;
+    STORAGE(USBDMA8A); break;
+    STORAGE(USBDMA8N); break;
+    STORAGE(USBE1RPC); break;
+    STORAGE(USBE2RPC); break;
+    STORAGE(USBE3RPC); break;
+    STORAGE(USBE4RPC); break;
+    STORAGE(USBE5RPC); break;
+    STORAGE(USBE6RPC); break;
+    STORAGE(USBE7RPC); break;
+    STORAGE(USBDPBFD); break;
+    STORAGE(USBTMCON1); break;
+    STORAGE(USBTMCON2); break;
+    STORAGE(USBLPMR1); break;
+    STORAGE(USBLMPR2); break;
+
+    default:
+        printf("--- Read 1f8%05x: peripheral register not supported\n",
+            offset);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Read 1f8%05x: peripheral
register not supported\n",
+                offset);
+        exit(1);
+    }
+    return *bufp;
+}
+
+static void pps_input_group1(unsigned address, unsigned data)
+{
+    // 0000 = RPD1
+    // 0001 = RPG9
+    // 0010 = RPB14
+    // 0011 = RPD0
+    // 0101 = RPB6
+    // 0110 = RPD5
+    // 0111 = RPB2
+    // 1000 = RPF3
+    // 1001 = RPF13
+    // 1011 = RPF2
+    // 1100 = RPC2
+    // 1101 = RPE8
+}
+
+static void pps_input_group2(unsigned address, unsigned data)
+{
+    // 0000 = RPD9
+    // 0001 = RPG6
+    // 0010 = RPB8
+    // 0011 = RPB15
+    // 0100 = RPD4
+    // 0101 = RPB0
+    // 0110 = RPE3
+    // 0111 = RPB7
+    // 1001 = RPF12
+    // 1010 = RPD12
+    // 1011 = RPF8
+    // 1100 = RPC3
+    // 1101 = RPE9
+}
+
+static void pps_input_group3(unsigned address, unsigned data)
+{
+    // 0000 = RPD2
+    // 0001 = RPG8
+    // 0010 = RPF4
+    // 0011 = RPD10
+    // 0100 = RPF1
+    // 0101 = RPB9
+    // 0110 = RPB10
+    // 0111 = RPC14
+    // 1000 = RPB5
+    // 1010 = RPC1
+    // 1011 = RPD14
+    // 1100 = RPG1
+    // 1101 = RPA14
+    // 1110 = RPD6
+}
+
+static void pps_input_group4(unsigned address, unsigned data)
+{
+    // 0000 = RPD3
+    // 0001 = RPG7
+    // 0010 = RPF5
+    // 0011 = RPD11
+    // 0100 = RPF0
+    // 0101 = RPB1
+    // 0110 = RPE5
+    // 0111 = RPC13
+    // 1000 = RPB3
+    // 1010 = RPC4
+    // 1011 = RPD15
+    // 1100 = RPG0
+    // 1101 = RPA15
+    // 1110 = RPD7
+}
+
+static void pps_output_group1(unsigned address, unsigned data)
+{
+    // 0000 = No Connect
+    // 0001 = U1TX
+    // 0010 = U2RTS
+    // 0011 = U5TX
+    // 0100 = U6RTS
+    // 0101 = SDO1
+    // 0110 = SDO2
+    // 0111 = SDO3
+    // 1000 = SDO4
+    // 1001 = SDO5
+    // 1011 = OC4
+    // 1100 = OC7
+    // 1111 = REFCLKO1
+}
+
+static void pps_output_group2(unsigned address, unsigned data)
+{
+    // 0000 = No Connect
+    // 0001 = U1RTS
+    // 0010 = U2TX
+    // 0011 = U5RTS
+    // 0100 = U6TX
+    // 0110 = SS2
+    // 1000 = SDO4
+    // 1010 = SDO6
+    // 1011 = OC2
+    // 1100 = OC1
+    // 1101 = OC9
+    // 1111 = C2TX
+}
+
+static void pps_output_group3(unsigned address, unsigned data)
+{
+    // 0000 = No Connect
+    // 0001 = U3TX
+    // 0010 = U4RTS
+    // 0101 = SDO1
+    // 0110 = SDO2
+    // 0111 = SDO3
+    // 1001 = SDO5
+    // 1010 = SS6
+    // 1011 = OC3
+    // 1100 = OC6
+    // 1101 = REFCLKO4
+    // 1110 = C2OUT
+    // 1111 = C1TX
+}
+
+static void pps_output_group4(unsigned address, unsigned data)
+{
+    // 0000 = No Connect
+    // 0001 = U3RTS
+    // 0010 = U4TX
+    // 0100 = U6TX
+    // 0101 = SS1
+    // 0111 = SS3
+    // 1000 = SS4
+    // 1001 = SS5
+    // 1010 = SDO6
+    // 1011 = OC5
+    // 1100 = OC8
+    // 1110 = C1OUT
+    // 1111 = REFCLKO3
+}
+
+static void io_write32(pic32_t *s, unsigned offset, unsigned data,
const char **namep)
+{
+    unsigned *bufp = &VALUE(offset);
+    unsigned mask;
+
+    switch (offset) {
+    /*-------------------------------------------------------------------------
+     * Interrupt controller registers.
+     */
+    WRITEOP(INTCON); return;    // Interrupt Control
+    READONLY(INTSTAT);          // Interrupt Status
+    WRITEOP(IPTMR);  return;    // Temporal Proximity Timer
+    WRITEOP(IFS0); goto irq;    // IFS(0..2) - Interrupt Flag Status
+    WRITEOP(IFS1); goto irq;
+    WRITEOP(IFS2); goto irq;
+    WRITEOP(IFS3); goto irq;
+    WRITEOP(IFS4); goto irq;
+    WRITEOP(IFS5); goto irq;
+    WRITEOP(IEC0); goto irq;    // IEC(0..2) - Interrupt Enable Control
+    WRITEOP(IEC1); goto irq;
+    WRITEOP(IEC2); goto irq;
+    WRITEOP(IEC3); goto irq;
+    WRITEOP(IEC4); goto irq;
+    WRITEOP(IEC5); goto irq;
+
+    // IPC(0..11) - Interrupt Priority Control
+    WRITEOP(IPC0); goto irq;    WRITEOP(IPC1); goto irq;
+    WRITEOP(IPC2); goto irq;    WRITEOP(IPC3); goto irq;
+    WRITEOP(IPC4); goto irq;    WRITEOP(IPC5); goto irq;
+    WRITEOP(IPC6); goto irq;    WRITEOP(IPC7); goto irq;
+    WRITEOP(IPC8); goto irq;    WRITEOP(IPC9); goto irq;
+    WRITEOP(IPC10); goto irq;   WRITEOP(IPC11); goto irq;
+    WRITEOP(IPC12); goto irq;   WRITEOP(IPC13); goto irq;
+    WRITEOP(IPC14); goto irq;   WRITEOP(IPC15); goto irq;
+    WRITEOP(IPC16); goto irq;   WRITEOP(IPC17); goto irq;
+    WRITEOP(IPC18); goto irq;   WRITEOP(IPC19); goto irq;
+    WRITEOP(IPC20); goto irq;   WRITEOP(IPC21); goto irq;
+    WRITEOP(IPC22); goto irq;   WRITEOP(IPC23); goto irq;
+    WRITEOP(IPC24); goto irq;   WRITEOP(IPC25); goto irq;
+    WRITEOP(IPC26); goto irq;   WRITEOP(IPC27); goto irq;
+    WRITEOP(IPC28); goto irq;   WRITEOP(IPC29); goto irq;
+    WRITEOP(IPC30); goto irq;   WRITEOP(IPC31); goto irq;
+    WRITEOP(IPC32); goto irq;   WRITEOP(IPC33); goto irq;
+    WRITEOP(IPC34); goto irq;   WRITEOP(IPC35); goto irq;
+    WRITEOP(IPC36); goto irq;   WRITEOP(IPC37); goto irq;
+    WRITEOP(IPC38); goto irq;   WRITEOP(IPC39); goto irq;
+    WRITEOP(IPC40); goto irq;   WRITEOP(IPC41); goto irq;
+    WRITEOP(IPC42); goto irq;   WRITEOP(IPC43); goto irq;
+    WRITEOP(IPC44); goto irq;   WRITEOP(IPC45); goto irq;
+    WRITEOP(IPC46); goto irq;   WRITEOP(IPC47);
+irq:    update_irq_status(s);
+        return;
+
+    // OFF000..OFF190 - Interrupt Vector Address Offset
+    STORAGE(OFF(0)); break;     STORAGE(OFF(1)); break;
+    STORAGE(OFF(2)); break;     STORAGE(OFF(3)); break;
+    STORAGE(OFF(4)); break;     STORAGE(OFF(5)); break;
+    STORAGE(OFF(6)); break;     STORAGE(OFF(7)); break;
+    STORAGE(OFF(8)); break;     STORAGE(OFF(9)); break;
+    STORAGE(OFF(10)); break;    STORAGE(OFF(11)); break;
+    STORAGE(OFF(12)); break;    STORAGE(OFF(13)); break;
+    STORAGE(OFF(14)); break;    STORAGE(OFF(15)); break;
+    STORAGE(OFF(16)); break;    STORAGE(OFF(17)); break;
+    STORAGE(OFF(18)); break;    STORAGE(OFF(19)); break;
+    STORAGE(OFF(20)); break;    STORAGE(OFF(21)); break;
+    STORAGE(OFF(22)); break;    STORAGE(OFF(23)); break;
+    STORAGE(OFF(24)); break;    STORAGE(OFF(25)); break;
+    STORAGE(OFF(26)); break;    STORAGE(OFF(27)); break;
+    STORAGE(OFF(28)); break;    STORAGE(OFF(29)); break;
+    STORAGE(OFF(30)); break;    STORAGE(OFF(31)); break;
+    STORAGE(OFF(32)); break;    STORAGE(OFF(33)); break;
+    STORAGE(OFF(34)); break;    STORAGE(OFF(35)); break;
+    STORAGE(OFF(36)); break;    STORAGE(OFF(37)); break;
+    STORAGE(OFF(38)); break;    STORAGE(OFF(39)); break;
+    STORAGE(OFF(40)); break;    STORAGE(OFF(41)); break;
+    STORAGE(OFF(42)); break;    STORAGE(OFF(43)); break;
+    STORAGE(OFF(44)); break;    STORAGE(OFF(45)); break;
+    STORAGE(OFF(46)); break;    STORAGE(OFF(47)); break;
+    STORAGE(OFF(48)); break;    STORAGE(OFF(49)); break;
+    STORAGE(OFF(50)); break;    STORAGE(OFF(51)); break;
+    STORAGE(OFF(52)); break;    STORAGE(OFF(53)); break;
+    STORAGE(OFF(54)); break;    STORAGE(OFF(55)); break;
+    STORAGE(OFF(56)); break;    STORAGE(OFF(57)); break;
+    STORAGE(OFF(58)); break;    STORAGE(OFF(59)); break;
+    STORAGE(OFF(60)); break;    STORAGE(OFF(61)); break;
+    STORAGE(OFF(62)); break;    STORAGE(OFF(63)); break;
+    STORAGE(OFF(64)); break;    STORAGE(OFF(65)); break;
+    STORAGE(OFF(66)); break;    STORAGE(OFF(67)); break;
+    STORAGE(OFF(68)); break;    STORAGE(OFF(69)); break;
+    STORAGE(OFF(70)); break;    STORAGE(OFF(71)); break;
+    STORAGE(OFF(72)); break;    STORAGE(OFF(73)); break;
+    STORAGE(OFF(74)); break;    STORAGE(OFF(75)); break;
+    STORAGE(OFF(76)); break;    STORAGE(OFF(77)); break;
+    STORAGE(OFF(78)); break;    STORAGE(OFF(79)); break;
+    STORAGE(OFF(80)); break;    STORAGE(OFF(81)); break;
+    STORAGE(OFF(82)); break;    STORAGE(OFF(83)); break;
+    STORAGE(OFF(84)); break;    STORAGE(OFF(85)); break;
+    STORAGE(OFF(86)); break;    STORAGE(OFF(87)); break;
+    STORAGE(OFF(88)); break;    STORAGE(OFF(89)); break;
+    STORAGE(OFF(90)); break;    STORAGE(OFF(91)); break;
+    STORAGE(OFF(92)); break;    STORAGE(OFF(93)); break;
+    STORAGE(OFF(94)); break;    STORAGE(OFF(95)); break;
+    STORAGE(OFF(96)); break;    STORAGE(OFF(97)); break;
+    STORAGE(OFF(98)); break;    STORAGE(OFF(99)); break;
+    STORAGE(OFF(100)); break;   STORAGE(OFF(101)); break;
+    STORAGE(OFF(102)); break;   STORAGE(OFF(103)); break;
+    STORAGE(OFF(104)); break;   STORAGE(OFF(105)); break;
+    STORAGE(OFF(106)); break;   STORAGE(OFF(107)); break;
+    STORAGE(OFF(108)); break;   STORAGE(OFF(109)); break;
+    STORAGE(OFF(110)); break;   STORAGE(OFF(111)); break;
+    STORAGE(OFF(112)); break;   STORAGE(OFF(113)); break;
+    STORAGE(OFF(114)); break;   STORAGE(OFF(115)); break;
+    STORAGE(OFF(116)); break;   STORAGE(OFF(117)); break;
+    STORAGE(OFF(118)); break;   STORAGE(OFF(119)); break;
+    STORAGE(OFF(120)); break;   STORAGE(OFF(121)); break;
+    STORAGE(OFF(122)); break;   STORAGE(OFF(123)); break;
+    STORAGE(OFF(124)); break;   STORAGE(OFF(125)); break;
+    STORAGE(OFF(126)); break;   STORAGE(OFF(127)); break;
+    STORAGE(OFF(128)); break;   STORAGE(OFF(129)); break;
+    STORAGE(OFF(130)); break;   STORAGE(OFF(131)); break;
+    STORAGE(OFF(132)); break;   STORAGE(OFF(133)); break;
+    STORAGE(OFF(134)); break;   STORAGE(OFF(135)); break;
+    STORAGE(OFF(136)); break;   STORAGE(OFF(137)); break;
+    STORAGE(OFF(138)); break;   STORAGE(OFF(139)); break;
+    STORAGE(OFF(140)); break;   STORAGE(OFF(141)); break;
+    STORAGE(OFF(142)); break;   STORAGE(OFF(143)); break;
+    STORAGE(OFF(144)); break;   STORAGE(OFF(145)); break;
+    STORAGE(OFF(146)); break;   STORAGE(OFF(147)); break;
+    STORAGE(OFF(148)); break;   STORAGE(OFF(149)); break;
+    STORAGE(OFF(150)); break;   STORAGE(OFF(151)); break;
+    STORAGE(OFF(152)); break;   STORAGE(OFF(153)); break;
+    STORAGE(OFF(154)); break;   STORAGE(OFF(155)); break;
+    STORAGE(OFF(156)); break;   STORAGE(OFF(157)); break;
+    STORAGE(OFF(158)); break;   STORAGE(OFF(159)); break;
+    STORAGE(OFF(160)); break;   STORAGE(OFF(161)); break;
+    STORAGE(OFF(162)); break;   STORAGE(OFF(163)); break;
+    STORAGE(OFF(164)); break;   STORAGE(OFF(165)); break;
+    STORAGE(OFF(166)); break;   STORAGE(OFF(167)); break;
+    STORAGE(OFF(168)); break;   STORAGE(OFF(169)); break;
+    STORAGE(OFF(170)); break;   STORAGE(OFF(171)); break;
+    STORAGE(OFF(172)); break;   STORAGE(OFF(173)); break;
+    STORAGE(OFF(174)); break;   STORAGE(OFF(175)); break;
+    STORAGE(OFF(176)); break;   STORAGE(OFF(177)); break;
+    STORAGE(OFF(178)); break;   STORAGE(OFF(179)); break;
+    STORAGE(OFF(180)); break;   STORAGE(OFF(181)); break;
+    STORAGE(OFF(182)); break;   STORAGE(OFF(183)); break;
+    STORAGE(OFF(184)); break;   STORAGE(OFF(185)); break;
+    STORAGE(OFF(186)); break;   STORAGE(OFF(187)); break;
+    STORAGE(OFF(188)); break;   STORAGE(OFF(189)); break;
+    STORAGE(OFF(190)); break;
+
+    /*-------------------------------------------------------------------------
+     * Prefetch controller.
+     */
+    WRITEOP(PRECON); return;    // Prefetch Control
+    WRITEOP(PRESTAT); return;   // Prefetch Status
+
+    /*-------------------------------------------------------------------------
+     * System controller.
+     */
+    STORAGE(CFGCON);            // Configuration Control
+        // TODO: use unlock sequence
+        mask = PIC32_CFGCON_DMAPRI | PIC32_CFGCON_CPUPRI |
+            PIC32_CFGCON_ICACLK | PIC32_CFGCON_OCACLK |
+            PIC32_CFGCON_IOLOCK | PIC32_CFGCON_PMDLOCK |
+            PIC32_CFGCON_PGLOCK | PIC32_CFGCON_USBSSEN |
+            PIC32_CFGCON_ECC_MASK | PIC32_CFGCON_JTAGEN |
+            PIC32_CFGCON_TROEN | PIC32_CFGCON_TDOEN;
+        data = (data & mask) | (*bufp & ~mask);
+        break;
+    READONLY(DEVID);            // Device Identifier
+    STORAGE(SYSKEY);            // System Key
+        /* Unlock state machine. */
+        if (s->syskey_unlock == 0 && VALUE(SYSKEY) == 0xaa996655)
+            s->syskey_unlock = 1;
+        if (s->syskey_unlock == 1 && VALUE(SYSKEY) == 0x556699aa)
+            s->syskey_unlock = 2;
+        else
+            s->syskey_unlock = 0;
+        break;
+    STORAGE(RCON); break;       // Reset Control
+    WRITEOP(RSWRST);            // Software Reset
+        if (s->syskey_unlock == 2 && (VALUE(RSWRST) & 1)) {
+            /* Reset CPU. */
+            qemu_system_reset_request();
+
+            /* Reset all devices */
+            io_reset(s);
+            pic32_sdcard_reset(s);
+        }
+        break;
+    STORAGE(OSCCON); break;     // Oscillator Control
+    STORAGE(OSCTUN); break;     // Oscillator Tuning
+    STORAGE(SPLLCON); break;    // System PLL Control
+    WRITEOP(REFO1CON); return;
+    WRITEOP(REFO2CON); return;
+    WRITEOP(REFO3CON); return;
+    WRITEOP(REFO4CON); return;
+    WRITEOP(PB1DIV); return;    // Peripheral bus 1 divisor
+    WRITEOP(PB2DIV); return;    // Peripheral bus 2 divisor
+    WRITEOP(PB3DIV); return;    // Peripheral bus 3 divisor
+    WRITEOP(PB4DIV); return;    // Peripheral bus 4 divisor
+    WRITEOP(PB5DIV); return;    // Peripheral bus 5 divisor
+    WRITEOP(PB7DIV); return;    // Peripheral bus 7 divisor
+    WRITEOP(PB8DIV); return;    // Peripheral bus 8 divisor
+
+    /*-------------------------------------------------------------------------
+     * Peripheral port select registers: input.
+     */
+    STORAGE(INT1R);    pps_input_group1(offset, data); break;
+    STORAGE(T4CKR);    pps_input_group1(offset, data); break;
+    STORAGE(T9CKR);    pps_input_group1(offset, data); break;
+    STORAGE(IC1R);     pps_input_group1(offset, data); break;
+    STORAGE(IC6R);     pps_input_group1(offset, data); break;
+    STORAGE(U3CTSR);   pps_input_group1(offset, data); break;
+    STORAGE(U4RXR);    pps_input_group1(offset, data); break;
+    STORAGE(U6RXR);    pps_input_group1(offset, data); break;
+    STORAGE(SS2R);     pps_input_group1(offset, data); break;
+    STORAGE(SDI6R);    pps_input_group1(offset, data); break;
+    STORAGE(OCFAR);    pps_input_group1(offset, data); break;
+    STORAGE(REFCLKI3R);pps_input_group1(offset, data); break;
+
+    STORAGE(INT2R);    pps_input_group2(offset, data); break;
+    STORAGE(T3CKR);    pps_input_group2(offset, data); break;
+    STORAGE(T8CKR);    pps_input_group2(offset, data); break;
+    STORAGE(IC2R);     pps_input_group2(offset, data); break;
+    STORAGE(IC5R);     pps_input_group2(offset, data); break;
+    STORAGE(IC9R);     pps_input_group2(offset, data); break;
+    STORAGE(U1CTSR);   pps_input_group2(offset, data); break;
+    STORAGE(U2RXR);    pps_input_group2(offset, data); break;
+    STORAGE(U5CTSR);   pps_input_group2(offset, data); break;
+    STORAGE(SS1R);     pps_input_group2(offset, data); break;
+    STORAGE(SS3R);     pps_input_group2(offset, data); break;
+    STORAGE(SS4R);     pps_input_group2(offset, data); break;
+    STORAGE(SS5R);     pps_input_group2(offset, data); break;
+    STORAGE(C2RXR);    pps_input_group2(offset, data); break;
+
+    STORAGE(INT3R);    pps_input_group3(offset, data); break;
+    STORAGE(T2CKR);    pps_input_group3(offset, data); break;
+    STORAGE(T6CKR);    pps_input_group3(offset, data); break;
+    STORAGE(IC3R);     pps_input_group3(offset, data); break;
+    STORAGE(IC7R);     pps_input_group3(offset, data); break;
+    STORAGE(U1RXR);    pps_input_group3(offset, data); break;
+    STORAGE(U2CTSR);   pps_input_group3(offset, data); break;
+    STORAGE(U5RXR);    pps_input_group3(offset, data); break;
+    STORAGE(U6CTSR);   pps_input_group3(offset, data); break;
+    STORAGE(SDI1R);    pps_input_group3(offset, data); break;
+    STORAGE(SDI3R);    pps_input_group3(offset, data); break;
+    STORAGE(SDI5R);    pps_input_group3(offset, data); break;
+    STORAGE(SS6R);     pps_input_group3(offset, data); break;
+    STORAGE(REFCLKI1R);pps_input_group3(offset, data); break;
+
+    STORAGE(INT4R);    pps_input_group4(offset, data); break;
+    STORAGE(T5CKR);    pps_input_group4(offset, data); break;
+    STORAGE(T7CKR);    pps_input_group4(offset, data); break;
+    STORAGE(IC4R);     pps_input_group4(offset, data); break;
+    STORAGE(IC8R);     pps_input_group4(offset, data); break;
+    STORAGE(U3RXR);    pps_input_group4(offset, data); break;
+    STORAGE(U4CTSR);   pps_input_group4(offset, data); break;
+    STORAGE(SDI2R);    pps_input_group4(offset, data); break;
+    STORAGE(SDI4R);    pps_input_group4(offset, data); break;
+    STORAGE(C1RXR);    pps_input_group4(offset, data); break;
+    STORAGE(REFCLKI4R);pps_input_group4(offset, data); break;
+
+    /*-------------------------------------------------------------------------
+     * Peripheral port select registers: output.
+     */
+    STORAGE(RPA15R);   pps_output_group1(offset, data); break;
+    STORAGE(RPB1R);    pps_output_group1(offset, data); break;
+    STORAGE(RPB3R);    pps_output_group1(offset, data); break;
+    STORAGE(RPC4R);    pps_output_group1(offset, data); break;
+    STORAGE(RPC13R);   pps_output_group1(offset, data); break;
+    STORAGE(RPD3R);    pps_output_group1(offset, data); break;
+    STORAGE(RPD7R);    pps_output_group1(offset, data); break;
+    STORAGE(RPD11R);   pps_output_group1(offset, data); break;
+    STORAGE(RPD15R);   pps_output_group1(offset, data); break;
+    STORAGE(RPE5R);    pps_output_group1(offset, data); break;
+    STORAGE(RPF0R);    pps_output_group1(offset, data); break;
+    STORAGE(RPF5R);    pps_output_group1(offset, data); break;
+    STORAGE(RPG0R);    pps_output_group1(offset, data); break;
+    STORAGE(RPG7R);    pps_output_group1(offset, data); break;
+
+    STORAGE(RPB2R);    pps_output_group2(offset, data); break;
+    STORAGE(RPB6R);    pps_output_group2(offset, data); break;
+    STORAGE(RPB14R);   pps_output_group2(offset, data); break;
+    STORAGE(RPC2R);    pps_output_group2(offset, data); break;
+    STORAGE(RPD0R);    pps_output_group2(offset, data); break;
+    STORAGE(RPD1R);    pps_output_group2(offset, data); break;
+    STORAGE(RPD5R);    pps_output_group2(offset, data); break;
+    STORAGE(RPE8R);    pps_output_group2(offset, data); break;
+    STORAGE(RPF2R);    pps_output_group2(offset, data); break;
+    STORAGE(RPF3R);    pps_output_group2(offset, data); break;
+    STORAGE(RPF13R);   pps_output_group2(offset, data); break;
+    STORAGE(RPG9R);    pps_output_group2(offset, data); break;
+
+    STORAGE(RPA14R);   pps_output_group3(offset, data); break;
+    STORAGE(RPB5R);    pps_output_group3(offset, data); break;
+    STORAGE(RPB9R);    pps_output_group3(offset, data); break;
+    STORAGE(RPB10R);   pps_output_group3(offset, data); break;
+    STORAGE(RPC1R);    pps_output_group3(offset, data); break;
+    STORAGE(RPC14R);   pps_output_group3(offset, data); break;
+    STORAGE(RPD2R);    pps_output_group3(offset, data); break;
+    STORAGE(RPD6R);    pps_output_group3(offset, data); break;
+    STORAGE(RPD10R);   pps_output_group3(offset, data); break;
+    STORAGE(RPD14R);   pps_output_group3(offset, data); break;
+    STORAGE(RPF1R);    pps_output_group3(offset, data); break;
+    STORAGE(RPF4R);    pps_output_group3(offset, data); break;
+    STORAGE(RPG1R);    pps_output_group3(offset, data); break;
+    STORAGE(RPG8R);    pps_output_group3(offset, data); break;
+
+    STORAGE(RPB0R);    pps_output_group4(offset, data); break;
+    STORAGE(RPB7R);    pps_output_group4(offset, data); break;
+    STORAGE(RPB8R);    pps_output_group4(offset, data); break;
+    STORAGE(RPB15R);   pps_output_group4(offset, data); break;
+    STORAGE(RPC3R);    pps_output_group4(offset, data); break;
+    STORAGE(RPD4R);    pps_output_group4(offset, data); break;
+    STORAGE(RPD9R);    pps_output_group4(offset, data); break;
+    STORAGE(RPD12R);   pps_output_group4(offset, data); break;
+    STORAGE(RPE3R);    pps_output_group4(offset, data); break;
+    STORAGE(RPE9R);    pps_output_group4(offset, data); break;
+    STORAGE(RPF8R);    pps_output_group4(offset, data); break;
+    STORAGE(RPF12R);   pps_output_group4(offset, data); break;
+    STORAGE(RPG6R);    pps_output_group4(offset, data); break;
+
+    /*-------------------------------------------------------------------------
+     * General purpose IO signals.
+     */
+    WRITEOP(ANSELA); return;        // Port A: analog select
+    WRITEOP(TRISA); return;         // Port A: mask of inputs
+    WRITEOPX(PORTA, LATA);          // Port A: write outputs
+    WRITEOP(LATA);                  // Port A: write outputs
+        pic32_gpio_write(s, 0, VALUE(LATA));
+        return;
+    WRITEOP(ODCA); return;          // Port A: open drain configuration
+    WRITEOP(CNPUA); return;         // Input pin pull-up
+    WRITEOP(CNPDA); return;         // Input pin pull-down
+    WRITEOP(CNCONA); return;        // Interrupt-on-change control
+    WRITEOP(CNENA); return;         // Input change interrupt enable
+    WRITEOP(CNSTATA); return;       // Input change status
+
+    WRITEOP(ANSELB); return;        // Port B: analog select
+    WRITEOP(TRISB); return;         // Port B: mask of inputs
+    WRITEOPX(PORTB, LATB);          // Port B: write outputs
+    WRITEOP(LATB);                  // Port B: write outputs
+        pic32_gpio_write(s, 1, VALUE(LATB));
+        return;
+    WRITEOP(ODCB); return;          // Port B: open drain configuration
+    WRITEOP(CNPUB); return;         // Input pin pull-up
+    WRITEOP(CNPDB); return;         // Input pin pull-down
+    WRITEOP(CNCONB); return;        // Interrupt-on-change control
+    WRITEOP(CNENB); return;         // Input change interrupt enable
+    WRITEOP(CNSTATB); return;       // Input change status
+
+    WRITEOP(ANSELC); return;        // Port C: analog select
+    WRITEOP(TRISC); return;         // Port C: mask of inputs
+    WRITEOPX(PORTC, LATC);          // Port C: write outputs
+    WRITEOP(LATC);                  // Port C: write outputs
+        pic32_gpio_write(s, 2, VALUE(LATC));
+        return;
+    WRITEOP(ODCC); return;          // Port C: open drain configuration
+    WRITEOP(CNPUC); return;         // Input pin pull-up
+    WRITEOP(CNPDC); return;         // Input pin pull-down
+    WRITEOP(CNCONC); return;        // Interrupt-on-change control
+    WRITEOP(CNENC); return;         // Input change interrupt enable
+    WRITEOP(CNSTATC); return;       // Input change status
+
+    WRITEOP(ANSELD); return;        // Port D: analog select
+    WRITEOP(TRISD); return;         // Port D: mask of inputs
+    WRITEOPX(PORTD, LATD);          // Port D: write outputs
+    WRITEOP(LATD);                  // Port D: write outputs
+        pic32_gpio_write(s, 3, VALUE(LATD));
+        return;
+    WRITEOP(ODCD); return;          // Port D: open drain configuration
+    WRITEOP(CNPUD); return;         // Input pin pull-up
+    WRITEOP(CNPDD); return;         // Input pin pull-down
+    WRITEOP(CNCOND); return;        // Interrupt-on-change control
+    WRITEOP(CNEND); return;         // Input change interrupt enable
+    WRITEOP(CNSTATD); return;       // Input change status
+
+    WRITEOP(ANSELE); return;        // Port E: analog select
+    WRITEOP(TRISE); return;         // Port E: mask of inputs
+    WRITEOPX(PORTE, LATE);          // Port E: write outputs
+    WRITEOP(LATE);                  // Port E: write outputs
+        pic32_gpio_write(s, 4, VALUE(LATE));
+        return;
+    WRITEOP(ODCE); return;          // Port E: open drain configuration
+    WRITEOP(CNPUE); return;         // Input pin pull-up
+    WRITEOP(CNPDE); return;         // Input pin pull-down
+    WRITEOP(CNCONE); return;        // Interrupt-on-change control
+    WRITEOP(CNENE); return;         // Input change interrupt enable
+    WRITEOP(CNSTATE); return;       // Input change status
+
+    WRITEOP(ANSELF); return;        // Port F: analog select
+    WRITEOP(TRISF); return;         // Port F: mask of inputs
+    WRITEOPX(PORTF, LATF);          // Port F: write outputs
+    WRITEOP(LATF);                  // Port F: write outputs
+        pic32_gpio_write(s, 5, VALUE(LATF));
+        return;
+    WRITEOP(ODCF); return;          // Port F: open drain configuration
+    WRITEOP(CNPUF); return;         // Input pin pull-up
+    WRITEOP(CNPDF); return;         // Input pin pull-down
+    WRITEOP(CNCONF); return;        // Interrupt-on-change control
+    WRITEOP(CNENF); return;         // Input change interrupt enable
+    WRITEOP(CNSTATF); return;       // Input change status
+
+    WRITEOP(ANSELG); return;        // Port G: analog select
+    WRITEOP(TRISG); return;         // Port G: mask of inputs
+    WRITEOPX(PORTG, LATG);          // Port G: write outputs
+    WRITEOP(LATG);                  // Port G: write outputs
+        pic32_gpio_write(s, 6, VALUE(LATG));
+        return;
+    WRITEOP(ODCG); return;          // Port G: open drain configuration
+    WRITEOP(CNPUG); return;         // Input pin pull-up
+    WRITEOP(CNPDG); return;         // Input pin pull-down
+    WRITEOP(CNCONG); return;        // Interrupt-on-change control
+    WRITEOP(CNENG); return;         // Input change interrupt enable
+    WRITEOP(CNSTATG); return;       // Input change status
+
+    WRITEOP(ANSELH); return;        // Port H: analog select
+    WRITEOP(TRISH); return;         // Port H: mask of inputs
+    WRITEOPX(PORTH, LATH);          // Port H: write outputs
+    WRITEOP(LATH);                  // Port H: write outputs
+        pic32_gpio_write(s, 7, VALUE(LATH));
+        return;
+    WRITEOP(ODCH); return;          // Port H: open drain configuration
+    WRITEOP(CNPUH); return;         // Input pin pull-up
+    WRITEOP(CNPDH); return;         // Input pin pull-down
+    WRITEOP(CNCONH); return;        // Interrupt-on-change control
+    WRITEOP(CNENH); return;         // Input change interrupt enable
+    WRITEOP(CNSTATH); return;       // Input change status
+
+    WRITEOP(ANSELJ); return;        // Port J: analog select
+    WRITEOP(TRISJ); return;         // Port J: mask of inputs
+    WRITEOPX(PORTJ, LATJ);          // Port J: write outputs
+    WRITEOP(LATJ);                  // Port J: write outputs
+        pic32_gpio_write(s, 8, VALUE(LATJ));
+        return;
+    WRITEOP(ODCJ); return;          // Port J: open drain configuration
+    WRITEOP(CNPUJ); return;         // Input pin pull-up
+    WRITEOP(CNPDJ); return;         // Input pin pull-down
+    WRITEOP(CNCONJ); return;        // Interrupt-on-change control
+    WRITEOP(CNENJ); return;         // Input change interrupt enable
+    WRITEOP(CNSTATJ); return;       // Input change status
+
+    WRITEOP(TRISK); return;         // Port K: mask of inputs
+    WRITEOPX(PORTK, LATK);          // Port K: write outputs
+    WRITEOP(LATK);                  // Port K: write outputs
+        pic32_gpio_write(s, 9, VALUE(LATK));
+        return;
+    WRITEOP(ODCK); return;          // Port K: open drain configuration
+    WRITEOP(CNPUK); return;         // Input pin pull-up
+    WRITEOP(CNPDK); return;         // Input pin pull-down
+    WRITEOP(CNCONK); return;        // Interrupt-on-change control
+    WRITEOP(CNENK); return;         // Input change interrupt enable
+    WRITEOP(CNSTATK); return;       // Input change status
+
+    /*-------------------------------------------------------------------------
+     * UART 1.
+     */
+    STORAGE(U1TXREG);                               // Transmit
+        pic32_uart_put_char(s, 0, data);
+        break;
+    WRITEOP(U1MODE);                                // Mode
+        pic32_uart_update_mode(s, 0);
+        return;
+    WRITEOPR(U1STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 0);
+        return;
+    WRITEOP(U1BRG); return;                         // Baud rate
+    READONLY(U1RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 2.
+     */
+    STORAGE(U2TXREG);                               // Transmit
+        pic32_uart_put_char(s, 1, data);
+        break;
+    WRITEOP(U2MODE);                                // Mode
+        pic32_uart_update_mode(s, 1);
+        return;
+    WRITEOPR(U2STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 1);
+        return;
+    WRITEOP(U2BRG); return;                         // Baud rate
+    READONLY(U2RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 3.
+     */
+    STORAGE(U3TXREG);                               // Transmit
+        pic32_uart_put_char(s, 2, data);
+        break;
+    WRITEOP(U3MODE);                                // Mode
+        pic32_uart_update_mode(s, 2);
+        return;
+    WRITEOPR(U3STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 2);
+        return;
+    WRITEOP(U3BRG); return;                         // Baud rate
+    READONLY(U3RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 4.
+     */
+    STORAGE(U4TXREG);                               // Transmit
+        pic32_uart_put_char(s, 3, data);
+        break;
+    WRITEOP(U4MODE);                                // Mode
+        pic32_uart_update_mode(s, 3);
+        return;
+    WRITEOPR(U4STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 3);
+        return;
+    WRITEOP(U4BRG); return;                         // Baud rate
+    READONLY(U4RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 5.
+     */
+    STORAGE(U5TXREG);                               // Transmit
+        pic32_uart_put_char(s, 4, data);
+        break;
+    WRITEOP(U5MODE);                                // Mode
+        pic32_uart_update_mode(s, 4);
+        return;
+    WRITEOPR(U5STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 4);
+        return;
+    WRITEOP(U5BRG); return;                         // Baud rate
+    READONLY(U5RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * UART 6.
+     */
+    STORAGE(U6TXREG);                               // Transmit
+        pic32_uart_put_char(s, 5, data);
+        break;
+    WRITEOP(U6MODE);                                // Mode
+        pic32_uart_update_mode(s, 5);
+        return;
+    WRITEOPR(U6STA,                                 // Status and control
+        PIC32_USTA_URXDA | PIC32_USTA_FERR | PIC32_USTA_PERR |
+        PIC32_USTA_RIDLE | PIC32_USTA_TRMT | PIC32_USTA_UTXBF);
+        pic32_uart_update_status(s, 5);
+        return;
+    WRITEOP(U6BRG); return;                         // Baud rate
+    READONLY(U6RXREG);                              // Receive
+
+    /*-------------------------------------------------------------------------
+     * SPI.
+     */
+    WRITEOP(SPI1CON);                               // Control
+        pic32_spi_control(s, 0);
+        return;
+    WRITEOPR(SPI1STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI1BUF);                               // Buffer
+        pic32_spi_writebuf(s, 0, data);
+        return;
+    WRITEOP(SPI1BRG); return;                       // Baud rate
+    WRITEOP(SPI1CON2); return;                      // Control 2
+
+    WRITEOP(SPI2CON);                               // Control
+        pic32_spi_control(s, 1);
+        return;
+    WRITEOPR(SPI2STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI2BUF);                               // Buffer
+        pic32_spi_writebuf(s, 1, data);
+        return;
+    WRITEOP(SPI2BRG); return;                       // Baud rate
+    WRITEOP(SPI2CON2); return;                      // Control 2
+
+    WRITEOP(SPI3CON);                               // Control
+        pic32_spi_control(s, 2);
+        return;
+    WRITEOPR(SPI3STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI3BUF);                               // Buffer
+        pic32_spi_writebuf(s, 2, data);
+        return;
+    WRITEOP(SPI3BRG); return;                       // Baud rate
+    WRITEOP(SPI3CON2); return;                      // Control 2
+
+    WRITEOP(SPI4CON);                               // Control
+        pic32_spi_control(s, 3);
+        return;
+    WRITEOPR(SPI4STAT, ~PIC32_SPISTAT_SPIROV);      // Status
+        return;                                     // Only ROV bit is writable
+    STORAGE(SPI4BUF);                               // Buffer
+        pic32_spi_writebuf(s, 3, data);
+        return;
+    WRITEOP(SPI4BRG); return;                       // Baud rate
+    WRITEOP(SPI4CON2); return;                      // Control 2
+
+    /*
+     * Timers 1-9.
+     */
+    WRITEOP(T1CON); return;
+    WRITEOP(TMR1); return;
+    WRITEOP(PR1); return;
+    WRITEOP(T2CON); return;
+    WRITEOP(TMR2); return;
+    WRITEOP(PR2); return;
+    WRITEOP(T3CON); return;
+    WRITEOP(TMR3); return;
+    WRITEOP(PR3); return;
+    WRITEOP(T4CON); return;
+    WRITEOP(TMR4); return;
+    WRITEOP(PR4); return;
+    WRITEOP(T5CON); return;
+    WRITEOP(TMR5); return;
+    WRITEOP(PR5); return;
+    WRITEOP(T6CON); return;
+    WRITEOP(TMR6); return;
+    WRITEOP(PR6); return;
+    WRITEOP(T7CON); return;
+    WRITEOP(TMR7); return;
+    WRITEOP(PR7); return;
+    WRITEOP(T8CON); return;
+    WRITEOP(TMR8); return;
+    WRITEOP(PR8); return;
+    WRITEOP(T9CON); return;
+    WRITEOP(TMR9); return;
+    WRITEOP(PR9); return;
+
+    /*-------------------------------------------------------------------------
+     * Ethernet.
+     */
+    WRITEOP(ETHCON1);                   // Control 1
+        pic32_eth_control(s);
+        return;
+    WRITEOP(ETHCON2); return;           // Control 2: RX data buffer size
+    WRITEOP(ETHTXST); return;           // Tx descriptor start address
+    WRITEOP(ETHRXST); return;           // Rx descriptor start address
+    WRITEOP(ETHHT0); return;            // Hash tasble 0
+    WRITEOP(ETHHT1); return;            // Hash tasble 1
+    WRITEOP(ETHPMM0); return;           // Pattern match mask 0
+    WRITEOP(ETHPMM1); return;           // Pattern match mask 1
+    WRITEOP(ETHPMCS); return;           // Pattern match checksum
+    WRITEOP(ETHPMO); return;            // Pattern match offset
+    WRITEOP(ETHRXFC); return;           // Receive filter configuration
+    WRITEOP(ETHRXWM); return;           // Receive watermarks
+    WRITEOP(ETHIEN); return;            // Interrupt enable
+    WRITEOP(ETHIRQ); return;            // Interrupt request
+    STORAGE(ETHSTAT); break;            // Status
+    WRITEOP(ETHRXOVFLOW); return;       // Receive overflow statistics
+    WRITEOP(ETHFRMTXOK); return;        // Frames transmitted OK statistics
+    WRITEOP(ETHSCOLFRM); return;        // Single collision frames statistics
+    WRITEOP(ETHMCOLFRM); return;        // Multiple collision frames statistics
+    WRITEOP(ETHFRMRXOK); return;        // Frames received OK statistics
+    WRITEOP(ETHFCSERR); return;         // Frame check sequence error
statistics
+    WRITEOP(ETHALGNERR); return;        // Alignment errors statistics
+    WRITEOP(EMAC1CFG1); return;         // MAC configuration 1
+    WRITEOP(EMAC1CFG2); return;         // MAC configuration 2
+    WRITEOP(EMAC1IPGT); return;         // MAC back-to-back interpacket gap
+    WRITEOP(EMAC1IPGR); return;         // MAC non-back-to-back interpacket gap
+    WRITEOP(EMAC1CLRT); return;         // MAC collision window/retry limit
+    WRITEOP(EMAC1MAXF); return;         // MAC maximum frame length
+    WRITEOP(EMAC1SUPP); return;         // MAC PHY support
+    WRITEOP(EMAC1TEST); return;         // MAC test
+    WRITEOP(EMAC1MCFG); return;         // MII configuration
+    WRITEOP(EMAC1MCMD);                 // MII command
+        pic32_mii_command(s);
+        return;
+    WRITEOP(EMAC1MADR); return;         // MII address
+    WRITEOP(EMAC1MWTD);                 // MII write data
+        pic32_mii_write(s);
+        return;
+    WRITEOP(EMAC1MRDD); return;         // MII read data
+    WRITEOP(EMAC1MIND); return;         // MII indicators
+    WRITEOP(EMAC1SA0); return;          // MAC station address 0
+    WRITEOP(EMAC1SA1); return;          // MAC station address 1
+    WRITEOP(EMAC1SA2); return;          // MAC station address 2
+
+    /*-------------------------------------------------------------------------
+     * USB.
+     */
+    STORAGE(USBCSR0); break;
+    STORAGE(USBCSR1); break;
+    STORAGE(USBCSR2); break;
+    STORAGE(USBCSR3); break;
+    STORAGE(USBIENCSR0); break;
+    STORAGE(USBIENCSR1); break;
+    STORAGE(USBIENCSR2); break;
+    STORAGE(USBIENCSR3); break;
+    STORAGE(USBFIFO0); break;
+    STORAGE(USBFIFO1); break;
+    STORAGE(USBFIFO2); break;
+    STORAGE(USBFIFO3); break;
+    STORAGE(USBFIFO4); break;
+    STORAGE(USBFIFO5); break;
+    STORAGE(USBFIFO6); break;
+    STORAGE(USBFIFO7); break;
+    STORAGE(USBOTG); break;
+    STORAGE(USBFIFOA); break;
+    STORAGE(USBHWVER); break;
+    STORAGE(USBINFO); break;
+    STORAGE(USBEOFRST); break;
+    STORAGE(USBE0TXA); break;
+    STORAGE(USBE0RXA); break;
+    STORAGE(USBE1TXA); break;
+    STORAGE(USBE1RXA); break;
+    STORAGE(USBE2TXA); break;
+    STORAGE(USBE2RXA); break;
+    STORAGE(USBE3TXA); break;
+    STORAGE(USBE3RXA); break;
+    STORAGE(USBE4TXA); break;
+    STORAGE(USBE4RXA); break;
+    STORAGE(USBE5TXA); break;
+    STORAGE(USBE5RXA); break;
+    STORAGE(USBE6TXA); break;
+    STORAGE(USBE6RXA); break;
+    STORAGE(USBE7TXA); break;
+    STORAGE(USBE7RXA); break;
+    STORAGE(USBE0CSR0); break;
+    STORAGE(USBE0CSR2); break;
+    STORAGE(USBE0CSR3); break;
+    STORAGE(USBE1CSR0); break;
+    STORAGE(USBE1CSR1); break;
+    STORAGE(USBE1CSR2); break;
+    STORAGE(USBE1CSR3); break;
+    STORAGE(USBE2CSR0); break;
+    STORAGE(USBE2CSR1); break;
+    STORAGE(USBE2CSR2); break;
+    STORAGE(USBE2CSR3); break;
+    STORAGE(USBE3CSR0); break;
+    STORAGE(USBE3CSR1); break;
+    STORAGE(USBE3CSR2); break;
+    STORAGE(USBE3CSR3); break;
+    STORAGE(USBE4CSR0); break;
+    STORAGE(USBE4CSR1); break;
+    STORAGE(USBE4CSR2); break;
+    STORAGE(USBE4CSR3); break;
+    STORAGE(USBE5CSR0); break;
+    STORAGE(USBE5CSR1); break;
+    STORAGE(USBE5CSR2); break;
+    STORAGE(USBE5CSR3); break;
+    STORAGE(USBE6CSR0); break;
+    STORAGE(USBE6CSR1); break;
+    STORAGE(USBE6CSR2); break;
+    STORAGE(USBE6CSR3); break;
+    STORAGE(USBE7CSR0); break;
+    STORAGE(USBE7CSR1); break;
+    STORAGE(USBE7CSR2); break;
+    STORAGE(USBE7CSR3); break;
+    STORAGE(USBDMAINT); break;
+    STORAGE(USBDMA1C); break;
+    STORAGE(USBDMA1A); break;
+    STORAGE(USBDMA1N); break;
+    STORAGE(USBDMA2C); break;
+    STORAGE(USBDMA2A); break;
+    STORAGE(USBDMA2N); break;
+    STORAGE(USBDMA3C); break;
+    STORAGE(USBDMA3A); break;
+    STORAGE(USBDMA3N); break;
+    STORAGE(USBDMA4C); break;
+    STORAGE(USBDMA4A); break;
+    STORAGE(USBDMA4N); break;
+    STORAGE(USBDMA5C); break;
+    STORAGE(USBDMA5A); break;
+    STORAGE(USBDMA5N); break;
+    STORAGE(USBDMA6C); break;
+    STORAGE(USBDMA6A); break;
+    STORAGE(USBDMA6N); break;
+    STORAGE(USBDMA7C); break;
+    STORAGE(USBDMA7A); break;
+    STORAGE(USBDMA7N); break;
+    STORAGE(USBDMA8C); break;
+    STORAGE(USBDMA8A); break;
+    STORAGE(USBDMA8N); break;
+    STORAGE(USBE1RPC); break;
+    STORAGE(USBE2RPC); break;
+    STORAGE(USBE3RPC); break;
+    STORAGE(USBE4RPC); break;
+    STORAGE(USBE5RPC); break;
+    STORAGE(USBE6RPC); break;
+    STORAGE(USBE7RPC); break;
+    STORAGE(USBDPBFD); break;
+    STORAGE(USBTMCON1); break;
+    STORAGE(USBTMCON2); break;
+    STORAGE(USBLPMR1); break;
+    STORAGE(USBLMPR2); break;
+
+    default:
+        printf("--- Write %08x to 1f8%05x: peripheral register not
supported\n",
+            data, offset);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Write %08x to 1f8%05x:
peripheral register not supported\n",
+                data, offset);
+        exit(1);
+readonly:
+        printf("--- Write %08x to %s: readonly register\n",
+            data, *namep);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Write %08x to %s: readonly register\n",
+                data, *namep);
+        *namep = 0;
+        return;
+    }
+    *bufp = data;
+}
+
+static uint64_t pic32_io_read(void *opaque, hwaddr addr, unsigned bytes)
+{
+    pic32_t *s = opaque;
+    uint32_t offset = addr & 0xfffff;
+    const char *name = "???";
+    uint32_t data = 0;
+
+    data = io_read32(s, offset & ~3, &name);
+    switch (bytes) {
+    case 1:
+        if ((offset &= 3) != 0) {
+            // Unaligned read.
+            data >>= offset * 8;
+        }
+        data = (uint8_t) data;
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %02x from %s\n", data, name);
+        }
+        break;
+    case 2:
+        if (offset & 2) {
+            // Unaligned read.
+            data >>= 16;
+        }
+        data = (uint16_t) data;
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %04x from %s\n", data, name);
+        }
+        break;
+    default:
+        if (TRACE) {
+            fprintf(qemu_logfile, "--- I/O Read  %08x from %s\n", data, name);
+        }
+        break;
+    }
+    return data;
+}
+
+static void pic32_io_write(void *opaque, hwaddr addr, uint64_t data,
unsigned bytes)
+{
+    pic32_t *s = opaque;
+    uint32_t offset = addr & 0xfffff;
+    const char *name = "???";
+
+    // Fetch data and align to word format.
+    switch (bytes) {
+    case 1:
+        data = (uint8_t) data;
+        data <<= (offset & 3) * 8;
+        break;
+    case 2:
+        data = (uint16_t) data;
+        data <<= (offset & 2) * 8;
+        break;
+    }
+    io_write32(s, offset & ~3, data, &name);
+
+    if (TRACE && name != 0) {
+        fprintf(qemu_logfile, "--- I/O Write %08x to %s\n",
+            (uint32_t) data, name);
+    }
+}
+
+static const MemoryRegionOps pic32_io_ops = {
+    .read       = pic32_io_read,
+    .write      = pic32_io_write,
+    .endianness = DEVICE_NATIVE_ENDIAN,
+};
+
+static void main_cpu_reset(void *opaque)
+{
+    MIPSCPU *cpu = opaque;
+    CPUMIPSState *env = &cpu->env;
+    int i;
+
+    cpu_reset(CPU(cpu));
+
+    /* Adjust the initial configuration for microAptivP core. */
+    env->CP0_IntCtl = 0x00030000;
+    env->CP0_Debug = (1 << CP0DB_CNT) | (5 << CP0DB_VER);
+    env->CP0_Performance0 = 0x80000000;
+    for (i=0; i<7; i++)
+        env->CP0_WatchHi[i] = (i < 3) ? 0x80000000 : 0;
+}
+
+static void store_byte(unsigned address, unsigned char byte)
+{
+    if (address >= PROGRAM_FLASH_START &&
+        address < PROGRAM_FLASH_START + PROGRAM_FLASH_SIZE)
+    {
+        //printf("Store %02x to program memory %08x\n", byte, address);
+        prog_ptr[address & 0xfffff] = byte;
+    }
+    else if (address >= BOOT_FLASH_START &&
+             address < BOOT_FLASH_START + BOOT_FLASH_SIZE)
+    {
+        //printf("Store %02x to boot memory %08x\n", byte, address);
+        boot_ptr[address & 0xffff] = byte;
+    }
+    else {
+        printf("Bad hex file: incorrect address %08X, must be
%08X-%08X or %08X-%08X\n",
+            address, PROGRAM_FLASH_START,
+            PROGRAM_FLASH_START + PROGRAM_FLASH_SIZE - 1,
+            BOOT_FLASH_START, BOOT_FLASH_START + BOOT_FLASH_SIZE - 1);
+        exit(1);
+    }
+}
+
+/*
+ * Ignore ^C and ^\ signals and pass these characters to the target.
+ */
+static void pic32_pass_signal_chars(void)
+{
+    struct termios tty;
+
+    tcgetattr(0, &tty);
+    tty.c_lflag &= ~ISIG;
+    tcsetattr(0, TCSANOW, &tty);
+}
+
+static void pic32_init(MachineState *machine, int board_type)
+{
+    const char *cpu_model = machine->cpu_model;
+    unsigned ram_size = DATA_MEM_SIZE;
+    MemoryRegion *system_memory = get_system_memory();
+    MemoryRegion *ram_main = g_new(MemoryRegion, 1);
+    MemoryRegion *prog_mem = g_new(MemoryRegion, 1);
+    MemoryRegion *boot_mem = g_new(MemoryRegion, 1);
+    MemoryRegion *io_mem = g_new(MemoryRegion, 1);
+    MIPSCPU *cpu;
+    CPUMIPSState *env;
+
+    DeviceState *dev = qdev_create(NULL, TYPE_MIPS_PIC32);
+    pic32_t *s = OBJECT_CHECK(pic32_t, dev, TYPE_MIPS_PIC32);
+    s->board_type = board_type;
+    s->stop_on_reset = 1;               /* halt simulation on soft reset */
+    s->iomem = g_malloc0(IO_MEM_SIZE);  /* backing storage for I/O area */
+
+    qdev_init_nofail(dev);
+
+    /* Init CPU. */
+    if (! cpu_model) {
+        cpu_model = "microAptivP";
+    }
+    printf("Board: %s\n", board_name[board_type]);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Board: %s\n", board_name[board_type]);
+
+    printf("Processor: %s\n", cpu_model);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Processor: %s\n", cpu_model);
+
+    cpu = cpu_mips_init(cpu_model);
+    if (! cpu) {
+        fprintf(stderr, "Unable to find CPU definition\n");
+        exit(1);
+    }
+    s->cpu = cpu;
+    env = &cpu->env;
+
+    /* Register RAM */
+    printf("RAM size: %u kbytes\n", ram_size / 1024);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "RAM size: %u kbytes\n", ram_size / 1024);
+
+    memory_region_init_ram(ram_main, NULL, "kernel.ram",
+        ram_size, &error_abort);
+    vmstate_register_ram_global(ram_main);
+    memory_region_add_subregion(system_memory, DATA_MEM_START, ram_main);
+
+    /* Special function registers. */
+    memory_region_init_io(io_mem, NULL, &pic32_io_ops, s,
+                          "io", IO_MEM_SIZE);
+    memory_region_add_subregion(system_memory, IO_MEM_START, io_mem);
+
+    /*
+     * Map the flash memory.
+     */
+    memory_region_init_ram(boot_mem, NULL, "boot.flash",
BOOT_FLASH_SIZE, &error_abort);
+    memory_region_init_ram(prog_mem, NULL, "prog.flash",
PROGRAM_FLASH_SIZE, &error_abort);
+
+    /* Load a Flash memory image. */
+    if (! machine->kernel_filename) {
+        error_report("No -kernel argument was specified.");
+        exit(1);
+    }
+    prog_ptr = memory_region_get_ram_ptr(prog_mem);
+    boot_ptr = memory_region_get_ram_ptr(boot_mem);
+    if (bios_name)
+        pic32_load_hex_file(bios_name, store_byte);
+    pic32_load_hex_file(machine->kernel_filename, store_byte);
+
+    memory_region_set_readonly(boot_mem, true);
+    memory_region_set_readonly(prog_mem, true);
+    memory_region_add_subregion(system_memory, BOOT_FLASH_START, boot_mem);
+    memory_region_add_subregion(system_memory, PROGRAM_FLASH_START, prog_mem);
+
+    /* Init internal devices */
+    s->irq_raise = irq_raise;
+    s->irq_clear = irq_clear;
+    qemu_register_reset(main_cpu_reset, cpu);
+
+    /* Setup interrupt controller in EIC mode. */
+    env->CP0_Config3 |= 1 << CP0C3_VEIC;
+    cpu_mips_irq_init_cpu(env);
+    env->eic_timer_irq = pic32_timer_irq;
+    env->eic_soft_irq = pic32_soft_irq;
+    env->eic_context = s;
+
+    /* CPU runs at 200MHz.
+     * Count register increases at half this rate. */
+    cpu_mips_clock_init(env, 100*1000*1000);
+
+    /*
+     * Initialize board-specific parameters.
+     */
+    int cs0_port, cs0_pin, cs1_port, cs1_pin;
+    switch (board_type) {
+    default:
+    case BOARD_WIFIRE:                      // console on UART4
+        BOOTMEM(DEVCFG0) = 0xfffffff7;
+        BOOTMEM(DEVCFG1) = 0x7f743cb9;
+        BOOTMEM(DEVCFG2) = 0xfff9b11a;
+        BOOTMEM(DEVCFG3) = 0xbeffffff;
+        VALUE(DEVID)     = 0x4510e053;      // MZ2048ECG100 rev A4
+        VALUE(OSCCON)    = 0x00001120;      // external oscillator 24MHz
+        s->sdcard_spi_port = 2;             // SD card at SPI3,
+        cs0_port = 2;  cs0_pin = 3;         // select0 at C3,
+        cs1_port = -1; cs1_pin = -1;        // select1 not available
+        break;
+    case BOARD_MEBII:                       // console on UART1
+        BOOTMEM(DEVCFG0) = 0x7fffffdb;
+        BOOTMEM(DEVCFG1) = 0x0000fc81;
+        BOOTMEM(DEVCFG2) = 0x3ff8b11a;
+        BOOTMEM(DEVCFG3) = 0x86ffffff;
+        VALUE(DEVID)     = 0x45127053;      // MZ2048ECH144 rev A4
+        VALUE(OSCCON)    = 0x00001120;      // external oscillator 24MHz
+        s->sdcard_spi_port = 1;             // SD card at SPI2,
+        cs0_port = 1;  cs0_pin = 14;        // select0 at B14,
+        cs1_port = -1; cs1_pin = -1;        // select1 not available
+        break;
+    case BOARD_EXPLORER16:                  // console on UART1
+        BOOTMEM(DEVCFG0) = 0x7fffffdb;
+        BOOTMEM(DEVCFG1) = 0x0000fc81;
+        BOOTMEM(DEVCFG2) = 0x3ff8b11a;
+        BOOTMEM(DEVCFG3) = 0x86ffffff;
+        VALUE(DEVID)     = 0x35113053;      // MZ2048ECH100 rev A3
+        VALUE(OSCCON)    = 0x00001120;      // external oscillator 24MHz
+        s->sdcard_spi_port = 0;             // SD card at SPI1,
+        cs0_port = 1;  cs0_pin = 1;         // select0 at B1,
+        cs1_port = 1;  cs1_pin = 2;         // select1 at B2
+        break;
+    }
+
+    /* UARTs */
+    pic32_uart_init(s, 0, PIC32_IRQ_U1E, U1STA, U1MODE);
+    pic32_uart_init(s, 1, PIC32_IRQ_U2E, U2STA, U2MODE);
+    pic32_uart_init(s, 2, PIC32_IRQ_U3E, U3STA, U3MODE);
+    pic32_uart_init(s, 3, PIC32_IRQ_U4E, U4STA, U4MODE);
+    pic32_uart_init(s, 4, PIC32_IRQ_U5E, U5STA, U5MODE);
+    pic32_uart_init(s, 5, PIC32_IRQ_U6E, U6STA, U6MODE);
+
+    /* SPIs */
+    pic32_spi_init(s, 0, PIC32_IRQ_SPI1E, SPI1CON, SPI1STAT);
+    pic32_spi_init(s, 1, PIC32_IRQ_SPI2E, SPI2CON, SPI2STAT);
+    pic32_spi_init(s, 2, PIC32_IRQ_SPI3E, SPI3CON, SPI3STAT);
+    pic32_spi_init(s, 3, PIC32_IRQ_SPI4E, SPI4CON, SPI4STAT);
+    pic32_spi_init(s, 4, PIC32_IRQ_SPI5E, SPI5CON, SPI5STAT);
+    pic32_spi_init(s, 5, PIC32_IRQ_SPI6E, SPI6CON, SPI6STAT);
+
+    /*
+     * Load SD card images.
+     * Use options:
+     *      -sd filename
+     * or   -hda filename
+     * and  -hdb filename
+     */
+    const char *sd0_file = 0, *sd1_file = 0;
+    DriveInfo *dinfo = drive_get(IF_IDE, 0, 0);
+    if (dinfo) {
+        sd0_file = qemu_opt_get(dinfo->opts, "file");
+        dinfo->is_default = 1;
+
+        dinfo = drive_get(IF_IDE, 0, 1);
+        if (dinfo) {
+            sd1_file = qemu_opt_get(dinfo->opts, "file");
+            dinfo->is_default = 1;
+        }
+    }
+    if (! sd0_file) {
+        dinfo = drive_get(IF_SD, 0, 0);
+        if (dinfo) {
+            sd0_file = qemu_opt_get(dinfo->opts, "file");
+            dinfo->is_default = 1;
+        }
+    }
+    pic32_sdcard_init(s, 0, "sd0", sd0_file, cs0_port, cs0_pin);
+    pic32_sdcard_init(s, 1, "sd1", sd1_file, cs1_port, cs1_pin);
+
+    /* Ethernet. */
+    if (nd_table[0].used)
+        pic32_eth_init(s, &nd_table[0]);
+
+    io_reset(s);
+    pic32_sdcard_reset(s);
+    pic32_pass_signal_chars();
+}
+
+static void pic32_init_wifire(MachineState *machine)
+{
+    pic32_init(machine, BOARD_WIFIRE);
+}
+
+static void pic32_init_meb2(MachineState *machine)
+{
+    pic32_init(machine, BOARD_MEBII);
+}
+
+static void pic32_init_explorer16(MachineState *machine)
+{
+    pic32_init(machine, BOARD_EXPLORER16);
+}
+
+static int pic32_sysbus_device_init(SysBusDevice *sysbusdev)
+{
+    return 0;
+}
+
+static void pic32_class_init(ObjectClass *klass, void *data)
+{
+    SysBusDeviceClass *k = SYS_BUS_DEVICE_CLASS(klass);
+
+    k->init = pic32_sysbus_device_init;
+}
+
+static const TypeInfo pic32_device = {
+    .name          = TYPE_MIPS_PIC32,
+    .parent        = TYPE_SYS_BUS_DEVICE,
+    .instance_size = sizeof(pic32_t),
+    .class_init    = pic32_class_init,
+};
+
+static void pic32_register_types(void)
+{
+    type_register_static(&pic32_device);
+}
+
+static QEMUMachine pic32_board[3] = {
+    {
+        .name       = "pic32mz-wifire",
+        .desc       = "PIC32MZ microcontroller on chipKIT WiFire board",
+        .init       = pic32_init_wifire,
+        .max_cpus   = 1,
+    },
+    {
+        .name       = "pic32mz-meb2",
+        .desc       = "PIC32MZ microcontroller on Microchip MEB-II board",
+        .init       = pic32_init_meb2,
+        .max_cpus   = 1,
+    },
+    {
+        .name       = "pic32mz-explorer16",
+        .desc       = "PIC32MZ microcontroller on Microchip Explorer-16 board",
+        .init       = pic32_init_explorer16,
+        .max_cpus   = 1,
+    },
+};
+
+static void pic32_machine_init(void)
+{
+    qemu_register_machine(&pic32_board[0]);
+    qemu_register_machine(&pic32_board[1]);
+    qemu_register_machine(&pic32_board[2]);
+}
+
+type_init(pic32_register_types)
+machine_init(pic32_machine_init);
+
+#endif /* !TARGET_MIPS64 && !TARGET_WORDS_BIGENDIAN */
diff --git a/hw/mips/pic32_ethernet.c b/hw/mips/pic32_ethernet.c
new file mode 100644
index 0000000..1e8464e
--- /dev/null
+++ b/hw/mips/pic32_ethernet.c
@@ -0,0 +1,535 @@
+/*
+ * Ethernet port.
+ *
+ * Copyright (C) 2014-2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/hw.h"
+#include "exec/address-spaces.h"
+#include "sysemu/dma.h"
+#include "pic32_peripherals.h"
+
+#include "pic32mz.h"
+
+//#define DPRINT      printf
+#ifndef DPRINT
+#define DPRINT(...) /*empty*/
+#endif
+
+/*
+ * TODO: add option to enable tracing.
+ */
+#define TRACE   0
+
+#define NAME_PIC32_ETH "pic32-eth"
+
+#define MIN_RX_SIZE 60
+
+/*
+ * PIC32 Ethernet device.
+ */
+struct _eth_t {
+    SysBusDevice parent_obj;
+
+    pic32_t     *pic32;
+    NICState    *eth_nic;       /* virtual network interface */
+    NICConf     eth_conf;       /* network configuration */
+
+    uint16_t    phy_reg[32];    /* PHY registers */
+
+};
+
+/*
+ * DMA buffer descriptor.
+ */
+typedef struct {
+    uint32_t hdr;               /* Flags */
+    uint32_t paddr;             /* Phys address of data buffer */
+    uint32_t ctl;               /* TX options / RX filter status */
+    uint32_t status;            /* Status */
+} eth_desc_t;
+
+/* Start of packet */
+#define DESC_SOP(d)             ((d)->hdr & 0x80000000)
+#define DESC_SET_SOP(d)         ((d)->hdr |= 0x80000000)
+#define DESC_CLEAR_SOP(d)       ((d)->hdr &= ~0x80000000)
+
+/* End of packet */
+#define DESC_EOP(d)             ((d)->hdr & 0x40000000)
+#define DESC_SET_EOP(d)         ((d)->hdr |= 0x40000000)
+#define DESC_CLEAR_EOP(d)       ((d)->hdr &= ~0x40000000)
+
+/* Number of data bytes */
+#define DESC_BYTECNT(d)         ((d)->hdr >> 16 & 0x7ff)
+#define DESC_SET_BYTECNT(d,n)   ((d)->hdr = ((d)->hdr & ~0x7ff0000) |
(n) << 16)
+
+/* Next descriptor pointer valid */
+#define DESC_NPV(d)             ((d)->hdr & 0x00000100)
+#define DESC_SET_NPV(d)         ((d)->hdr |= 0x00000100)
+#define DESC_CLEAR_NPV(d)       ((d)->hdr &= ~0x00000100)
+
+/* Eth controller owns this desc */
+#define DESC_EOWN(d)            ((d)->hdr & 0x00000080)
+#define DESC_SET_EOWN(d)        ((d)->hdr |= 0x00000080)
+#define DESC_CLEAR_EOWN(d)      ((d)->hdr &= ~0x00000080)
+
+/* Size of received packet */
+#define DESC_FRAMESZ(d)         ((d)->status & 0xffff)
+#define DESC_SET_FRAMESZ(d,n)   ((d)->status = ((d)->status & ~0xffff) | (n))
+
+/* Receive filter status */
+#define DESC_RXF(d)             ((d)->ctl >> 24)
+#define DESC_SET_RXF(d,n)       ((d)->ctl = ((d)->ctl & 0xffffff) | (n) << 24)
+
+/*-------------------------------------------------------------
+ * PHY declarations for SMSC LAN8720A/8740A chip.
+ */
+#define PHY_CONTROL             0       /* Basic Control Register */
+#define PHY_STATUS              1       /* Basic Status Register */
+#define PHY_ID1                 2       /* PHY identifier 1 */
+#define PHY_ID2                 3       /* PHY identifier 2 */
+#define PHY_MODE                18      /* Special Modes */
+#define PHY_SPECIAL             31      /* Special Control/Status Register */
+
+#define PHY_CONTROL_RESET       0x8000  /* Soft reset, bit self cleared */
+
+#define PHY_STATUS_CAP_100_FDX  0x4000  /* Can do 100Base-TX full duplex */
+#define PHY_STATUS_CAP_100_HDX  0x2000  /* Can do 100Base-TX half duplex */
+#define PHY_STATUS_CAP_10_FDX   0x1000  /* Can do 10Base-TX full duplex */
+#define PHY_STATUS_CAP_10_HDX   0x0800  /* Can do 10Base-TX half duplex */
+#define PHY_STATUS_ANEG_ACK     0x0020  /* Auto-negotiation acknowledge */
+#define PHY_STATUS_CAP_ANEG     0x0008  /* Auto-negotiation available */
+#define PHY_STATUS_LINK         0x0004  /* Link valid */
+
+#define PHY_MODE_PHYAD          0x000f  /* PHY address mask */
+
+#define PHY_SPECIAL_AUTODONE    0x1000  /* Auto-negotiation is done */
+#define PHY_SPECIAL_FDX         0x0010  /* Full duplex */
+#define PHY_SPECIAL_100         0x0008  /* Speed 100 Mbps */
+
+/*
+ * Reset the PHY chip.
+ */
+static void phy_reset(eth_t *e)
+{
+    DPRINT("---     PHY reset\n");
+    e->phy_reg[PHY_ID1]     = 0x0007;               /* Vendor: SMSC */
+    e->phy_reg[PHY_ID2]     = 0xc111;               /* Device: LAN8740A */
+    e->phy_reg[PHY_CONTROL] = 0x1000;
+    e->phy_reg[PHY_MODE]    = 0x4000;               /* RMII interface */
+    e->phy_reg[PHY_STATUS]  = PHY_STATUS_ANEG_ACK |
+                              PHY_STATUS_CAP_ANEG |
+                              PHY_STATUS_LINK |
+                              PHY_STATUS_CAP_100_FDX |
+                              PHY_STATUS_CAP_100_HDX |
+                              PHY_STATUS_CAP_10_FDX |
+                              PHY_STATUS_CAP_10_HDX;
+    e->phy_reg[PHY_SPECIAL] = PHY_SPECIAL_AUTODONE |
+                              PHY_SPECIAL_FDX |
+                              PHY_SPECIAL_100;
+}
+
+/*
+ * Reset the Ethernet controller.
+ */
+static void eth_reset(eth_t *e)
+{
+    uint8_t *macaddr = e->eth_conf.macaddr.a;
+    pic32_t *s = e->pic32;
+
+    DPRINT("--- %s()\n", __func__);
+    if (TRACE)
+        fprintf(qemu_logfile, "--- Ethernet reset\n");
+    s->irq_clear(s, PIC32_IRQ_ETH);
+    VALUE(ETHSTAT) = 0;
+    VALUE(EMAC1SA2) = macaddr[0] | (macaddr[1] << 8);
+    VALUE(EMAC1SA1) = macaddr[2] | (macaddr[3] << 8);
+    VALUE(EMAC1SA0) = macaddr[4] | (macaddr[5] << 8);
+}
+
+/*
+ * Write to ETHCON1 register.
+ */
+void pic32_eth_control(pic32_t *s)
+{
+    eth_t *e = s->eth;
+
+    if (! (VALUE(ETHCON1) & PIC32_ETHCON1_ON)) {
+        /* Ethernet controller is disabled. */
+        DPRINT("--- %s() ETH disabled\n", __func__);
+        eth_reset(e);
+        return;
+    }
+
+    if (VALUE(ETHCON1) & PIC32_ETHCON1_TXRTS) {
+        /* Transmit request. */
+        eth_desc_t d = { 0 };
+        unsigned paddr = VALUE(ETHTXST);
+        unsigned nbytes, i;
+        unsigned char buf[2048];
+
+        d.hdr   = ldl_le_phys(&address_space_memory, paddr);
+        d.paddr = ldl_le_phys(&address_space_memory, paddr + 4);
+
+        nbytes = DESC_BYTECNT(&d);
+        DPRINT("--- %s() trasmit request %u bytes\n", __func__, nbytes);
+        DPRINT("--- TX desc [%08x] = %08x %08x\n", paddr, d.hdr, d.paddr);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Ethernet transmit request, %u
bytes\n", nbytes);
+        if (nbytes > 0 && nbytes <= sizeof(buf)) {
+            for (i=0; i<nbytes; i+=4)
+                *(uint32_t*) (buf + i) = ldl_le_phys(&address_space_memory,
+                                                     d.paddr + i);
+
+            DPRINT("--- %u bytes of data: %02x", nbytes, buf[0]);
+            for (i=1; i<nbytes; i++)
+                DPRINT("-%02x", buf[i]);
+            DPRINT("\n");
+
+            qemu_send_packet(qemu_get_queue(e->eth_nic), buf, nbytes);
+        }
+
+        /* Activate TXDONE interrupt. */
+        VALUE(ETHCON1) &= ~PIC32_ETHCON1_TXRTS;
+        VALUE(ETHIRQ) |= PIC32_ETHIRQ_TXDONE;
+        s->irq_raise(s, PIC32_IRQ_ETH);
+    }
+}
+
+/*
+ * Write to EMAC1MCMD register.
+ */
+void pic32_mii_command(pic32_t *s)
+{
+    eth_t *e = s->eth;
+    unsigned cmd = VALUE(EMAC1MCMD);
+    unsigned addr = VALUE(EMAC1MADR);
+    unsigned data;
+
+    if (cmd & (PIC32_EMAC1MCMD_READ | PIC32_EMAC1MCMD_SCAN)) {
+        data = e->phy_reg[addr & 0x1f];
+        //DPRINT("--- %s() cmd = %04x, addr = %04x\n", __func__, cmd, addr);
+        DPRINT("--- %s() read register [%u] = %04x\n", __func__, addr
& 0x1f, data);
+        if (TRACE)
+            fprintf(qemu_logfile, "--- Ethernet MII read register
[%u] = %04x\n",
+                addr & 0x1f, data);
+        VALUE(EMAC1MRDD) = data;
+    }
+}
+
+/*
+ * Write to EMAC1MWTD register.
+ */
+void pic32_mii_write(pic32_t *s)
+{
+    eth_t *e = s->eth;
+    unsigned addr = VALUE(EMAC1MADR);
+    unsigned data = VALUE(EMAC1MWTD);
+
+    DPRINT("--- %s() write register [%u] = %04x\n", __func__, addr &
0x1f, data);
+    if (TRACE)
+        fprintf(qemu_logfile, "--- Ethernet MII write register [%u] = %04x\n",
+            addr & 0x1f, data);
+    switch (addr & 0x1f) {
+    case PHY_CONTROL:                   /* Basic Control Register */
+        e->phy_reg[PHY_CONTROL] = data;
+        if (data & PHY_CONTROL_RESET) {
+            phy_reset(e);
+        }
+        break;
+    }
+}
+
+/*
+ * Return true when no receive buffers available.
+ */
+static int eth_buffer_full(pic32_t *s)
+{
+    eth_desc_t d = { 0 };
+
+    d.hdr = ldl_le_phys(&address_space_memory, VALUE(ETHRXST));
+    return !DESC_EOWN(&d);
+}
+
+/*
+ * Return true when we are ready to receive a packet.
+ */
+static int nic_can_receive(NetClientState *nc)
+{
+    eth_t *e = qemu_get_nic_opaque(nc);
+    pic32_t *s = e->pic32;
+
+    //DPRINT("--- %s()\n", __func__);
+    if (! (VALUE(ETHCON1) & PIC32_ETHCON1_ON)) {
+        /* While interface is down,
+         * we can receive anything (and discard). */
+        return 1;
+    }
+
+    /* Check whether we have at least one receive buffer available. */
+    return !eth_buffer_full(s);
+}
+
+/*
+ * Receive a packet.
+ */
+static ssize_t nic_receive(NetClientState *nc, const uint8_t *buf, size_t size)
+{
+    eth_t *e = qemu_get_nic_opaque(nc);
+    pic32_t *s = e->pic32;
+    unsigned rxfc, rxf, rxst, rxst0, rxbufsz, nbytes, len;
+    int start_of_packet;
+    uint8_t buf1[60];
+    eth_desc_t *d, desc0, desc1;
+
+    DPRINT("--- %s: %d bytes\n", __func__, (int) size);
+    if (TRACE)
+        fprintf(qemu_logfile, "--- Ethernet receive, %u bytes\n",
(unsigned)size);
+    if (! (VALUE(ETHCON1) & PIC32_ETHCON1_ON)) {
+        /* Ethernet controller is down. */
+        return -1;
+    }
+
+    if (eth_buffer_full(s))
+        return -1;
+
+    /* Cast acceptance filter. */
+    rxfc = VALUE(ETHRXFC);
+    if (buf[0] == 0xff && buf[1] == 0xff && buf[2] == 0xff &&
+        buf[3] == 0xff && buf[4] == 0xff && buf[5] == 0xff) {
+        /* Broadcast address. */
+        if (! (rxfc & PIC32_ETHRXFC_BCEN))
+            return size;
+        rxf = 0x40;
+    } else if (buf[0] & 0x01) {
+        /* Multicast. */
+        if (! (rxfc & PIC32_ETHRXFC_MCEN))
+            return size;
+        rxf = 0x80;
+    } else if (VALUE(EMAC1SA2) == (buf[0] | (buf[1] << 8)) ||
+               VALUE(EMAC1SA2) == (buf[2] | (buf[3] << 8)) ||
+               VALUE(EMAC1SA2) == (buf[4] | (buf[5] << 8))) {
+        /* Unicast for our MAC address. */
+        if (! (rxfc & PIC32_ETHRXFC_UCEN))
+            return size;
+        rxf = 0x20;
+    } else {
+        /* Not-Me Unicast. */
+        if (! (rxfc & PIC32_ETHRXFC_NOTMEEN))
+            return size;
+        rxf = 0x00;
+    }
+
+    /* If packet too small, then expand it */
+    nbytes = size;
+    if (nbytes < MIN_RX_SIZE) {
+        memcpy(buf1, buf, nbytes);
+        memset(buf1 + nbytes, 0, MIN_RX_SIZE - nbytes);
+        buf = buf1;
+        nbytes = MIN_RX_SIZE;
+    }
+
+    /* Copy data to descriptor chain. */
+    rxst0 = VALUE(ETHRXST);
+    rxbufsz = VALUE(ETHCON2) & 0x7f0;
+    start_of_packet = 1;
+    d = &desc0;
+    rxst = rxst0;
+    for (;;) {
+        /* Get descriptor. */
+        dma_memory_read(&address_space_memory, rxst, d, 16);
+        if (! DESC_EOWN(d) || (! start_of_packet && rxst == rxst0)) {
+            DPRINT("--- No more descriptors available\n");
+            VALUE(ETHIRQ) |= PIC32_ETHIRQ_RXBUFNA;
+            break;
+        }
+
+        /* Copy data to buffer. */
+        len = nbytes;
+        if (len > rxbufsz)
+            len = rxbufsz;
+        DPRINT("--- Copy %d bytes to %08x\n", len, d->paddr);
+        dma_memory_write(&address_space_memory, d->paddr, buf, len);
+        buf += len;
+
+        /* Update the descriptor. */
+        DESC_CLEAR_EOWN(d);
+        DESC_SET_BYTECNT(d, len);
+        if (start_of_packet) {
+            DESC_SET_SOP(d);
+            DESC_SET_FRAMESZ(d, nbytes);
+            DESC_SET_RXF(d, rxf);
+            start_of_packet = 0;
+        } else
+            DESC_CLEAR_SOP(d);
+        if (nbytes == len)
+            DESC_SET_EOP(d);
+        else
+            DESC_CLEAR_EOP(d);
+
+        /* Write the descriptor back memory (all but the first). */
+        if (d == &desc1) {
+            DPRINT("--- RX desc [%08x] = %08x ... ... %08x\n", rxst,
desc1.hdr, desc1.status);
+            dma_memory_write(&address_space_memory, rxst, &desc1, 16);
+        }
+
+        /* Switch to next descriptor. */
+        rxst += 16;
+        if (DESC_NPV(d))
+            rxst = ldl_le_phys(&address_space_memory, rxst);
+        VALUE(ETHRXST) = rxst;
+        d = &desc1;
+
+        nbytes -= len;
+        if (nbytes == 0) {
+            /* Update the first descriptor. */
+            DPRINT("--- RX desc [%08x] = %08x ... ... %08x\n", rxst0,
desc0.hdr, desc0.status);
+            dma_memory_write(&address_space_memory, rxst0, &desc0, 16);
+
+            /* Packet successfully received. */
+            VALUE(ETHIRQ) |= PIC32_ETHIRQ_RXDONE;
+            break;
+        }
+    }
+
+    /* Activate interrupt. */
+    s->irq_raise(s, PIC32_IRQ_ETH);
+    return size;
+}
+
+/*
+ * Deallocate the QEMU network interface.
+ */
+static void nic_cleanup(NetClientState *nc)
+{
+    eth_t *e = qemu_get_nic_opaque(nc);
+
+    //DPRINT("--- %s()\n", __func__);
+    e->eth_nic = 0;
+}
+
+/*
+ * Initialize Ethernet device.
+ */
+void pic32_eth_init(pic32_t *s, NICInfo *nd)
+{
+    DPRINT("--- %s()\n", __func__);
+
+    /* Create Ethernet device. */
+    s->eth_dev = qdev_create(NULL, NAME_PIC32_ETH);
+    qdev_set_nic_properties(s->eth_dev, nd);
+    qdev_init_nofail(s->eth_dev);
+
+    /* Setup back pointer from Ethernet device to pic32 object. */
+    s->eth = OBJECT_CHECK(eth_t, s->eth_dev, NAME_PIC32_ETH);
+    s->eth->pic32 = s;
+}
+
+/*
+ * Initialize pic32-eth object.
+ */
+static int eth_object_init(SysBusDevice *sbd)
+{
+    /* Table of methods for QEMU network interface. */
+    static NetClientInfo nic_info = {
+        .type           = NET_CLIENT_OPTIONS_KIND_NIC,
+        .size           = sizeof(NICState),
+        .can_receive    = nic_can_receive,
+        .receive        = nic_receive,
+        .cleanup        = nic_cleanup,
+    };
+    DeviceState *dev = DEVICE(sbd);
+    eth_t *e = OBJECT_CHECK(eth_t, dev, NAME_PIC32_ETH);
+
+    //DPRINT("--- %s()\n", __func__);
+
+    /* Initialize MAC address. */
+    qemu_macaddr_default_if_unset(&e->eth_conf.macaddr);
+
+    /* Create a QEMU network interface. */
+    e->eth_nic = qemu_new_nic(&nic_info, &e->eth_conf,
+        object_get_typename(OBJECT(dev)), dev->id, e);
+
+    qemu_format_nic_info_str(qemu_get_queue(e->eth_nic),
+        e->eth_conf.macaddr.a);
+
+    return 0;
+}
+
+/*
+ * Reset pic32-eth object.
+ */
+static void eth_object_reset(DeviceState *dev)
+{
+    eth_t *e = OBJECT_CHECK(eth_t, dev, NAME_PIC32_ETH);
+
+    //DPRINT("--- %s()\n", __func__);
+    eth_reset(e);
+    phy_reset(e);
+}
+
+/*
+ * Descriptor of eth_t data structure.
+ */
+static const VMStateDescription vmstate_info = {
+    .name               = NAME_PIC32_ETH,
+    .version_id         = 0,
+    .minimum_version_id = 0,
+    .fields             = (VMStateField[]) {
+        VMSTATE_END_OF_LIST()
+    }
+};
+
+/*
+ * Build pic32-eth object.
+ */
+static void eth_object_constructor(ObjectClass *klass, void *data)
+{
+    static Property eth_properties[] = {
+        DEFINE_NIC_PROPERTIES(eth_t, eth_conf),
+        DEFINE_PROP_END_OF_LIST(),
+    };
+    DeviceClass *dc = DEVICE_CLASS(klass);
+    SysBusDeviceClass *k = SYS_BUS_DEVICE_CLASS(klass);
+
+    k->init = eth_object_init;
+    set_bit(DEVICE_CATEGORY_NETWORK, dc->categories);
+    dc->desc = "PIC32 Ethernet device";
+    dc->reset = eth_object_reset;
+    dc->vmsd = &vmstate_info;
+    dc->props = eth_properties;
+}
+
+/*
+ * Instantiate pic32-eth class.
+ */
+static void eth_register_types(void)
+{
+    static const TypeInfo eth_class_info = {
+        .name          = NAME_PIC32_ETH,
+        .parent        = TYPE_SYS_BUS_DEVICE,
+        .instance_size = sizeof(eth_t),
+        .class_init    = eth_object_constructor,
+    };
+
+    type_register_static(&eth_class_info);
+}
+
+type_init(eth_register_types)
diff --git a/hw/mips/pic32_gpio.c b/hw/mips/pic32_gpio.c
new file mode 100644
index 0000000..d39299b
--- /dev/null
+++ b/hw/mips/pic32_gpio.c
@@ -0,0 +1,39 @@
+/*
+ * GPIO ports.
+ *
+ * Copyright (C) 2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/hw.h"
+#include "pic32_peripherals.h"
+
+#include "pic32mz.h"
+
+void pic32_gpio_write(pic32_t *s, int gpio_port, unsigned lat_value)
+{
+    /* Control SD card 0 */
+    if (gpio_port == s->sdcard[0].gpio_port && s->sdcard[0].gpio_cs) {
+        pic32_sdcard_select(s, 0, ! (lat_value & s->sdcard[0].gpio_cs));
+    }
+    /* Control SD card 1 */
+    if (gpio_port == s->sdcard[1].gpio_port && s->sdcard[0].gpio_cs) {
+        pic32_sdcard_select(s, 1, ! (lat_value & s->sdcard[1].gpio_cs));
+    }
+}
diff --git a/hw/mips/pic32_load_hex.c b/hw/mips/pic32_load_hex.c
new file mode 100644
index 0000000..a85f5da
--- /dev/null
+++ b/hw/mips/pic32_load_hex.c
@@ -0,0 +1,230 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <ctype.h>
+
+#include "pic32_peripherals.h"
+
+/* Macros for converting between hex and binary. */
+#define NIBBLE(x)       (isdigit(x) ? (x)-'0' : tolower(x)+10-'a')
+#define HEX(buffer)     ((NIBBLE((buffer)[0])<<4) + NIBBLE((buffer)[1]))
+
+static unsigned virt_to_phys(unsigned address)
+{
+    if (address >= 0xa0000000 && address <= 0xbfffffff)
+        return address - 0xa0000000;
+    if (address >= 0x80000000 && address <= 0x9fffffff)
+        return address - 0x80000000;
+    return address;
+}
+
+/*
+ * Read the S record file.
+ */
+static int load_srec(const char *filename,
+    void (*store_byte)(unsigned address, unsigned char byte))
+{
+    FILE *fd;
+    unsigned char buf [256];
+    unsigned char *data;
+    unsigned address;
+    int bytes, output_len;
+
+    fd = fopen(filename, "r");
+    if (! fd) {
+        perror(filename);
+        exit(1);
+    }
+    output_len = 0;
+    while (fgets((char*) buf, sizeof(buf), fd)) {
+        if (buf[0] == '\n')
+            continue;
+        if (buf[0] != 'S') {
+            if (output_len == 0)
+                break;
+            printf("%s: bad file format\n", filename);
+            exit(1);
+        }
+
+        /* Starting an S-record.  */
+        if (! isxdigit(buf[2]) || ! isxdigit(buf[3])) {
+            printf("%s: bad record: %s\n", filename, buf);
+            exit(1);
+        }
+        bytes = HEX(buf + 2);
+
+        /* Ignore the checksum byte.  */
+        --bytes;
+
+        address = 0;
+        data = buf + 4;
+        switch (buf[1]) {
+        case '7':
+            address = HEX(data);
+            data += 2;
+            --bytes;
+            /* Fall through.  */
+        case '8':
+            address = (address << 8) | HEX(data);
+            data += 2;
+            --bytes;
+            /* Fall through.  */
+        case '9':
+            address = (address << 8) | HEX(data);
+            data += 2;
+            address = (address << 8) | HEX(data);
+            data += 2;
+            bytes -= 2;
+            if (bytes == 0) {
+                //printf("%s: start address = %08x\n", filename, address);
+                //TODO: set start address
+            }
+            goto done;
+
+        case '3':
+            address = HEX(data);
+            data += 2;
+            --bytes;
+            /* Fall through.  */
+        case '2':
+            address = (address << 8) | HEX(data);
+            data += 2;
+            --bytes;
+            /* Fall through.  */
+        case '1':
+            address = (address << 8) | HEX(data);
+            data += 2;
+            address = (address << 8) | HEX(data);
+            data += 2;
+            bytes -= 2;
+
+            address = virt_to_phys(address);
+            output_len += bytes;
+            while (bytes-- > 0) {
+                store_byte(address++, HEX(data));
+                data += 2;
+            }
+            break;
+        }
+    }
+done:
+    fclose(fd);
+    return output_len;
+}
+
+/*
+ * Read HEX file.
+ */
+static int load_hex(const char *filename,
+    void (*store_byte)(unsigned address, unsigned char byte))
+{
+    FILE *fd;
+    unsigned char buf [256], data[16], record_type, sum;
+    unsigned address, high;
+    int bytes, output_len, i;
+
+    fd = fopen(filename, "r");
+    if (! fd) {
+        perror(filename);
+        exit(1);
+    }
+    output_len = 0;
+    high = 0;
+    while (fgets((char*) buf, sizeof(buf), fd)) {
+        if (buf[0] == '\n')
+            continue;
+        if (buf[0] != ':') {
+            if (output_len == 0)
+                break;
+            printf("%s: bad HEX file format\n", filename);
+            exit(1);
+        }
+        if (! isxdigit(buf[1]) || ! isxdigit(buf[2]) ||
+            ! isxdigit(buf[3]) || ! isxdigit(buf[4]) ||
+            ! isxdigit(buf[5]) || ! isxdigit(buf[6]) ||
+            ! isxdigit(buf[7]) || ! isxdigit(buf[8])) {
+            printf("%s: bad record: %s\n", filename, buf);
+            exit(1);
+        }
+        record_type = HEX(buf+7);
+        if (record_type == 1) {
+            /* End of file. */
+            break;
+        }
+        bytes = HEX(buf+1);
+        if (strlen((char*) buf) < bytes * 2 + 11) {
+            printf("%s: too short hex line\n", filename);
+            exit(1);
+        }
+        address = high << 16 | HEX(buf+3) << 8 | HEX(buf+5);
+        if (address & 3) {
+            printf("%s: odd address\n", filename);
+            exit(1);
+        }
+
+        sum = 0;
+        for (i=0; i<bytes; ++i) {
+            data [i] = HEX(buf+9 + i + i);
+            sum += data [i];
+        }
+        sum += record_type + bytes + (address & 0xff) + (address >> 8 & 0xff);
+        if (sum != (unsigned char) - HEX(buf+9 + bytes + bytes)) {
+            printf("%s: bad hex checksum\n", filename);
+            printf("Line %s", buf);
+            exit(1);
+        }
+
+        if (record_type == 5) {
+            /* Start address. */
+            if (bytes != 4) {
+                printf("%s: invalid length of hex start address
record: %d bytes\n",
+                    filename, bytes);
+                exit(1);
+            }
+            address = data[0] << 24 | data[1] << 16 | data[2] << 8 | data[3];
+            //printf("%s: start address = %08x\n", filename, address);
+            //TODO: set start address
+            continue;
+        }
+        if (record_type == 4) {
+            /* Extended address. */
+            if (bytes != 2) {
+                printf("%s: invalid length of hex linear address
record: %d bytes\n",
+                    filename, bytes);
+                exit(1);
+            }
+            high = data[0] << 8 | data[1];
+            continue;
+        }
+        if (record_type != 0) {
+            printf("%s: unknown hex record type: %d\n",
+                filename, record_type);
+            exit(1);
+        }
+
+        /* Data record found. */
+        address = virt_to_phys(address);
+        output_len += bytes;
+        for (i=0; i<bytes; i++) {
+            store_byte(address++, data [i]);
+        }
+    }
+    fclose(fd);
+    return output_len;
+}
+
+int pic32_load_hex_file(const char *filename,
+    void (*store_byte)(unsigned address, unsigned char byte))
+{
+    int memory_len = load_srec(filename, store_byte);
+    if (memory_len == 0) {
+        memory_len = load_hex(filename, store_byte);
+        if (memory_len == 0) {
+            return 0;
+        }
+    }
+    printf("Load file: '%s', %d bytes\n", filename, memory_len);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Load file: '%s', %d bytes\n",
filename, memory_len);
+    return 1;
+}
diff --git a/hw/mips/pic32_peripherals.h b/hw/mips/pic32_peripherals.h
new file mode 100644
index 0000000..4d95fd2
--- /dev/null
+++ b/hw/mips/pic32_peripherals.h
@@ -0,0 +1,176 @@
+/*
+ * Define memory map for PIC32 microcontroller.
+ *
+ * Copyright (C) 2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/sysbus.h"                  /* SysBusDevice */
+#include "net/net.h"
+
+#define IO_MEM_SIZE     (1024*1024)     /* 1 Mbyte */
+
+typedef struct _uart_t uart_t;
+typedef struct _spi_t spi_t;
+typedef struct _sdcard_t sdcard_t;
+typedef struct _pic32_t pic32_t;
+typedef struct _eth_t eth_t;
+
+/*
+ * UART private data.
+ */
+struct _uart_t {
+    pic32_t     *mcu;                   /* back pointer to pic32 object */
+    unsigned    irq;                    /* interrupt number */
+    int         oactive;                /* output active */
+    unsigned    sta;                    /* UxSTA address */
+    unsigned    mode;                   /* UxMODE address */
+    unsigned    rxbyte;                 /* received byte */
+    CharDriverState *chr;               /* pointer to serial_hds[i] */
+    QEMUTimer   *transmit_timer;        /* needed to delay TX interrupt */
+};
+
+/*
+ * SPI private data.
+ */
+struct _spi_t {
+    unsigned    buf[4];                 /* transmit and receive buffer */
+    unsigned    rfifo;                  /* read fifo counter */
+    unsigned    wfifo;                  /* write fifo counter */
+    unsigned    irq;                    /* interrupt numbers */
+    unsigned    con;                    /* SPIxCON address */
+    unsigned    stat;                   /* SPIxSTAT address */
+};
+
+/*
+ * SD card private data.
+ */
+struct _sdcard_t {
+    const char  *name;                  /* Device name */
+    unsigned    gpio_port;              /* GPIO port number of CS0 signal */
+    unsigned    gpio_cs;                /* GPIO pin mask of CS0 signal */
+    unsigned    kbytes;                 /* Disk size */
+    int         unit;                   /* Index (sd0 or sd1) */
+    int         fd;                     /* Image file */
+    int         select;                 /* Selected */
+    int         read_multiple;          /* Read-multiple mode */
+    unsigned    blen;                   /* Block length */
+    unsigned    wbecnt;                 /* Write block erase count */
+    unsigned    offset;                 /* Read/write offset */
+    unsigned    count;                  /* Byte count */
+    unsigned    limit;                  /* Reply length */
+    unsigned    char buf [1024 + 16];
+};
+
+/*
+ * PIC32 data structure.
+ */
+struct _pic32_t {
+    SysBusDevice parent_obj;
+    MIPSCPU     *cpu;                   /* back pointer to cpu object */
+    uint32_t    *iomem;                 /* backing storage for I/O area */
+
+    int         board_type;             /* board variant */
+    int         stop_on_reset;          /* halt simulation on soft reset */
+    unsigned    syskey_unlock;          /* syskey state */
+
+#define NUM_UART 6                      /* number of UART ports */
+    uart_t      uart [NUM_UART];        /* UART data */
+
+#define NUM_SPI 6                       /* max number of SPI ports */
+    spi_t       spi [NUM_SPI];          /* SPI data */
+
+    unsigned    sdcard_spi_port;        /* SPI port number of SD card */
+    sdcard_t    sdcard [2];             /* SD card data */
+
+    DeviceState *eth_dev;               /* Ethernet device */
+    eth_t       *eth;                   /* Ethernet driver data */
+
+    void (*irq_raise)(pic32_t *s, int irq); /* set interrupt request */
+    void (*irq_clear)(pic32_t *s, int irq); /* clear interrupt request */
+};
+
+/*
+ * GPIO routines.
+ */
+void pic32_gpio_write(pic32_t *s, int unit, unsigned val);
+
+/*
+ * UART routines.
+ */
+void pic32_uart_init(pic32_t *s, int unit, int irq, int sta, int mode);
+unsigned pic32_uart_get_char(pic32_t *s, int unit);
+void pic32_uart_put_char(pic32_t *s, int unit, unsigned char data);
+void pic32_uart_poll_status(pic32_t *s, int unit);
+void pic32_uart_update_mode(pic32_t *s, int unit);
+void pic32_uart_update_status(pic32_t *s, int unit);
+
+/*
+ * SPI routines.
+ */
+void pic32_spi_init(pic32_t *s, int unit, int irq, int con, int stat);
+void pic32_spi_control(pic32_t *s, int unit);
+unsigned pic32_spi_readbuf(pic32_t *s, int unit);
+void pic32_spi_writebuf(pic32_t *s, int unit, unsigned val);
+
+/*
+ * SD card routines.
+ */
+void pic32_sdcard_init(pic32_t *s, int unit, const char *name,
+    const char *filename, int cs_port, int cs_pin);
+void pic32_sdcard_reset(pic32_t *s);
+void pic32_sdcard_select(pic32_t *s, int unit, int on);
+unsigned pic32_sdcard_io(pic32_t *s, unsigned data);
+
+/*
+ * Ethernet routines.
+ */
+void pic32_eth_init(pic32_t *s, NICInfo *nd);
+void pic32_eth_control(pic32_t *s);
+void pic32_mii_command(pic32_t *s);
+void pic32_mii_write(pic32_t *s);
+
+/*
+ * Load a binary file in hex or srec format.
+ */
+int pic32_load_hex_file(const char *filename,
+    void (*store_byte)(unsigned address, unsigned char byte));
+
+/*
+ * Helper defines for i/o switch.
+ */
+#define VALUE(name)     s->iomem[(name & 0xfffff) >> 2]
+#define STORAGE(name)   case name: *namep = #name;
+#define READONLY(name)  case name: *namep = #name; goto readonly
+#define WRITEOP(name)   case name: *namep = #name; goto op_##name;\
+                        case name+4: *namep = #name"CLR"; goto op_##name;\
+                        case name+8: *namep = #name"SET"; goto op_##name;\
+                        case name+12: *namep = #name"INV"; op_##name: \
+                        VALUE(name) = write_op(VALUE(name), data, offset)
+#define WRITEOPX(name,label) \
+                        case name: *namep = #name; goto op_##label;\
+                        case name+4: *namep = #name"CLR"; goto op_##label;\
+                        case name+8: *namep = #name"SET"; goto op_##label;\
+                        case name+12: *namep = #name"INV"; goto op_##label
+#define WRITEOPR(name,romask) \
+                        case name: *namep = #name; goto op_##name;\
+                        case name+4: *namep = #name"CLR"; goto op_##name;\
+                        case name+8: *namep = #name"SET"; goto op_##name;\
+                        case name+12: *namep = #name"INV"; op_##name: \
+                        VALUE(name) = (VALUE(name) & (romask)) |
(write_op(VALUE(name), data, offset) & ~(romask))
diff --git a/hw/mips/pic32_sdcard.c b/hw/mips/pic32_sdcard.c
new file mode 100644
index 0000000..ea698da
--- /dev/null
+++ b/hw/mips/pic32_sdcard.c
@@ -0,0 +1,383 @@
+/*
+ * SD/MMC card emulation.
+ *
+ * Copyright (C) 2011-2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/hw.h"
+#include "pic32_peripherals.h"
+
+/*
+ * Definitions for MMC/SDC commands.
+ */
+#define CMD_GO_IDLE         (0x40+0)    /* CMD0 */
+#define CMD_SEND_OP_SDC     (0x40+41)   /* ACMD41 (SDC) */
+#define CMD_SET_BLEN        (0x40+16)
+#define CMD_SEND_IF_COND    (0x40+8)
+#define CMD_SEND_CSD        (0x40+9)
+#define CMD_STOP            (0x40+12)
+#define CMD_READ_SINGLE     (0x40+17)
+#define CMD_READ_MULTIPLE   (0x40+18)
+#define CMD_SET_WBECNT      (0x40+23)   /* ACMD23 */
+#define CMD_WRITE_SINGLE    (0x40+24)
+#define CMD_WRITE_MULTIPLE  (0x40+25)
+#define CMD_APP             (0x40+55)   /* CMD55 */
+
+#define DATA_START_BLOCK        0xFE    /* start data for single block */
+#define STOP_TRAN_TOKEN         0xFD    /* stop token for write multiple */
+#define WRITE_MULTIPLE_TOKEN    0xFC    /* start data for write multiple */
+
+/*
+ * TODO: add option to enable tracing.
+ */
+#define TRACE   0
+
+static void read_data(int fd, unsigned offset,
+    unsigned char *buf, unsigned blen)
+{
+    /* Fill uninitialized blocks by FF: simulate real flash media. */
+    memset(buf, 0xFF, blen);
+
+    if (pread(fd, buf, blen, offset) != blen) {
+        printf("sdcard: pread failed, offset %#x\n", offset);
+        return;
+    }
+#if 0
+    printf("(%#x)\n", offset);
+    int i, k;
+    for (i=0; i<blen; i+=32) {
+        for (k=0; k<32; k++) {
+            printf(" %02x", buf[i+k]);
+        }
+        printf("\n");
+    }
+#endif
+}
+
+static void write_data(int fd, unsigned offset,
+    unsigned char *buf, unsigned blen)
+{
+    if (pwrite(fd, buf, blen, offset) != blen) {
+        printf("sdcard: pwrite failed, offset %#x\n", offset);
+        return;
+    }
+}
+
+static void card_reset(sdcard_t *d)
+{
+    d->select = 0;
+    d->blen = 512;
+    d->count = 0;
+}
+
+/*
+ * Reset sdcard.
+ */
+void pic32_sdcard_reset(pic32_t *s)
+{
+    card_reset(&s->sdcard[0]);
+    card_reset(&s->sdcard[1]);
+}
+
+/*
+ * Initialize SD card.
+ */
+void pic32_sdcard_init(pic32_t *s, int unit, const char *name,
+    const char *filename, int cs_port, int cs_pin)
+{
+    sdcard_t *d = &s->sdcard[unit];
+    struct stat st;
+
+    memset(d, 0, sizeof(*d));
+    d->name = name;
+    if (! filename) {
+        /* No SD card installed. */
+        return;
+    }
+    d->gpio_port = cs_port;
+    d->gpio_cs = (cs_pin >= 0) ? (1 << cs_pin) : 0;
+
+    d->fd = open(filename, O_RDWR);
+    if (d->fd < 0) {
+        /* Fatal: no image available. */
+        perror(filename);
+        exit(1);
+    }
+    fstat(d->fd, &st);
+    d->kbytes = st.st_size / 1024;
+    printf("Card%u image '%s', %d kbytes\n", unit, filename, d->kbytes);
+    if (qemu_logfile)
+        fprintf(qemu_logfile, "Card%u image '%s', %d kbytes\n",
+            unit, filename, d->kbytes);
+}
+
+void pic32_sdcard_select(pic32_t *s, int unit, int on)
+{
+    sdcard_t *d = &s->sdcard[unit];
+
+    if (on) {
+        d->select = 1;
+        d->count = 0;
+    } else {
+        d->select = 0;
+    }
+}
+
+/*
+ * Data i/o: send byte to device.
+ * Return received byte.
+ */
+unsigned pic32_sdcard_io(pic32_t *s, unsigned data)
+{
+    sdcard_t *d = s->sdcard[0].select ? &s->sdcard[0] :
+                  s->sdcard[1].select ? &s->sdcard[1] : 0;
+    unsigned reply;
+
+    if (! d || ! d->fd) {
+        /* Unselected i/o. */
+        return 0xFF;
+    }
+    data = (unsigned char) data;
+    reply = 0xFF;
+    if (d->count == 0) {
+        d->buf[0] = data;
+        if (data != 0xFF)
+            d->count++;
+    } else {
+        switch (d->buf[0]) {
+        case CMD_GO_IDLE:               /* CMD0: reset */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7)
+                reply = 0x01;
+            break;
+        case CMD_APP:                   /* CMD55: application prefix */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                reply = 0;
+                d->count = 0;
+            }
+            break;
+        case CMD_SEND_OP_SDC:           /* ACMD41: initialization */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7)
+                reply = 0;
+            break;
+        case CMD_SET_BLEN:              /* Set block length */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                d->blen = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: set block
length %u bytes\n",
+                        d->unit, d->blen);
+                reply = (d->blen > 0 && d->blen <= 1024) ? 0 : 4;
+            }
+            break;
+        case CMD_SET_WBECNT:            /* Set write block erase count */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                d->wbecnt = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: set write
block erase count %u\n",
+                        d->unit, d->wbecnt);
+                reply = 0;
+                d->count = 0;
+            }
+            break;
+        case CMD_SEND_CSD:              /* Get card data */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                /* Send reply */
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: send media
size %u sectors\n",
+                        d->unit, d->kbytes * 2);
+                reply = 0;
+                d->limit = 16 + 3;
+                d->count = 1;
+                d->buf[0] = 0;
+                d->buf[1] = DATA_START_BLOCK;
+                d->buf[2+0] = 1 << 6;     /* SDC ver 2.00 */
+                d->buf[2+1] = 0;
+                d->buf[2+2] = 0;
+                d->buf[2+3] = 0;
+                d->buf[2+4] = 0;
+                d->buf[2+5] = 0;
+                d->buf[2+6] = 0;
+                d->buf[2+7] = 0;
+                d->buf[2+8] = (d->kbytes / 512 - 1) >> 8;
+                d->buf[2+9] = d->kbytes / 512 - 1;
+                d->buf[2+10] = 0;
+                d->buf[2+11] = 0;
+                d->buf[2+12] = 0;
+                d->buf[2+13] = 0;
+                d->buf[2+14] = 0;
+                d->buf[2+15] = 0;
+                d->buf[d->limit - 1] = 0xFF;
+                d->buf[d->limit] = 0xFF;
+            }
+            break;
+        case CMD_READ_SINGLE:           /* Read block */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                /* Send reply */
+                reply = 0;
+                d->offset = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: read
offset %#x, length %u bytes\n",
+                        d->unit, d->offset, d->blen);
+                d->limit = d->blen + 3;
+                d->count = 1;
+                d->buf[0] = 0;
+                d->buf[1] = DATA_START_BLOCK;
+                read_data(d->fd, d->offset, &d->buf[2], d->blen);
+                d->buf[d->limit - 1] = 0xFF;
+                d->buf[d->limit] = 0xFF;
+            }
+            break;
+        case CMD_READ_MULTIPLE:         /* Read multiple blocks */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                /* Send reply */
+                reply = 0;
+                d->read_multiple = 1;
+                d->offset = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: read
offset %#x, length %u bytes\n",
+                        d->unit, d->offset, d->blen);
+                d->limit = d->blen + 3;
+                d->count = 1;
+                d->buf[0] = 0;
+                d->buf[1] = DATA_START_BLOCK;
+                read_data(d->fd, d->offset, &d->buf[2], d->blen);
+                d->buf[d->limit - 1] = 0xFF;
+                d->buf[d->limit] = 0xFF;
+            }
+            break;
+        case CMD_WRITE_SINGLE:          /* Write block */
+            if (d->count >= sizeof(d->buf))
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                /* Accept command */
+                reply = 0;
+                d->offset = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: write offset %#x\n",
+                        d->unit, d->offset);
+            } else if (d->count == 7 + d->blen + 2 + 2) {
+                if (d->buf[7] == DATA_START_BLOCK) {
+                    /* Accept data */
+                    reply = 0x05;
+                    d->offset = d->buf[1] << 24 | d->buf[2] << 16 |
+                        d->buf[3] << 8 | d->buf[4];
+                    write_data(d->fd, d->offset, &d->buf[8], d->blen);
+                    if (TRACE)
+                        fprintf(qemu_logfile, "--- SD card %d: write
data, length %u bytes\n",
+                            d->unit, d->blen);
+                } else {
+                    /* Reject data */
+                    reply = 4;
+                    if (TRACE)
+                        fprintf(qemu_logfile, "--- SD card %d: reject
write data, tag=%02x\n",
+                            d->unit, d->buf[7]);
+                }
+            }
+            break;
+        case CMD_WRITE_MULTIPLE:        /* Write multiple blocks */
+            if (d->count >= 7)
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 7) {
+                /* Accept command */
+                reply = 0;
+                d->offset = d->buf[1] << 24 | d->buf[2] << 16 |
+                    d->buf[3] << 8 | d->buf[4];
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: write
multiple offset %#x\n",
+                        d->unit, d->offset);
+                d->count = 0;
+            }
+            break;
+        case WRITE_MULTIPLE_TOKEN:      /* Data for write-miltiple */
+            if (d->count >= sizeof(d->buf))
+                break;
+            d->buf [d->count++] = data;
+            if (d->count == 2 + d->blen + 2) {
+                /* Accept data */
+                reply = 0x05;
+                write_data(d->fd, d->offset, &d->buf[1], d->blen);
+                if (TRACE)
+                    fprintf(qemu_logfile, "--- SD card %d: write
sector %u, length %u bytes\n",
+                        d->unit, d->offset / 512, d->blen);
+                d->offset += 512;
+                d->count = 0;
+            }
+            break;
+        case CMD_STOP:                  /* Stop read-multiple sequence */
+            if (d->count > 1)
+                break;
+            d->read_multiple = 0;
+            reply = 0;
+            break;
+        case CMD_SEND_IF_COND:          /* Stop read-multiple sequence */
+            if (d->count > 1)
+                break;
+            d->read_multiple = 0;
+            reply = 4;                  /* Unknown command */
+            break;
+        case 0:                         /* Reply */
+            if (d->count <= d->limit) {
+                reply = d->buf [d->count++];
+                break;
+            }
+            if (d->read_multiple) {
+                /* Next read-multiple block. */
+                d->offset += d->blen;
+                d->count = 1;
+                read_data(d->fd, d->offset, &d->buf[2], d->blen);
+                reply = 0;
+            }
+            break;
+        default:                        /* Ignore */
+            break;
+        }
+    }
+    return reply;
+}
diff --git a/hw/mips/pic32_spi.c b/hw/mips/pic32_spi.c
new file mode 100644
index 0000000..985fd0c
--- /dev/null
+++ b/hw/mips/pic32_spi.c
@@ -0,0 +1,121 @@
+/*
+ * SPI ports.
+ *
+ * Copyright (C) 2014-2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/hw.h"
+#include "pic32_peripherals.h"
+
+#include "pic32mz.h"
+
+#define SPI_IRQ_FAULT   0               // error irq offset
+#define SPI_IRQ_TX      1               // transmitter irq offset
+#define SPI_IRQ_RX      2               // receiver irq offset
+
+unsigned pic32_spi_readbuf(pic32_t *s, int unit)
+{
+    spi_t *p = &s->spi[unit];
+    unsigned result = p->buf[p->rfifo];
+
+    if (VALUE(p->con) & PIC32_SPICON_ENHBUF) {
+        p->rfifo++;
+        p->rfifo &= 3;
+    }
+    if (VALUE(p->stat) & PIC32_SPISTAT_SPIRBF) {
+        VALUE(p->stat) &= ~PIC32_SPISTAT_SPIRBF;
+        //s->irq_clear(s, p->irq + SPI_IRQ_RX);
+    }
+    return result;
+}
+
+void pic32_spi_writebuf(pic32_t *s, int unit, unsigned val)
+{
+    spi_t *p = &s->spi[unit];
+
+    /* Perform SD card i/o on configured SPI port. */
+    if (unit == s->sdcard_spi_port) {
+        unsigned result = 0;
+
+        if (VALUE(p->con) & PIC32_SPICON_MODE32) {
+            /* 32-bit data width */
+            result  = (unsigned char) pic32_sdcard_io(s, val >> 24) << 24;
+            result |= (unsigned char) pic32_sdcard_io(s, val >> 16) << 16;
+            result |= (unsigned char) pic32_sdcard_io(s, val >> 8) << 8;
+            result |= (unsigned char) pic32_sdcard_io(s, val);
+
+        } else if (VALUE(p->con) & PIC32_SPICON_MODE16) {
+            /* 16-bit data width */
+            result = (unsigned char) pic32_sdcard_io(s, val >> 8) << 8;
+            result |= (unsigned char) pic32_sdcard_io(s, val);
+
+        } else {
+            /* 8-bit data width */
+            result = (unsigned char) pic32_sdcard_io(s, val);
+        }
+        p->buf[p->wfifo] = result;
+    } else {
+        /* No device */
+        p->buf[p->wfifo] = ~0;
+    }
+    if (VALUE(p->stat) & PIC32_SPISTAT_SPIRBF) {
+        VALUE(p->stat) |= PIC32_SPISTAT_SPIROV;
+        //s->irq_raise(s, p->irq + SPI_IRQ_FAULT);
+    } else if (VALUE(p->con) & PIC32_SPICON_ENHBUF) {
+        p->wfifo++;
+        p->wfifo &= 3;
+        if (p->wfifo == p->rfifo) {
+            VALUE(p->stat) |= PIC32_SPISTAT_SPIRBF;
+            //s->irq_raise(s, p->irq + SPI_IRQ_RX);
+        }
+    } else {
+        VALUE(p->stat) |= PIC32_SPISTAT_SPIRBF;
+        //s->irq_raise(s, p->irq + SPI_IRQ_RX);
+    }
+}
+
+void pic32_spi_control(pic32_t *s, int unit)
+{
+    spi_t *p = &s->spi[unit];
+
+    if (! (VALUE(p->con) & PIC32_SPICON_ON)) {
+        s->irq_clear(s, p->irq + SPI_IRQ_FAULT);
+        s->irq_clear(s, p->irq + SPI_IRQ_RX);
+        s->irq_clear(s, p->irq + SPI_IRQ_TX);
+        VALUE(p->stat) = PIC32_SPISTAT_SPITBE;
+    } else if (! (VALUE(p->con) & PIC32_SPICON_ENHBUF)) {
+        p->rfifo = 0;
+        p->wfifo = 0;
+    }
+}
+
+/*
+ * Initialize the SPI data structure.
+ */
+void pic32_spi_init(pic32_t *s, int unit, int irq, int con, int stat)
+{
+    spi_t *p = &s->spi[unit];
+
+    p->irq = irq;
+    p->con = con;
+    p->stat = stat;
+    p->rfifo = 0;
+    p->wfifo = 0;
+}
diff --git a/hw/mips/pic32_uart.c b/hw/mips/pic32_uart.c
new file mode 100644
index 0000000..2b21f1b
--- /dev/null
+++ b/hw/mips/pic32_uart.c
@@ -0,0 +1,226 @@
+/*
+ * UART ports.
+ *
+ * Copyright (C) 2014-2015 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#include "hw/hw.h"
+#include "hw/char/serial.h"
+#include "sysemu/char.h"
+#include "pic32_peripherals.h"
+
+#include "pic32mz.h"
+
+#define UART_IRQ_ERR    0               // error irq offset
+#define UART_IRQ_RX     1               // receiver irq offset
+#define UART_IRQ_TX     2               // transmitter irq offset
+
+/*
+ * Read of UxRXREG register.
+ */
+unsigned pic32_uart_get_char(pic32_t *s, int unit)
+{
+    uart_t *u = &s->uart[unit];
+    unsigned value;
+
+    /* Read a byte from input queue. */
+    value = u->rxbyte;
+    VALUE(u->sta) &= ~PIC32_USTA_URXDA;
+
+    s->irq_clear(s, u->irq + UART_IRQ_RX);
+    return value;
+}
+
+/*
+ * Write to UxTXREG register.
+ */
+void pic32_uart_put_char(pic32_t *s, int unit, unsigned char byte)
+{
+    uart_t *u = &s->uart[unit];
+
+    if (! u->chr) {
+        printf("--- %s(unit = %u) serial port not configured\n",
+            __func__, unit);
+        return;
+    }
+
+    /* Send the byte. */
+    if (qemu_chr_fe_write(u->chr, &byte, 1) != 1) {
+        //TODO: suspend simulation until serial port ready
+        printf("--- %s(unit = %u) failed\n", __func__, unit);
+        return;
+    }
+
+    if ((VALUE(u->mode) & PIC32_UMODE_ON) &&
+        (VALUE(u->sta) & PIC32_USTA_UTXEN))
+    {
+        VALUE(u->sta) |= PIC32_USTA_UTXBF;
+        VALUE(u->sta) &= ~PIC32_USTA_TRMT;
+
+        /* Generate TX interrupt with some delay. */
+        timer_mod(u->transmit_timer, qemu_clock_get_ns(QEMU_CLOCK_VIRTUAL) +
+            get_ticks_per_sec() / 5000);
+        u->oactive = 1;
+    }
+}
+
+/*
+ * Called before reading a value of UxBRG, UxMODE or UxSTA registers.
+ */
+void pic32_uart_poll_status(pic32_t *s, int unit)
+{
+    uart_t *u = &s->uart[unit];
+
+    // Keep receiver idle, transmit shift register always empty
+    VALUE(u->sta) |= PIC32_USTA_RIDLE;
+
+    //printf("<%x>", VALUE(u->sta)); fflush(stdout);
+}
+
+/*
+ * Write to UxMODE register.
+ */
+void pic32_uart_update_mode(pic32_t *s, int unit)
+{
+    uart_t *u = &s->uart[unit];
+
+    if (! (VALUE(u->mode) & PIC32_UMODE_ON)) {
+        s->irq_clear(s, u->irq + UART_IRQ_RX);
+        s->irq_clear(s, u->irq + UART_IRQ_TX);
+        VALUE(u->sta) &= ~(PIC32_USTA_URXDA | PIC32_USTA_FERR |
+                           PIC32_USTA_PERR | PIC32_USTA_UTXBF);
+        VALUE(u->sta) |= PIC32_USTA_RIDLE | PIC32_USTA_TRMT;
+    }
+}
+
+/*
+ * Write to UxSTA register.
+ */
+void pic32_uart_update_status(pic32_t *s, int unit)
+{
+    uart_t *u = &s->uart[unit];
+
+    if (! (VALUE(u->sta) & PIC32_USTA_URXEN)) {
+        s->irq_clear(s, u->irq + UART_IRQ_RX);
+        VALUE(u->sta) &= ~(PIC32_USTA_URXDA | PIC32_USTA_FERR |
+                           PIC32_USTA_PERR);
+    }
+    if (! (VALUE(u->sta) & PIC32_USTA_UTXEN)) {
+        s->irq_clear(s, u->irq + UART_IRQ_TX);
+        VALUE(u->sta) &= ~PIC32_USTA_UTXBF;
+        VALUE(u->sta) |= PIC32_USTA_TRMT;
+    }
+}
+
+/*
+ * Return a number of free bytes in the receive FIFO.
+ */
+static int uart_can_receive(void *opaque)
+{
+    uart_t *u = opaque;
+    pic32_t *s = u->mcu;        /* used in VALUE() */
+
+//printf("--- %s(%p) called\n", __func__, u);
+
+    if (! (VALUE(u->mode) & PIC32_UMODE_ON) ||
+        ! (VALUE(u->sta) & PIC32_USTA_URXEN)) {
+        /* UART disabled. */
+        return 0;
+    }
+
+    if (VALUE(u->sta) & PIC32_USTA_URXDA) {
+        /* Receive buffer full. */
+        return 0;
+    }
+    return 1;
+}
+
+/*
+ * Process the received data.
+ */
+static void uart_receive(void *opaque, const uint8_t *buf, int size)
+{
+    uart_t *u = opaque;
+    pic32_t *s = u->mcu;        /* used in VALUE() */
+
+//printf("--- %s(%p) called\n", __func__, u);
+    if (! (VALUE(u->mode) & PIC32_UMODE_ON) ||
+        ! (VALUE(u->sta) & PIC32_USTA_URXEN)) {
+        /* UART disabled. */
+        return;
+    }
+
+    if (VALUE(u->sta) & PIC32_USTA_URXDA) {
+        /* Receive buffer full. */
+        return;
+    }
+
+    u->rxbyte = buf[0];
+    VALUE(u->sta) |= PIC32_USTA_URXDA;
+
+    /* Activate receive interrupt. */
+    s->irq_raise(s, u->irq + UART_IRQ_RX);
+}
+
+/*
+ * Activate the transmit interrupt.
+ */
+static void uart_timeout(void *opaque)
+{
+    uart_t *u = opaque;
+    pic32_t *s = u->mcu;        /* used in VALUE() */
+
+//printf("--- %s() called\n", __func__);
+    if (u->oactive) {
+        /* Activate transmit interrupt. */
+//printf("uart%u: raise tx irq %u\n", unit, u->irq + UART_IRQ_TX);
+        if ((VALUE(u->mode) & PIC32_UMODE_ON) &&
+            (VALUE(u->sta) & PIC32_USTA_UTXEN))
+            s->irq_raise(s, u->irq + UART_IRQ_TX);
+        VALUE(u->sta) &= ~PIC32_USTA_UTXBF;
+        VALUE(u->sta) |= PIC32_USTA_TRMT;
+        u->oactive = 0;
+    }
+}
+
+/*
+ * Initialize the UART data structure.
+ */
+void pic32_uart_init(pic32_t *s, int unit, int irq, int sta, int mode)
+{
+    uart_t *u = &s->uart[unit];
+
+    u->mcu = s;
+    u->irq = irq;
+    u->sta = sta;
+    u->mode = mode;
+    u->transmit_timer = timer_new_ns(QEMU_CLOCK_VIRTUAL, uart_timeout, u);
+
+    if (unit >= MAX_SERIAL_PORTS) {
+        /* Cannot instantiate so many serial ports. */
+        u->chr = 0;
+        return;
+    }
+    u->chr = serial_hds[unit];
+
+    /* Setup callback functions. */
+    if (u->chr)
+        qemu_chr_add_handlers(u->chr, uart_can_receive, uart_receive, NULL, u);
+}
diff --git a/hw/mips/pic32mx.h b/hw/mips/pic32mx.h
new file mode 100644
index 0000000..e5d14b1
--- /dev/null
+++ b/hw/mips/pic32mx.h
@@ -0,0 +1,1288 @@
+/*
+ * Hardware register defines for Microchip PIC32MX microcontrollers.
+ *
+ * Copyright (C) 2010 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#ifndef _IO_PIC32MX_H
+#define _IO_PIC32MX_H
+
+/*--------------------------------------
+ * Peripheral registers.
+ */
+#define PIC32_R(a)              (a)
+
+/*--------------------------------------
+ * UART registers.
+ */
+#define U1MODE          PIC32_R (0x6000) /* Mode */
+#define U1MODECLR       PIC32_R (0x6004)
+#define U1MODESET       PIC32_R (0x6008)
+#define U1MODEINV       PIC32_R (0x600C)
+#define U1STA           PIC32_R (0x6010) /* Status and control */
+#define U1STACLR        PIC32_R (0x6014)
+#define U1STASET        PIC32_R (0x6018)
+#define U1STAINV        PIC32_R (0x601C)
+#define U1TXREG         PIC32_R (0x6020) /* Transmit */
+#define U1RXREG         PIC32_R (0x6030) /* Receive */
+#define U1BRG           PIC32_R (0x6040) /* Baud rate */
+#define U1BRGCLR        PIC32_R (0x6044)
+#define U1BRGSET        PIC32_R (0x6048)
+#define U1BRGINV        PIC32_R (0x604C)
+
+#ifdef PIC32MX4
+#define U2MODE          PIC32_R (0x6200) /* Mode */
+#define U2MODECLR       PIC32_R (0x6204)
+#define U2MODESET       PIC32_R (0x6208)
+#define U2MODEINV       PIC32_R (0x620C)
+#define U2STA           PIC32_R (0x6210) /* Status and control */
+#define U2STACLR        PIC32_R (0x6214)
+#define U2STASET        PIC32_R (0x6218)
+#define U2STAINV        PIC32_R (0x621C)
+#define U2TXREG         PIC32_R (0x6220) /* Transmit */
+#define U2RXREG         PIC32_R (0x6230) /* Receive */
+#define U2BRG           PIC32_R (0x6240) /* Baud rate */
+#define U2BRGCLR        PIC32_R (0x6244)
+#define U2BRGSET        PIC32_R (0x6248)
+#define U2BRGINV        PIC32_R (0x624C)
+#endif
+#ifdef PIC32MX7
+#define U4MODE          PIC32_R (0x6200) /* Mode */
+#define U4MODECLR       PIC32_R (0x6204)
+#define U4MODESET       PIC32_R (0x6208)
+#define U4MODEINV       PIC32_R (0x620C)
+#define U4STA           PIC32_R (0x6210) /* Status and control */
+#define U4STACLR        PIC32_R (0x6214)
+#define U4STASET        PIC32_R (0x6218)
+#define U4STAINV        PIC32_R (0x621C)
+#define U4TXREG         PIC32_R (0x6220) /* Transmit */
+#define U4RXREG         PIC32_R (0x6230) /* Receive */
+#define U4BRG           PIC32_R (0x6240) /* Baud rate */
+#define U4BRGCLR        PIC32_R (0x6244)
+#define U4BRGSET        PIC32_R (0x6248)
+#define U4BRGINV        PIC32_R (0x624C)
+
+#define U3MODE          PIC32_R (0x6400) /* Mode */
+#define U3MODECLR       PIC32_R (0x6404)
+#define U3MODESET       PIC32_R (0x6408)
+#define U3MODEINV       PIC32_R (0x640C)
+#define U3STA           PIC32_R (0x6410) /* Status and control */
+#define U3STACLR        PIC32_R (0x6414)
+#define U3STASET        PIC32_R (0x6418)
+#define U3STAINV        PIC32_R (0x641C)
+#define U3TXREG         PIC32_R (0x6420) /* Transmit */
+#define U3RXREG         PIC32_R (0x6430) /* Receive */
+#define U3BRG           PIC32_R (0x6440) /* Baud rate */
+#define U3BRGCLR        PIC32_R (0x6444)
+#define U3BRGSET        PIC32_R (0x6448)
+#define U3BRGINV        PIC32_R (0x644C)
+
+#define U6MODE          PIC32_R (0x6600) /* Mode */
+#define U6MODECLR       PIC32_R (0x6604)
+#define U6MODESET       PIC32_R (0x6608)
+#define U6MODEINV       PIC32_R (0x660C)
+#define U6STA           PIC32_R (0x6610) /* Status and control */
+#define U6STACLR        PIC32_R (0x6614)
+#define U6STASET        PIC32_R (0x6618)
+#define U6STAINV        PIC32_R (0x661C)
+#define U6TXREG         PIC32_R (0x6620) /* Transmit */
+#define U6RXREG         PIC32_R (0x6630) /* Receive */
+#define U6BRG           PIC32_R (0x6640) /* Baud rate */
+#define U6BRGCLR        PIC32_R (0x6644)
+#define U6BRGSET        PIC32_R (0x6648)
+#define U6BRGINV        PIC32_R (0x664C)
+
+#define U2MODE          PIC32_R (0x6800) /* Mode */
+#define U2MODECLR       PIC32_R (0x6804)
+#define U2MODESET       PIC32_R (0x6808)
+#define U2MODEINV       PIC32_R (0x680C)
+#define U2STA           PIC32_R (0x6810) /* Status and control */
+#define U2STACLR        PIC32_R (0x6814)
+#define U2STASET        PIC32_R (0x6818)
+#define U2STAINV        PIC32_R (0x681C)
+#define U2TXREG         PIC32_R (0x6820) /* Transmit */
+#define U2RXREG         PIC32_R (0x6830) /* Receive */
+#define U2BRG           PIC32_R (0x6840) /* Baud rate */
+#define U2BRGCLR        PIC32_R (0x6844)
+#define U2BRGSET        PIC32_R (0x6848)
+#define U2BRGINV        PIC32_R (0x684C)
+
+#define U5MODE          PIC32_R (0x6A00) /* Mode */
+#define U5MODECLR       PIC32_R (0x6A04)
+#define U5MODESET       PIC32_R (0x6A08)
+#define U5MODEINV       PIC32_R (0x6A0C)
+#define U5STA           PIC32_R (0x6A10) /* Status and control */
+#define U5STACLR        PIC32_R (0x6A14)
+#define U5STASET        PIC32_R (0x6A18)
+#define U5STAINV        PIC32_R (0x6A1C)
+#define U5TXREG         PIC32_R (0x6A20) /* Transmit */
+#define U5RXREG         PIC32_R (0x6A30) /* Receive */
+#define U5BRG           PIC32_R (0x6A40) /* Baud rate */
+#define U5BRGCLR        PIC32_R (0x6A44)
+#define U5BRGSET        PIC32_R (0x6A48)
+#define U5BRGINV        PIC32_R (0x6A4C)
+#endif
+
+/*
+ * UART Mode register.
+ */
+#define PIC32_UMODE_STSEL       0x0001  /* 2 Stop bits */
+#define PIC32_UMODE_PDSEL       0x0006  /* Bitmask: */
+#define PIC32_UMODE_PDSEL_8NPAR 0x0000  /* 8-bit data, no parity */
+#define PIC32_UMODE_PDSEL_8EVEN 0x0002  /* 8-bit data, even parity */
+#define PIC32_UMODE_PDSEL_8ODD  0x0004  /* 8-bit data, odd parity */
+#define PIC32_UMODE_PDSEL_9NPAR 0x0006  /* 9-bit data, no parity */
+#define PIC32_UMODE_BRGH        0x0008  /* High Baud Rate Enable */
+#define PIC32_UMODE_RXINV       0x0010  /* Receive Polarity Inversion */
+#define PIC32_UMODE_ABAUD       0x0020  /* Auto-Baud Enable */
+#define PIC32_UMODE_LPBACK      0x0040  /* UARTx Loopback Mode */
+#define PIC32_UMODE_WAKE        0x0080  /* Wake-up on start bit
during Sleep Mode */
+#define PIC32_UMODE_UEN         0x0300  /* Bitmask: */
+#define PIC32_UMODE_UEN_RTS     0x0100  /* Using UxRTS pin */
+#define PIC32_UMODE_UEN_RTSCTS  0x0200  /* Using UxCTS and UxRTS pins */
+#define PIC32_UMODE_UEN_BCLK    0x0300  /* Using UxBCLK pin */
+#define PIC32_UMODE_RTSMD       0x0800  /* UxRTS Pin Simplex mode */
+#define PIC32_UMODE_IREN        0x1000  /* IrDA Encoder and Decoder
Enable bit */
+#define PIC32_UMODE_SIDL        0x2000  /* Stop in Idle Mode */
+#define PIC32_UMODE_FRZ         0x4000  /* Freeze in Debug Exception Mode */
+#define PIC32_UMODE_ON          0x8000  /* UART Enable */
+
+/*
+ * UART Control and status register.
+ */
+#define PIC32_USTA_URXDA        0x00000001 /* Receive Data Available
(read-only) */
+#define PIC32_USTA_OERR         0x00000002 /* Receive Buffer Overrun */
+#define PIC32_USTA_FERR         0x00000004 /* Framing error detected
(read-only) */
+#define PIC32_USTA_PERR         0x00000008 /* Parity error detected
(read-only) */
+#define PIC32_USTA_RIDLE        0x00000010 /* Receiver is idle (read-only) */
+#define PIC32_USTA_ADDEN        0x00000020 /* Address Detect mode */
+#define PIC32_USTA_URXISEL      0x000000C0 /* Bitmask: receive
interrupt is set when... */
+#define PIC32_USTA_URXISEL_NEMP 0x00000000 /* ...receive buffer is not empty */
+#define PIC32_USTA_URXISEL_HALF 0x00000040 /* ...receive buffer
becomes 1/2 full */
+#define PIC32_USTA_URXISEL_3_4  0x00000080 /* ...receive buffer
becomes 3/4 full */
+#define PIC32_USTA_TRMT         0x00000100 /* Transmit shift register
is empty (read-only) */
+#define PIC32_USTA_UTXBF        0x00000200 /* Transmit buffer is full
(read-only) */
+#define PIC32_USTA_UTXEN        0x00000400 /* Transmit Enable */
+#define PIC32_USTA_UTXBRK       0x00000800 /* Transmit Break */
+#define PIC32_USTA_URXEN        0x00001000 /* Receiver Enable */
+#define PIC32_USTA_UTXINV       0x00002000 /* Transmit Polarity Inversion */
+#define PIC32_USTA_UTXISEL      0x0000C000 /* Bitmask: TX interrupt
is generated when... */
+#define PIC32_USTA_UTXISEL_1    0x00000000 /* ...the transmit buffer
contains at least one empty space */
+#define PIC32_USTA_UTXISEL_ALL  0x00004000 /* ...all characters have
been transmitted */
+#define PIC32_USTA_UTXISEL_EMP  0x00008000 /* ...the transmit buffer
becomes empty */
+#define PIC32_USTA_ADDR         0x00FF0000 /* Automatic Address Mask */
+#define PIC32_USTA_ADM_EN       0x01000000 /* Automatic Address Detect */
+
+/*
+ * Compute the 16-bit baud rate divisor, given
+ * the bus frequency and baud rate.
+ * Round to the nearest integer.
+ */
+#define PIC32_BRG_BAUD(fr,bd)   ((((fr)/8 + (bd)) / (bd) / 2) - 1)
+
+/*--------------------------------------
+ * Port A-G registers.
+ */
+#define TRISA           PIC32_R (0x86000) /* Port A: mask of inputs */
+#define TRISACLR        PIC32_R (0x86004)
+#define TRISASET        PIC32_R (0x86008)
+#define TRISAINV        PIC32_R (0x8600C)
+#define PORTA           PIC32_R (0x86010) /* Port A: read inputs,
write outputs */
+#define PORTACLR        PIC32_R (0x86014)
+#define PORTASET        PIC32_R (0x86018)
+#define PORTAINV        PIC32_R (0x8601C)
+#define LATA            PIC32_R (0x86020) /* Port A: read/write outputs */
+#define LATACLR         PIC32_R (0x86024)
+#define LATASET         PIC32_R (0x86028)
+#define LATAINV         PIC32_R (0x8602C)
+#define ODCA            PIC32_R (0x86030) /* Port A: open drain
configuration */
+#define ODCACLR         PIC32_R (0x86034)
+#define ODCASET         PIC32_R (0x86038)
+#define ODCAINV         PIC32_R (0x8603C)
+
+#define TRISB           PIC32_R (0x86040) /* Port B: mask of inputs */
+#define TRISBCLR        PIC32_R (0x86044)
+#define TRISBSET        PIC32_R (0x86048)
+#define TRISBINV        PIC32_R (0x8604C)
+#define PORTB           PIC32_R (0x86050) /* Port B: read inputs,
write outputs */
+#define PORTBCLR        PIC32_R (0x86054)
+#define PORTBSET        PIC32_R (0x86058)
+#define PORTBINV        PIC32_R (0x8605C)
+#define LATB            PIC32_R (0x86060) /* Port B: read/write outputs */
+#define LATBCLR         PIC32_R (0x86064)
+#define LATBSET         PIC32_R (0x86068)
+#define LATBINV         PIC32_R (0x8606C)
+#define ODCB            PIC32_R (0x86070) /* Port B: open drain
configuration */
+#define ODCBCLR         PIC32_R (0x86074)
+#define ODCBSET         PIC32_R (0x86078)
+#define ODCBINV         PIC32_R (0x8607C)
+
+#define TRISC           PIC32_R (0x86080) /* Port C: mask of inputs */
+#define TRISCCLR        PIC32_R (0x86084)
+#define TRISCSET        PIC32_R (0x86088)
+#define TRISCINV        PIC32_R (0x8608C)
+#define PORTC           PIC32_R (0x86090) /* Port C: read inputs,
write outputs */
+#define PORTCCLR        PIC32_R (0x86094)
+#define PORTCSET        PIC32_R (0x86098)
+#define PORTCINV        PIC32_R (0x8609C)
+#define LATC            PIC32_R (0x860A0) /* Port C: read/write outputs */
+#define LATCCLR         PIC32_R (0x860A4)
+#define LATCSET         PIC32_R (0x860A8)
+#define LATCINV         PIC32_R (0x860AC)
+#define ODCC            PIC32_R (0x860B0) /* Port C: open drain
configuration */
+#define ODCCCLR         PIC32_R (0x860B4)
+#define ODCCSET         PIC32_R (0x860B8)
+#define ODCCINV         PIC32_R (0x860BC)
+
+#define TRISD           PIC32_R (0x860C0) /* Port D: mask of inputs */
+#define TRISDCLR        PIC32_R (0x860C4)
+#define TRISDSET        PIC32_R (0x860C8)
+#define TRISDINV        PIC32_R (0x860CC)
+#define PORTD           PIC32_R (0x860D0) /* Port D: read inputs,
write outputs */
+#define PORTDCLR        PIC32_R (0x860D4)
+#define PORTDSET        PIC32_R (0x860D8)
+#define PORTDINV        PIC32_R (0x860DC)
+#define LATD            PIC32_R (0x860E0) /* Port D: read/write outputs */
+#define LATDCLR         PIC32_R (0x860E4)
+#define LATDSET         PIC32_R (0x860E8)
+#define LATDINV         PIC32_R (0x860EC)
+#define ODCD            PIC32_R (0x860F0) /* Port D: open drain
configuration */
+#define ODCDCLR         PIC32_R (0x860F4)
+#define ODCDSET         PIC32_R (0x860F8)
+#define ODCDINV         PIC32_R (0x860FC)
+
+#define TRISE           PIC32_R (0x86100) /* Port E: mask of inputs */
+#define TRISECLR        PIC32_R (0x86104)
+#define TRISESET        PIC32_R (0x86108)
+#define TRISEINV        PIC32_R (0x8610C)
+#define PORTE           PIC32_R (0x86110) /* Port E: read inputs,
write outputs */
+#define PORTECLR        PIC32_R (0x86114)
+#define PORTESET        PIC32_R (0x86118)
+#define PORTEINV        PIC32_R (0x8611C)
+#define LATE            PIC32_R (0x86120) /* Port E: read/write outputs */
+#define LATECLR         PIC32_R (0x86124)
+#define LATESET         PIC32_R (0x86128)
+#define LATEINV         PIC32_R (0x8612C)
+#define ODCE            PIC32_R (0x86130) /* Port E: open drain
configuration */
+#define ODCECLR         PIC32_R (0x86134)
+#define ODCESET         PIC32_R (0x86138)
+#define ODCEINV         PIC32_R (0x8613C)
+
+#define TRISF           PIC32_R (0x86140) /* Port F: mask of inputs */
+#define TRISFCLR        PIC32_R (0x86144)
+#define TRISFSET        PIC32_R (0x86148)
+#define TRISFINV        PIC32_R (0x8614C)
+#define PORTF           PIC32_R (0x86150) /* Port F: read inputs,
write outputs */
+#define PORTFCLR        PIC32_R (0x86154)
+#define PORTFSET        PIC32_R (0x86158)
+#define PORTFINV        PIC32_R (0x8615C)
+#define LATF            PIC32_R (0x86160) /* Port F: read/write outputs */
+#define LATFCLR         PIC32_R (0x86164)
+#define LATFSET         PIC32_R (0x86168)
+#define LATFINV         PIC32_R (0x8616C)
+#define ODCF            PIC32_R (0x86170) /* Port F: open drain
configuration */
+#define ODCFCLR         PIC32_R (0x86174)
+#define ODCFSET         PIC32_R (0x86178)
+#define ODCFINV         PIC32_R (0x8617C)
+
+#define TRISG           PIC32_R (0x86180) /* Port G: mask of inputs */
+#define TRISGCLR        PIC32_R (0x86184)
+#define TRISGSET        PIC32_R (0x86188)
+#define TRISGINV        PIC32_R (0x8618C)
+#define PORTG           PIC32_R (0x86190) /* Port G: read inputs,
write outputs */
+#define PORTGCLR        PIC32_R (0x86194)
+#define PORTGSET        PIC32_R (0x86198)
+#define PORTGINV        PIC32_R (0x8619C)
+#define LATG            PIC32_R (0x861A0) /* Port G: read/write outputs */
+#define LATGCLR         PIC32_R (0x861A4)
+#define LATGSET         PIC32_R (0x861A8)
+#define LATGINV         PIC32_R (0x861AC)
+#define ODCG            PIC32_R (0x861B0) /* Port G: open drain
configuration */
+#define ODCGCLR         PIC32_R (0x861B4)
+#define ODCGSET         PIC32_R (0x861B8)
+#define ODCGINV         PIC32_R (0x861BC)
+
+#define CNCON           PIC32_R (0x861C0) /* Interrupt-on-change control */
+#define CNCONCLR        PIC32_R (0x861C4)
+#define CNCONSET        PIC32_R (0x861C8)
+#define CNCONINV        PIC32_R (0x861CC)
+#define CNEN            PIC32_R (0x861D0) /* Input change interrupt enable */
+#define CNENCLR         PIC32_R (0x861D4)
+#define CNENSET         PIC32_R (0x861D8)
+#define CNENINV         PIC32_R (0x861DC)
+#define CNPUE           PIC32_R (0x861E0) /* Input pin pull-up enable */
+#define CNPUECLR        PIC32_R (0x861E4)
+#define CNPUESET        PIC32_R (0x861E8)
+#define CNPUEINV        PIC32_R (0x861EC)
+
+/*--------------------------------------
+ * A/D Converter registers.
+ */
+#define AD1CON1         PIC32_R (0x9000) /* Control register 1 */
+#define AD1CON1CLR      PIC32_R (0x9004)
+#define AD1CON1SET      PIC32_R (0x9008)
+#define AD1CON1INV      PIC32_R (0x900C)
+#define AD1CON2         PIC32_R (0x9010) /* Control register 2 */
+#define AD1CON2CLR      PIC32_R (0x9014)
+#define AD1CON2SET      PIC32_R (0x9018)
+#define AD1CON2INV      PIC32_R (0x901C)
+#define AD1CON3         PIC32_R (0x9020) /* Control register 3 */
+#define AD1CON3CLR      PIC32_R (0x9024)
+#define AD1CON3SET      PIC32_R (0x9028)
+#define AD1CON3INV      PIC32_R (0x902C)
+#define AD1CHS          PIC32_R (0x9040) /* Channel select */
+#define AD1CHSCLR       PIC32_R (0x9044)
+#define AD1CHSSET       PIC32_R (0x9048)
+#define AD1CHSINV       PIC32_R (0x904C)
+#define AD1CSSL         PIC32_R (0x9050) /* Input scan selection */
+#define AD1CSSLCLR      PIC32_R (0x9054)
+#define AD1CSSLSET      PIC32_R (0x9058)
+#define AD1CSSLINV      PIC32_R (0x905C)
+#define AD1PCFG         PIC32_R (0x9060) /* Port configuration */
+#define AD1PCFGCLR      PIC32_R (0x9064)
+#define AD1PCFGSET      PIC32_R (0x9068)
+#define AD1PCFGINV      PIC32_R (0x906C)
+#define ADC1BUF0        PIC32_R (0x9070) /* Result words */
+#define ADC1BUF1        PIC32_R (0x9080)
+#define ADC1BUF2        PIC32_R (0x9090)
+#define ADC1BUF3        PIC32_R (0x90A0)
+#define ADC1BUF4        PIC32_R (0x90B0)
+#define ADC1BUF5        PIC32_R (0x90C0)
+#define ADC1BUF6        PIC32_R (0x90D0)
+#define ADC1BUF7        PIC32_R (0x90E0)
+#define ADC1BUF8        PIC32_R (0x90F0)
+#define ADC1BUF9        PIC32_R (0x9100)
+#define ADC1BUFA        PIC32_R (0x9110)
+#define ADC1BUFB        PIC32_R (0x9120)
+#define ADC1BUFC        PIC32_R (0x9130)
+#define ADC1BUFD        PIC32_R (0x9140)
+#define ADC1BUFE        PIC32_R (0x9150)
+#define ADC1BUFF        PIC32_R (0x9160)
+
+/*--------------------------------------
+ * Parallel master port registers.
+ */
+#define PMCON           PIC32_R (0x7000) /* Control */
+#define PMCONCLR        PIC32_R (0x7004)
+#define PMCONSET        PIC32_R (0x7008)
+#define PMCONINV        PIC32_R (0x700C)
+#define PMMODE          PIC32_R (0x7010) /* Mode */
+#define PMMODECLR       PIC32_R (0x7014)
+#define PMMODESET       PIC32_R (0x7018)
+#define PMMODEINV       PIC32_R (0x701C)
+#define PMADDR          PIC32_R (0x7020) /* Address */
+#define PMADDRCLR       PIC32_R (0x7024)
+#define PMADDRSET       PIC32_R (0x7028)
+#define PMADDRINV       PIC32_R (0x702C)
+#define PMDOUT          PIC32_R (0x7030) /* Data output */
+#define PMDOUTCLR       PIC32_R (0x7034)
+#define PMDOUTSET       PIC32_R (0x7038)
+#define PMDOUTINV       PIC32_R (0x703C)
+#define PMDIN           PIC32_R (0x7040) /* Data input */
+#define PMDINCLR        PIC32_R (0x7044)
+#define PMDINSET        PIC32_R (0x7048)
+#define PMDININV        PIC32_R (0x704C)
+#define PMAEN           PIC32_R (0x7050) /* Pin enable */
+#define PMAENCLR        PIC32_R (0x7054)
+#define PMAENSET        PIC32_R (0x7058)
+#define PMAENINV        PIC32_R (0x705C)
+#define PMSTAT          PIC32_R (0x7060) /* Status (slave only) */
+#define PMSTATCLR       PIC32_R (0x7064)
+#define PMSTATSET       PIC32_R (0x7068)
+#define PMSTATINV       PIC32_R (0x706C)
+
+/*
+ * PMP Control register.
+ */
+#define PIC32_PMCON_RDSP        0x0001 /* Read strobe polarity active-high */
+#define PIC32_PMCON_WRSP        0x0002 /* Write strobe polarity active-high */
+#define PIC32_PMCON_CS1P        0x0008 /* Chip select 0 polarity active-high */
+#define PIC32_PMCON_CS2P        0x0010 /* Chip select 1 polarity active-high */
+#define PIC32_PMCON_ALP         0x0020 /* Address latch polarity active-high */
+#define PIC32_PMCON_CSF         0x00C0 /* Chip select function bitmask: */
+#define PIC32_PMCON_CSF_NONE    0x0000 /* PMCS2 and PMCS1 as A[15:14] */
+#define PIC32_PMCON_CSF_CS2     0x0040 /* PMCS2 as chip select */
+#define PIC32_PMCON_CSF_CS21    0x0080 /* PMCS2 and PMCS1 as chip select */
+#define PIC32_PMCON_PTRDEN      0x0100 /* Read/write strobe port enable */
+#define PIC32_PMCON_PTWREN      0x0200 /* Write enable strobe port enable */
+#define PIC32_PMCON_PMPTTL      0x0400 /* TTL input buffer select */
+#define PIC32_PMCON_ADRMUX      0x1800 /* Address/data mux selection
bitmask: */
+#define PIC32_PMCON_ADRMUX_NONE 0x0000 /* Address and data separate */
+#define PIC32_PMCON_ADRMUX_AD   0x0800 /* Lower address on PMD[7:0],
high on PMA[15:8] */
+#define PIC32_PMCON_ADRMUX_D8   0x1000 /* All address on PMD[7:0] */
+#define PIC32_PMCON_ADRMUX_D16  0x1800 /* All address on PMD[15:0] */
+#define PIC32_PMCON_SIDL        0x2000 /* Stop in idle */
+#define PIC32_PMCON_FRZ         0x4000 /* Freeze in debug exception */
+#define PIC32_PMCON_ON          0x8000 /* Parallel master port enable */
+
+/*
+ * PMP Mode register.
+ */
+#define PIC32_PMMODE_WAITE(x)   ((x)<<0) /* Wait states: data hold
after RW strobe */
+#define PIC32_PMMODE_WAITM(x)   ((x)<<2) /* Wait states: data RW strobe */
+#define PIC32_PMMODE_WAITB(x)   ((x)<<6) /* Wait states: data setup
to RW strobe */
+#define PIC32_PMMODE_MODE       0x0300  /* Mode select bitmask: */
+#define PIC32_PMMODE_MODE_SLAVE 0x0000  /* Legacy slave */
+#define PIC32_PMMODE_MODE_SLENH 0x0100  /* Enhanced slave */
+#define PIC32_PMMODE_MODE_MAST2 0x0200  /* Master mode 2 */
+#define PIC32_PMMODE_MODE_MAST1 0x0300  /* Master mode 1 */
+#define PIC32_PMMODE_MODE16     0x0400  /* 16-bit mode */
+#define PIC32_PMMODE_INCM       0x1800  /* Address increment mode bitmask: */
+#define PIC32_PMMODE_INCM_NONE  0x0000  /* No increment/decrement */
+#define PIC32_PMMODE_INCM_INC   0x0800  /* Increment address */
+#define PIC32_PMMODE_INCM_DEC   0x1000  /* Decrement address */
+#define PIC32_PMMODE_INCM_SLAVE 0x1800  /* Slave auto-increment */
+#define PIC32_PMMODE_IRQM       0x6000  /* Interrupt request bitmask: */
+#define PIC32_PMMODE_IRQM_DIS   0x0000  /* No interrupt generated */
+#define PIC32_PMMODE_IRQM_END   0x2000  /* Interrupt at end of
read/write cycle */
+#define PIC32_PMMODE_IRQM_A3    0x4000  /* Interrupt on address 3 */
+#define PIC32_PMMODE_BUSY       0x8000  /* Port is busy */
+
+/*
+ * PMP Address register.
+ */
+#define PIC32_PMADDR_PADDR      0x3FFF /* Destination address */
+#define PIC32_PMADDR_CS1        0x4000 /* Chip select 1 is active */
+#define PIC32_PMADDR_CS2        0x8000 /* Chip select 2 is active */
+
+/*
+ * PMP status register (slave only).
+ */
+#define PIC32_PMSTAT_OB0E       0x0001 /* Output buffer 0 empty */
+#define PIC32_PMSTAT_OB1E       0x0002 /* Output buffer 1 empty */
+#define PIC32_PMSTAT_OB2E       0x0004 /* Output buffer 2 empty */
+#define PIC32_PMSTAT_OB3E       0x0008 /* Output buffer 3 empty */
+#define PIC32_PMSTAT_OBUF       0x0040 /* Output buffer underflow */
+#define PIC32_PMSTAT_OBE        0x0080 /* Output buffer empty */
+#define PIC32_PMSTAT_IB0F       0x0100 /* Input buffer 0 full */
+#define PIC32_PMSTAT_IB1F       0x0200 /* Input buffer 1 full */
+#define PIC32_PMSTAT_IB2F       0x0400 /* Input buffer 2 full */
+#define PIC32_PMSTAT_IB3F       0x0800 /* Input buffer 3 full */
+#define PIC32_PMSTAT_IBOV       0x4000 /* Input buffer overflow */
+#define PIC32_PMSTAT_IBF        0x8000 /* Input buffer full */
+
+/*--------------------------------------
+ * USB registers.
+ */
+#define U1OTGIR         PIC32_R (0x85040) /* OTG interrupt flags */
+#define U1OTGIE         PIC32_R (0x85050) /* OTG interrupt enable */
+#define U1OTGSTAT       PIC32_R (0x85060) /* Comparator and pin status */
+#define U1OTGCON        PIC32_R (0x85070) /* Resistor and pin control */
+#define U1PWRC          PIC32_R (0x85080) /* Power control */
+#define U1IR            PIC32_R (0x85200) /* Pending interrupt */
+#define U1IE            PIC32_R (0x85210) /* Interrupt enable */
+#define U1EIR           PIC32_R (0x85220) /* Pending error interrupt */
+#define U1EIE           PIC32_R (0x85230) /* Error interrupt enable */
+#define U1STAT          PIC32_R (0x85240) /* Status FIFO */
+#define U1CON           PIC32_R (0x85250) /* Control */
+#define U1ADDR          PIC32_R (0x85260) /* Address */
+#define U1BDTP1         PIC32_R (0x85270) /* Buffer descriptor table
pointer 1 */
+#define U1FRML          PIC32_R (0x85280) /* Frame counter low */
+#define U1FRMH          PIC32_R (0x85290) /* Frame counter high */
+#define U1TOK           PIC32_R (0x852A0) /* Host control */
+#define U1SOF           PIC32_R (0x852B0) /* SOF counter */
+#define U1BDTP2         PIC32_R (0x852C0) /* Buffer descriptor table
pointer 2 */
+#define U1BDTP3         PIC32_R (0x852D0) /* Buffer descriptor table
pointer 3 */
+#define U1CNFG1         PIC32_R (0x852E0) /* Debug and idle */
+#define U1EP(n)         PIC32_R (0x85300 + (n << 4)) /* Endpoint control */
+
+/*
+ * USB Control register.
+ */
+#define PIC32_U1CON_USBEN       0x0001 /* USB module enable (device mode) */
+#define PIC32_U1CON_SOFEN       0x0001 /* SOF sent every 1 ms (host mode) */
+#define PIC32_U1CON_PPBRST      0x0002 /* Ping-pong buffers reset */
+#define PIC32_U1CON_RESUME      0x0004 /* Resume signaling enable */
+#define PIC32_U1CON_HOSTEN      0x0008 /* Host mode enable */
+#define PIC32_U1CON_USBRST      0x0010 /* USB reset */
+#define PIC32_U1CON_PKTDIS      0x0020 /* Packet transfer disable */
+#define PIC32_U1CON_TOKBUSY     0x0020 /* Token busy indicator */
+#define PIC32_U1CON_SE0         0x0040 /* Single ended zero detected */
+#define PIC32_U1CON_JSTATE      0x0080 /* Live differential receiver
JSTATE flag */
+
+/*
+ * USB Power control register.
+ */
+#define PIC32_U1PWRC_USBPWR     0x0001 /* USB operation enable */
+#define PIC32_U1PWRC_USUSPEND   0x0002 /* USB suspend mode */
+#define PIC32_U1PWRC_USLPGRD    0x0010 /* USB sleep entry guard */
+#define PIC32_U1PWRC_UACTPND    0x0080 /* UAB activity pending */
+
+/*
+ * USB Pending interrupt register.
+ * USB Interrupt enable register.
+ */
+#define PIC32_U1I_DETACH        0x0001 /* Detach (host mode) */
+#define PIC32_U1I_URST          0x0001 /* USB reset (device mode) */
+#define PIC32_U1I_UERR          0x0002 /* USB error condition */
+#define PIC32_U1I_SOF           0x0004 /* SOF token  */
+#define PIC32_U1I_TRN           0x0008 /* Token processing complete */
+#define PIC32_U1I_IDLE          0x0010 /* Idle detect */
+#define PIC32_U1I_RESUME        0x0020 /* Resume */
+#define PIC32_U1I_ATTACH        0x0040 /* Peripheral attach */
+#define PIC32_U1I_STALL         0x0080 /* STALL handshake */
+
+/*
+ * USB OTG interrupt flags register.
+ * USB OTG interrupt enable register.
+ */
+#define PIC32_U1OTGI_VBUSVD     0x0001 /* A-device Vbus change */
+#define PIC32_U1OTGI_SESEND     0x0004 /* B-device Vbus change */
+#define PIC32_U1OTGI_SESVD      0x0008 /* Session valid change */
+#define PIC32_U1OTGI_ACTV       0x0010 /* Bus activity indicator */
+#define PIC32_U1OTGI_LSTATE     0x0020 /* Line state stable */
+#define PIC32_U1OTGI_T1MSEC     0x0040 /* 1 millisecond timer expired */
+#define PIC32_U1OTGI_ID         0x0080 /* ID state change */
+
+#define PIC32_U1OTGSTAT_VBUSVD  0x0001 /*  */
+#define PIC32_U1OTGSTAT_SESEND  0x0004 /*  */
+#define PIC32_U1OTGSTAT_SESVD   0x0008 /*  */
+#define PIC32_U1OTGSTAT_LSTATE  0x0020 /*  */
+#define PIC32_U1OTGSTAT_ID      0x0080 /*  */
+
+#define PIC32_U1OTGCON_VBUSDIS  0x0001 /*  */
+#define PIC32_U1OTGCON_VBUSCHG  0x0002 /*  */
+#define PIC32_U1OTGCON_OTGEN    0x0004 /*  */
+#define PIC32_U1OTGCON_VBUSON   0x0008 /*  */
+#define PIC32_U1OTGCON_DMPULDWN 0x0010 /*  */
+#define PIC32_U1OTGCON_DPPULDWN 0x0020 /*  */
+#define PIC32_U1OTGCON_DMPULUP  0x0040 /*  */
+#define PIC32_U1OTGCON_DPPULUP  0x0080 /*  */
+
+#define PIC32_U1EI_PID          0x0001 /*  */
+#define PIC32_U1EI_CRC5         0x0002 /*  */
+#define PIC32_U1EI_EOF          0x0002 /*  */
+#define PIC32_U1EI_CRC16        0x0004 /*  */
+#define PIC32_U1EI_DFN8         0x0008 /*  */
+#define PIC32_U1EI_BTO          0x0010 /*  */
+#define PIC32_U1EI_DMA          0x0020 /*  */
+#define PIC32_U1EI_BMX          0x0040 /*  */
+#define PIC32_U1EI_BTS          0x0080 /*  */
+
+#define PIC32_U1STAT_PPBI       0x0004 /*  */
+#define PIC32_U1STAT_DIR        0x0008 /*  */
+#define PIC32_U1STAT_ENDPT(x)   (((x) >> 4) & 0xF) /*  */
+
+#define PIC32_U1ADDR_DEVADDR    0x007F /*  */
+#define PIC32_U1ADDR_USBADDR0   0x0001 /*  */
+#define PIC32_U1ADDR_DEVADDR1   0x0002 /*  */
+#define PIC32_U1ADDR_DEVADDR2   0x0004 /*  */
+#define PIC32_U1ADDR_DEVADDR3   0x0008 /*  */
+#define PIC32_U1ADDR_DEVADDR4   0x0010 /*  */
+#define PIC32_U1ADDR_DEVADDR5   0x0020 /*  */
+#define PIC32_U1ADDR_DEVADDR6   0x0040 /*  */
+#define PIC32_U1ADDR_LSPDEN     0x0080 /*  */
+
+#define PIC32_U1FRML_FRM0       0x0001 /*  */
+#define PIC32_U1FRML_FRM1       0x0002 /*  */
+#define PIC32_U1FRML_FRM2       0x0004 /*  */
+#define PIC32_U1FRML_FRM3       0x0008 /*  */
+#define PIC32_U1FRML_FRM4       0x0010 /*  */
+#define PIC32_U1FRML_FRM5       0x0020 /*  */
+#define PIC32_U1FRML_FRM6       0x0040 /*  */
+#define PIC32_U1FRML_FRM7       0x0080 /*  */
+
+#define PIC32_U1FRMH_FRM8       0x0001 /*  */
+#define PIC32_U1FRMH_FRM9       0x0002 /*  */
+#define PIC32_U1FRMH_FRM10      0x0004 /*  */
+
+#define PIC32_U1TOK_EP0         0x0001 /*  */
+#define PIC32_U1TOK_EP          0x000F /*  */
+#define PIC32_U1TOK_EP1         0x0002 /*  */
+#define PIC32_U1TOK_EP2         0x0004 /*  */
+#define PIC32_U1TOK_EP3         0x0008 /*  */
+#define PIC32_U1TOK_PID0        0x0010 /*  */
+#define PIC32_U1TOK_PID         0x00F0 /*  */
+#define PIC32_U1TOK_PID1        0x0020 /*  */
+#define PIC32_U1TOK_PID2        0x0040 /*  */
+#define PIC32_U1TOK_PID3        0x0080 /*  */
+
+#define PIC32_U1CNFG1_USBSIDL   0x0010 /*  */
+#define PIC32_U1CNFG1_USBFRZ    0x0020 /*  */
+#define PIC32_U1CNFG1_UOEMON    0x0040 /*  */
+#define PIC32_U1CNFG1_UTEYE     0x0080 /*  */
+
+#define PIC32_U1EP_EPHSHK       0x0001 /*  */
+#define PIC32_U1EP_EPSTALL      0x0002 /*  */
+#define PIC32_U1EP_EPTXEN       0x0004 /*  */
+#define PIC32_U1EP_EPRXEN       0x0008 /*  */
+#define PIC32_U1EP_EPCONDIS     0x0010 /*  */
+#define PIC32_U1EP_RETRYDIS     0x0040 /*  */
+#define PIC32_U1EP_LSPD         0x0080 /*  */
+
+/* DB status field values */
+#define PIC32_DB_BSTALL         (1 << 2)
+#define PIC32_DB_DTS            (1 << 3)
+#define PIC32_DB_NINC           (1 << 4)
+#define PIC32_DB_KEEP           (1 << 5)
+#define PIC32_DB_DATA1          (1 << 6)
+#define PIC32_DB_UOWN           (1 << 7)
+#define PIC32_DB_GET_PID(x)     (((x) >> 2) & 0xF)
+#define PIC32_DB_SET_PID(x)     (((x) & 0xF) << 2)
+#define PIC32_DB_GET_COUNT(x)   (((x) >> 16) & 0x3FF)
+#define PIC32_DB_SET_COUNT(x)   (((x) & 0x3FF) << 16)
+
+/*--------------------------------------
+ * SPI registers.
+ */
+#ifdef PIC32MX4
+#define SPI1CON         PIC32_R (0x5800) /* Control */
+#define SPI1CONCLR      PIC32_R (0x5804)
+#define SPI1CONSET      PIC32_R (0x5808)
+#define SPI1CONINV      PIC32_R (0x580C)
+#define SPI1STAT        PIC32_R (0x5810) /* Status */
+#define SPI1STATCLR     PIC32_R (0x5814)
+#define SPI1STATSET     PIC32_R (0x5818)
+#define SPI1STATINV     PIC32_R (0x581C)
+#define SPI1BUF         PIC32_R (0x5820) /* Transmit and receive buffer */
+#define SPI1BRG         PIC32_R (0x5830) /* Baud rate generator */
+#define SPI1BRGCLR      PIC32_R (0x5834)
+#define SPI1BRGSET      PIC32_R (0x5838)
+#define SPI1BRGINV      PIC32_R (0x583C)
+#endif
+#ifdef PIC32MX7
+#define SPI3CON         PIC32_R (0x5800) /* Control */
+#define SPI3CONCLR      PIC32_R (0x5804)
+#define SPI3CONSET      PIC32_R (0x5808)
+#define SPI3CONINV      PIC32_R (0x580C)
+#define SPI3STAT        PIC32_R (0x5810) /* Status */
+#define SPI3STATCLR     PIC32_R (0x5814)
+#define SPI3STATSET     PIC32_R (0x5818)
+#define SPI3STATINV     PIC32_R (0x581C)
+#define SPI3BUF         PIC32_R (0x5820) /* Transmit and receive buffer */
+#define SPI3BRG         PIC32_R (0x5830) /* Baud rate generator */
+#define SPI3BRGCLR      PIC32_R (0x5834)
+#define SPI3BRGSET      PIC32_R (0x5838)
+#define SPI3BRGINV      PIC32_R (0x583C)
+
+#define SPI4CON         PIC32_R (0x5C00) /* Control */
+#define SPI4CONCLR      PIC32_R (0x5C04)
+#define SPI4CONSET      PIC32_R (0x5C08)
+#define SPI4CONINV      PIC32_R (0x5C0C)
+#define SPI4STAT        PIC32_R (0x5C10) /* Status */
+#define SPI4STATCLR     PIC32_R (0x5C14)
+#define SPI4STATSET     PIC32_R (0x5C18)
+#define SPI4STATINV     PIC32_R (0x5C1C)
+#define SPI4BUF         PIC32_R (0x5C20) /* Transmit and receive buffer */
+#define SPI4BRG         PIC32_R (0x5C30) /* Baud rate generator */
+#define SPI4BRGCLR      PIC32_R (0x5C34)
+#define SPI4BRGSET      PIC32_R (0x5C38)
+#define SPI4BRGINV      PIC32_R (0x5C3C)
+
+#define SPI1CON         PIC32_R (0x5E00) /* Control */
+#define SPI1CONCLR      PIC32_R (0x5E04)
+#define SPI1CONSET      PIC32_R (0x5E08)
+#define SPI1CONINV      PIC32_R (0x5E0C)
+#define SPI1STAT        PIC32_R (0x5E10) /* Status */
+#define SPI1STATCLR     PIC32_R (0x5E14)
+#define SPI1STATSET     PIC32_R (0x5E18)
+#define SPI1STATINV     PIC32_R (0x5E1C)
+#define SPI1BUF         PIC32_R (0x5E20) /* Transmit and receive buffer */
+#define SPI1BRG         PIC32_R (0x5E30) /* Baud rate generator */
+#define SPI1BRGCLR      PIC32_R (0x5E34)
+#define SPI1BRGSET      PIC32_R (0x5E38)
+#define SPI1BRGINV      PIC32_R (0x5E3C)
+#endif
+
+#define SPI2CON         PIC32_R (0x5A00) /* Control */
+#define SPI2CONCLR      PIC32_R (0x5A04)
+#define SPI2CONSET      PIC32_R (0x5A08)
+#define SPI2CONINV      PIC32_R (0x5A0C)
+#define SPI2STAT        PIC32_R (0x5A10) /* Status */
+#define SPI2STATCLR     PIC32_R (0x5A14)
+#define SPI2STATSET     PIC32_R (0x5A18)
+#define SPI2STATINV     PIC32_R (0x5A1C)
+#define SPI2BUF         PIC32_R (0x5A20) /* Transmit and receive buffer */
+#define SPI2BRG         PIC32_R (0x5A30) /* Baud rate generator */
+#define SPI2BRGCLR      PIC32_R (0x5A34)
+#define SPI2BRGSET      PIC32_R (0x5A38)
+#define SPI2BRGINV      PIC32_R (0x5A3C)
+
+/*
+ * SPI Control register.
+ */
+#define PIC32_SPICON_MSTEN      0x00000020      /* Master mode */
+#define PIC32_SPICON_CKP        0x00000040      /* Idle clock is high level */
+#define PIC32_SPICON_SSEN       0x00000080      /* Slave mode: SSx
pin enable */
+#define PIC32_SPICON_CKE        0x00000100      /* Output data changes on
+                                                 * transition from active clock
+                                                 * state to Idle clock state */
+#define PIC32_SPICON_SMP        0x00000200      /* Master mode: input
data sampled
+                                                 * at end of data
output time. */
+#define PIC32_SPICON_MODE16     0x00000400      /* 16-bit data width */
+#define PIC32_SPICON_MODE32     0x00000800      /* 32-bit data width */
+#define PIC32_SPICON_DISSDO     0x00001000      /* SDOx pin is not used */
+#define PIC32_SPICON_SIDL       0x00002000      /* Stop in Idle mode */
+#define PIC32_SPICON_FRZ        0x00004000      /* Freeze in Debug mode */
+#define PIC32_SPICON_ON         0x00008000      /* SPI Peripheral is enabled */
+#define PIC32_SPICON_ENHBUF     0x00010000      /* Enhanced buffer enable */
+#define PIC32_SPICON_SPIFE      0x00020000      /* Frame synchronization pulse
+                                                 * coincides with the
first bit clock */
+#define PIC32_SPICON_FRMPOL     0x20000000      /* Frame pulse is
active-high */
+#define PIC32_SPICON_FRMSYNC    0x40000000      /* Frame sync pulse
input (Slave mode) */
+#define PIC32_SPICON_FRMEN      0x80000000      /* Framed SPI support */
+
+/*
+ * SPI Status register.
+ */
+#define PIC32_SPISTAT_SPIRBF    0x00000001      /* Receive buffer is full */
+#define PIC32_SPISTAT_SPITBF    0x00000002      /* Transmit buffer is full */
+#define PIC32_SPISTAT_SPITBE    0x00000008      /* Transmit buffer is empty */
+#define PIC32_SPISTAT_SPIRBE    0x00000020      /* Receive buffer is empty */
+#define PIC32_SPISTAT_SPIROV    0x00000040      /* Receive overflow flag */
+#define PIC32_SPISTAT_SPIBUSY   0x00000800      /* SPI is busy */
+
+/*--------------------------------------
+ * DMA controller registers.
+ */
+#define DMACON          PIC32_R (0x83000)       /* DMA Control */
+#define DMACONCLR       PIC32_R (0x83004)
+#define DMACONSET       PIC32_R (0x83008)
+#define DMACONINV       PIC32_R (0x8300C)
+#define DMASTAT         PIC32_R (0x83010)       /* DMA Status */
+#define DMAADDR         PIC32_R (0x83020)       /* DMA Address */
+// TODO: other DMA registers.
+
+/*--------------------------------------
+ * System controller registers.
+ */
+#define OSCCON          PIC32_R (0xf000)
+#define OSCCONCLR       PIC32_R (0xf004)
+#define OSCCONSET       PIC32_R (0xf008)
+#define OSCCONINV       PIC32_R (0xf00c)
+#define OSCTUN          PIC32_R (0xf010)
+#define OSCTUNCLR       PIC32_R (0xf014)
+#define OSCTUNSET       PIC32_R (0xf018)
+#define OSCTUNINV       PIC32_R (0xf01c)
+#define DDPCON          PIC32_R (0xf200)        /* Debug Data Port Control */
+#define DEVID           PIC32_R (0xf220)
+#define SYSKEY          PIC32_R (0xf230)
+#define RCON            PIC32_R (0xf600)
+#define RCONCLR         PIC32_R (0xf604)
+#define RCONSET         PIC32_R (0xf608)
+#define RCONINV         PIC32_R (0xf60C)
+#define RSWRST          PIC32_R (0xf610)
+#define RSWRSTCLR       PIC32_R (0xf614)
+#define RSWRSTSET       PIC32_R (0xf618)
+#define RSWRSTINV       PIC32_R (0xf61C)
+
+/*
+ * Oscillator control register.
+ */
+#define PIC32_OSCCON_UNUSED     0xc0a08800
+#define PIC32_OSCCON_OSWEN      0x00000001
+#define PIC32_OSCCON_SOSCEN     0x00000002
+#define PIC32_OSCCON_UFRCEN     0x00000004
+#define PIC32_OSCCON_CF         0x00000008
+#define PIC32_OSCCON_SLPEN      0x00000010
+#define PIC32_OSCCON_SLOCK      0x00000020
+#define PIC32_OSCCON_ULOCK      0x00000040
+#define PIC32_OSCCON_CLKLOCK    0x00000080
+#define PIC32_OSCCON_NOSC       0x00000700
+#define PIC32_OSCCON_COSC       0x00007000
+#define PIC32_OSCCON_PLLMULT    0x00070000
+#define PIC32_OSCCON_PBDIV      0x00180000
+#define PIC32_OSCCON_SOSCRDY    0x00400000
+#define PIC32_OSCCON_FRCDIV     0x07000000
+#define PIC32_OSCCON_PLLODIV    0x38000000
+
+/*
+ * Oscillator tune register.
+ */
+#define PIC32_OSCTUN_UNUSED     0xffffffc0
+#define PIC32_OSCTUN_TUN        0x0000003f
+
+/*
+ * Reset control register.
+ */
+#define PIC32_RCON_UNUSED       0xfffffc20
+#define PIC32_RCON_POR          0x00000001
+#define PIC32_RCON_BOR          0x00000002
+#define PIC32_RCON_IDLE         0x00000004
+#define PIC32_RCON_SLEEP        0x00000008
+#define PIC32_RCON_WDTO         0x00000010
+#define PIC32_RCON_SWR          0x00000040
+#define PIC32_RCON_EXTR         0x00000080
+#define PIC32_RCON_VREGS        0x00000100
+#define PIC32_RCON_CMR          0x00000200
+
+/*--------------------------------------
+ * Prefetch cache controller registers.
+ */
+#define CHECON          PIC32_R (0x84000)       /* Prefetch cache control */
+#define CHECONCLR       PIC32_R (0x84004)
+#define CHECONSET       PIC32_R (0x84008)
+#define CHECONINV       PIC32_R (0x8400C)
+// TODO: other prefetch registers
+
+/*--------------------------------------
+ * Bus matrix control registers.
+ */
+#define BMXCON          PIC32_R (0x82000)       /* Memory configuration */
+#define BMXCONCLR       PIC32_R (0x82004)
+#define BMXCONSET       PIC32_R (0x82008)
+#define BMXCONINV       PIC32_R (0x8200C)
+#define BMXDKPBA        PIC32_R (0x82010)       /* Data RAM kernel
program base address */
+#define BMXDUDBA        PIC32_R (0x82020)       /* Data RAM user data
base address */
+#define BMXDUPBA        PIC32_R (0x82030)       /* Data RAM user
program base address */
+#define BMXDRMSZ        PIC32_R (0x82040)       /* Data RAM size */
+#define BMXPUPBA        PIC32_R (0x82050)       /* Program Flash user
program base address */
+#define BMXPFMSZ        PIC32_R (0x82060)       /* Program Flash size */
+#define BMXBOOTSZ       PIC32_R (0x82070)       /* Boot Flash size */
+
+/*--------------------------------------
+ * Non-volatile memory control registers.
+ */
+#define NVMCON          PIC32_R (0x0F400)
+#define NVMCONCLR       PIC32_R (0x0F404)
+#define NVMCONSET       PIC32_R (0x0F408)
+#define NVMCONINV       PIC32_R (0x0F40C)
+#define NVMKEY          PIC32_R (0x0F410)
+#define NVMADDR         PIC32_R (0x0F420)
+#define NVMADDRCLR      PIC32_R (0x0F424)
+#define NVMADDRSET      PIC32_R (0x0F428)
+#define NVMADDRINV      PIC32_R (0x0F42C)
+#define NVMDATA         PIC32_R (0x0F430)
+#define NVMSRCADDR      PIC32_R (0x0F440)
+
+#define PIC32_NVMCON_NVMOP      0x0000000F
+#define PIC32_NVMCON_NOP                 0 /* No operation */
+#define PIC32_NVMCON_WORD_PGM            1 /* Word program */
+#define PIC32_NVMCON_ROW_PGM             3 /* Row program */
+#define PIC32_NVMCON_PAGE_ERASE          4 /* Page erase */
+
+#define PIC32_NVMCON_LVDSTAT    0x00000800
+#define PIC32_NVMCON_LVDERR     0x00001000
+#define PIC32_NVMCON_WRERR      0x00002000
+#define PIC32_NVMCON_WREN       0x00004000
+#define PIC32_NVMCON_WR         0x00008000
+
+/*
+ * Timer2 registers
+ */
+#define T2CON           PIC32_R (0x0800)
+#define T2CONSET        PIC32_R (0x0808)
+#define TMR2            PIC32_R (0x0810)
+#define PR2             PIC32_R (0x0820)
+
+/*
+ * Output compare registers
+ */
+#define OC1CON          PIC32_R (0x3000)
+#define OC1R            PIC32_R (0x3010)
+#define OC1RS           PIC32_R (0x3020)
+#define OC4CON          PIC32_R (0x3600)
+#define OC4R            PIC32_R (0x3610)
+#define OC4RS           PIC32_R (0x3620)
+
+/*
+ * Watchdog registers
+ */
+#define WDTCON          PIC32_R (0x0000)    /* Watchdog timer control */
+#define WDTCONCLR       PIC32_R (0x0004)
+#define WDTCONSET       PIC32_R (0x0008)
+
+/*--------------------------------------
+ * Configuration registers.
+ */
+#define DEVCFG0         0x9fc02ffc
+#define DEVCFG1         0x9fc02ff8
+#define DEVCFG2         0x9fc02ff4
+#define DEVCFG3         0x9fc02ff0
+
+#define PIC32_DEVCFG(cfg0, cfg1, cfg2, cfg3) \
+    asm (".section .config"); \
+    unsigned __DEVCFG0 __attribute__ ((section(".config0"))) = (cfg0)
^ 0x7fffffff; \
+    unsigned __DEVCFG1 __attribute__ ((section(".config1"))) = (cfg1)
| DEVCFG1_UNUSED; \
+    unsigned __DEVCFG2 __attribute__ ((section(".config2"))) = (cfg2)
| DEVCFG2_UNUSED; \
+    unsigned __DEVCFG3 __attribute__ ((section(".config3"))) = (cfg3)
| DEVCFG3_UNUSED
+
+/*
+ * Config0 register at 1fc02ffc, inverted.
+ */
+#define DEVCFG0_DEBUG_MASK      0x00000003 /* Debugger enable bits */
+#define DEVCFG0_DEBUG_DISABLED  0x00000000 /* Debugger disabled */
+#define DEVCFG0_DEBUG_ENABLED   0x00000002 /* Debugger enabled */
+#define DEVCFG0_ICESEL          0x00000008 /* Use PGC1/PGD1 (default
PGC2/PGD2) */
+#define DEVCFG0_PWP_MASK        0x000ff000 /* Program flash write protect */
+#define DEVCFG0_BWP             0x01000000 /* Boot flash write protect */
+#define DEVCFG0_CP              0x10000000 /* Code protect */
+
+/*
+ * Config1 register at 1fc02ff8.
+ */
+#define DEVCFG1_UNUSED          0xff600858
+#define DEVCFG1_FNOSC_MASK      0x00000007 /* Oscillator selection */
+#define DEVCFG1_FNOSC_FRC       0x00000000 /* Fast RC */
+#define DEVCFG1_FNOSC_FRCDIVPLL 0x00000001 /* Fast RC with
divide-by-N and PLL */
+#define DEVCFG1_FNOSC_PRI       0x00000002 /* Primary oscillator XT, HS, EC */
+#define DEVCFG1_FNOSC_PRIPLL    0x00000003 /* Primary with PLL */
+#define DEVCFG1_FNOSC_SEC       0x00000004 /* Secondary oscillator */
+#define DEVCFG1_FNOSC_LPRC      0x00000005 /* Low-power RC */
+#define DEVCFG1_FNOSC_FRCDIV    0x00000007 /* Fast RC with divide-by-N */
+#define DEVCFG1_FSOSCEN         0x00000020 /* Secondary oscillator enable */
+#define DEVCFG1_IESO            0x00000080 /* Internal-external switch over */
+#define DEVCFG1_POSCMOD_MASK    0x00000300 /* Primary oscillator config */
+#define DEVCFG1_POSCMOD_EXT     0x00000000 /* External mode */
+#define DEVCFG1_POSCMOD_XT      0x00000100 /* XT oscillator */
+#define DEVCFG1_POSCMOD_HS      0x00000200 /* HS oscillator */
+#define DEVCFG1_POSCMOD_DISABLE 0x00000300 /* Disabled */
+#define DEVCFG1_OSCIOFNC        0x00000400 /* CLKO output active */
+#define DEVCFG1_FPBDIV_MASK     0x00003000 /* Peripheral bus clock divisor */
+#define DEVCFG1_FPBDIV_1        0x00000000 /* SYSCLK / 1 */
+#define DEVCFG1_FPBDIV_2        0x00001000 /* SYSCLK / 2 */
+#define DEVCFG1_FPBDIV_4        0x00002000 /* SYSCLK / 4 */
+#define DEVCFG1_FPBDIV_8        0x00003000 /* SYSCLK / 8 */
+#define DEVCFG1_FCKM_DISABLE    0x00004000 /* Fail-safe clock monitor
disable */
+#define DEVCFG1_FCKS_DISABLE    0x00008000 /* Clock switching disable */
+#define DEVCFG1_WDTPS_MASK      0x001f0000 /* Watchdog postscale */
+#define DEVCFG1_WDTPS_1         0x00000000 /* 1:1 */
+#define DEVCFG1_WDTPS_2         0x00010000 /* 1:2 */
+#define DEVCFG1_WDTPS_4         0x00020000 /* 1:4 */
+#define DEVCFG1_WDTPS_8         0x00030000 /* 1:8 */
+#define DEVCFG1_WDTPS_16        0x00040000 /* 1:16 */
+#define DEVCFG1_WDTPS_32        0x00050000 /* 1:32 */
+#define DEVCFG1_WDTPS_64        0x00060000 /* 1:64 */
+#define DEVCFG1_WDTPS_128       0x00070000 /* 1:128 */
+#define DEVCFG1_WDTPS_256       0x00080000 /* 1:256 */
+#define DEVCFG1_WDTPS_512       0x00090000 /* 1:512 */
+#define DEVCFG1_WDTPS_1024      0x000a0000 /* 1:1024 */
+#define DEVCFG1_WDTPS_2048      0x000b0000 /* 1:2048 */
+#define DEVCFG1_WDTPS_4096      0x000c0000 /* 1:4096 */
+#define DEVCFG1_WDTPS_8192      0x000d0000 /* 1:8192 */
+#define DEVCFG1_WDTPS_16384     0x000e0000 /* 1:16384 */
+#define DEVCFG1_WDTPS_32768     0x000f0000 /* 1:32768 */
+#define DEVCFG1_WDTPS_65536     0x00100000 /* 1:65536 */
+#define DEVCFG1_WDTPS_131072    0x00110000 /* 1:131072 */
+#define DEVCFG1_WDTPS_262144    0x00120000 /* 1:262144 */
+#define DEVCFG1_WDTPS_524288    0x00130000 /* 1:524288 */
+#define DEVCFG1_WDTPS_1048576   0x00140000 /* 1:1048576 */
+#define DEVCFG1_FWDTEN          0x00800000 /* Watchdog enable */
+
+/*
+ * Config2 register at 1fc02ff4.
+ */
+#define DEVCFG2_UNUSED          0xfff87888
+#define DEVCFG2_FPLLIDIV_MASK   0x00000007 /* PLL input divider */
+#define DEVCFG2_FPLLIDIV_1      0x00000000 /* 1x */
+#define DEVCFG2_FPLLIDIV_2      0x00000001 /* 2x */
+#define DEVCFG2_FPLLIDIV_3      0x00000002 /* 3x */
+#define DEVCFG2_FPLLIDIV_4      0x00000003 /* 4x */
+#define DEVCFG2_FPLLIDIV_5      0x00000004 /* 5x */
+#define DEVCFG2_FPLLIDIV_6      0x00000005 /* 6x */
+#define DEVCFG2_FPLLIDIV_10     0x00000006 /* 10x */
+#define DEVCFG2_FPLLIDIV_12     0x00000007 /* 12x */
+#define DEVCFG2_FPLLMUL_MASK    0x00000070 /* PLL multiplier */
+#define DEVCFG2_FPLLMUL_15      0x00000000 /* 15x */
+#define DEVCFG2_FPLLMUL_16      0x00000010 /* 16x */
+#define DEVCFG2_FPLLMUL_17      0x00000020 /* 17x */
+#define DEVCFG2_FPLLMUL_18      0x00000030 /* 18x */
+#define DEVCFG2_FPLLMUL_19      0x00000040 /* 19x */
+#define DEVCFG2_FPLLMUL_20      0x00000050 /* 20x */
+#define DEVCFG2_FPLLMUL_21      0x00000060 /* 21x */
+#define DEVCFG2_FPLLMUL_24      0x00000070 /* 24x */
+#define DEVCFG2_UPLLIDIV_MASK   0x00000700 /* USB PLL input divider */
+#define DEVCFG2_UPLLIDIV_1      0x00000000 /* 1x */
+#define DEVCFG2_UPLLIDIV_2      0x00000100 /* 2x */
+#define DEVCFG2_UPLLIDIV_3      0x00000200 /* 3x */
+#define DEVCFG2_UPLLIDIV_4      0x00000300 /* 4x */
+#define DEVCFG2_UPLLIDIV_5      0x00000400 /* 5x */
+#define DEVCFG2_UPLLIDIV_6      0x00000500 /* 6x */
+#define DEVCFG2_UPLLIDIV_10     0x00000600 /* 10x */
+#define DEVCFG2_UPLLIDIV_12     0x00000700 /* 12x */
+#define DEVCFG2_UPLLDIS         0x00008000 /* Disable USB PLL */
+#define DEVCFG2_FPLLODIV_MASK   0x00070000 /* Default postscaler for PLL */
+#define DEVCFG2_FPLLODIV_1      0x00000000 /* 1x */
+#define DEVCFG2_FPLLODIV_2      0x00010000 /* 2x */
+#define DEVCFG2_FPLLODIV_4      0x00020000 /* 4x */
+#define DEVCFG2_FPLLODIV_8      0x00030000 /* 8x */
+#define DEVCFG2_FPLLODIV_16     0x00040000 /* 16x */
+#define DEVCFG2_FPLLODIV_32     0x00050000 /* 32x */
+#define DEVCFG2_FPLLODIV_64     0x00060000 /* 64x */
+#define DEVCFG2_FPLLODIV_256    0x00070000 /* 256x */
+
+/*
+ * Config3 register at 1fc02ff0.
+ */
+#define DEVCFG3_UNUSED          0x38f80000
+#define DEVCFG3_USERID_MASK     0x0000ffff /* User-defined ID */
+#define DEVCFG3_USERID(x)       ((x) & 0xffff)
+#define DEVCFG3_FSRSSEL_MASK    0x00070000 /* SRS select */
+#define DEVCFG3_FSRSSEL_ALL     0x00000000 /* All irqs assigned to
shadow set */
+#define DEVCFG3_FSRSSEL_1       0x00010000 /* Assign irq priority 1
to shadow set */
+#define DEVCFG3_FSRSSEL_2       0x00020000 /* Assign irq priority 2
to shadow set */
+#define DEVCFG3_FSRSSEL_3       0x00030000 /* Assign irq priority 3
to shadow set */
+#define DEVCFG3_FSRSSEL_4       0x00040000 /* Assign irq priority 4
to shadow set */
+#define DEVCFG3_FSRSSEL_5       0x00050000 /* Assign irq priority 5
to shadow set */
+#define DEVCFG3_FSRSSEL_6       0x00060000 /* Assign irq priority 6
to shadow set */
+#define DEVCFG3_FSRSSEL_7       0x00070000 /* Assign irq priority 7
to shadow set */
+#define DEVCFG3_FMIIEN          0x01000000 /* Ethernet MII enable */
+#define DEVCFG3_FETHIO          0x02000000 /* Ethernet pins default */
+#define DEVCFG3_FCANIO          0x04000000 /* CAN pins default */
+#define DEVCFG3_FUSBIDIO        0x40000000 /* USBID pin: controlled by USB */
+#define DEVCFG3_FVBUSONIO       0x80000000 /* VBuson pin: controlled by USB */
+
+/*--------------------------------------
+ * Interrupt controller registers.
+ */
+#define INTCON          PIC32_R (0x81000)       /* Interrupt Control */
+#define INTCONCLR       PIC32_R (0x81004)
+#define INTCONSET       PIC32_R (0x81008)
+#define INTCONINV       PIC32_R (0x8100C)
+#define INTSTAT         PIC32_R (0x81010)       /* Interrupt Status */
+#define IPTMR           PIC32_R (0x81020)       /* Temporal Proximity Timer */
+#define IPTMRCLR        PIC32_R (0x81024)
+#define IPTMRSET        PIC32_R (0x81028)
+#define IPTMRINV        PIC32_R (0x8102C)
+#define IFS(n)          PIC32_R (0x81030+((n)<<4)) /* IFS(0..2) -
Interrupt Flag Status */
+#define IFSCLR(n)       PIC32_R (0x81034+((n)<<4))
+#define IFSSET(n)       PIC32_R (0x81038+((n)<<4))
+#define IFSINV(n)       PIC32_R (0x8103C+((n)<<4))
+#define IFS0            IFS(0)
+#define IFS1            IFS(1)
+#define IFS2            IFS(2)
+#define IEC(n)          PIC32_R (0x81060+((n)<<4)) /* IEC(0..2) -
Interrupt Enable Control */
+#define IECCLR(n)       PIC32_R (0x81064+((n)<<4))
+#define IECSET(n)       PIC32_R (0x81068+((n)<<4))
+#define IECINV(n)       PIC32_R (0x8106C+((n)<<4))
+#define IEC0            IEC(0)
+#define IEC1            IEC(1)
+#define IEC2            IEC(2)
+#define IPC(n)          PIC32_R (0x81090+((n)<<4)) /* IPC(0..12) -
Interrupt Priority Control */
+#define IPCCLR(n)       PIC32_R (0x81094+((n)<<4))
+#define IPCSET(n)       PIC32_R (0x81098+((n)<<4))
+#define IPCINV(n)       PIC32_R (0x8109C+((n)<<4))
+#define IPC0            IPC(0)
+#define IPC1            IPC(1)
+#define IPC2            IPC(2)
+#define IPC3            IPC(3)
+#define IPC4            IPC(4)
+#define IPC5            IPC(5)
+#define IPC6            IPC(6)
+#define IPC7            IPC(7)
+#define IPC8            IPC(8)
+#define IPC9            IPC(9)
+#define IPC10           IPC(10)
+#define IPC11           IPC(11)
+#define IPC12           IPC(12)
+
+/*
+ * Interrupt Control register.
+ */
+#define PIC32_INTCON_INT0EP     0x0001  /* External interrupt 0
polarity rising edge */
+#define PIC32_INTCON_INT1EP     0x0002  /* External interrupt 1
polarity rising edge */
+#define PIC32_INTCON_INT2EP     0x0004  /* External interrupt 2
polarity rising edge */
+#define PIC32_INTCON_INT3EP     0x0008  /* External interrupt 3
polarity rising edge */
+#define PIC32_INTCON_INT4EP     0x0010  /* External interrupt 4
polarity rising edge */
+#define PIC32_INTCON_TPC(x)     ((x)<<8) /* Temporal proximity group
priority */
+#define PIC32_INTCON_MVEC       0x1000  /* Multi-vectored mode */
+#define PIC32_INTCON_FRZ        0x4000  /* Freeze in debug mode */
+#define PIC32_INTCON_SS0        0x8000  /* Single vector has a shadow
register set */
+
+/*
+ * Interrupt Status register.
+ */
+#define PIC32_INTSTAT_VEC(s)    ((s) & 0xFF)    /* Interrupt vector */
+#define PIC32_INTSTAT_SRIPL(s)  ((s) >> 8 & 7)  /* Requested priority level */
+#define PIC32_INTSTAT_SRIPL_MASK 0x0700
+
+/*
+ * Interrupt Prority Control register.
+ */
+#define PIC32_IPC_IS0(x)        (x)             /* Interrupt 0 subpriority */
+#define PIC32_IPC_IP0(x)        ((x)<<2)        /* Interrupt 0 priority */
+#define PIC32_IPC_IS1(x)        ((x)<<8)        /* Interrupt 1 subpriority */
+#define PIC32_IPC_IP1(x)        ((x)<<10)       /* Interrupt 1 priority */
+#define PIC32_IPC_IS2(x)        ((x)<<16)       /* Interrupt 2 subpriority */
+#define PIC32_IPC_IP2(x)        ((x)<<18)       /* Interrupt 2 priority */
+#define PIC32_IPC_IS3(x)        ((x)<<24)       /* Interrupt 3 subpriority */
+#define PIC32_IPC_IP3(x)        ((x)<<26)       /* Interrupt 3 priority */
+
+/*
+ * IRQ numbers for PIC32MX3xx/4xx/5xx/6xx/7xx
+ */
+#define PIC32_IRQ_CT        0   /* Core Timer Interrupt */
+#define PIC32_IRQ_CS0       1   /* Core Software Interrupt 0 */
+#define PIC32_IRQ_CS1       2   /* Core Software Interrupt 1 */
+#define PIC32_IRQ_INT0      3   /* External Interrupt 0 */
+#define PIC32_IRQ_T1        4   /* Timer1 */
+#define PIC32_IRQ_IC1       5   /* Input Capture 1 */
+#define PIC32_IRQ_OC1       6   /* Output Compare 1 */
+#define PIC32_IRQ_INT1      7   /* External Interrupt 1 */
+#define PIC32_IRQ_T2        8   /* Timer2 */
+#define PIC32_IRQ_IC2       9   /* Input Capture 2 */
+#define PIC32_IRQ_OC2       10  /* Output Compare 2 */
+#define PIC32_IRQ_INT2      11  /* External Interrupt 2 */
+#define PIC32_IRQ_T3        12  /* Timer3 */
+#define PIC32_IRQ_IC3       13  /* Input Capture 3 */
+#define PIC32_IRQ_OC3       14  /* Output Compare 3 */
+#define PIC32_IRQ_INT3      15  /* External Interrupt 3 */
+#define PIC32_IRQ_T4        16  /* Timer4 */
+#define PIC32_IRQ_IC4       17  /* Input Capture 4 */
+#define PIC32_IRQ_OC4       18  /* Output Compare 4 */
+#define PIC32_IRQ_INT4      19  /* External Interrupt 4 */
+#define PIC32_IRQ_T5        20  /* Timer5 */
+#define PIC32_IRQ_IC5       21  /* Input Capture 5 */
+#define PIC32_IRQ_OC5       22  /* Output Compare 5 */
+#define PIC32_IRQ_SPI1E     23  /* SPI1 Fault */
+#define PIC32_IRQ_SPI1TX    24  /* SPI1 Transfer Done */
+#define PIC32_IRQ_SPI1RX    25  /* SPI1 Receive Done */
+
+#define PIC32_IRQ_SPI3E     26  /* SPI3 Fault */
+#define PIC32_IRQ_SPI3TX    27  /* SPI3 Transfer Done */
+#define PIC32_IRQ_SPI3RX    28  /* SPI3 Receive Done */
+#define PIC32_IRQ_U1E       26  /* UART1 Error */
+#define PIC32_IRQ_U1RX      27  /* UART1 Receiver */
+#define PIC32_IRQ_U1TX      28  /* UART1 Transmitter */
+#define PIC32_IRQ_I2C3B     26  /* I2C3 Bus Collision Event */
+#define PIC32_IRQ_I2C3S     27  /* I2C3 Slave Event */
+#define PIC32_IRQ_I2C3M     28  /* I2C3 Master Event */
+
+#define PIC32_IRQ_I2C1B     29  /* I2C1 Bus Collision Event */
+#define PIC32_IRQ_I2C1S     30  /* I2C1 Slave Event */
+#define PIC32_IRQ_I2C1M     31  /* I2C1 Master Event */
+#define PIC32_IRQ_CN        32  /* Input Change Interrupt */
+#define PIC32_IRQ_AD1       33  /* ADC1 Convert Done */
+#define PIC32_IRQ_PMP       34  /* Parallel Master Port */
+#define PIC32_IRQ_CMP1      35  /* Comparator Interrupt */
+#define PIC32_IRQ_CMP2      36  /* Comparator Interrupt */
+
+#define PIC32_IRQ_SPI2E     37  /* SPI2 Fault */
+#define PIC32_IRQ_SPI2TX    38  /* SPI2 Transfer Done */
+#define PIC32_IRQ_SPI2RX    39  /* SPI2 Receive Done */
+#define PIC32_IRQ_U3E       37  /* UART3 Error */
+#define PIC32_IRQ_U3RX      38  /* UART3 Receiver */
+#define PIC32_IRQ_U3TX      39  /* UART3 Transmitter */
+#define PIC32_IRQ_I2C4B     37  /* I2C4 Bus Collision Event */
+#define PIC32_IRQ_I2C4S     38  /* I2C4 Slave Event */
+#define PIC32_IRQ_I2C4M     39  /* I2C4 Master Event */
+
+#define PIC32_IRQ_SPI4E     40  /* SPI4 Fault */
+#define PIC32_IRQ_SPI4TX    41  /* SPI4 Transfer Done */
+#define PIC32_IRQ_SPI4RX    42  /* SPI4 Receive Done */
+#define PIC32_IRQ_U2E       40  /* UART2 Error */
+#define PIC32_IRQ_U2RX      41  /* UART2 Receiver */
+#define PIC32_IRQ_U2TX      42  /* UART2 Transmitter */
+#define PIC32_IRQ_I2C5B     40  /* I2C5 Bus Collision Event */
+#define PIC32_IRQ_I2C5S     41  /* I2C5 Slave Event */
+#define PIC32_IRQ_I2C5M     42  /* I2C5 Master Event */
+
+#define PIC32_IRQ_I2C2B     43  /* I2C2 Bus Collision Event */
+#define PIC32_IRQ_I2C2S     44  /* I2C2 Slave Event */
+#define PIC32_IRQ_I2C2M     45  /* I2C2 Master Event */
+#define PIC32_IRQ_FSCM      46  /* Fail-Safe Clock Monitor */
+#define PIC32_IRQ_RTCC      47  /* Real-Time Clock and Calendar */
+#define PIC32_IRQ_DMA0      48  /* DMA Channel 0 */
+#define PIC32_IRQ_DMA1      49  /* DMA Channel 1 */
+#define PIC32_IRQ_DMA2      50  /* DMA Channel 2 */
+#define PIC32_IRQ_DMA3      51  /* DMA Channel 3 */
+#define PIC32_IRQ_DMA4      52  /* DMA Channel 4 */
+#define PIC32_IRQ_DMA5      53  /* DMA Channel 5 */
+#define PIC32_IRQ_DMA6      54  /* DMA Channel 6 */
+#define PIC32_IRQ_DMA7      55  /* DMA Channel 7 */
+#define PIC32_IRQ_FCE       56  /* Flash Control Event */
+#define PIC32_IRQ_USB       57  /* USB */
+#define PIC32_IRQ_CAN1      58  /* Control Area Network 1 */
+#define PIC32_IRQ_CAN2      59  /* Control Area Network 2 */
+#define PIC32_IRQ_ETH       60  /* Ethernet Interrupt */
+#define PIC32_IRQ_IC1E      61  /* Input Capture 1 Error */
+#define PIC32_IRQ_IC2E      62  /* Input Capture 2 Error */
+#define PIC32_IRQ_IC3E      63  /* Input Capture 3 Error */
+#define PIC32_IRQ_IC4E      64  /* Input Capture 4 Error */
+#define PIC32_IRQ_IC5E      65  /* Input Capture 5 Error */
+#define PIC32_IRQ_PMPE      66  /* Parallel Master Port Error */
+#define PIC32_IRQ_U4E       67  /* UART4 Error */
+#define PIC32_IRQ_U4RX      68  /* UART4 Receiver */
+#define PIC32_IRQ_U4TX      69  /* UART4 Transmitter */
+#define PIC32_IRQ_U6E       70  /* UART6 Error */
+#define PIC32_IRQ_U6RX      71  /* UART6 Receiver */
+#define PIC32_IRQ_U6TX      72  /* UART6 Transmitter */
+#define PIC32_IRQ_U5E       73  /* UART5 Error */
+#define PIC32_IRQ_U5RX      74  /* UART5 Receiver */
+#define PIC32_IRQ_U5TX      75  /* UART5 Transmitter */
+
+/*
+ * Interrupt vector numbers for PIC32MX3xx/4xx/5xx/6xx/7xx
+ */
+#define PIC32_VECT_CT       0   /* Core Timer Interrupt */
+#define PIC32_VECT_CS0      1   /* Core Software Interrupt 0 */
+#define PIC32_VECT_CS1      2   /* Core Software Interrupt 1 */
+#define PIC32_VECT_INT0     3   /* External Interrupt 0 */
+#define PIC32_VECT_T1       4   /* Timer1 */
+#define PIC32_VECT_IC1      5   /* Input Capture 1 */
+#define PIC32_VECT_OC1      6   /* Output Compare 1 */
+#define PIC32_VECT_INT1     7   /* External Interrupt 1 */
+#define PIC32_VECT_T2       8   /* Timer2 */
+#define PIC32_VECT_IC2      9   /* Input Capture 2 */
+#define PIC32_VECT_OC2      10  /* Output Compare 2 */
+#define PIC32_VECT_INT2     11  /* External Interrupt 2 */
+#define PIC32_VECT_T3       12  /* Timer3 */
+#define PIC32_VECT_IC3      13  /* Input Capture 3 */
+#define PIC32_VECT_OC3      14  /* Output Compare 3 */
+#define PIC32_VECT_INT3     15  /* External Interrupt 3 */
+#define PIC32_VECT_T4       16  /* Timer4 */
+#define PIC32_VECT_IC4      17  /* Input Capture 4 */
+#define PIC32_VECT_OC4      18  /* Output Compare 4 */
+#define PIC32_VECT_INT4     19  /* External Interrupt 4 */
+#define PIC32_VECT_T5       20  /* Timer5 */
+#define PIC32_VECT_IC5      21  /* Input Capture 5 */
+#define PIC32_VECT_OC5      22  /* Output Compare 5 */
+#define PIC32_VECT_SPI1     23  /* SPI1 */
+
+#define PIC32_VECT_SPI3     24  /* SPI3 */
+#define PIC32_VECT_U1       24  /* UART1 */
+#define PIC32_VECT_I2C3     24  /* I2C3 */
+
+#define PIC32_VECT_I2C1     25  /* I2C1 */
+#define PIC32_VECT_CN       26  /* Input Change Interrupt */
+#define PIC32_VECT_AD1      27  /* ADC1 Convert Done */
+#define PIC32_VECT_PMP      28  /* Parallel Master Port */
+#define PIC32_VECT_CMP1     29  /* Comparator Interrupt */
+#define PIC32_VECT_CMP2     30  /* Comparator Interrupt */
+
+#define PIC32_VECT_SPI2     31  /* SPI2 */
+#define PIC32_VECT_U3       31  /* UART3 */
+#define PIC32_VECT_I2C4     31  /* I2C4 */
+
+#define PIC32_VECT_SPI4     32  /* SPI4 */
+#define PIC32_VECT_U2       32  /* UART2 */
+#define PIC32_VECT_I2C5     32  /* I2C5 */
+
+#define PIC32_VECT_I2C2     33  /* I2C2 */
+#define PIC32_VECT_FSCM     34  /* Fail-Safe Clock Monitor */
+#define PIC32_VECT_RTCC     35  /* Real-Time Clock and Calendar */
+#define PIC32_VECT_DMA0     36  /* DMA Channel 0 */
+#define PIC32_VECT_DMA1     37  /* DMA Channel 1 */
+#define PIC32_VECT_DMA2     38  /* DMA Channel 2 */
+#define PIC32_VECT_DMA3     39  /* DMA Channel 3 */
+#define PIC32_VECT_DMA4     40  /* DMA Channel 4 */
+#define PIC32_VECT_DMA5     41  /* DMA Channel 5 */
+#define PIC32_VECT_DMA6     42  /* DMA Channel 6 */
+#define PIC32_VECT_DMA7     43  /* DMA Channel 7 */
+#define PIC32_VECT_FCE      44  /* Flash Control Event */
+#define PIC32_VECT_USB      45  /* USB */
+#define PIC32_VECT_CAN1     46  /* Control Area Network 1 */
+#define PIC32_VECT_CAN2     47  /* Control Area Network 2 */
+#define PIC32_VECT_ETH      48  /* Ethernet Interrupt */
+#define PIC32_VECT_U4       49  /* UART4 */
+#define PIC32_VECT_U6       50  /* UART6 */
+#define PIC32_VECT_U5       51  /* UART5 */
+
+#endif /* _IO_PIC32MX_H */
diff --git a/hw/mips/pic32mz.h b/hw/mips/pic32mz.h
new file mode 100644
index 0000000..0ed92b2
--- /dev/null
+++ b/hw/mips/pic32mz.h
@@ -0,0 +1,2073 @@
+/*
+ * Hardware register defines for Microchip PIC32MZ microcontroller.
+ *
+ * Copyright (C) 2013 Serge Vakulenko
+ *
+ * Permission to use, copy, modify, and distribute this software
+ * and its documentation for any purpose and without fee is hereby
+ * granted, provided that the above copyright notice appear in all
+ * copies and that both that the copyright notice and this
+ * permission notice and warranty disclaimer appear in supporting
+ * documentation, and that the name of the author not be used in
+ * advertising or publicity pertaining to distribution of the
+ * software without specific, written prior permission.
+ *
+ * The author disclaim all warranties with regard to this
+ * software, including all implied warranties of merchantability
+ * and fitness.  In no event shall the author be liable for any
+ * special, indirect or consequential damages or any damages
+ * whatsoever resulting from loss of use, data or profits, whether
+ * in an action of contract, negligence or other tortious action,
+ * arising out of or in connection with the use or performance of
+ * this software.
+ */
+#ifndef _IO_PIC32MZ_H
+#define _IO_PIC32MZ_H
+
+/*
+ * Register memory map:
+ *
+ *  BF80 0000...03FF    Configuration
+ *  BF80 0600...07FF    Flash Controller
+ *  BF80 0800...09FF    Watchdog Timer
+ *  BF80 0A00...0BFF    Deadman Timer
+ *  BF80 0C00...0DFF    RTCC
+ *  BF80 0E00...0FFF    CVref
+ *  BF80 1200...13FF    Oscillator
+ *  BF80 1400...17FF    PPS
+ *
+ *  BF81 0000...0FFF    Interrupt Controller
+ *  BF81 1000...1FFF    DMA
+ *
+ *  BF82 0000...09FF    I2C1 - I2C5
+ *  BF82 1000...1BFF    SPI1 - SPI6
+ *  BF82 2000...2BFF    UART1 - UART6
+ *  BF82 E000...E1FF    PMP
+ *
+ *  BF84 0000...11FF    Timer1 - Timer9
+ *  BF84 2000...31FF    IC1 - IC9
+ *  BF84 4000...51FF    OC1 - OC9
+ *  BF84 B000...B3FF    ADC1
+ *  BF84 C000...C1FF    Comparator 1, 2
+ *
+ *  BF86 0000...09FF    PORTA - PORTK
+ *
+ *  BF88 0000...1FFF    CAN1 and CAN2
+ *  BF88 2000...2FFF    Ethernet
+ *
+ *  BF8E 0000...0FFF    Prefetch
+ *  BF8E 1000...1FFF    EBI
+ *  BF8E 2000...2FFF    SQI1
+ *  BF8E 3000...3FFF    USB
+ *  BF8E 5000...5FFF    Crypto
+ *  BF8E 6000...6FFF    RNG
+ *
+ *  BF8F 0000...FFFF    System Bus
+ */
+
+/*--------------------------------------
+ * Configuration registers.
+ */
+#define DEVCFG0         0x9fc0fffc
+#define DEVCFG1         0x9fc0fff8
+#define DEVCFG2         0x9fc0fff4
+#define DEVCFG3         0x9fc0fff0
+
+#define PIC32_DEVCFG(cfg0, cfg1, cfg2, cfg3) \
+    unsigned __DEVCFG0 __attribute__ ((section(".config0"))) = (cfg0)
^ 0x7fffffff; \
+    unsigned __DEVCFG1 __attribute__ ((section(".config1"))) = (cfg1)
| DEVCFG1_UNUSED; \
+    unsigned __DEVCFG2 __attribute__ ((section(".config2"))) = (cfg2)
| DEVCFG2_UNUSED; \
+    unsigned __DEVCFG3 __attribute__ ((section(".config3"))) = (cfg3)
| DEVCFG3_UNUSED
+
+/*
+ * Config0 register at 1fc0ffcc, inverted.
+ */
+#define DEVCFG0_DEBUG_ENABLE    0x00000002 /* Enable background debugger */
+#define DEVCFG0_JTAG_DISABLE    0x00000004 /* Disable JTAG port */
+#define DEVCFG0_ICESEL_PGE2     0x00000008 /* Use PGC2/PGD2 (default
PGC1/PGD1) */
+#define DEVCFG0_TRC_DISABLE     0x00000020 /* Disable Trace port */
+#define DEVCFG0_MICROMIPS       0x00000040 /* Boot in microMIPS mode */
+#define DEVCFG0_ECC_MASK        0x00000300 /* Flash ECC mode mask */
+#define DEVCFG0_ECC_ENABLE      0x00000300 /* Enable Flash ECC */
+#define DEVCFG0_DECC_ENABLE     0x00000200 /* Enable Dynamic Flash ECC */
+#define DEVCFG0_ECC_DIS_LOCK    0x00000100 /* Disable ECC, lock ECCCON */
+#define DEVCFG0_FSLEEP          0x00000400 /* Flash power down
controlled by VREGS bit */
+#define DEVCFG0_DBGPER0         0x00001000 /* In Debug mode, deny CPU access to
+                                            * Permission Group 0
permission regions */
+#define DEVCFG0_DBGPER1         0x00002000 /* In Debug mode, deny CPU access to
+                                            * Permission Group 1
permission regions */
+#define DEVCFG0_DBGPER2         0x00004000 /* In Debug mode, deny CPU access to
+                                            * Permission Group 2
permission regions */
+#define DEVCFG0_EJTAG_REDUCED   0x40000000 /* Reduced EJTAG functionality */
+
+/*
+ * Config1 register at 1fc0ffc8.
+ */
+#define DEVCFG1_UNUSED          0x00003800
+#define DEVCFG1_FNOSC_MASK      0x00000007 /* Oscillator selection */
+#define DEVCFG1_FNOSC_SPLL      0x00000001 /* SPLL */
+#define DEVCFG1_FNOSC_POSC      0x00000002 /* Primary oscillator XT, HS, EC */
+#define DEVCFG1_FNOSC_SOSC      0x00000004 /* Secondary oscillator */
+#define DEVCFG1_FNOSC_LPRC      0x00000005 /* Low-power RC */
+#define DEVCFG1_FNOSC_FRCDIV    0x00000007 /* Fast RC with divide-by-N */
+#define DEVCFG1_DMTINV_MASK     0x00000038 /* Deadman Timer Count
Window Interval */
+#define DEVCFG1_DMTINV_1_2      0x00000008 /* 1/2 of counter value */
+#define DEVCFG1_DMTINV_3_4      0x00000010 /* 3/4 of counter value */
+#define DEVCFG1_DMTINV_7_8      0x00000018 /* 7/8 of counter value */
+#define DEVCFG1_DMTINV_15_16    0x00000020 /* 15/16 of counter value */
+#define DEVCFG1_DMTINV_31_32    0x00000028 /* 31/32 of counter value */
+#define DEVCFG1_DMTINV_63_64    0x00000030 /* 63/64 of counter value */
+#define DEVCFG1_DMTINV_127_128  0x00000038 /* 127/128 of counter value */
+#define DEVCFG1_FSOSCEN         0x00000040 /* Secondary oscillator enable */
+#define DEVCFG1_IESO            0x00000080 /* Internal-external switch over */
+#define DEVCFG1_POSCMOD_MASK    0x00000300 /* Primary oscillator config */
+#define DEVCFG1_POSCMOD_EXT     0x00000000 /* External mode */
+#define DEVCFG1_POSCMOD_HS      0x00000200 /* HS oscillator */
+#define DEVCFG1_POSCMOD_DISABLE 0x00000300 /* Disabled */
+#define DEVCFG1_CLKO_DISABLE    0x00000400 /* Disable CLKO output */
+#define DEVCFG1_FCKS_ENABLE     0x00004000 /* Enable clock switching */
+#define DEVCFG1_FCKM_ENABLE     0x00008000 /* Enable fail-safe clock
monitoring */
+#define DEVCFG1_WDTPS_MASK      0x001f0000 /* Watchdog postscale */
+#define DEVCFG1_WDTPS_1         0x00000000 /* 1:1 */
+#define DEVCFG1_WDTPS_2         0x00010000 /* 1:2 */
+#define DEVCFG1_WDTPS_4         0x00020000 /* 1:4 */
+#define DEVCFG1_WDTPS_8         0x00030000 /* 1:8 */
+#define DEVCFG1_WDTPS_16        0x00040000 /* 1:16 */
+#define DEVCFG1_WDTPS_32        0x00050000 /* 1:32 */
+#define DEVCFG1_WDTPS_64        0x00060000 /* 1:64 */
+#define DEVCFG1_WDTPS_128       0x00070000 /* 1:128 */
+#define DEVCFG1_WDTPS_256       0x00080000 /* 1:256 */
+#define DEVCFG1_WDTPS_512       0x00090000 /* 1:512 */
+#define DEVCFG1_WDTPS_1024      0x000a0000 /* 1:1024 */
+#define DEVCFG1_WDTPS_2048      0x000b0000 /* 1:2048 */
+#define DEVCFG1_WDTPS_4096      0x000c0000 /* 1:4096 */
+#define DEVCFG1_WDTPS_8192      0x000d0000 /* 1:8192 */
+#define DEVCFG1_WDTPS_16384     0x000e0000 /* 1:16384 */
+#define DEVCFG1_WDTPS_32768     0x000f0000 /* 1:32768 */
+#define DEVCFG1_WDTPS_65536     0x00100000 /* 1:65536 */
+#define DEVCFG1_WDTPS_131072    0x00110000 /* 1:131072 */
+#define DEVCFG1_WDTPS_262144    0x00120000 /* 1:262144 */
+#define DEVCFG1_WDTPS_524288    0x00130000 /* 1:524288 */
+#define DEVCFG1_WDTPS_1048576   0x00140000 /* 1:1048576 */
+#define DEVCFG1_WDTSPGM         0x00200000 /* Watchdog stops during
Flash programming */
+#define DEVCFG1_WINDIS          0x00400000 /* Watchdog is in non-Window mode */
+#define DEVCFG1_FWDTEN          0x00800000 /* Watchdog enable */
+#define DEVCFG1_FWDTWINSZ_75    0x00000000 /* Watchdog window size is 75% */
+#define DEVCFG1_FWDTWINSZ_50    0x01000000 /* 50% */
+#define DEVCFG1_FWDTWINSZ_375   0x02000000 /* 37.5% */
+#define DEVCFG1_FWDTWINSZ_25    0x03000000 /* 25% */
+#define DEVCFG1_DMTCNT(n)       ((n)<<26)  /* Deadman Timer Count Select */
+#define DEVCFG1_FDMTEN          0x80000000 /* Deadman Timer enable */
+
+/*
+ * Config2 register at 1fc0ffc4.
+ */
+#define DEVCFG2_UNUSED          0x3ff88008
+#define DEVCFG2_FPLLIDIV_MASK   0x00000007 /* PLL input divider */
+#define DEVCFG2_FPLLIDIV_1      0x00000000 /* 1x */
+#define DEVCFG2_FPLLIDIV_2      0x00000001 /* 2x */
+#define DEVCFG2_FPLLIDIV_3      0x00000002 /* 3x */
+#define DEVCFG2_FPLLIDIV_4      0x00000003 /* 4x */
+#define DEVCFG2_FPLLIDIV_5      0x00000004 /* 5x */
+#define DEVCFG2_FPLLIDIV_6      0x00000005 /* 6x */
+#define DEVCFG2_FPLLIDIV_7      0x00000006 /* 7x */
+#define DEVCFG2_FPLLIDIV_8      0x00000007 /* 8x */
+#define DEVCFG2_FPLLRNG_MASK    0x00000070 /* PLL input frequency range */
+#define DEVCFG2_FPLLRNG_BYPASS  0x00000000 /* Bypass */
+#define DEVCFG2_FPLLRNG_5_10    0x00000010 /* 5-10 MHz */
+#define DEVCFG2_FPLLRNG_8_16    0x00000020 /* 8-16 MHz */
+#define DEVCFG2_FPLLRNG_13_26   0x00000030 /* 13-26 MHz */
+#define DEVCFG2_FPLLRNG_21_42   0x00000040 /* 21-42 MHz */
+#define DEVCFG2_FPLLRNG_34_64   0x00000050 /* 34-64 MHz */
+#define DEVCFG2_FPLLICLK_FRC    0x00000080 /* Select FRC as input to PLL */
+#define DEVCFG2_FPLLMULT(n)     (((n)-1)<<8) /* PLL Feedback Divider */
+#define DEVCFG2_FPLLODIV_MASK   0x00070000 /* Default PLL output divisor */
+#define DEVCFG2_FPLLODIV_2      0x00000000 /* 2x */
+#define DEVCFG2_FPLLODIV_4      0x00020000 /* 4x */
+#define DEVCFG2_FPLLODIV_8      0x00030000 /* 8x */
+#define DEVCFG2_FPLLODIV_16     0x00040000 /* 16x */
+#define DEVCFG2_FPLLODIV_32     0x00050000 /* 32x */
+#define DEVCFG2_UPLLFSEL_24     0x40000000 /* USB PLL input clock is
24 MHz (default 12 MHz) */
+#define DEVCFG2_UPLLEN          0x80000000 /* Enable USB PLL */
+
+/*
+ * Config3 register at 1fc0ffc0.
+ */
+#define DEVCFG3_UNUSED          0x84ff0000
+#define DEVCFG3_USERID_MASK     0x0000ffff /* User-defined ID */
+#define DEVCFG3_USERID(x)       ((x) & 0xffff)
+#define DEVCFG3_FMIIEN          0x01000000 /* Ethernet MII enable */
+#define DEVCFG3_FETHIO          0x02000000 /* Default Ethernet pins */
+#define DEVCFG3_PGL1WAY         0x08000000 /* Permission Group Lock -
only 1 reconfig */
+#define DEVCFG3_PMDL1WAY        0x10000000 /* Peripheral Module
Disable - only 1 reconfig */
+#define DEVCFG3_IOL1WAY         0x20000000 /* Peripheral Pin Select -
only 1 reconfig */
+#define DEVCFG3_FUSBIDIO        0x40000000 /* USBID pin: controlled by USB */
+
+/*--------------------------------------
+ * Peripheral registers.
+ */
+#define PIC32_R(a)              (a)
+
+/*--------------------------------------
+ * Port A-K registers.
+ */
+#define ANSELA          PIC32_R (0x60000) /* Port A: analog select */
+#define ANSELACLR       PIC32_R (0x60004)
+#define ANSELASET       PIC32_R (0x60008)
+#define ANSELAINV       PIC32_R (0x6000C)
+#define TRISA           PIC32_R (0x60010) /* Port A: mask of inputs */
+#define TRISACLR        PIC32_R (0x60014)
+#define TRISASET        PIC32_R (0x60018)
+#define TRISAINV        PIC32_R (0x6001C)
+#define PORTA           PIC32_R (0x60020) /* Port A: read inputs,
write outputs */
+#define PORTACLR        PIC32_R (0x60024)
+#define PORTASET        PIC32_R (0x60028)
+#define PORTAINV        PIC32_R (0x6002C)
+#define LATA            PIC32_R (0x60030) /* Port A: read/write outputs */
+#define LATACLR         PIC32_R (0x60034)
+#define LATASET         PIC32_R (0x60038)
+#define LATAINV         PIC32_R (0x6003C)
+#define ODCA            PIC32_R (0x60040) /* Port A: open drain
configuration */
+#define ODCACLR         PIC32_R (0x60044)
+#define ODCASET         PIC32_R (0x60048)
+#define ODCAINV         PIC32_R (0x6004C)
+#define CNPUA           PIC32_R (0x60050) /* Port A: input pin
pull-up enable */
+#define CNPUACLR        PIC32_R (0x60054)
+#define CNPUASET        PIC32_R (0x60058)
+#define CNPUAINV        PIC32_R (0x6005C)
+#define CNPDA           PIC32_R (0x60060) /* Port A: input pin
pull-down enable */
+#define CNPDACLR        PIC32_R (0x60064)
+#define CNPDASET        PIC32_R (0x60068)
+#define CNPDAINV        PIC32_R (0x6006C)
+#define CNCONA          PIC32_R (0x60070) /* Port A:
interrupt-on-change control */
+#define CNCONACLR       PIC32_R (0x60074)
+#define CNCONASET       PIC32_R (0x60078)
+#define CNCONAINV       PIC32_R (0x6007C)
+#define CNENA           PIC32_R (0x60080) /* Port A: input change
interrupt enable */
+#define CNENACLR        PIC32_R (0x60084)
+#define CNENASET        PIC32_R (0x60088)
+#define CNENAINV        PIC32_R (0x6008C)
+#define CNSTATA         PIC32_R (0x60090) /* Port A: status */
+#define CNSTATACLR      PIC32_R (0x60094)
+#define CNSTATASET      PIC32_R (0x60098)
+#define CNSTATAINV      PIC32_R (0x6009C)
+
+#define ANSELB          PIC32_R (0x60100) /* Port B: analog select */
+#define ANSELBCLR       PIC32_R (0x60104)
+#define ANSELBSET       PIC32_R (0x60108)
+#define ANSELBINV       PIC32_R (0x6010C)
+#define TRISB           PIC32_R (0x60110) /* Port B: mask of inputs */
+#define TRISBCLR        PIC32_R (0x60114)
+#define TRISBSET        PIC32_R (0x60118)
+#define TRISBINV        PIC32_R (0x6011C)
+#define PORTB           PIC32_R (0x60120) /* Port B: read inputs,
write outputs */
+#define PORTBCLR        PIC32_R (0x60124)
+#define PORTBSET        PIC32_R (0x60128)
+#define PORTBINV        PIC32_R (0x6012C)
+#define LATB            PIC32_R (0x60130) /* Port B: read/write outputs */
+#define LATBCLR         PIC32_R (0x60134)
+#define LATBSET         PIC32_R (0x60138)
+#define LATBINV         PIC32_R (0x6013C)
+#define ODCB            PIC32_R (0x60140) /* Port B: open drain
configuration */
+#define ODCBCLR         PIC32_R (0x60144)
+#define ODCBSET         PIC32_R (0x60148)
+#define ODCBINV         PIC32_R (0x6014C)
+#define CNPUB           PIC32_R (0x60150) /* Port B: input pin
pull-up enable */
+#define CNPUBCLR        PIC32_R (0x60154)
+#define CNPUBSET        PIC32_R (0x60158)
+#define CNPUBINV        PIC32_R (0x6015C)
+#define CNPDB           PIC32_R (0x60160) /* Port B: input pin
pull-down enable */
+#define CNPDBCLR        PIC32_R (0x60164)
+#define CNPDBSET        PIC32_R (0x60168)
+#define CNPDBINV        PIC32_R (0x6016C)
+#define CNCONB          PIC32_R (0x60170) /* Port B:
interrupt-on-change control */
+#define CNCONBCLR       PIC32_R (0x60174)
+#define CNCONBSET       PIC32_R (0x60178)
+#define CNCONBINV       PIC32_R (0x6017C)
+#define CNENB           PIC32_R (0x60180) /* Port B: input change
interrupt enable */
+#define CNENBCLR        PIC32_R (0x60184)
+#define CNENBSET        PIC32_R (0x60188)
+#define CNENBINV        PIC32_R (0x6018C)
+#define CNSTATB         PIC32_R (0x60190) /* Port B: status */
+#define CNSTATBCLR      PIC32_R (0x60194)
+#define CNSTATBSET      PIC32_R (0x60198)
+#define CNSTATBINV      PIC32_R (0x6019C)
+
+#define ANSELC          PIC32_R (0x60200) /* Port C: analog select */
+#define ANSELCCLR       PIC32_R (0x60204)
+#define ANSELCSET       PIC32_R (0x60208)
+#define ANSELCINV       PIC32_R (0x6020C)
+#define TRISC           PIC32_R (0x60210) /* Port C: mask of inputs */
+#define TRISCCLR        PIC32_R (0x60214)
+#define TRISCSET        PIC32_R (0x60218)
+#define TRISCINV        PIC32_R (0x6021C)
+#define PORTC           PIC32_R (0x60220) /* Port C: read inputs,
write outputs */
+#define PORTCCLR        PIC32_R (0x60224)
+#define PORTCSET        PIC32_R (0x60228)
+#define PORTCINV        PIC32_R (0x6022C)
+#define LATC            PIC32_R (0x60230) /* Port C: read/write outputs */
+#define LATCCLR         PIC32_R (0x60234)
+#define LATCSET         PIC32_R (0x60238)
+#define LATCINV         PIC32_R (0x6023C)
+#define ODCC            PIC32_R (0x60240) /* Port C: open drain
configuration */
+#define ODCCCLR         PIC32_R (0x60244)
+#define ODCCSET         PIC32_R (0x60248)
+#define ODCCINV         PIC32_R (0x6024C)
+#define CNPUC           PIC32_R (0x60250) /* Port C: input pin
pull-up enable */
+#define CNPUCCLR        PIC32_R (0x60254)
+#define CNPUCSET        PIC32_R (0x60258)
+#define CNPUCINV        PIC32_R (0x6025C)
+#define CNPDC           PIC32_R (0x60260) /* Port C: input pin
pull-down enable */
+#define CNPDCCLR        PIC32_R (0x60264)
+#define CNPDCSET        PIC32_R (0x60268)
+#define CNPDCINV        PIC32_R (0x6026C)
+#define CNCONC          PIC32_R (0x60270) /* Port C:
interrupt-on-change control */
+#define CNCONCCLR       PIC32_R (0x60274)
+#define CNCONCSET       PIC32_R (0x60278)
+#define CNCONCINV       PIC32_R (0x6027C)
+#define CNENC           PIC32_R (0x60280) /* Port C: input change
interrupt enable */
+#define CNENCCLR        PIC32_R (0x60284)
+#define CNENCSET        PIC32_R (0x60288)
+#define CNENCINV        PIC32_R (0x6028C)
+#define CNSTATC         PIC32_R (0x60290) /* Port C: status */
+#define CNSTATCCLR      PIC32_R (0x60294)
+#define CNSTATCSET      PIC32_R (0x60298)
+#define CNSTATCINV      PIC32_R (0x6029C)
+
+#define ANSELD          PIC32_R (0x60300) /* Port D: analog select */
+#define ANSELDCLR       PIC32_R (0x60304)
+#define ANSELDSET       PIC32_R (0x60308)
+#define ANSELDINV       PIC32_R (0x6030C)
+#define TRISD           PIC32_R (0x60310) /* Port D: mask of inputs */
+#define TRISDCLR        PIC32_R (0x60314)
+#define TRISDSET        PIC32_R (0x60318)
+#define TRISDINV        PIC32_R (0x6031C)
+#define PORTD           PIC32_R (0x60320) /* Port D: read inputs,
write outputs */
+#define PORTDCLR        PIC32_R (0x60324)
+#define PORTDSET        PIC32_R (0x60328)
+#define PORTDINV        PIC32_R (0x6032C)
+#define LATD            PIC32_R (0x60330) /* Port D: read/write outputs */
+#define LATDCLR         PIC32_R (0x60334)
+#define LATDSET         PIC32_R (0x60338)
+#define LATDINV         PIC32_R (0x6033C)
+#define ODCD            PIC32_R (0x60340) /* Port D: open drain
configuration */
+#define ODCDCLR         PIC32_R (0x60344)
+#define ODCDSET         PIC32_R (0x60348)
+#define ODCDINV         PIC32_R (0x6034C)
+#define CNPUD           PIC32_R (0x60350) /* Port D: input pin
pull-up enable */
+#define CNPUDCLR        PIC32_R (0x60354)
+#define CNPUDSET        PIC32_R (0x60358)
+#define CNPUDINV        PIC32_R (0x6035C)
+#define CNPDD           PIC32_R (0x60360) /* Port D: input pin
pull-down enable */
+#define CNPDDCLR        PIC32_R (0x60364)
+#define CNPDDSET        PIC32_R (0x60368)
+#define CNPDDINV        PIC32_R (0x6036C)
+#define CNCOND          PIC32_R (0x60370) /* Port D:
interrupt-on-change control */
+#define CNCONDCLR       PIC32_R (0x60374)
+#define CNCONDSET       PIC32_R (0x60378)
+#define CNCONDINV       PIC32_R (0x6037C)
+#define CNEND           PIC32_R (0x60380) /* Port D: input change
interrupt enable */
+#define CNENDCLR        PIC32_R (0x60384)
+#define CNENDSET        PIC32_R (0x60388)
+#define CNENDINV        PIC32_R (0x6038C)
+#define CNSTATD         PIC32_R (0x60390) /* Port D: status */
+#define CNSTATDCLR      PIC32_R (0x60394)
+#define CNSTATDSET      PIC32_R (0x60398)
+#define CNSTATDINV      PIC32_R (0x6039C)
+
+#define ANSELE          PIC32_R (0x60400) /* Port E: analog select */
+#define ANSELECLR       PIC32_R (0x60404)
+#define ANSELESET       PIC32_R (0x60408)
+#define ANSELEINV       PIC32_R (0x6040C)
+#define TRISE           PIC32_R (0x60410) /* Port E: mask of inputs */
+#define TRISECLR        PIC32_R (0x60414)
+#define TRISESET        PIC32_R (0x60418)
+#define TRISEINV        PIC32_R (0x6041C)
+#define PORTE           PIC32_R (0x60420) /* Port E: read inputs,
write outputs */
+#define PORTECLR        PIC32_R (0x60424)
+#define PORTESET        PIC32_R (0x60428)
+#define PORTEINV        PIC32_R (0x6042C)
+#define LATE            PIC32_R (0x60430) /* Port E: read/write outputs */
+#define LATECLR         PIC32_R (0x60434)
+#define LATESET         PIC32_R (0x60438)
+#define LATEINV         PIC32_R (0x6043C)
+#define ODCE            PIC32_R (0x60440) /* Port E: open drain
configuration */
+#define ODCECLR         PIC32_R (0x60444)
+#define ODCESET         PIC32_R (0x60448)
+#define ODCEINV         PIC32_R (0x6044C)
+#define CNPUE           PIC32_R (0x60450) /* Port E: input pin
pull-up enable */
+#define CNPUECLR        PIC32_R (0x60454)
+#define CNPUESET        PIC32_R (0x60458)
+#define CNPUEINV        PIC32_R (0x6045C)
+#define CNPDE           PIC32_R (0x60460) /* Port E: input pin
pull-down enable */
+#define CNPDECLR        PIC32_R (0x60464)
+#define CNPDESET        PIC32_R (0x60468)
+#define CNPDEINV        PIC32_R (0x6046C)
+#define CNCONE          PIC32_R (0x60470) /* Port E:
interrupt-on-change control */
+#define CNCONECLR       PIC32_R (0x60474)
+#define CNCONESET       PIC32_R (0x60478)
+#define CNCONEINV       PIC32_R (0x6047C)
+#define CNENE           PIC32_R (0x60480) /* Port E: input change
interrupt enable */
+#define CNENECLR        PIC32_R (0x60484)
+#define CNENESET        PIC32_R (0x60488)
+#define CNENEINV        PIC32_R (0x6048C)
+#define CNSTATE         PIC32_R (0x60490) /* Port E: status */
+#define CNSTATECLR      PIC32_R (0x60494)
+#define CNSTATESET      PIC32_R (0x60498)
+#define CNSTATEINV      PIC32_R (0x6049C)
+
+#define ANSELF          PIC32_R (0x60500) /* Port F: analog select */
+#define ANSELFCLR       PIC32_R (0x60504)
+#define ANSELFSET       PIC32_R (0x60508)
+#define ANSELFINV       PIC32_R (0x6050C)
+#define TRISF           PIC32_R (0x60510) /* Port F: mask of inputs */
+#define TRISFCLR        PIC32_R (0x60514)
+#define TRISFSET        PIC32_R (0x60518)
+#define TRISFINV        PIC32_R (0x6051C)
+#define PORTF           PIC32_R (0x60520) /* Port F: read inputs,
write outputs */
+#define PORTFCLR        PIC32_R (0x60524)
+#define PORTFSET        PIC32_R (0x60528)
+#define PORTFINV        PIC32_R (0x6052C)
+#define LATF            PIC32_R (0x60530) /* Port F: read/write outputs */
+#define LATFCLR         PIC32_R (0x60534)
+#define LATFSET         PIC32_R (0x60538)
+#define LATFINV         PIC32_R (0x6053C)
+#define ODCF            PIC32_R (0x60540) /* Port F: open drain
configuration */
+#define ODCFCLR         PIC32_R (0x60544)
+#define ODCFSET         PIC32_R (0x60548)
+#define ODCFINV         PIC32_R (0x6054C)
+#define CNPUF           PIC32_R (0x60550) /* Port F: input pin
pull-up enable */
+#define CNPUFCLR        PIC32_R (0x60554)
+#define CNPUFSET        PIC32_R (0x60558)
+#define CNPUFINV        PIC32_R (0x6055C)
+#define CNPDF           PIC32_R (0x60560) /* Port F: input pin
pull-down enable */
+#define CNPDFCLR        PIC32_R (0x60564)
+#define CNPDFSET        PIC32_R (0x60568)
+#define CNPDFINV        PIC32_R (0x6056C)
+#define CNCONF          PIC32_R (0x60570) /* Port F:
interrupt-on-change control */
+#define CNCONFCLR       PIC32_R (0x60574)
+#define CNCONFSET       PIC32_R (0x60578)
+#define CNCONFINV       PIC32_R (0x6057C)
+#define CNENF           PIC32_R (0x60580) /* Port F: input change
interrupt enable */
+#define CNENFCLR        PIC32_R (0x60584)
+#define CNENFSET        PIC32_R (0x60588)
+#define CNENFINV        PIC32_R (0x6058C)
+#define CNSTATF         PIC32_R (0x60590) /* Port F: status */
+#define CNSTATFCLR      PIC32_R (0x60594)
+#define CNSTATFSET      PIC32_R (0x60598)
+#define CNSTATFINV      PIC32_R (0x6059C)
+
+#define ANSELG          PIC32_R (0x60600) /* Port G: analog select */
+#define ANSELGCLR       PIC32_R (0x60604)
+#define ANSELGSET       PIC32_R (0x60608)
+#define ANSELGINV       PIC32_R (0x6060C)
+#define TRISG           PIC32_R (0x60610) /* Port G: mask of inputs */
+#define TRISGCLR        PIC32_R (0x60614)
+#define TRISGSET        PIC32_R (0x60618)
+#define TRISGINV        PIC32_R (0x6061C)
+#define PORTG           PIC32_R (0x60620) /* Port G: read inputs,
write outputs */
+#define PORTGCLR        PIC32_R (0x60624)
+#define PORTGSET        PIC32_R (0x60628)
+#define PORTGINV        PIC32_R (0x6062C)
+#define LATG            PIC32_R (0x60630) /* Port G: read/write outputs */
+#define LATGCLR         PIC32_R (0x60634)
+#define LATGSET         PIC32_R (0x60638)
+#define LATGINV         PIC32_R (0x6063C)
+#define ODCG            PIC32_R (0x60640) /* Port G: open drain
configuration */
+#define ODCGCLR         PIC32_R (0x60644)
+#define ODCGSET         PIC32_R (0x60648)
+#define ODCGINV         PIC32_R (0x6064C)
+#define CNPUG           PIC32_R (0x60650) /* Port G: input pin
pull-up enable */
+#define CNPUGCLR        PIC32_R (0x60654)
+#define CNPUGSET        PIC32_R (0x60658)
+#define CNPUGINV        PIC32_R (0x6065C)
+#define CNPDG           PIC32_R (0x60660) /* Port G: input pin
pull-down enable */
+#define CNPDGCLR        PIC32_R (0x60664)
+#define CNPDGSET        PIC32_R (0x60668)
+#define CNPDGINV        PIC32_R (0x6066C)
+#define CNCONG          PIC32_R (0x60670) /* Port G:
interrupt-on-change control */
+#define CNCONGCLR       PIC32_R (0x60674)
+#define CNCONGSET       PIC32_R (0x60678)
+#define CNCONGINV       PIC32_R (0x6067C)
+#define CNENG           PIC32_R (0x60680) /* Port G: input change
interrupt enable */
+#define CNENGCLR        PIC32_R (0x60684)
+#define CNENGSET        PIC32_R (0x60688)
+#define CNENGINV        PIC32_R (0x6068C)
+#define CNSTATG         PIC32_R (0x60690) /* Port G: status */
+#define CNSTATGCLR      PIC32_R (0x60694)
+#define CNSTATGSET      PIC32_R (0x60698)
+#define CNSTATGINV      PIC32_R (0x6069C)
+
+#define ANSELH          PIC32_R (0x60700) /* Port H: analog select */
+#define ANSELHCLR       PIC32_R (0x60704)
+#define ANSELHSET       PIC32_R (0x60708)
+#define ANSELHINV       PIC32_R (0x6070C)
+#define TRISH           PIC32_R (0x60710) /* Port H: mask of inputs */
+#define TRISHCLR        PIC32_R (0x60714)
+#define TRISHSET        PIC32_R (0x60718)
+#define TRISHINV        PIC32_R (0x6071C)
+#define PORTH           PIC32_R (0x60720) /* Port H: read inputs,
write outputs */
+#define PORTHCLR        PIC32_R (0x60724)
+#define PORTHSET        PIC32_R (0x60728)
+#define PORTHINV        PIC32_R (0x6072C)
+#define LATH            PIC32_R (0x60730) /* Port H: read/write outputs */
+#define LATHCLR         PIC32_R (0x60734)
+#define LATHSET         PIC32_R (0x60738)
+#define LATHINV         PIC32_R (0x6073C)
+#define ODCH            PIC32_R (0x60740) /* Port H: open drain
configuration */
+#define ODCHCLR         PIC32_R (0x60744)
+#define ODCHSET         PIC32_R (0x60748)
+#define ODCHINV         PIC32_R (0x6074C)
+#define CNPUH           PIC32_R (0x60750) /* Port H: input pin
pull-up enable */
+#define CNPUHCLR        PIC32_R (0x60754)
+#define CNPUHSET        PIC32_R (0x60758)
+#define CNPUHINV        PIC32_R (0x6075C)
+#define CNPDH           PIC32_R (0x60760) /* Port H: input pin
pull-down enable */
+#define CNPDHCLR        PIC32_R (0x60764)
+#define CNPDHSET        PIC32_R (0x60768)
+#define CNPDHINV        PIC32_R (0x6076C)
+#define CNCONH          PIC32_R (0x60770) /* Port H:
interrupt-on-change control */
+#define CNCONHCLR       PIC32_R (0x60774)
+#define CNCONHSET       PIC32_R (0x60778)
+#define CNCONHINV       PIC32_R (0x6077C)
+#define CNENH           PIC32_R (0x60780) /* Port H: input change
interrupt enable */
+#define CNENHCLR        PIC32_R (0x60784)
+#define CNENHSET        PIC32_R (0x60788)
+#define CNENHINV        PIC32_R (0x6078C)
+#define CNSTATH         PIC32_R (0x60790) /* Port H: status */
+#define CNSTATHCLR      PIC32_R (0x60794)
+#define CNSTATHSET      PIC32_R (0x60798)
+#define CNSTATHINV      PIC32_R (0x6079C)
+
+#define ANSELJ          PIC32_R (0x60800) /* Port J: analog select */
+#define ANSELJCLR       PIC32_R (0x60804)
+#define ANSELJSET       PIC32_R (0x60808)
+#define ANSELJINV       PIC32_R (0x6080C)
+#define TRISJ           PIC32_R (0x60810) /* Port J: mask of inputs */
+#define TRISJCLR        PIC32_R (0x60814)
+#define TRISJSET        PIC32_R (0x60818)
+#define TRISJINV        PIC32_R (0x6081C)
+#define PORTJ           PIC32_R (0x60820) /* Port J: read inputs,
write outputs */
+#define PORTJCLR        PIC32_R (0x60824)
+#define PORTJSET        PIC32_R (0x60828)
+#define PORTJINV        PIC32_R (0x6082C)
+#define LATJ            PIC32_R (0x60830) /* Port J: read/write outputs */
+#define LATJCLR         PIC32_R (0x60834)
+#define LATJSET         PIC32_R (0x60838)
+#define LATJINV         PIC32_R (0x6083C)
+#define ODCJ            PIC32_R (0x60840) /* Port J: open drain
configuration */
+#define ODCJCLR         PIC32_R (0x60844)
+#define ODCJSET         PIC32_R (0x60848)
+#define ODCJINV         PIC32_R (0x6084C)
+#define CNPUJ           PIC32_R (0x60850) /* Port J: input pin
pull-up enable */
+#define CNPUJCLR        PIC32_R (0x60854)
+#define CNPUJSET        PIC32_R (0x60858)
+#define CNPUJINV        PIC32_R (0x6085C)
+#define CNPDJ           PIC32_R (0x60860) /* Port J: input pin
pull-down enable */
+#define CNPDJCLR        PIC32_R (0x60864)
+#define CNPDJSET        PIC32_R (0x60868)
+#define CNPDJINV        PIC32_R (0x6086C)
+#define CNCONJ          PIC32_R (0x60870) /* Port J:
interrupt-on-change control */
+#define CNCONJCLR       PIC32_R (0x60874)
+#define CNCONJSET       PIC32_R (0x60878)
+#define CNCONJINV       PIC32_R (0x6087C)
+#define CNENJ           PIC32_R (0x60880) /* Port J: input change
interrupt enable */
+#define CNENJCLR        PIC32_R (0x60884)
+#define CNENJSET        PIC32_R (0x60888)
+#define CNENJINV        PIC32_R (0x6088C)
+#define CNSTATJ         PIC32_R (0x60890) /* Port J: status */
+#define CNSTATJCLR      PIC32_R (0x60894)
+#define CNSTATJSET      PIC32_R (0x60898)
+#define CNSTATJINV      PIC32_R (0x6089C)
+
+#define TRISK           PIC32_R (0x60910) /* Port K: mask of inputs */
+#define TRISKCLR        PIC32_R (0x60914)
+#define TRISKSET        PIC32_R (0x60918)
+#define TRISKINV        PIC32_R (0x6091C)
+#define PORTK           PIC32_R (0x60920) /* Port K: read inputs,
write outputs */
+#define PORTKCLR        PIC32_R (0x60924)
+#define PORTKSET        PIC32_R (0x60928)
+#define PORTKINV        PIC32_R (0x6092C)
+#define LATK            PIC32_R (0x60930) /* Port K: read/write outputs */
+#define LATKCLR         PIC32_R (0x60934)
+#define LATKSET         PIC32_R (0x60938)
+#define LATKINV         PIC32_R (0x6093C)
+#define ODCK            PIC32_R (0x60940) /* Port K: open drain
configuration */
+#define ODCKCLR         PIC32_R (0x60944)
+#define ODCKSET         PIC32_R (0x60948)
+#define ODCKINV         PIC32_R (0x6094C)
+#define CNPUK           PIC32_R (0x60950) /* Port K: input pin
pull-up enable */
+#define CNPUKCLR        PIC32_R (0x60954)
+#define CNPUKSET        PIC32_R (0x60958)
+#define CNPUKINV        PIC32_R (0x6095C)
+#define CNPDK           PIC32_R (0x60960) /* Port K: input pin
pull-down enable */
+#define CNPDKCLR        PIC32_R (0x60964)
+#define CNPDKSET        PIC32_R (0x60968)
+#define CNPDKINV        PIC32_R (0x6096C)
+#define CNCONK          PIC32_R (0x60970) /* Port K:
interrupt-on-change control */
+#define CNCONKCLR       PIC32_R (0x60974)
+#define CNCONKSET       PIC32_R (0x60978)
+#define CNCONKINV       PIC32_R (0x6097C)
+#define CNENK           PIC32_R (0x60980) /* Port K: input change
interrupt enable */
+#define CNENKCLR        PIC32_R (0x60984)
+#define CNENKSET        PIC32_R (0x60988)
+#define CNENKINV        PIC32_R (0x6098C)
+#define CNSTATK         PIC32_R (0x60990) /* Port K: status */
+#define CNSTATKCLR      PIC32_R (0x60994)
+#define CNSTATKSET      PIC32_R (0x60998)
+#define CNSTATKINV      PIC32_R (0x6099C)
+
+/*--------------------------------------
+ * Timer registers.
+ */
+#define T1CON           PIC32_R (0x40000) /* Timer 1: Control */
+#define T1CONCLR        PIC32_R (0x40004)
+#define T1CONSET        PIC32_R (0x40008)
+#define T1CONINV        PIC32_R (0x4000C)
+#define TMR1            PIC32_R (0x40010) /* Timer 1: Count */
+#define TMR1CLR         PIC32_R (0x40014)
+#define TMR1SET         PIC32_R (0x40018)
+#define TMR1INV         PIC32_R (0x4001C)
+#define PR1             PIC32_R (0x40020) /* Timer 1: Period register */
+#define PR1CLR          PIC32_R (0x40024)
+#define PR1SET          PIC32_R (0x40028)
+#define PR1INV          PIC32_R (0x4002C)
+#define T2CON           PIC32_R (0x40200) /* Timer 2: Control */
+#define T2CONCLR        PIC32_R (0x40204)
+#define T2CONSET        PIC32_R (0x40208)
+#define T2CONINV        PIC32_R (0x4020C)
+#define TMR2            PIC32_R (0x40210) /* Timer 2: Count */
+#define TMR2CLR         PIC32_R (0x40214)
+#define TMR2SET         PIC32_R (0x40218)
+#define TMR2INV         PIC32_R (0x4021C)
+#define PR2             PIC32_R (0x40220) /* Timer 2: Period register */
+#define PR2CLR          PIC32_R (0x40224)
+#define PR2SET          PIC32_R (0x40228)
+#define PR2INV          PIC32_R (0x4022C)
+#define T3CON           PIC32_R (0x40400) /* Timer 3: Control */
+#define T3CONCLR        PIC32_R (0x40404)
+#define T3CONSET        PIC32_R (0x40408)
+#define T3CONINV        PIC32_R (0x4040C)
+#define TMR3            PIC32_R (0x40410) /* Timer 3: Count */
+#define TMR3CLR         PIC32_R (0x40414)
+#define TMR3SET         PIC32_R (0x40418)
+#define TMR3INV         PIC32_R (0x4041C)
+#define PR3             PIC32_R (0x40420) /* Timer 3: Period register */
+#define PR3CLR          PIC32_R (0x40424)
+#define PR3SET          PIC32_R (0x40428)
+#define PR3INV          PIC32_R (0x4042C)
+#define T4CON           PIC32_R (0x40600) /* Timer 4: Control */
+#define T4CONCLR        PIC32_R (0x40604)
+#define T4CONSET        PIC32_R (0x40608)
+#define T4CONINV        PIC32_R (0x4060C)
+#define TMR4            PIC32_R (0x40610) /* Timer 4: Count */
+#define TMR4CLR         PIC32_R (0x40614)
+#define TMR4SET         PIC32_R (0x40618)
+#define TMR4INV         PIC32_R (0x4061C)
+#define PR4             PIC32_R (0x40620) /* Timer 4: Period register */
+#define PR4CLR          PIC32_R (0x40624)
+#define PR4SET          PIC32_R (0x40628)
+#define PR4INV          PIC32_R (0x4062C)
+#define T5CON           PIC32_R (0x40800) /* Timer 5: Control */
+#define T5CONCLR        PIC32_R (0x40804)
+#define T5CONSET        PIC32_R (0x40808)
+#define T5CONINV        PIC32_R (0x4080C)
+#define TMR5            PIC32_R (0x40810) /* Timer 5: Count */
+#define TMR5CLR         PIC32_R (0x40814)
+#define TMR5SET         PIC32_R (0x40818)
+#define TMR5INV         PIC32_R (0x4081C)
+#define PR5             PIC32_R (0x40820) /* Timer 5: Period register */
+#define PR5CLR          PIC32_R (0x40824)
+#define PR5SET          PIC32_R (0x40828)
+#define PR5INV          PIC32_R (0x4082C)
+#define T6CON           PIC32_R (0x40A00) /* Timer 6: Control */
+#define T6CONCLR        PIC32_R (0x40A04)
+#define T6CONSET        PIC32_R (0x40A08)
+#define T6CONINV        PIC32_R (0x40A0C)
+#define TMR6            PIC32_R (0x40A10) /* Timer 6: Count */
+#define TMR6CLR         PIC32_R (0x40A14)
+#define TMR6SET         PIC32_R (0x40A18)
+#define TMR6INV         PIC32_R (0x40A1C)
+#define PR6             PIC32_R (0x40A20) /* Timer 6: Period register */
+#define PR6CLR          PIC32_R (0x40A24)
+#define PR6SET          PIC32_R (0x40A28)
+#define PR6INV          PIC32_R (0x40A2C)
+#define T7CON           PIC32_R (0x40C00) /* Timer 7: Control */
+#define T7CONCLR        PIC32_R (0x40C04)
+#define T7CONSET        PIC32_R (0x40C08)
+#define T7CONINV        PIC32_R (0x40C0C)
+#define TMR7            PIC32_R (0x40C10) /* Timer 7: Count */
+#define TMR7CLR         PIC32_R (0x40C14)
+#define TMR7SET         PIC32_R (0x40C18)
+#define TMR7INV         PIC32_R (0x40C1C)
+#define PR7             PIC32_R (0x40C20) /* Timer 7: Period register */
+#define PR7CLR          PIC32_R (0x40C24)
+#define PR7SET          PIC32_R (0x40C28)
+#define PR7INV          PIC32_R (0x40C2C)
+#define T8CON           PIC32_R (0x40E00) /* Timer 8: Control */
+#define T8CONCLR        PIC32_R (0x40E04)
+#define T8CONSET        PIC32_R (0x40E08)
+#define T8CONINV        PIC32_R (0x40E0C)
+#define TMR8            PIC32_R (0x40E10) /* Timer 8: Count */
+#define TMR8CLR         PIC32_R (0x40E14)
+#define TMR8SET         PIC32_R (0x40E18)
+#define TMR8INV         PIC32_R (0x40E1C)
+#define PR8             PIC32_R (0x40E20) /* Timer 8: Period register */
+#define PR8CLR          PIC32_R (0x40E24)
+#define PR8SET          PIC32_R (0x40E28)
+#define PR8INV          PIC32_R (0x40E2C)
+#define T9CON           PIC32_R (0x41000) /* Timer 9: Control */
+#define T9CONCLR        PIC32_R (0x41004)
+#define T9CONSET        PIC32_R (0x41008)
+#define T9CONINV        PIC32_R (0x4100C)
+#define TMR9            PIC32_R (0x41010) /* Timer 9: Count */
+#define TMR9CLR         PIC32_R (0x41014)
+#define TMR9SET         PIC32_R (0x41018)
+#define TMR9INV         PIC32_R (0x4101C)
+#define PR9             PIC32_R (0x41020) /* Timer 9: Period register */
+#define PR9CLR          PIC32_R (0x41024)
+#define PR9SET          PIC32_R (0x41028)
+#define PR9INV          PIC32_R (0x4102C)
+
+/*--------------------------------------
+ * Parallel master port registers.
+ */
+#define PMCON           PIC32_R (0x2E000) /* Control */
+#define PMCONCLR        PIC32_R (0x2E004)
+#define PMCONSET        PIC32_R (0x2E008)
+#define PMCONINV        PIC32_R (0x2E00C)
+#define PMMODE          PIC32_R (0x2E010) /* Mode */
+#define PMMODECLR       PIC32_R (0x2E014)
+#define PMMODESET       PIC32_R (0x2E018)
+#define PMMODEINV       PIC32_R (0x2E01C)
+#define PMADDR          PIC32_R (0x2E020) /* Address */
+#define PMADDRCLR       PIC32_R (0x2E024)
+#define PMADDRSET       PIC32_R (0x2E028)
+#define PMADDRINV       PIC32_R (0x2E02C)
+#define PMDOUT          PIC32_R (0x2E030) /* Data output */
+#define PMDOUTCLR       PIC32_R (0x2E034)
+#define PMDOUTSET       PIC32_R (0x2E038)
+#define PMDOUTINV       PIC32_R (0x2E03C)
+#define PMDIN           PIC32_R (0x2E040) /* Data input */
+#define PMDINCLR        PIC32_R (0x2E044)
+#define PMDINSET        PIC32_R (0x2E048)
+#define PMDININV        PIC32_R (0x2E04C)
+#define PMAEN           PIC32_R (0x2E050) /* Pin enable */
+#define PMAENCLR        PIC32_R (0x2E054)
+#define PMAENSET        PIC32_R (0x2E058)
+#define PMAENINV        PIC32_R (0x2E05C)
+#define PMSTAT          PIC32_R (0x2E060) /* Status (slave only) */
+#define PMSTATCLR       PIC32_R (0x2E064)
+#define PMSTATSET       PIC32_R (0x2E068)
+#define PMSTATINV       PIC32_R (0x2E06C)
+
+/*
+ * PMP Control register.
+ */
+#define PIC32_PMCON_RDSP        0x0001 /* Read strobe polarity active-high */
+#define PIC32_PMCON_WRSP        0x0002 /* Write strobe polarity active-high */
+#define PIC32_PMCON_CS1P        0x0008 /* Chip select 0 polarity active-high */
+#define PIC32_PMCON_CS2P        0x0010 /* Chip select 1 polarity active-high */
+#define PIC32_PMCON_ALP         0x0020 /* Address latch polarity active-high */
+#define PIC32_PMCON_CSF         0x00C0 /* Chip select function bitmask: */
+#define PIC32_PMCON_CSF_NONE    0x0000 /* PMCS2 and PMCS1 as A[15:14] */
+#define PIC32_PMCON_CSF_CS2     0x0040 /* PMCS2 as chip select */
+#define PIC32_PMCON_CSF_CS21    0x0080 /* PMCS2 and PMCS1 as chip select */
+#define PIC32_PMCON_PTRDEN      0x0100 /* Read/write strobe port enable */
+#define PIC32_PMCON_PTWREN      0x0200 /* Write enable strobe port enable */
+#define PIC32_PMCON_PMPTTL      0x0400 /* TTL input buffer select */
+#define PIC32_PMCON_ADRMUX      0x1800 /* Address/data mux selection
bitmask: */
+#define PIC32_PMCON_ADRMUX_NONE 0x0000 /* Address and data separate */
+#define PIC32_PMCON_ADRMUX_AD   0x0800 /* Lower address on PMD[7:0],
high on PMA[15:8] */
+#define PIC32_PMCON_ADRMUX_D8   0x1000 /* All address on PMD[7:0] */
+#define PIC32_PMCON_ADRMUX_D16  0x1800 /* All address on PMD[15:0] */
+#define PIC32_PMCON_SIDL        0x2000 /* Stop in idle */
+#define PIC32_PMCON_FRZ         0x4000 /* Freeze in debug exception */
+#define PIC32_PMCON_ON          0x8000 /* Parallel master port enable */
+
+/*
+ * PMP Mode register.
+ */
+#define PIC32_PMMODE_WAITE(x)   ((x)<<0) /* Wait states: data hold
after RW strobe */
+#define PIC32_PMMODE_WAITM(x)   ((x)<<2) /* Wait states: data RW strobe */
+#define PIC32_PMMODE_WAITB(x)   ((x)<<6) /* Wait states: data setup
to RW strobe */
+#define PIC32_PMMODE_MODE       0x0300  /* Mode select bitmask: */
+#define PIC32_PMMODE_MODE_SLAVE 0x0000  /* Legacy slave */
+#define PIC32_PMMODE_MODE_SLENH 0x0100  /* Enhanced slave */
+#define PIC32_PMMODE_MODE_MAST2 0x0200  /* Master mode 2 */
+#define PIC32_PMMODE_MODE_MAST1 0x0300  /* Master mode 1 */
+#define PIC32_PMMODE_MODE16     0x0400  /* 16-bit mode */
+#define PIC32_PMMODE_INCM       0x1800  /* Address increment mode bitmask: */
+#define PIC32_PMMODE_INCM_NONE  0x0000  /* No increment/decrement */
+#define PIC32_PMMODE_INCM_INC   0x0800  /* Increment address */
+#define PIC32_PMMODE_INCM_DEC   0x1000  /* Decrement address */
+#define PIC32_PMMODE_INCM_SLAVE 0x1800  /* Slave auto-increment */
+#define PIC32_PMMODE_IRQM       0x6000  /* Interrupt request bitmask: */
+#define PIC32_PMMODE_IRQM_DIS   0x0000  /* No interrupt generated */
+#define PIC32_PMMODE_IRQM_END   0x2000  /* Interrupt at end of
read/write cycle */
+#define PIC32_PMMODE_IRQM_A3    0x4000  /* Interrupt on address 3 */
+#define PIC32_PMMODE_BUSY       0x8000  /* Port is busy */
+
+/*
+ * PMP Address register.
+ */
+#define PIC32_PMADDR_PADDR      0x3FFF /* Destination address */
+#define PIC32_PMADDR_CS1        0x4000 /* Chip select 1 is active */
+#define PIC32_PMADDR_CS2        0x8000 /* Chip select 2 is active */
+
+/*
+ * PMP status register (slave only).
+ */
+#define PIC32_PMSTAT_OB0E       0x0001 /* Output buffer 0 empty */
+#define PIC32_PMSTAT_OB1E       0x0002 /* Output buffer 1 empty */
+#define PIC32_PMSTAT_OB2E       0x0004 /* Output buffer 2 empty */
+#define PIC32_PMSTAT_OB3E       0x0008 /* Output buffer 3 empty */
+#define PIC32_PMSTAT_OBUF       0x0040 /* Output buffer underflow */
+#define PIC32_PMSTAT_OBE        0x0080 /* Output buffer empty */
+#define PIC32_PMSTAT_IB0F       0x0100 /* Input buffer 0 full */
+#define PIC32_PMSTAT_IB1F       0x0200 /* Input buffer 1 full */
+#define PIC32_PMSTAT_IB2F       0x0400 /* Input buffer 2 full */
+#define PIC32_PMSTAT_IB3F       0x0800 /* Input buffer 3 full */
+#define PIC32_PMSTAT_IBOV       0x4000 /* Input buffer overflow */
+#define PIC32_PMSTAT_IBF        0x8000 /* Input buffer full */
+
+/*--------------------------------------
+ * UART registers.
+ */
+#define U1MODE          PIC32_R (0x22000) /* Mode */
+#define U1MODECLR       PIC32_R (0x22004)
+#define U1MODESET       PIC32_R (0x22008)
+#define U1MODEINV       PIC32_R (0x2200C)
+#define U1STA           PIC32_R (0x22010) /* Status and control */
+#define U1STACLR        PIC32_R (0x22014)
+#define U1STASET        PIC32_R (0x22018)
+#define U1STAINV        PIC32_R (0x2201C)
+#define U1TXREG         PIC32_R (0x22020) /* Transmit */
+#define U1RXREG         PIC32_R (0x22030) /* Receive */
+#define U1BRG           PIC32_R (0x22040) /* Baud rate */
+#define U1BRGCLR        PIC32_R (0x22044)
+#define U1BRGSET        PIC32_R (0x22048)
+#define U1BRGINV        PIC32_R (0x2204C)
+
+#define U2MODE          PIC32_R (0x22200) /* Mode */
+#define U2MODECLR       PIC32_R (0x22204)
+#define U2MODESET       PIC32_R (0x22208)
+#define U2MODEINV       PIC32_R (0x2220C)
+#define U2STA           PIC32_R (0x22210) /* Status and control */
+#define U2STACLR        PIC32_R (0x22214)
+#define U2STASET        PIC32_R (0x22218)
+#define U2STAINV        PIC32_R (0x2221C)
+#define U2TXREG         PIC32_R (0x22220) /* Transmit */
+#define U2RXREG         PIC32_R (0x22230) /* Receive */
+#define U2BRG           PIC32_R (0x22240) /* Baud rate */
+#define U2BRGCLR        PIC32_R (0x22244)
+#define U2BRGSET        PIC32_R (0x22248)
+#define U2BRGINV        PIC32_R (0x2224C)
+
+#define U3MODE          PIC32_R (0x22400) /* Mode */
+#define U3MODECLR       PIC32_R (0x22404)
+#define U3MODESET       PIC32_R (0x22408)
+#define U3MODEINV       PIC32_R (0x2240C)
+#define U3STA           PIC32_R (0x22410) /* Status and control */
+#define U3STACLR        PIC32_R (0x22414)
+#define U3STASET        PIC32_R (0x22418)
+#define U3STAINV        PIC32_R (0x2241C)
+#define U3TXREG         PIC32_R (0x22420) /* Transmit */
+#define U3RXREG         PIC32_R (0x22430) /* Receive */
+#define U3BRG           PIC32_R (0x22440) /* Baud rate */
+#define U3BRGCLR        PIC32_R (0x22444)
+#define U3BRGSET        PIC32_R (0x22448)
+#define U3BRGINV        PIC32_R (0x2244C)
+
+#define U4MODE          PIC32_R (0x22600) /* Mode */
+#define U4MODECLR       PIC32_R (0x22604)
+#define U4MODESET       PIC32_R (0x22608)
+#define U4MODEINV       PIC32_R (0x2260C)
+#define U4STA           PIC32_R (0x22610) /* Status and control */
+#define U4STACLR        PIC32_R (0x22614)
+#define U4STASET        PIC32_R (0x22618)
+#define U4STAINV        PIC32_R (0x2261C)
+#define U4TXREG         PIC32_R (0x22620) /* Transmit */
+#define U4RXREG         PIC32_R (0x22630) /* Receive */
+#define U4BRG           PIC32_R (0x22640) /* Baud rate */
+#define U4BRGCLR        PIC32_R (0x22644)
+#define U4BRGSET        PIC32_R (0x22648)
+#define U4BRGINV        PIC32_R (0x2264C)
+
+#define U5MODE          PIC32_R (0x22800) /* Mode */
+#define U5MODECLR       PIC32_R (0x22804)
+#define U5MODESET       PIC32_R (0x22808)
+#define U5MODEINV       PIC32_R (0x2280C)
+#define U5STA           PIC32_R (0x22810) /* Status and control */
+#define U5STACLR        PIC32_R (0x22814)
+#define U5STASET        PIC32_R (0x22818)
+#define U5STAINV        PIC32_R (0x2281C)
+#define U5TXREG         PIC32_R (0x22820) /* Transmit */
+#define U5RXREG         PIC32_R (0x22830) /* Receive */
+#define U5BRG           PIC32_R (0x22840) /* Baud rate */
+#define U5BRGCLR        PIC32_R (0x22844)
+#define U5BRGSET        PIC32_R (0x22848)
+#define U5BRGINV        PIC32_R (0x2284C)
+
+#define U6MODE          PIC32_R (0x22A00) /* Mode */
+#define U6MODECLR       PIC32_R (0x22A04)
+#define U6MODESET       PIC32_R (0x22A08)
+#define U6MODEINV       PIC32_R (0x22A0C)
+#define U6STA           PIC32_R (0x22A10) /* Status and control */
+#define U6STACLR        PIC32_R (0x22A14)
+#define U6STASET        PIC32_R (0x22A18)
+#define U6STAINV        PIC32_R (0x22A1C)
+#define U6TXREG         PIC32_R (0x22A20) /* Transmit */
+#define U6RXREG         PIC32_R (0x22A30) /* Receive */
+#define U6BRG           PIC32_R (0x22A40) /* Baud rate */
+#define U6BRGCLR        PIC32_R (0x22A44)
+#define U6BRGSET        PIC32_R (0x22A48)
+#define U6BRGINV        PIC32_R (0x22A4C)
+
+/*
+ * UART Mode register.
+ */
+#define PIC32_UMODE_STSEL       0x0001  /* 2 Stop bits */
+#define PIC32_UMODE_PDSEL       0x0006  /* Bitmask: */
+#define PIC32_UMODE_PDSEL_8NPAR 0x0000  /* 8-bit data, no parity */
+#define PIC32_UMODE_PDSEL_8EVEN 0x0002  /* 8-bit data, even parity */
+#define PIC32_UMODE_PDSEL_8ODD  0x0004  /* 8-bit data, odd parity */
+#define PIC32_UMODE_PDSEL_9NPAR 0x0006  /* 9-bit data, no parity */
+#define PIC32_UMODE_BRGH        0x0008  /* High Baud Rate Enable */
+#define PIC32_UMODE_RXINV       0x0010  /* Receive Polarity Inversion */
+#define PIC32_UMODE_ABAUD       0x0020  /* Auto-Baud Enable */
+#define PIC32_UMODE_LPBACK      0x0040  /* UARTx Loopback Mode */
+#define PIC32_UMODE_WAKE        0x0080  /* Wake-up on start bit
during Sleep Mode */
+#define PIC32_UMODE_UEN         0x0300  /* Bitmask: */
+#define PIC32_UMODE_UEN_RTS     0x0100  /* Using UxRTS pin */
+#define PIC32_UMODE_UEN_RTSCTS  0x0200  /* Using UxCTS and UxRTS pins */
+#define PIC32_UMODE_UEN_BCLK    0x0300  /* Using UxBCLK pin */
+#define PIC32_UMODE_RTSMD       0x0800  /* UxRTS Pin Simplex mode */
+#define PIC32_UMODE_IREN        0x1000  /* IrDA Encoder and Decoder
Enable bit */
+#define PIC32_UMODE_SIDL        0x2000  /* Stop in Idle Mode */
+#define PIC32_UMODE_FRZ         0x4000  /* Freeze in Debug Exception Mode */
+#define PIC32_UMODE_ON          0x8000  /* UART Enable */
+
+/*
+ * UART Control and status register.
+ */
+#define PIC32_USTA_URXDA        0x00000001 /* Receive Data Available
(read-only) */
+#define PIC32_USTA_OERR         0x00000002 /* Receive Buffer Overrun */
+#define PIC32_USTA_FERR         0x00000004 /* Framing error detected
(read-only) */
+#define PIC32_USTA_PERR         0x00000008 /* Parity error detected
(read-only) */
+#define PIC32_USTA_RIDLE        0x00000010 /* Receiver is idle (read-only) */
+#define PIC32_USTA_ADDEN        0x00000020 /* Address Detect mode */
+#define PIC32_USTA_URXISEL      0x000000C0 /* Bitmask: receive
interrupt is set when... */
+#define PIC32_USTA_URXISEL_NEMP 0x00000000 /* ...receive buffer is not empty */
+#define PIC32_USTA_URXISEL_HALF 0x00000040 /* ...receive buffer
becomes 1/2 full */
+#define PIC32_USTA_URXISEL_3_4  0x00000080 /* ...receive buffer
becomes 3/4 full */
+#define PIC32_USTA_TRMT         0x00000100 /* Transmit shift register
is empty (read-only) */
+#define PIC32_USTA_UTXBF        0x00000200 /* Transmit buffer is full
(read-only) */
+#define PIC32_USTA_UTXEN        0x00000400 /* Transmit Enable */
+#define PIC32_USTA_UTXBRK       0x00000800 /* Transmit Break */
+#define PIC32_USTA_URXEN        0x00001000 /* Receiver Enable */
+#define PIC32_USTA_UTXINV       0x00002000 /* Transmit Polarity Inversion */
+#define PIC32_USTA_UTXISEL      0x0000C000 /* Bitmask: TX interrupt
is generated when... */
+#define PIC32_USTA_UTXISEL_1    0x00000000 /* ...the transmit buffer
contains at least one empty space */
+#define PIC32_USTA_UTXISEL_ALL  0x00004000 /* ...all characters have
been transmitted */
+#define PIC32_USTA_UTXISEL_EMP  0x00008000 /* ...the transmit buffer
becomes empty */
+#define PIC32_USTA_ADDR         0x00FF0000 /* Automatic Address Mask */
+#define PIC32_USTA_ADM_EN       0x01000000 /* Automatic Address Detect */
+
+/*
+ * Compute the 16-bit baud rate divisor, given
+ * the bus frequency and baud rate.
+ * Round to the nearest integer.
+ */
+#define PIC32_BRG_BAUD(fr,bd)   ((((fr)/8 + (bd)) / (bd) / 2) - 1)
+
+/*--------------------------------------
+ * Peripheral port select registers.
+ */
+#define INT1R           PIC32_R (0x1404)
+#define INT2R           PIC32_R (0x1408)
+#define INT3R           PIC32_R (0x140C)
+#define INT4R           PIC32_R (0x1410)
+#define T2CKR           PIC32_R (0x1418)
+#define T3CKR           PIC32_R (0x141C)
+#define T4CKR           PIC32_R (0x1420)
+#define T5CKR           PIC32_R (0x1424)
+#define T6CKR           PIC32_R (0x1428)
+#define T7CKR           PIC32_R (0x142C)
+#define T8CKR           PIC32_R (0x1430)
+#define T9CKR           PIC32_R (0x1434)
+#define IC1R            PIC32_R (0x1438)
+#define IC2R            PIC32_R (0x143C)
+#define IC3R            PIC32_R (0x1440)
+#define IC4R            PIC32_R (0x1444)
+#define IC5R            PIC32_R (0x1448)
+#define IC6R            PIC32_R (0x144C)
+#define IC7R            PIC32_R (0x1450)
+#define IC8R            PIC32_R (0x1454)
+#define IC9R            PIC32_R (0x1458)
+#define OCFAR           PIC32_R (0x1460)
+#define U1RXR           PIC32_R (0x1468)
+#define U1CTSR          PIC32_R (0x146C)
+#define U2RXR           PIC32_R (0x1470)
+#define U2CTSR          PIC32_R (0x1474)
+#define U3RXR           PIC32_R (0x1478)
+#define U3CTSR          PIC32_R (0x147C)
+#define U4RXR           PIC32_R (0x1480)
+#define U4CTSR          PIC32_R (0x1484)
+#define U5RXR           PIC32_R (0x1488)
+#define U5CTSR          PIC32_R (0x148C)
+#define U6RXR           PIC32_R (0x1490)
+#define U6CTSR          PIC32_R (0x1494)
+#define SDI1R           PIC32_R (0x149C)
+#define SS1R            PIC32_R (0x14A0)
+#define SDI2R           PIC32_R (0x14A8)
+#define SS2R            PIC32_R (0x14AC)
+#define SDI3R           PIC32_R (0x14B4)
+#define SS3R            PIC32_R (0x14B8)
+#define SDI4R           PIC32_R (0x14C0)
+#define SS4R            PIC32_R (0x14C4)
+#define SDI5R           PIC32_R (0x14CC)
+#define SS5R            PIC32_R (0x14D0)
+#define SDI6R           PIC32_R (0x14D8)
+#define SS6R            PIC32_R (0x14DC)
+#define C1RXR           PIC32_R (0x14E0)
+#define C2RXR           PIC32_R (0x14E4)
+#define REFCLKI1R       PIC32_R (0x14E8)
+#define REFCLKI3R       PIC32_R (0x14F0)
+#define REFCLKI4R       PIC32_R (0x14F4)
+
+#define RPA14R          PIC32_R (0x1538)
+#define RPA15R          PIC32_R (0x153C)
+#define RPB0R           PIC32_R (0x1540)
+#define RPB1R           PIC32_R (0x1544)
+#define RPB2R           PIC32_R (0x1548)
+#define RPB3R           PIC32_R (0x154C)
+#define RPB5R           PIC32_R (0x1554)
+#define RPB6R           PIC32_R (0x1558)
+#define RPB7R           PIC32_R (0x155C)
+#define RPB8R           PIC32_R (0x1560)
+#define RPB9R           PIC32_R (0x1564)
+#define RPB10R          PIC32_R (0x1568)
+#define RPB14R          PIC32_R (0x1578)
+#define RPB15R          PIC32_R (0x157C)
+#define RPC1R           PIC32_R (0x1584)
+#define RPC2R           PIC32_R (0x1588)
+#define RPC3R           PIC32_R (0x158C)
+#define RPC4R           PIC32_R (0x1590)
+#define RPC13R          PIC32_R (0x15B4)
+#define RPC14R          PIC32_R (0x15B8)
+#define RPD0R           PIC32_R (0x15C0)
+#define RPD1R           PIC32_R (0x15C4)
+#define RPD2R           PIC32_R (0x15C8)
+#define RPD3R           PIC32_R (0x15CC)
+#define RPD4R           PIC32_R (0x15D0)
+#define RPD5R           PIC32_R (0x15D4)
+#define RPD6R           PIC32_R (0x15D8)
+#define RPD7R           PIC32_R (0x15DC)
+#define RPD9R           PIC32_R (0x15E4)
+#define RPD10R          PIC32_R (0x15E8)
+#define RPD11R          PIC32_R (0x15EC)
+#define RPD12R          PIC32_R (0x15F0)
+#define RPD14R          PIC32_R (0x15F8)
+#define RPD15R          PIC32_R (0x15FC)
+#define RPE3R           PIC32_R (0x160C)
+#define RPE5R           PIC32_R (0x1614)
+#define RPE8R           PIC32_R (0x1620)
+#define RPE9R           PIC32_R (0x1624)
+#define RPF0R           PIC32_R (0x1640)
+#define RPF1R           PIC32_R (0x1644)
+#define RPF2R           PIC32_R (0x1648)
+#define RPF3R           PIC32_R (0x164C)
+#define RPF4R           PIC32_R (0x1650)
+#define RPF5R           PIC32_R (0x1654)
+#define RPF8R           PIC32_R (0x1660)
+#define RPF12R          PIC32_R (0x1670)
+#define RPF13R          PIC32_R (0x1674)
+#define RPG0R           PIC32_R (0x1680)
+#define RPG1R           PIC32_R (0x1684)
+#define RPG6R           PIC32_R (0x1698)
+#define RPG7R           PIC32_R (0x169C)
+#define RPG8R           PIC32_R (0x16A0)
+#define RPG9R           PIC32_R (0x16A4)
+
+/*--------------------------------------
+ * Prefetch cache controller registers.
+ */
+#define PRECON          PIC32_R (0xe0000)       /* Prefetch cache control */
+#define PRECONCLR       PIC32_R (0xe0004)
+#define PRECONSET       PIC32_R (0xe0008)
+#define PRECONINV       PIC32_R (0xe000C)
+#define PRESTAT         PIC32_R (0xe0010)       /* Prefetch status */
+#define PRESTATCLR      PIC32_R (0xe0014)
+#define PRESTATSET      PIC32_R (0xe0018)
+#define PRESTATINV      PIC32_R (0xe001C)
+// TODO: other prefetch registers
+
+/*--------------------------------------
+ * System controller registers.
+ */
+#define CFGCON          PIC32_R (0x0000)
+#define DEVID           PIC32_R (0x0020)
+#define SYSKEY          PIC32_R (0x0030)
+#define CFGEBIA         PIC32_R (0x00c0)
+#define CFGEBIACLR      PIC32_R (0x00c4)
+#define CFGEBIASET      PIC32_R (0x00c8)
+#define CFGEBIAINV      PIC32_R (0x00cc)
+#define CFGEBIC         PIC32_R (0x00d0)
+#define CFGEBICCLR      PIC32_R (0x00d4)
+#define CFGEBICSET      PIC32_R (0x00d8)
+#define CFGEBICINV      PIC32_R (0x00dc)
+#define CFGPG           PIC32_R (0x00e0)
+
+#define OSCCON          PIC32_R (0x1200)    /* Oscillator Control */
+#define OSCTUN          PIC32_R (0x1210)
+#define SPLLCON         PIC32_R (0x1220)
+#define RCON            PIC32_R (0x1240)
+#define RSWRST          PIC32_R (0x1250)
+#define RSWRSTCLR       PIC32_R (0x1254)
+#define RSWRSTSET       PIC32_R (0x1258)
+#define RSWRSTINV       PIC32_R (0x125c)
+#define RNMICON         PIC32_R (0x1260)
+#define PWRCON          PIC32_R (0x1270)
+#define REFO1CON        PIC32_R (0x1280)
+#define REFO1CONCLR     PIC32_R (0x1284)
+#define REFO1CONSET     PIC32_R (0x1288)
+#define REFO1CONINV     PIC32_R (0x128c)
+#define REFO1TRIM       PIC32_R (0x1290)
+#define REFO2CON        PIC32_R (0x12A0)
+#define REFO2CONCLR     PIC32_R (0x12A4)
+#define REFO2CONSET     PIC32_R (0x12A8)
+#define REFO2CONINV     PIC32_R (0x12Ac)
+#define REFO2TRIM       PIC32_R (0x12B0)
+#define REFO3CON        PIC32_R (0x12C0)
+#define REFO3CONCLR     PIC32_R (0x12C4)
+#define REFO3CONSET     PIC32_R (0x12C8)
+#define REFO3CONINV     PIC32_R (0x12Cc)
+#define REFO3TRIM       PIC32_R (0x12D0)
+#define REFO4CON        PIC32_R (0x12E0)
+#define REFO4CONCLR     PIC32_R (0x12E4)
+#define REFO4CONSET     PIC32_R (0x12E8)
+#define REFO4CONINV     PIC32_R (0x12Ec)
+#define REFO4TRIM       PIC32_R (0x12F0)
+#define PB1DIV          PIC32_R (0x1300)
+#define PB1DIVCLR       PIC32_R (0x1304)
+#define PB1DIVSET       PIC32_R (0x1308)
+#define PB1DIVINV       PIC32_R (0x130c)
+#define PB2DIV          PIC32_R (0x1310)
+#define PB2DIVCLR       PIC32_R (0x1314)
+#define PB2DIVSET       PIC32_R (0x1318)
+#define PB2DIVINV       PIC32_R (0x131c)
+#define PB3DIV          PIC32_R (0x1320)
+#define PB3DIVCLR       PIC32_R (0x1324)
+#define PB3DIVSET       PIC32_R (0x1328)
+#define PB3DIVINV       PIC32_R (0x132c)
+#define PB4DIV          PIC32_R (0x1330)
+#define PB4DIVCLR       PIC32_R (0x1334)
+#define PB4DIVSET       PIC32_R (0x1338)
+#define PB4DIVINV       PIC32_R (0x133c)
+#define PB5DIV          PIC32_R (0x1340)
+#define PB5DIVCLR       PIC32_R (0x1344)
+#define PB5DIVSET       PIC32_R (0x1348)
+#define PB5DIVINV       PIC32_R (0x134c)
+#define PB7DIV          PIC32_R (0x1360)
+#define PB7DIVCLR       PIC32_R (0x1364)
+#define PB7DIVSET       PIC32_R (0x1368)
+#define PB7DIVINV       PIC32_R (0x136c)
+#define PB8DIV          PIC32_R (0x1370)
+#define PB8DIVCLR       PIC32_R (0x1374)
+#define PB8DIVSET       PIC32_R (0x1378)
+#define PB8DIVINV       PIC32_R (0x137c)
+
+/*
+ * Configuration Control register.
+ */
+#define PIC32_CFGCON_DMAPRI     0x02000000 /* DMA gets High Priority
access to SRAM */
+#define PIC32_CFGCON_CPUPRI     0x01000000 /* CPU gets High Priority
access to SRAM */
+#define PIC32_CFGCON_ICACLK     0x00020000 /* Input Capture alternate
clock selection */
+#define PIC32_CFGCON_OCACLK     0x00010000 /* Output Compare
alternate clock selection */
+#define PIC32_CFGCON_IOLOCK     0x00002000 /* Peripheral pin select lock */
+#define PIC32_CFGCON_PMDLOCK    0x00001000 /* Peripheral module disable */
+#define PIC32_CFGCON_PGLOCK     0x00000800 /* Permission group lock */
+#define PIC32_CFGCON_USBSSEN    0x00000100 /* USB suspend sleep enable */
+#define PIC32_CFGCON_ECC_MASK   0x00000030 /* Flash ECC Configuration */
+#define PIC32_CFGCON_ECC_DISWR  0x00000030 /* ECC disabled,
ECCCON<1:0> writable */
+#define PIC32_CFGCON_ECC_DISRO  0x00000020 /* ECC disabled,
ECCCON<1:0> locked */
+#define PIC32_CFGCON_ECC_DYN    0x00000010 /* Dynamic Flash ECC is enabled */
+#define PIC32_CFGCON_ECC_EN     0x00000000 /* Flash ECC is enabled */
+#define PIC32_CFGCON_JTAGEN     0x00000008 /* JTAG port enable */
+#define PIC32_CFGCON_TROEN      0x00000004 /* Trace output enable */
+#define PIC32_CFGCON_TDOEN      0x00000001 /* 2-wire JTAG protocol uses TDO */
+
+/*--------------------------------------
+ * A/D Converter registers.
+ */
+#define AD1CON1         PIC32_R (0x4b000)   /* Control register 1 */
+#define AD1CON2         PIC32_R (0x4b004)   /* Control register 2 */
+#define AD1CON3         PIC32_R (0x4b008)   /* Control register 3 */
+#define AD1IMOD         PIC32_R (0x4b00c)
+#define AD1GIRQEN1      PIC32_R (0x4b010)
+#define AD1GIRQEN2      PIC32_R (0x4b014)
+#define AD1CSS1         PIC32_R (0x4b018)
+#define AD1CSS2         PIC32_R (0x4b01c)
+#define AD1DSTAT1       PIC32_R (0x4b020)
+#define AD1DSTAT2       PIC32_R (0x4b024)
+#define AD1CMPEN1       PIC32_R (0x4b028)
+#define AD1CMP1         PIC32_R (0x4b02c)
+#define AD1CMPEN2       PIC32_R (0x4b030)
+#define AD1CMP2         PIC32_R (0x4b034)
+#define AD1CMPEN3       PIC32_R (0x4b038)
+#define AD1CMP3         PIC32_R (0x4b03c)
+#define AD1CMPEN4       PIC32_R (0x4b040)
+#define AD1CMP4         PIC32_R (0x4b044)
+#define AD1CMPEN5       PIC32_R (0x4b048)
+#define AD1CMP5         PIC32_R (0x4b04c)
+#define AD1CMPEN6       PIC32_R (0x4b050)
+#define AD1CMP6         PIC32_R (0x4b054)
+#define AD1FLTR1        PIC32_R (0x4b058)
+#define AD1FLTR2        PIC32_R (0x4b05c)
+#define AD1FLTR3        PIC32_R (0x4b060)
+#define AD1FLTR4        PIC32_R (0x4b064)
+#define AD1FLTR5        PIC32_R (0x4b068)
+#define AD1FLTR6        PIC32_R (0x4b06c)
+#define AD1TRG1         PIC32_R (0x4b070)
+#define AD1TRG2         PIC32_R (0x4b074)
+#define AD1TRG3         PIC32_R (0x4b078)
+#define AD1CMPCON1      PIC32_R (0x4b090)
+#define AD1CMPCON2      PIC32_R (0x4b094)
+#define AD1CMPCON3      PIC32_R (0x4b098)
+#define AD1CMPCON4      PIC32_R (0x4b09c)
+#define AD1CMPCON5      PIC32_R (0x4b0a0)
+#define AD1CMPCON6      PIC32_R (0x4b0a4)
+#define AD1DATA0        PIC32_R (0x4b0b8)
+#define AD1DATA1        PIC32_R (0x4b0bc)
+#define AD1DATA2        PIC32_R (0x4b0c0)
+#define AD1DATA3        PIC32_R (0x4b0c4)
+#define AD1DATA4        PIC32_R (0x4b0c8)
+#define AD1DATA5        PIC32_R (0x4b0cc)
+#define AD1DATA6        PIC32_R (0x4b0d0)
+#define AD1DATA7        PIC32_R (0x4b0d4)
+#define AD1DATA8        PIC32_R (0x4b0d8)
+#define AD1DATA9        PIC32_R (0x4b0dc)
+#define AD1DATA10       PIC32_R (0x4b0e0)
+#define AD1DATA11       PIC32_R (0x4b0e4)
+#define AD1DATA12       PIC32_R (0x4b0e8)
+#define AD1DATA13       PIC32_R (0x4b0ec)
+#define AD1DATA14       PIC32_R (0x4b0f0)
+#define AD1DATA15       PIC32_R (0x4b0f4)
+#define AD1DATA16       PIC32_R (0x4b0f8)
+#define AD1DATA17       PIC32_R (0x4b0fc)
+#define AD1DATA18       PIC32_R (0x4b100)
+#define AD1DATA19       PIC32_R (0x4b104)
+#define AD1DATA20       PIC32_R (0x4b108)
+#define AD1DATA21       PIC32_R (0x4b10c)
+#define AD1DATA22       PIC32_R (0x4b110)
+#define AD1DATA23       PIC32_R (0x4b114)
+#define AD1DATA24       PIC32_R (0x4b118)
+#define AD1DATA25       PIC32_R (0x4b11c)
+#define AD1DATA26       PIC32_R (0x4b120)
+#define AD1DATA27       PIC32_R (0x4b124)
+#define AD1DATA28       PIC32_R (0x4b128)
+#define AD1DATA29       PIC32_R (0x4b12c)
+#define AD1DATA30       PIC32_R (0x4b130)
+#define AD1DATA31       PIC32_R (0x4b134)
+#define AD1DATA32       PIC32_R (0x4b138)
+#define AD1DATA33       PIC32_R (0x4b13c)
+#define AD1DATA34       PIC32_R (0x4b140)
+#define AD1DATA35       PIC32_R (0x4b144)
+#define AD1DATA36       PIC32_R (0x4b148)
+#define AD1DATA37       PIC32_R (0x4b14c)
+#define AD1DATA38       PIC32_R (0x4b150)
+#define AD1DATA39       PIC32_R (0x4b154)
+#define AD1DATA40       PIC32_R (0x4b158)
+#define AD1DATA41       PIC32_R (0x4b15c)
+#define AD1DATA42       PIC32_R (0x4b160)
+#define AD1DATA43       PIC32_R (0x4b164)
+#define AD1DATA44       PIC32_R (0x4b168)
+#define AD1CAL1         PIC32_R (0x4b200)   /* Calibration Data */
+#define AD1CAL2         PIC32_R (0x4b204)
+#define AD1CAL3         PIC32_R (0x4b208)
+#define AD1CAL4         PIC32_R (0x4b20c)
+#define AD1CAL5         PIC32_R (0x4b210)
+
+/*--------------------------------------
+ * SPI registers.
+ */
+#define SPI1CON         PIC32_R (0x21000) /* Control */
+#define SPI1CONCLR      PIC32_R (0x21004)
+#define SPI1CONSET      PIC32_R (0x21008)
+#define SPI1CONINV      PIC32_R (0x2100c)
+#define SPI1STAT        PIC32_R (0x21010) /* Status */
+#define SPI1STATCLR     PIC32_R (0x21014)
+#define SPI1STATSET     PIC32_R (0x21018)
+#define SPI1STATINV     PIC32_R (0x2101c)
+#define SPI1BUF         PIC32_R (0x21020) /* Transmit and receive buffer */
+#define SPI1BRG         PIC32_R (0x21030) /* Baud rate generator */
+#define SPI1BRGCLR      PIC32_R (0x21034)
+#define SPI1BRGSET      PIC32_R (0x21038)
+#define SPI1BRGINV      PIC32_R (0x2103c)
+#define SPI1CON2        PIC32_R (0x21040) /* Control 2 */
+#define SPI1CON2CLR     PIC32_R (0x21044)
+#define SPI1CON2SET     PIC32_R (0x21048)
+#define SPI1CON2INV     PIC32_R (0x2104c)
+
+#define SPI2CON         PIC32_R (0x21200) /* Control */
+#define SPI2CONCLR      PIC32_R (0x21204)
+#define SPI2CONSET      PIC32_R (0x21208)
+#define SPI2CONINV      PIC32_R (0x2120c)
+#define SPI2STAT        PIC32_R (0x21210) /* Status */
+#define SPI2STATCLR     PIC32_R (0x21214)
+#define SPI2STATSET     PIC32_R (0x21218)
+#define SPI2STATINV     PIC32_R (0x2121c)
+#define SPI2BUF         PIC32_R (0x21220) /* Transmit and receive buffer */
+#define SPI2BRG         PIC32_R (0x21230) /* Baud rate generator */
+#define SPI2BRGCLR      PIC32_R (0x21234)
+#define SPI2BRGSET      PIC32_R (0x21238)
+#define SPI2BRGINV      PIC32_R (0x2123c)
+#define SPI2CON2        PIC32_R (0x21240) /* Control 2 */
+#define SPI2CON2CLR     PIC32_R (0x21244)
+#define SPI2CON2SET     PIC32_R (0x21248)
+#define SPI2CON2INV     PIC32_R (0x2124c)
+
+#define SPI3CON         PIC32_R (0x21400) /* Control */
+#define SPI3CONCLR      PIC32_R (0x21404)
+#define SPI3CONSET      PIC32_R (0x21408)
+#define SPI3CONINV      PIC32_R (0x2140c)
+#define SPI3STAT        PIC32_R (0x21410) /* Status */
+#define SPI3STATCLR     PIC32_R (0x21414)
+#define SPI3STATSET     PIC32_R (0x21418)
+#define SPI3STATINV     PIC32_R (0x2141c)
+#define SPI3BUF         PIC32_R (0x21420) /* Transmit and receive buffer */
+#define SPI3BRG         PIC32_R (0x21430) /* Baud rate generator */
+#define SPI3BRGCLR      PIC32_R (0x21434)
+#define SPI3BRGSET      PIC32_R (0x21438)
+#define SPI3BRGINV      PIC32_R (0x2143c)
+#define SPI3CON2        PIC32_R (0x21440) /* Control 2 */
+#define SPI3CON2CLR     PIC32_R (0x21444)
+#define SPI3CON2SET     PIC32_R (0x21448)
+#define SPI3CON2INV     PIC32_R (0x2144c)
+
+#define SPI4CON         PIC32_R (0x21600) /* Control */
+#define SPI4CONCLR      PIC32_R (0x21604)
+#define SPI4CONSET      PIC32_R (0x21608)
+#define SPI4CONINV      PIC32_R (0x2160c)
+#define SPI4STAT        PIC32_R (0x21610) /* Status */
+#define SPI4STATCLR     PIC32_R (0x21614)
+#define SPI4STATSET     PIC32_R (0x21618)
+#define SPI4STATINV     PIC32_R (0x2161c)
+#define SPI4BUF         PIC32_R (0x21620) /* Transmit and receive buffer */
+#define SPI4BRG         PIC32_R (0x21630) /* Baud rate generator */
+#define SPI4BRGCLR      PIC32_R (0x21634)
+#define SPI4BRGSET      PIC32_R (0x21638)
+#define SPI4BRGINV      PIC32_R (0x2163c)
+#define SPI4CON2        PIC32_R (0x21640) /* Control 2 */
+#define SPI4CON2CLR     PIC32_R (0x21644)
+#define SPI4CON2SET     PIC32_R (0x21648)
+#define SPI4CON2INV     PIC32_R (0x2164c)
+
+#define SPI5CON         PIC32_R (0x21800) /* Control */
+#define SPI5CONCLR      PIC32_R (0x21804)
+#define SPI5CONSET      PIC32_R (0x21808)
+#define SPI5CONINV      PIC32_R (0x2180c)
+#define SPI5STAT        PIC32_R (0x21810) /* Status */
+#define SPI5STATCLR     PIC32_R (0x21814)
+#define SPI5STATSET     PIC32_R (0x21818)
+#define SPI5STATINV     PIC32_R (0x2181c)
+#define SPI5BUF         PIC32_R (0x21820) /* Transmit and receive buffer */
+#define SPI5BRG         PIC32_R (0x21830) /* Baud rate generator */
+#define SPI5BRGCLR      PIC32_R (0x21834)
+#define SPI5BRGSET      PIC32_R (0x21838)
+#define SPI5BRGINV      PIC32_R (0x2183c)
+#define SPI5CON2        PIC32_R (0x21840) /* Control 2 */
+#define SPI5CON2CLR     PIC32_R (0x21844)
+#define SPI5CON2SET     PIC32_R (0x21848)
+#define SPI5CON2INV     PIC32_R (0x2184c)
+
+#define SPI6CON         PIC32_R (0x21a00) /* Control */
+#define SPI6CONCLR      PIC32_R (0x21a04)
+#define SPI6CONSET      PIC32_R (0x21a08)
+#define SPI6CONINV      PIC32_R (0x21a0c)
+#define SPI6STAT        PIC32_R (0x21a10) /* Status */
+#define SPI6STATCLR     PIC32_R (0x21a14)
+#define SPI6STATSET     PIC32_R (0x21a18)
+#define SPI6STATINV     PIC32_R (0x21a1c)
+#define SPI6BUF         PIC32_R (0x21a20) /* Transmit and receive buffer */
+#define SPI6BRG         PIC32_R (0x21a30) /* Baud rate generator */
+#define SPI6BRGCLR      PIC32_R (0x21a34)
+#define SPI6BRGSET      PIC32_R (0x21a38)
+#define SPI6BRGINV      PIC32_R (0x21a3c)
+#define SPI6CON2        PIC32_R (0x21a40) /* Control 2 */
+#define SPI6CON2CLR     PIC32_R (0x21a44)
+#define SPI6CON2SET     PIC32_R (0x21a48)
+#define SPI6CON2INV     PIC32_R (0x21a4c)
+
+/*
+ * SPI Control register.
+ */
+#define PIC32_SPICON_MSTEN      0x00000020      /* Master mode */
+#define PIC32_SPICON_CKP        0x00000040      /* Idle clock is high level */
+#define PIC32_SPICON_SSEN       0x00000080      /* Slave mode: SSx
pin enable */
+#define PIC32_SPICON_CKE        0x00000100      /* Output data changes on
+                                                 * transition from active clock
+                                                 * state to Idle clock state */
+#define PIC32_SPICON_SMP        0x00000200      /* Master mode: input
data sampled
+                                                 * at end of data
output time. */
+#define PIC32_SPICON_MODE16     0x00000400      /* 16-bit data width */
+#define PIC32_SPICON_MODE32     0x00000800      /* 32-bit data width */
+#define PIC32_SPICON_DISSDO     0x00001000      /* SDOx pin is not used */
+#define PIC32_SPICON_SIDL       0x00002000      /* Stop in Idle mode */
+#define PIC32_SPICON_FRZ        0x00004000      /* Freeze in Debug mode */
+#define PIC32_SPICON_ON         0x00008000      /* SPI Peripheral is enabled */
+#define PIC32_SPICON_ENHBUF     0x00010000      /* Enhanced buffer enable */
+#define PIC32_SPICON_SPIFE      0x00020000      /* Frame synchronization pulse
+                                                 * coincides with the
first bit clock */
+#define PIC32_SPICON_FRMPOL     0x20000000      /* Frame pulse is
active-high */
+#define PIC32_SPICON_FRMSYNC    0x40000000      /* Frame sync pulse
input (Slave mode) */
+#define PIC32_SPICON_FRMEN      0x80000000      /* Framed SPI support */
+
+/*
+ * SPI Status register.
+ */
+#define PIC32_SPISTAT_SPIRBF    0x00000001      /* Receive buffer is full */
+#define PIC32_SPISTAT_SPITBF    0x00000002      /* Transmit buffer is full */
+#define PIC32_SPISTAT_SPITBE    0x00000008      /* Transmit buffer is empty */
+#define PIC32_SPISTAT_SPIRBE    0x00000020      /* Receive buffer is empty */
+#define PIC32_SPISTAT_SPIROV    0x00000040      /* Receive overflow flag */
+#define PIC32_SPISTAT_SPIBUSY   0x00000800      /* SPI is busy */
+
+/*--------------------------------------
+ * USB registers.
+ */
+#define USBCSR0         PIC32_R (0xE3000)   /*  */
+#define USBCSR1         PIC32_R (0xE3004)
+#define USBCSR2         PIC32_R (0xE3008)
+#define USBCSR3         PIC32_R (0xE300C)
+#define USBIENCSR0      PIC32_R (0xE3010)   /*  */
+#define USBIENCSR1      PIC32_R (0xE3014)
+#define USBIENCSR2      PIC32_R (0xE3018)
+#define USBIENCSR3      PIC32_R (0xE301C)
+#define USBFIFO0        PIC32_R (0xE3020)   /*  */
+#define USBFIFO1        PIC32_R (0xE3024)
+#define USBFIFO2        PIC32_R (0xE3028)
+#define USBFIFO3        PIC32_R (0xE302C)
+#define USBFIFO4        PIC32_R (0xE3030)
+#define USBFIFO5        PIC32_R (0xE3034)
+#define USBFIFO6        PIC32_R (0xE3038)
+#define USBFIFO7        PIC32_R (0xE303C)
+#define USBOTG          PIC32_R (0xE3060)   /*  */
+#define USBFIFOA        PIC32_R (0xE3064)   /*  */
+#define USBHWVER        PIC32_R (0xE306C)   /*  */
+#define USBINFO         PIC32_R (0xE3078)   /*  */
+#define USBEOFRST       PIC32_R (0xE307C)   /*  */
+#define USBE0TXA        PIC32_R (0xE3080)   /*  */
+#define USBE0RXA        PIC32_R (0xE3084)   /*  */
+#define USBE1TXA        PIC32_R (0xE3088)
+#define USBE1RXA        PIC32_R (0xE308C)
+#define USBE2TXA        PIC32_R (0xE3090)
+#define USBE2RXA        PIC32_R (0xE3094)
+#define USBE3TXA        PIC32_R (0xE3098)
+#define USBE3RXA        PIC32_R (0xE309C)
+#define USBE4TXA        PIC32_R (0xE30A0)
+#define USBE4RXA        PIC32_R (0xE30A4)
+#define USBE5TXA        PIC32_R (0xE30A8)
+#define USBE5RXA        PIC32_R (0xE30AC)
+#define USBE6TXA        PIC32_R (0xE30B0)
+#define USBE6RXA        PIC32_R (0xE30B4)
+#define USBE7TXA        PIC32_R (0xE30B8)
+#define USBE7RXA        PIC32_R (0xE30BC)
+#define USBE0CSR0       PIC32_R (0xE3100)   /*  */
+#define USBE0CSR2       PIC32_R (0xE3108)
+#define USBE0CSR3       PIC32_R (0xE310C)
+#define USBE1CSR0       PIC32_R (0xE3110)
+#define USBE1CSR1       PIC32_R (0xE3114)
+#define USBE1CSR2       PIC32_R (0xE3118)
+#define USBE1CSR3       PIC32_R (0xE311C)
+#define USBE2CSR0       PIC32_R (0xE3120)
+#define USBE2CSR1       PIC32_R (0xE3124)
+#define USBE2CSR2       PIC32_R (0xE3128)
+#define USBE2CSR3       PIC32_R (0xE312C)
+#define USBE3CSR0       PIC32_R (0xE3130)
+#define USBE3CSR1       PIC32_R (0xE3134)
+#define USBE3CSR2       PIC32_R (0xE3138)
+#define USBE3CSR3       PIC32_R (0xE313C)
+#define USBE4CSR0       PIC32_R (0xE3140)
+#define USBE4CSR1       PIC32_R (0xE3144)
+#define USBE4CSR2       PIC32_R (0xE3148)
+#define USBE4CSR3       PIC32_R (0xE314C)
+#define USBE5CSR0       PIC32_R (0xE3150)
+#define USBE5CSR1       PIC32_R (0xE3154)
+#define USBE5CSR2       PIC32_R (0xE3158)
+#define USBE5CSR3       PIC32_R (0xE315C)
+#define USBE6CSR0       PIC32_R (0xE3160)
+#define USBE6CSR1       PIC32_R (0xE3164)
+#define USBE6CSR2       PIC32_R (0xE3168)
+#define USBE6CSR3       PIC32_R (0xE316C)
+#define USBE7CSR0       PIC32_R (0xE3170)
+#define USBE7CSR1       PIC32_R (0xE3174)
+#define USBE7CSR2       PIC32_R (0xE3178)
+#define USBE7CSR3       PIC32_R (0xE317C)
+#define USBDMAINT       PIC32_R (0xE3200)   /*  */
+#define USBDMA1C        PIC32_R (0xE3204)   /*  */
+#define USBDMA1A        PIC32_R (0xE3208)   /*  */
+#define USBDMA1N        PIC32_R (0xE320C)   /*  */
+#define USBDMA2C        PIC32_R (0xE3214)
+#define USBDMA2A        PIC32_R (0xE3218)
+#define USBDMA2N        PIC32_R (0xE321C)
+#define USBDMA3C        PIC32_R (0xE3224)
+#define USBDMA3A        PIC32_R (0xE3228)
+#define USBDMA3N        PIC32_R (0xE322C)
+#define USBDMA4C        PIC32_R (0xE3234)
+#define USBDMA4A        PIC32_R (0xE3238)
+#define USBDMA4N        PIC32_R (0xE323C)
+#define USBDMA5C        PIC32_R (0xE3244)
+#define USBDMA5A        PIC32_R (0xE3248)
+#define USBDMA5N        PIC32_R (0xE324C)
+#define USBDMA6C        PIC32_R (0xE3254)
+#define USBDMA6A        PIC32_R (0xE3258)
+#define USBDMA6N        PIC32_R (0xE325C)
+#define USBDMA7C        PIC32_R (0xE3264)
+#define USBDMA7A        PIC32_R (0xE3268)
+#define USBDMA7N        PIC32_R (0xE326C)
+#define USBDMA8C        PIC32_R (0xE3274)
+#define USBDMA8A        PIC32_R (0xE3278)
+#define USBDMA8N        PIC32_R (0xE327C)
+#define USBE1RPC        PIC32_R (0xE3304)   /*  */
+#define USBE2RPC        PIC32_R (0xE3308)
+#define USBE3RPC        PIC32_R (0xE330C)
+#define USBE4RPC        PIC32_R (0xE3310)
+#define USBE5RPC        PIC32_R (0xE3314)
+#define USBE6RPC        PIC32_R (0xE3318)
+#define USBE7RPC        PIC32_R (0xE331C)
+#define USBDPBFD        PIC32_R (0xE3340)   /*  */
+#define USBTMCON1       PIC32_R (0xE3344)   /*  */
+#define USBTMCON2       PIC32_R (0xE3348)   /*  */
+#define USBLPMR1        PIC32_R (0xE3360)   /*  */
+#define USBLMPR2        PIC32_R (0xE3364)   /*  */
+
+/*--------------------------------------
+ * Ethernet registers.
+ */
+#define ETHCON1         PIC32_R (0x82000)   /* Control 1 */
+#define ETHCON1CLR      PIC32_R (0x82004)
+#define ETHCON1SET      PIC32_R (0x82008)
+#define ETHCON1INV      PIC32_R (0x8200c)
+#define ETHCON2         PIC32_R (0x82010)   /* Control 2: RX data
buffer size */
+#define ETHTXST         PIC32_R (0x82020)   /* Tx descriptor start address */
+#define ETHRXST         PIC32_R (0x82030)   /* Rx descriptor start address */
+#define ETHHT0          PIC32_R (0x82040)   /* Hash tasble 0 */
+#define ETHHT1          PIC32_R (0x82050)   /* Hash tasble 1 */
+#define ETHPMM0         PIC32_R (0x82060)   /* Pattern match mask 0 */
+#define ETHPMM1         PIC32_R (0x82070)   /* Pattern match mask 1 */
+#define ETHPMCS         PIC32_R (0x82080)   /* Pattern match checksum */
+#define ETHPMO          PIC32_R (0x82090)   /* Pattern match offset */
+#define ETHRXFC         PIC32_R (0x820a0)   /* Receive filter configuration */
+#define ETHRXWM         PIC32_R (0x820b0)   /* Receive watermarks */
+#define ETHIEN          PIC32_R (0x820c0)   /* Interrupt enable */
+#define ETHIENCLR       PIC32_R (0x820c4)
+#define ETHIENSET       PIC32_R (0x820c8)
+#define ETHIENINV       PIC32_R (0x820cc)
+#define ETHIRQ          PIC32_R (0x820d0)   /* Interrupt request */
+#define ETHIRQCLR       PIC32_R (0x820d4)
+#define ETHIRQSET       PIC32_R (0x820d8)
+#define ETHIRQINV       PIC32_R (0x820dc)
+#define ETHSTAT         PIC32_R (0x820e0)   /* Status */
+#define ETHRXOVFLOW     PIC32_R (0x82100)   /* Receive overflow statistics */
+#define ETHFRMTXOK      PIC32_R (0x82110)   /* Frames transmitted OK
statistics */
+#define ETHSCOLFRM      PIC32_R (0x82120)   /* Single collision
frames statistics */
+#define ETHMCOLFRM      PIC32_R (0x82130)   /* Multiple collision
frames statistics */
+#define ETHFRMRXOK      PIC32_R (0x82140)   /* Frames received OK statistics */
+#define ETHFCSERR       PIC32_R (0x82150)   /* Frame check sequence
error statistics */
+#define ETHALGNERR      PIC32_R (0x82160)   /* Alignment errors statistics */
+#define EMAC1CFG1       PIC32_R (0x82200)   /* MAC configuration 1 */
+#define EMAC1CFG2       PIC32_R (0x82210)   /* MAC configuration 2 */
+#define EMAC1CFG2CLR    PIC32_R (0x82214)
+#define EMAC1CFG2SET    PIC32_R (0x82218)
+#define EMAC1CFG2INV    PIC32_R (0x8221c)
+#define EMAC1IPGT       PIC32_R (0x82220)   /* MAC back-to-back
interpacket gap */
+#define EMAC1IPGR       PIC32_R (0x82230)   /* MAC non-back-to-back
interpacket gap */
+#define EMAC1CLRT       PIC32_R (0x82240)   /* MAC collision
window/retry limit */
+#define EMAC1MAXF       PIC32_R (0x82250)   /* MAC maximum frame length */
+#define EMAC1SUPP       PIC32_R (0x82260)   /* MAC PHY support */
+#define EMAC1SUPPCLR    PIC32_R (0x82264)
+#define EMAC1SUPPSET    PIC32_R (0x82268)
+#define EMAC1SUPPINV    PIC32_R (0x8226c)
+#define EMAC1TEST       PIC32_R (0x82270)   /* MAC test */
+#define EMAC1MCFG       PIC32_R (0x82280)   /* MII configuration */
+#define EMAC1MCMD       PIC32_R (0x82290)   /* MII command */
+#define EMAC1MCMDCLR    PIC32_R (0x82294)
+#define EMAC1MCMDSET    PIC32_R (0x82298)
+#define EMAC1MCMDINV    PIC32_R (0x8229c)
+#define EMAC1MADR       PIC32_R (0x822a0)   /* MII address */
+#define EMAC1MWTD       PIC32_R (0x822b0)   /* MII write data */
+#define EMAC1MRDD       PIC32_R (0x822c0)   /* MII read data */
+#define EMAC1MIND       PIC32_R (0x822d0)   /* MII indicators */
+#define EMAC1SA0        PIC32_R (0x82300)   /* MAC station address 0 */
+#define EMAC1SA1        PIC32_R (0x82310)   /* MAC station address 1 */
+#define EMAC1SA2        PIC32_R (0x82320)   /* MAC station address 2 */
+
+/*
+ * Ethernet Control register 1.
+ */
+#define PIC32_ETHCON1_PTV(n)    ((n)<<16)   /* Pause timer value */
+#define PIC32_ETHCON1_ON            0x8000  /* Ethernet module enabled */
+#define PIC32_ETHCON1_SIDL          0x2000  /* Stop in idle mode */
+#define PIC32_ETHCON1_TXRTS         0x0200  /* Transmit request to send */
+#define PIC32_ETHCON1_RXEN          0x0100  /* Receive enable */
+#define PIC32_ETHCON1_AUTOFC        0x0080  /* Automatic flow control */
+#define PIC32_ETHCON1_MANFC         0x0010  /* Manual flow control */
+#define PIC32_ETHCON1_BUFCDEC       0x0001  /* Descriptor buffer
count decrement */
+
+/*
+ * Ethernet Receive Filter Configuration register.
+ */
+#define PIC32_ETHRXFC_HTEN          0x8000  /* Enable hash table filtering */
+#define PIC32_ETHRXFC_MPEN          0x4000  /* Enable Magic Packet filtering */
+#define PIC32_ETHRXFC_NOTPM         0x1000  /* Pattern match inversion */
+#define PIC32_ETHRXFC_PMMODE_MAGIC  0x0900  /* Packet = magic */
+#define PIC32_ETHRXFC_PMMODE_HT     0x0800  /* Hash table filter match */
+#define PIC32_ETHRXFC_PMMODE_BCAST  0x0600  /* Destination =
broadcast address */
+#define PIC32_ETHRXFC_PMMODE_UCAST  0x0400  /* Destination = unicast address */
+#define PIC32_ETHRXFC_PMMODE_STN    0x0200  /* Destination = station address */
+#define PIC32_ETHRXFC_PMMODE_CSUM   0x0100  /* Successful if checksum
matches */
+#define PIC32_ETHRXFC_CRCERREN      0x0080  /* CRC error collection enable */
+#define PIC32_ETHRXFC_CRCOKEN       0x0040  /* CRC OK enable */
+#define PIC32_ETHRXFC_RUNTERREN     0x0020  /* Runt error collection enable */
+#define PIC32_ETHRXFC_RUNTEN        0x0010  /* Runt filter enable */
+#define PIC32_ETHRXFC_UCEN          0x0008  /* Unicast filter enable */
+#define PIC32_ETHRXFC_NOTMEEN       0x0004  /* Not Me unicast enable */
+#define PIC32_ETHRXFC_MCEN          0x0002  /* Multicast filter enable */
+#define PIC32_ETHRXFC_BCEN          0x0001  /* Broadcast filter enable */
+
+/*
+ * Ethernet Receive Watermarks register.
+ */
+#define PIC32_ETHRXWM_FWM(n)    ((n)<<16)   /* Receive Full Watermark */
+#define PIC32_ETHRXWM_EWM(n)    (n)         /* Receive Empty Watermark */
+
+/*
+ * Ethernet Interrupt Request register.
+ */
+#define PIC32_ETHIRQ_TXBUSE         0x4000  /* Transmit Bus Error */
+#define PIC32_ETHIRQ_RXBUSE         0x2000  /* Receive Bus Error */
+#define PIC32_ETHIRQ_EWMARK         0x0200  /* Empty Watermark */
+#define PIC32_ETHIRQ_FWMARK         0x0100  /* Full Watermark */
+#define PIC32_ETHIRQ_RXDONE         0x0080  /* Receive Done */
+#define PIC32_ETHIRQ_PKTPEND        0x0040  /* Packet Pending */
+#define PIC32_ETHIRQ_RXACT          0x0020  /* Receive Activity */
+#define PIC32_ETHIRQ_TXDONE         0x0008  /* Transmit Done */
+#define PIC32_ETHIRQ_TXABORT        0x0004  /* Transmitter Abort */
+#define PIC32_ETHIRQ_RXBUFNA        0x0002  /* Receive Buffer Not Available */
+#define PIC32_ETHIRQ_RXOVFLW        0x0001  /* Receive FIFO Overflow */
+
+/*
+ * Ethernet Status register.
+ */
+#define PIC32_ETHSTAT_BUFCNT    0x00ff0000  /* Packet buffer count */
+#define PIC32_ETHSTAT_ETHBUSY       0x0080  /* Ethernet logic is busy */
+#define PIC32_ETHSTAT_TXBUSY        0x0040  /* TX logic is receiving data */
+#define PIC32_ETHSTAT_RXBUSY        0x0020  /* RX logic is receiving data */
+
+/*
+ * Ethernet MAC configuration register 1.
+ */
+#define PIC32_EMAC1CFG1_SOFTRESET   0x8000  /* Soft reset */
+#define PIC32_EMAC1CFG1_SIMRESET    0x4000  /* Reset TX random number
generator */
+#define PIC32_EMAC1CFG1_RESETRMCS   0x0800  /* Reset MCS/RX logic */
+#define PIC32_EMAC1CFG1_RESETRFUN   0x0400  /* Reset RX function */
+#define PIC32_EMAC1CFG1_RESETTMCS   0x0200  /* Reset MCS/TX logic */
+#define PIC32_EMAC1CFG1_RESETTFUN   0x0100  /* Reset TX function */
+#define PIC32_EMAC1CFG1_LOOPBACK    0x0010  /* MAC Loopback mode */
+#define PIC32_EMAC1CFG1_TXPAUSE     0x0008  /* MAC TX flow control */
+#define PIC32_EMAC1CFG1_RXPAUSE     0x0004  /* MAC RX flow control */
+#define PIC32_EMAC1CFG1_PASSALL     0x0002  /* MAC accept control
frames as well */
+#define PIC32_EMAC1CFG1_RXENABLE    0x0001  /* MAC Receive Enable */
+
+/*
+ * Ethernet MAC configuration register 2.
+ */
+#define PIC32_EMAC1CFG2_EXCESSDFR   0x4000  /* Defer to carrier indefinitely */
+#define PIC32_EMAC1CFG2_BPNOBKOFF   0x2000  /* Backpressure/No Backoff */
+#define PIC32_EMAC1CFG2_NOBKOFF     0x1000  /* No Backoff */
+#define PIC32_EMAC1CFG2_LONGPRE     0x0200  /* Long preamble enforcement */
+#define PIC32_EMAC1CFG2_PUREPRE     0x0100  /* Pure preamble enforcement */
+#define PIC32_EMAC1CFG2_AUTOPAD     0x0080  /* Automatic detect pad enable */
+#define PIC32_EMAC1CFG2_VLANPAD     0x0040  /* VLAN pad enable */
+#define PIC32_EMAC1CFG2_PADENABLE   0x0020  /* Pad/CRC enable */
+#define PIC32_EMAC1CFG2_CRCENABLE   0x0010  /* CRC enable */
+#define PIC32_EMAC1CFG2_DELAYCRC    0x0008  /* Delayed CRC */
+#define PIC32_EMAC1CFG2_HUGEFRM     0x0004  /* Huge frame enable */
+#define PIC32_EMAC1CFG2_LENGTHCK    0x0002  /* Frame length checking */
+#define PIC32_EMAC1CFG2_FULLDPLX    0x0001  /* Full-duplex operation */
+
+/*
+ * Ethernet MAC non-back-to-back interpacket gap register.
+ */
+#define PIC32_EMAC1IPGR(p1, p2)     ((p1)<<8 | (p2))
+
+/*
+ * Ethernet MAC collision window/retry limit register.
+ */
+#define PIC32_EMAC1CLRT(w, r)       ((w)<<8 | (r))
+
+/*
+ * Ethernet PHY support register.
+ */
+#define PIC32_EMAC1SUPP_RESETRMII   0x0800  /* Reset the RMII module */
+#define PIC32_EMAC1SUPP_SPEEDRMII   0x0100  /* RMII speed: 1=100Mbps,
0=10Mbps */
+
+/*
+ * Ethernet MAC test register.
+ */
+#define PIC32_EMAC1TEST_TESTBP      0x0004  /* Test backpressure */
+#define PIC32_EMAC1TEST_TESTPAUSE   0x0002  /* Test pause */
+#define PIC32_EMAC1TEST_SHRTQNTA    0x0001  /* Shortcut pause quanta */
+
+/*
+ * Ethernet MII configuration register.
+ */
+#define PIC32_EMAC1MCFG_RESETMGMT   0x8000  /* Reset the MII module */
+#define PIC32_EMAC1MCFG_CLKSEL_4    0x0000  /* Clock divide by 4 */
+#define PIC32_EMAC1MCFG_CLKSEL_6    0x0008  /* Clock divide by 6 */
+#define PIC32_EMAC1MCFG_CLKSEL_8    0x000c  /* Clock divide by 8 */
+#define PIC32_EMAC1MCFG_CLKSEL_10   0x0010  /* Clock divide by 10 */
+#define PIC32_EMAC1MCFG_CLKSEL_14   0x0014  /* Clock divide by 14 */
+#define PIC32_EMAC1MCFG_CLKSEL_20   0x0018  /* Clock divide by 20 */
+#define PIC32_EMAC1MCFG_CLKSEL_28   0x001c  /* Clock divide by 28 */
+#define PIC32_EMAC1MCFG_CLKSEL_40   0x0020  /* Clock divide by 40 */
+#define PIC32_EMAC1MCFG_CLKSEL_48   0x0024  /* Clock divide by 48 */
+#define PIC32_EMAC1MCFG_CLKSEL_50   0x0028  /* Clock divide by 50 */
+#define PIC32_EMAC1MCFG_NOPRE       0x0002  /* Suppress preamble */
+#define PIC32_EMAC1MCFG_SCANINC     0x0001  /* Scan increment */
+
+/*
+ * Ethernet MII command register.
+ */
+#define PIC32_EMAC1MCMD_SCAN        0x0002  /* Continuous scan mode */
+#define PIC32_EMAC1MCMD_READ        0x0001  /* Single read cycle */
+
+/*
+ * Ethernet MII address register.
+ */
+#define PIC32_EMAC1MADR(p, r)       ((p)<<8 | (r))
+
+/*
+ * Ethernet MII indicators register.
+ */
+#define PIC32_EMAC1MIND_LINKFAIL    0x0008  /* Link fail */
+#define PIC32_EMAC1MIND_NOTVALID    0x0004  /* Read data not valid */
+#define PIC32_EMAC1MIND_SCAN        0x0002  /* Scanning in progress */
+#define PIC32_EMAC1MIND_MIIMBUSY    0x0001  /* Read/write cycle in progress */
+
+/*--------------------------------------
+ * Interrupt controller registers.
+ */
+#define INTCON          PIC32_R (0x10000)       /* Interrupt Control */
+#define INTCONCLR       PIC32_R (0x10004)
+#define INTCONSET       PIC32_R (0x10008)
+#define INTCONINV       PIC32_R (0x1000C)
+#define PRISS           PIC32_R (0x10010)       /* Priority Shadow Select */
+#define PRISSCLR        PIC32_R (0x10014)
+#define PRISSSET        PIC32_R (0x10018)
+#define PRISSINV        PIC32_R (0x1001C)
+#define INTSTAT         PIC32_R (0x10020)       /* Interrupt Status */
+#define IPTMR           PIC32_R (0x10030)       /* Temporal Proximity Timer */
+#define IPTMRCLR        PIC32_R (0x10034)
+#define IPTMRSET        PIC32_R (0x10038)
+#define IPTMRINV        PIC32_R (0x1003C)
+#define IFS(n)          PIC32_R (0x10040+((n)<<4)) /* IFS(0..5) -
Interrupt Flag Status */
+#define IFSCLR(n)       PIC32_R (0x10044+((n)<<4))
+#define IFSSET(n)       PIC32_R (0x10048+((n)<<4))
+#define IFSINV(n)       PIC32_R (0x1004C+((n)<<4))
+#define IFS0            IFS(0)
+#define IFS1            IFS(1)
+#define IFS2            IFS(2)
+#define IFS3            IFS(3)
+#define IFS4            IFS(4)
+#define IFS5            IFS(5)
+#define IEC(n)          PIC32_R (0x100c0+((n)<<4)) /* IEC(0..5) -
Interrupt Enable Control */
+#define IECCLR(n)       PIC32_R (0x100c4+((n)<<4))
+#define IECSET(n)       PIC32_R (0x100c8+((n)<<4))
+#define IECINV(n)       PIC32_R (0x100cC+((n)<<4))
+#define IEC0            IEC(0)
+#define IEC1            IEC(1)
+#define IEC2            IEC(2)
+#define IEC3            IEC(3)
+#define IEC4            IEC(4)
+#define IEC5            IEC(5)
+#define IPC(n)          PIC32_R (0x10140+((n)<<4)) /* IPC(0..47) -
Interrupt Priority Control */
+#define IPCCLR(n)       PIC32_R (0x10144+((n)<<4))
+#define IPCSET(n)       PIC32_R (0x10148+((n)<<4))
+#define IPCINV(n)       PIC32_R (0x1014C+((n)<<4))
+#define IPC0            IPC(0)
+#define IPC1            IPC(1)
+#define IPC2            IPC(2)
+#define IPC3            IPC(3)
+#define IPC4            IPC(4)
+#define IPC5            IPC(5)
+#define IPC6            IPC(6)
+#define IPC7            IPC(7)
+#define IPC8            IPC(8)
+#define IPC9            IPC(9)
+#define IPC10           IPC(10)
+#define IPC11           IPC(11)
+#define IPC12           IPC(12)
+#define IPC13           IPC(13)
+#define IPC14           IPC(14)
+#define IPC15           IPC(15)
+#define IPC16           IPC(16)
+#define IPC17           IPC(17)
+#define IPC18           IPC(18)
+#define IPC19           IPC(19)
+#define IPC20           IPC(20)
+#define IPC21           IPC(21)
+#define IPC22           IPC(22)
+#define IPC23           IPC(23)
+#define IPC24           IPC(24)
+#define IPC25           IPC(25)
+#define IPC26           IPC(26)
+#define IPC27           IPC(27)
+#define IPC28           IPC(28)
+#define IPC29           IPC(29)
+#define IPC30           IPC(30)
+#define IPC31           IPC(31)
+#define IPC32           IPC(32)
+#define IPC33           IPC(33)
+#define IPC34           IPC(34)
+#define IPC35           IPC(35)
+#define IPC36           IPC(36)
+#define IPC37           IPC(37)
+#define IPC38           IPC(38)
+#define IPC39           IPC(39)
+#define IPC40           IPC(40)
+#define IPC41           IPC(41)
+#define IPC42           IPC(42)
+#define IPC43           IPC(43)
+#define IPC44           IPC(44)
+#define IPC45           IPC(45)
+#define IPC46           IPC(46)
+#define IPC47           IPC(47)
+#define OFF(n)          PIC32_R (0x10540+((n)<<2)) /* OFF(0..190) -
Interrupt Vector Address Offset */
+
+/*
+ * Interrupt Control register.
+ */
+#define PIC32_INTCON_INT0EP     0x00000001  /* External interrupt 0
polarity rising edge */
+#define PIC32_INTCON_INT1EP     0x00000002  /* External interrupt 1
polarity rising edge */
+#define PIC32_INTCON_INT2EP     0x00000004  /* External interrupt 2
polarity rising edge */
+#define PIC32_INTCON_INT3EP     0x00000008  /* External interrupt 3
polarity rising edge */
+#define PIC32_INTCON_INT4EP     0x00000010  /* External interrupt 4
polarity rising edge */
+#define PIC32_INTCON_TPC(x)     ((x)<<8)    /* Temporal proximity
group priority */
+#define PIC32_INTCON_MVEC       0x00001000  /* Multi-vectored mode */
+#define PIC32_INTCON_SS0        0x00010000  /* Single vector has a
shadow register set */
+#define PIC32_INTCON_VS(x)      ((x)<<16)   /* Temporal proximity
group priority */
+
+/*
+ * Interrupt Status register.
+ */
+#define PIC32_INTSTAT_VEC(s)    ((s) & 0xff)    /* Interrupt vector */
+#define PIC32_INTSTAT_SRIPL(s)  ((s) >> 8 & 7)  /* Requested priority level */
+#define PIC32_INTSTAT_SRIPL_MASK 0x0700
+
+/*
+ * Interrupt Prority Control register.
+ */
+#define PIC32_IPC_IP(a,b,c,d)   ((a)<<2 | (b)<<10 | (c)<<18 |
(d)<<26)  /* Priority */
+#define PIC32_IPC_IS(a,b,c,d)   ((a) | (b)<<8 | (c)<<16 | (d)<<24)
  /* Subpriority */
+
+/*
+ * IRQ numbers for PIC32MZ
+ */
+#define PIC32_IRQ_CT        0   /* Core Timer Interrupt */
+#define PIC32_IRQ_CS0       1   /* Core Software Interrupt 0 */
+#define PIC32_IRQ_CS1       2   /* Core Software Interrupt 1 */
+#define PIC32_IRQ_INT0      3   /* External Interrupt 0 */
+#define PIC32_IRQ_T1        4   /* Timer1 */
+#define PIC32_IRQ_IC1E      5   /* Input Capture 1 Error */
+#define PIC32_IRQ_IC1       6   /* Input Capture 1 */
+#define PIC32_IRQ_OC1       7   /* Output Compare 1 */
+#define PIC32_IRQ_INT1      8   /* External Interrupt 1 */
+#define PIC32_IRQ_T2        9   /* Timer2 */
+#define PIC32_IRQ_IC2E      10  /* Input Capture 2 Error */
+#define PIC32_IRQ_IC2       11  /* Input Capture 2 */
+#define PIC32_IRQ_OC2       12  /* Output Compare 2 */
+#define PIC32_IRQ_INT2      13  /* External Interrupt 2 */
+#define PIC32_IRQ_T3        14  /* Timer3 */
+#define PIC32_IRQ_IC3E      15  /* Input Capture 3 Error */
+#define PIC32_IRQ_IC3       16  /* Input Capture 3 */
+#define PIC32_IRQ_OC3       17  /* Output Compare 3 */
+#define PIC32_IRQ_INT3      18  /* External Interrupt 3 */
+#define PIC32_IRQ_T4        19  /* Timer4 */
+#define PIC32_IRQ_IC4E      20  /* Input Capture 4 Error */
+#define PIC32_IRQ_IC4       21  /* Input Capture 4 */
+#define PIC32_IRQ_OC4       22  /* Output Compare 4 */
+#define PIC32_IRQ_INT4      23  /* External Interrupt 4 */
+#define PIC32_IRQ_T5        24  /* Timer5 */
+#define PIC32_IRQ_IC5E      25  /* Input Capture 5 Error */
+#define PIC32_IRQ_IC5       26  /* Input Capture 5 */
+#define PIC32_IRQ_OC5       27  /* Output Compare 5 */
+#define PIC32_IRQ_T6        28  /* Timer6 */
+#define PIC32_IRQ_IC6E      29  /* Input Capture 6 Error */
+#define PIC32_IRQ_IC6       30  /* Input Capture 6 */
+#define PIC32_IRQ_OC6       31  /* Output Compare 6 */
+#define PIC32_IRQ_T7        32  /* Timer7 */
+#define PIC32_IRQ_IC7E      33  /* Input Capture 7 Error */
+#define PIC32_IRQ_IC7       34  /* Input Capture 7 */
+#define PIC32_IRQ_OC7       35  /* Output Compare 7 */
+#define PIC32_IRQ_T8        36  /* Timer8 */
+#define PIC32_IRQ_IC8E      37  /* Input Capture 8 Error */
+#define PIC32_IRQ_IC8       38  /* Input Capture 8 */
+#define PIC32_IRQ_OC8       39  /* Output Compare 8 */
+#define PIC32_IRQ_T9        40  /* Timer9 */
+#define PIC32_IRQ_IC9E      41  /* Input Capture 9 Error */
+#define PIC32_IRQ_IC9       42  /* Input Capture 9 */
+#define PIC32_IRQ_OC9       43  /* Output Compare 9 */
+#define PIC32_IRQ_AD1       44  /* ADC1 Global Interrupt */
+                         /* 45  -- Reserved */
+#define PIC32_IRQ_AD1DC1    46  /* ADC1 Digital Comparator 1 */
+#define PIC32_IRQ_AD1DC2    47  /* ADC1 Digital Comparator 2 */
+#define PIC32_IRQ_AD1DC3    48  /* ADC1 Digital Comparator 3 */
+#define PIC32_IRQ_AD1DC4    49  /* ADC1 Digital Comparator 4 */
+#define PIC32_IRQ_AD1DC5    50  /* ADC1 Digital Comparator 5 */
+#define PIC32_IRQ_AD1DC6    51  /* ADC1 Digital Comparator 6 */
+#define PIC32_IRQ_AD1DF1    52  /* ADC1 Digital Filter 1 */
+#define PIC32_IRQ_AD1DF2    53  /* ADC1 Digital Filter 2 */
+#define PIC32_IRQ_AD1DF3    54  /* ADC1 Digital Filter 3 */
+#define PIC32_IRQ_AD1DF4    55  /* ADC1 Digital Filter 4 */
+#define PIC32_IRQ_AD1DF5    56  /* ADC1 Digital Filter 5 */
+#define PIC32_IRQ_AD1DF6    57  /* ADC1 Digital Filter 6 */
+                         /* 58  -- Reserved */
+#define PIC32_IRQ_AD1D0     59  /* ADC1 Data 0 */
+#define PIC32_IRQ_AD1D1     60  /* ADC1 Data 1 */
+#define PIC32_IRQ_AD1D2     61  /* ADC1 Data 2 */
+#define PIC32_IRQ_AD1D3     62  /* ADC1 Data 3 */
+#define PIC32_IRQ_AD1D4     63  /* ADC1 Data 4 */
+#define PIC32_IRQ_AD1D5     64  /* ADC1 Data 5 */
+#define PIC32_IRQ_AD1D6     65  /* ADC1 Data 6 */
+#define PIC32_IRQ_AD1D7     66  /* ADC1 Data 7 */
+#define PIC32_IRQ_AD1D8     67  /* ADC1 Data 8 */
+#define PIC32_IRQ_AD1D9     68  /* ADC1 Data 9 */
+#define PIC32_IRQ_AD1D10    69  /* ADC1 Data 10 */
+#define PIC32_IRQ_AD1D11    70  /* ADC1 Data 11 */
+#define PIC32_IRQ_AD1D12    71  /* ADC1 Data 12 */
+#define PIC32_IRQ_AD1D13    72  /* ADC1 Data 13 */
+#define PIC32_IRQ_AD1D14    73  /* ADC1 Data 14 */
+#define PIC32_IRQ_AD1D15    74  /* ADC1 Data 15 */
+#define PIC32_IRQ_AD1D16    75  /* ADC1 Data 16 */
+#define PIC32_IRQ_AD1D17    76  /* ADC1 Data 17 */
+#define PIC32_IRQ_AD1D18    77  /* ADC1 Data 18 */
+#define PIC32_IRQ_AD1D19    78  /* ADC1 Data 19 */
+#define PIC32_IRQ_AD1D20    79  /* ADC1 Data 20 */
+#define PIC32_IRQ_AD1D21    80  /* ADC1 Data 21 */
+#define PIC32_IRQ_AD1D22    81  /* ADC1 Data 22 */
+#define PIC32_IRQ_AD1D23    82  /* ADC1 Data 23 */
+#define PIC32_IRQ_AD1D24    83  /* ADC1 Data 24 */
+#define PIC32_IRQ_AD1D25    84  /* ADC1 Data 25 */
+#define PIC32_IRQ_AD1D26    85  /* ADC1 Data 26 */
+#define PIC32_IRQ_AD1D27    86  /* ADC1 Data 27 */
+#define PIC32_IRQ_AD1D28    87  /* ADC1 Data 28 */
+#define PIC32_IRQ_AD1D29    88  /* ADC1 Data 29 */
+#define PIC32_IRQ_AD1D30    89  /* ADC1 Data 30 */
+#define PIC32_IRQ_AD1D31    90  /* ADC1 Data 31 */
+#define PIC32_IRQ_AD1D32    91  /* ADC1 Data 32 */
+#define PIC32_IRQ_AD1D33    92  /* ADC1 Data 33 */
+#define PIC32_IRQ_AD1D34    93  /* ADC1 Data 34 */
+#define PIC32_IRQ_AD1D35    94  /* ADC1 Data 35 */
+#define PIC32_IRQ_AD1D36    95  /* ADC1 Data 36 */
+#define PIC32_IRQ_AD1D37    96  /* ADC1 Data 37 */
+#define PIC32_IRQ_AD1D38    97  /* ADC1 Data 38 */
+#define PIC32_IRQ_AD1D39    98  /* ADC1 Data 39 */
+#define PIC32_IRQ_AD1D40    99  /* ADC1 Data 40 */
+#define PIC32_IRQ_AD1D41    100 /* ADC1 Data 41 */
+#define PIC32_IRQ_AD1D42    101 /* ADC1 Data 42 */
+#define PIC32_IRQ_AD1D43    102 /* ADC1 Data 43 */
+#define PIC32_IRQ_AD1D44    103 /* ADC1 Data 44 */
+#define PIC32_IRQ_CPC       104 /* Core Performance Counter */
+#define PIC32_IRQ_CFDC      105 /* Core Fast Debug Channel */
+#define PIC32_IRQ_SB        106 /* System Bus Protection Violation */
+#define PIC32_IRQ_CRPT      107 /* Crypto Engine Event */
+                         /* 108 -- Reserved */
+#define PIC32_IRQ_SPI1E     109 /* SPI1 Fault */
+#define PIC32_IRQ_SPI1RX    110 /* SPI1 Receive Done */
+#define PIC32_IRQ_SPI1TX    111 /* SPI1 Transfer Done */
+#define PIC32_IRQ_U1E       112 /* UART1 Fault */
+#define PIC32_IRQ_U1RX      113 /* UART1 Receive Done */
+#define PIC32_IRQ_U1TX      114 /* UART1 Transfer Done */
+#define PIC32_IRQ_I2C1B     115 /* I2C1 Bus Collision Event */
+#define PIC32_IRQ_I2C1S     116 /* I2C1 Slave Event */
+#define PIC32_IRQ_I2C1M     117 /* I2C1 Master Event */
+#define PIC32_IRQ_CNA       118 /* PORTA Input Change Interrupt */
+#define PIC32_IRQ_CNB       119 /* PORTB Input Change Interrupt */
+#define PIC32_IRQ_CNC       120 /* PORTC Input Change Interrupt */
+#define PIC32_IRQ_CND       121 /* PORTD Input Change Interrupt */
+#define PIC32_IRQ_CNE       122 /* PORTE Input Change Interrupt */
+#define PIC32_IRQ_CNF       123 /* PORTF Input Change Interrupt */
+#define PIC32_IRQ_CNG       124 /* PORTG Input Change Interrupt */
+#define PIC32_IRQ_CNH       125 /* PORTH Input Change Interrupt */
+#define PIC32_IRQ_CNJ       126 /* PORTJ Input Change Interrupt */
+#define PIC32_IRQ_CNK       127 /* PORTK Input Change Interrupt */
+#define PIC32_IRQ_PMP       128 /* Parallel Master Port */
+#define PIC32_IRQ_PMPE      129 /* Parallel Master Port Error */
+#define PIC32_IRQ_CMP1      130 /* Comparator 1 Interrupt */
+#define PIC32_IRQ_CMP2      131 /* Comparator 2 Interrupt */
+#define PIC32_IRQ_USB       132 /* USB General Event */
+#define PIC32_IRQ_USBDMA    133 /* USB DMA Event */
+#define PIC32_IRQ_DMA0      134 /* DMA Channel 0 */
+#define PIC32_IRQ_DMA1      135 /* DMA Channel 1 */
+#define PIC32_IRQ_DMA2      136 /* DMA Channel 2 */
+#define PIC32_IRQ_DMA3      137 /* DMA Channel 3 */
+#define PIC32_IRQ_DMA4      138 /* DMA Channel 4 */
+#define PIC32_IRQ_DMA5      139 /* DMA Channel 5 */
+#define PIC32_IRQ_DMA6      140 /* DMA Channel 6 */
+#define PIC32_IRQ_DMA7      141 /* DMA Channel 7 */
+#define PIC32_IRQ_SPI2E     142 /* SPI2 Fault */
+#define PIC32_IRQ_SPI2RX    143 /* SPI2 Receive Done */
+#define PIC32_IRQ_SPI2TX    144 /* SPI2 Transfer Done */
+#define PIC32_IRQ_U2E       145 /* UART2 Fault */
+#define PIC32_IRQ_U2RX      146 /* UART2 Receive Done */
+#define PIC32_IRQ_U2TX      147 /* UART2 Transfer Done */
+#define PIC32_IRQ_I2C2B     148 /* I2C2 Bus Collision Event */
+#define PIC32_IRQ_I2C2S     149 /* I2C2 Slave Event */
+#define PIC32_IRQ_I2C2M     150 /* I2C2 Master Event */
+#define PIC32_IRQ_CAN1      151 /* Control Area Network 1 */
+#define PIC32_IRQ_CAN2      152 /* Control Area Network 2 */
+#define PIC32_IRQ_ETH       153 /* Ethernet Interrupt */
+#define PIC32_IRQ_SPI3E     154 /* SPI3 Fault */
+#define PIC32_IRQ_SPI3RX    155 /* SPI3 Receive Done */
+#define PIC32_IRQ_SPI3TX    156 /* SPI3 Transfer Done */
+#define PIC32_IRQ_U3E       157 /* UART3 Fault */
+#define PIC32_IRQ_U3RX      158 /* UART3 Receive Done */
+#define PIC32_IRQ_U3TX      159 /* UART3 Transfer Done */
+#define PIC32_IRQ_I2C3B     160 /* I2C3 Bus Collision Event */
+#define PIC32_IRQ_I2C3S     161 /* I2C3 Slave Event */
+#define PIC32_IRQ_I2C3M     162 /* I2C3 Master Event */
+#define PIC32_IRQ_SPI4E     163 /* SPI4 Fault */
+#define PIC32_IRQ_SPI4RX    164 /* SPI4 Receive Done */
+#define PIC32_IRQ_SPI4TX    165 /* SPI4 Transfer Done */
+#define PIC32_IRQ_RTCC      166 /* Real Time Clock */
+#define PIC32_IRQ_FCE       167 /* Flash Control Event */
+#define PIC32_IRQ_PRE       168 /* Prefetch Module SEC Event */
+#define PIC32_IRQ_SQI1      169 /* SQI1 Event */
+#define PIC32_IRQ_U4E       170 /* UART4 Fault */
+#define PIC32_IRQ_U4RX      171 /* UART4 Receive Done */
+#define PIC32_IRQ_U4TX      172 /* UART4 Transfer Done */
+#define PIC32_IRQ_I2C4B     173 /* I2C4 Bus Collision Event */
+#define PIC32_IRQ_I2C4S     174 /* I2C4 Slave Event */
+#define PIC32_IRQ_I2C4M     175 /* I2C4 Master Event */
+#define PIC32_IRQ_SPI5E     176 /* SPI5 Fault */
+#define PIC32_IRQ_SPI5RX    177 /* SPI5 Receive Done */
+#define PIC32_IRQ_SPI5TX    178 /* SPI5 Transfer Done */
+#define PIC32_IRQ_U5E       179 /* UART5 Fault */
+#define PIC32_IRQ_U5RX      180 /* UART5 Receive Done */
+#define PIC32_IRQ_U5TX      181 /* UART5 Transfer Done */
+#define PIC32_IRQ_I2C5B     182 /* I2C5 Bus Collision Event */
+#define PIC32_IRQ_I2C5S     183 /* I2C5 Slave Event */
+#define PIC32_IRQ_I2C5M     184 /* I2C5 Master Event */
+#define PIC32_IRQ_SPI6E     185 /* SPI6 Fault */
+#define PIC32_IRQ_SPI6RX    186 /* SPI6 Receive Done */
+#define PIC32_IRQ_SPI6TX    187 /* SPI6 Transfer Done */
+#define PIC32_IRQ_U6E       188 /* UART6 Fault */
+#define PIC32_IRQ_U6RX      189 /* UART6 Receive Done */
+#define PIC32_IRQ_U6TX      190 /* UART6 Transfer Done */
+                         /* 191 -- Reserved */
+#define PIC32_IRQ_LAST      190 /* Last valid irq number */
+
+#endif /* _IO_PIC32MZ_H */
--
1.9.1



reply via email to

[Prev in Thread] Current Thread [Next in Thread]