summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-23 08:10:49 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-23 08:10:49 -0600
commit510496d8fbcf3dc46263f1971bc0756d75b1479e (patch)
treeb3ad891b0d9c0a04dc9544f492765025d6542d23
parent3bf1913181c48e270f1dd9f1a42386f31b7c1c48 (diff)
downloadpx4-nuttx-510496d8fbcf3dc46263f1971bc0756d75b1479e.tar.gz
px4-nuttx-510496d8fbcf3dc46263f1971bc0756d75b1479e.tar.bz2
px4-nuttx-510496d8fbcf3dc46263f1971bc0756d75b1479e.zip
PIC32MZ: Clone PIC32MX Ethernet driver to PIC32MZX (not yet verified)
-rw-r--r--nuttx/arch/mips/src/pic32mz/chip/pic32mz_ethernet.h1001
-rw-r--r--nuttx/arch/mips/src/pic32mz/pic32mz_ethernet.c3273
2 files changed, 4274 insertions, 0 deletions
diff --git a/nuttx/arch/mips/src/pic32mz/chip/pic32mz_ethernet.h b/nuttx/arch/mips/src/pic32mz/chip/pic32mz_ethernet.h
new file mode 100644
index 000000000..753c3d9fd
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mz/chip/pic32mz_ethernet.h
@@ -0,0 +1,1001 @@
+/****************************************************************************************************
+ * arch/mips/src/pic32mz/chip/pic32mz-ethernet.h
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************************************/
+
+#ifndef __ARCH_MIPS_SRC_PIC32MZ_CHIP_PIC32MZ_ETHERNET_H
+#define __ARCH_MIPS_SRC_PIC32MZ_CHIP_PIC32MZ_ETHERNET_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <arch/pic32mz/chip.h>
+
+#include "chip/pic32mz-memorymap.h"
+
+#if CHIP_NETHERNET > 0
+
+/****************************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************************/
+/* Register Offsets *********************************************************************************/
+
+/* Controller and DMA Engine Configuration/Status Registers */
+
+#define PIC32MZ_ETH_CON1_OFFSET 0x0000 /* Ethernet Controller Control 1 Register */
+#define PIC32MZ_ETH_CON1CLR_OFFSET 0x0004
+#define PIC32MZ_ETH_CON1SET_OFFSET 0x0008
+#define PIC32MZ_ETH_CON1INV_OFFSET 0x000c
+
+#define PIC32MZ_ETH_CON2_OFFSET 0x0010 /* Ethernet Controller Control 2 Register */
+#define PIC32MZ_ETH_CON2CLR_OFFSET 0x0014
+#define PIC32MZ_ETH_CON2SET_OFFSET 0x0018
+#define PIC32MZ_ETH_CON2INV_OFFSET 0x001c
+
+#define PIC32MZ_ETH_TXST_OFFSET 0x0020 /* Ethernet Controller TX Packet Descriptor Start Address Register */
+#define PIC32MZ_ETH_TXSTCLR_OFFSET 0x0024
+#define PIC32MZ_ETH_TXSTSET_OFFSET 0x0028
+#define PIC32MZ_ETH_TXSTINV_OFFSET 0x002c
+
+#define PIC32MZ_ETH_RXST_OFFSET 0x0030 /* Ethernet Controller RX Packet Descriptor Start Address Register */
+#define PIC32MZ_ETH_RXSTCLR_OFFSET 0x0034
+#define PIC32MZ_ETH_RXSTSET_OFFSET 0x0038
+#define PIC32MZ_ETH_RXSTINV_OFFSET 0x003c
+
+#define PIC32MZ_ETH_IEN_OFFSET 0x00c0 /* Ethernet Controller Interrupt Enable Register */
+#define PIC32MZ_ETH_IENCLR_OFFSET 0x00c4
+#define PIC32MZ_ETH_IENSET_OFFSET 0x00c8
+#define PIC32MZ_ETH_IENINV_OFFSET 0x00cc
+
+#define PIC32MZ_ETH_IRQ_OFFSET 0x00d0 /* Ethernet Controller Interrupt Request Register */
+#define PIC32MZ_ETH_IRQCLR_OFFSET 0x00d4
+#define PIC32MZ_ETH_IRQSET_OFFSET 0x00d8
+#define PIC32MZ_ETH_IRQINV_OFFSET 0x00dc
+
+#define PIC32MZ_ETH_STAT_OFFSET 0x00e0 /* Ethernet Controller Status Register */
+
+/* RX Filtering Configuration Registers */
+
+#define PIC32MZ_ETH_RXFC_OFFSET 0x00a0 /* Ethernet Controller Receive Filter Configuration Register */
+#define PIC32MZ_ETH_RXFCCLR_OFFSET 0x00a4
+#define PIC32MZ_ETH_RXFCSET_OFFSET 0x00a8
+#define PIC32MZ_ETH_RXFCINV_OFFSET 0x00ac
+
+#define PIC32MZ_ETH_HT0_OFFSET 0x0040 /* Ethernet Controller Hash Table 0 Register */
+#define PIC32MZ_ETH_HT0CLR_OFFSET 0x0044
+#define PIC32MZ_ETH_HT0SET_OFFSET 0x0048
+#define PIC32MZ_ETH_HT0INV_OFFSET 0x004c
+
+#define PIC32MZ_ETH_HT1_OFFSET 0x0050 /* Ethernet Controller Hash Table 1 Register */
+#define PIC32MZ_ETH_HT1CLR_OFFSET 0x0054
+#define PIC32MZ_ETH_HT1SET_OFFSET 0x0058
+#define PIC32MZ_ETH_HT1INV_OFFSET 0x005c
+
+#define PIC32MZ_ETH_PMM0_OFFSET 0x0060 /* Ethernet Controller Pattern Match Mask 0 Register */
+#define PIC32MZ_ETH_PMM0CLR_OFFSET 0x0064
+#define PIC32MZ_ETH_PMM0SET_OFFSET 0x0068
+#define PIC32MZ_ETH_PMM0INV_OFFSET 0x006c
+
+#define PIC32MZ_ETH_PMM1_OFFSET 0x0070 /* Ethernet Controller Pattern Match Mask 1 Register */
+#define PIC32MZ_ETH_PMM1CLR_OFFSET 0x0074
+#define PIC32MZ_ETH_PMM1SET_OFFSET 0x0078
+#define PIC32MZ_ETH_PMM1INV_OFFSET 0x007c
+
+#define PIC32MZ_ETH_PMCS_OFFSET 0x0080 /* Ethernet Controller Pattern Match Checksum Register */
+#define PIC32MZ_ETH_PMCSCLR_OFFSET 0x0084
+#define PIC32MZ_ETH_PMCSSET_OFFSET 0x0088
+#define PIC32MZ_ETH_PMCSINV_OFFSET 0x008c
+
+#define PIC32MZ_ETH_PMO_OFFSET 0x0090 /* Ethernet Controller Pattern Match Offset Register */
+#define PIC32MZ_ETH_PMOCLR_OFFSET 0x0094
+#define PIC32MZ_ETH_PMOSET_OFFSET 0x0098
+#define PIC32MZ_ETH_PMOINV_OFFSET 0x009c
+
+/* Flow Control Configuring Register */
+
+#define PIC32MZ_ETH_RXWM_OFFSET 0x00b0 /* Ethernet Controller Receive Watermarks Register */
+#define PIC32MZ_ETH_RXWMCLR_OFFSET 0x00b4
+#define PIC32MZ_ETH_RXWMSET_OFFSET 0x00b8
+#define PIC32MZ_ETH_RXWMINV_OFFSET 0x00bc
+
+/* Ethernet Statistics Registers */
+
+#define PIC32MZ_ETH_RXOVFLOW_OFFSET 0x0100 /* Ethernet Controller Receive Overflow Statistics Register */
+#define PIC32MZ_ETH_RXOVFLOWCLR_OFFSET 0x0104
+#define PIC32MZ_ETH_RXOVFLOWSET_OFFSET 0x0108
+#define PIC32MZ_ETH_RXOVFLOWINV_OFFSET 0x010c
+
+#define PIC32MZ_ETH_FRMTXOK_OFFSET 0x0110 /* Ethernet Controller Frames Transmitted OK Statistics Register */
+#define PIC32MZ_ETH_FRMTXOKCLR_OFFSET 0x0114
+#define PIC32MZ_ETH_FRMTXOKSET_OFFSET 0x0118
+#define PIC32MZ_ETH_FRMTXOKINV_OFFSET 0x011c
+
+#define PIC32MZ_ETH_SCOLFRM_OFFSET 0x0120 /* Ethernet Controller Single Collision Frames Statistics Register */
+#define PIC32MZ_ETH_SCOLFRMCLR_OFFSET 0x0124
+#define PIC32MZ_ETH_SCOLFRMSET_OFFSET 0x0128
+#define PIC32MZ_ETH_SCOLFRMINV_OFFSET 0x012c
+
+#define PIC32MZ_ETH_MCOLFRM_OFFSET 0x0130 /* Ethernet Controller Multiple Collision Frames Statistics Register */
+#define PIC32MZ_ETH_MCOLFRMCLR_OFFSET 0x0134
+#define PIC32MZ_ETH_MCOLFRMSET_OFFSET 0x0138
+#define PIC32MZ_ETH_MCOLFRMINV_OFFSET 0x013c
+
+#define PIC32MZ_ETH_FRMRXOK_OFFSET 0x0140 /* Ethernet Controller Frames Received OK Statistics Register */
+#define PIC32MZ_ETH_FRMRXOKCLR_OFFSET 0x0144
+#define PIC32MZ_ETH_FRMRXOKSET_OFFSET 0x0148
+#define PIC32MZ_ETH_FRMRXOKINV_OFFSET 0x014c
+
+#define PIC32MZ_ETH_FCSERR_OFFSET 0x0150 /* Ethernet Controller Frame Check Sequence Error Statistics Register */
+#define PIC32MZ_ETH_FCSERRCLR_OFFSET 0x0154
+#define PIC32MZ_ETH_FCSERRSET_OFFSET 0x0158
+#define PIC32MZ_ETH_FCSERRINV_OFFSET 0x015c
+
+#define PIC32MZ_ETH_ALGNERR_OFFSET 0x0160 /* Ethernet Controller Alignment Errors Statistics Register */
+#define PIC32MZ_ETH_ALGNERRCLR_OFFSET 0x0164
+#define PIC32MZ_ETH_ALGNERRSET_OFFSET 0x0168
+#define PIC32MZ_ETH_ALGNERRINV_OFFSET 0x016c
+
+/* MAC Configuration Registers */
+
+#define PIC32MZ_EMAC1_CFG1_OFFSET 0x0200 /* Ethernet Controller MAC Configuration 1 Register */
+#define PIC32MZ_EMAC1_CFG1CLR_OFFSET 0x0204
+#define PIC32MZ_EMAC1_CFG1SET_OFFSET 0x0208
+#define PIC32MZ_EMAC1_CFG1INV_OFFSET 0x020c
+
+#define PIC32MZ_EMAC1_CFG2_OFFSET 0x0210 /* Ethernet Controller MAC Configuration 2 Register */
+#define PIC32MZ_EMAC1_CFG2CLR_OFFSET 0x0214
+#define PIC32MZ_EMAC1_CFG2SET_OFFSET 0x0218
+#define PIC32MZ_EMAC1_CFG2INV_OFFSET 0x021c
+
+#define PIC32MZ_EMAC1_IPGT_OFFSET 0x0220 /* Ethernet Controller MAC Back-to-Back Interpacket Gap Register */
+#define PIC32MZ_EMAC1_IPGTCLR_OFFSET 0x0224
+#define PIC32MZ_EMAC1_IPGTSET_OFFSET 0x0228
+#define PIC32MZ_EMAC1_IPGTINV_OFFSET 0x022c
+
+#define PIC32MZ_EMAC1_IPGR_OFFSET 0x0230 /* Ethernet Controller MAC Non-Back-to-Back Interpacket Gap Register */
+#define PIC32MZ_EMAC1_IPGRCLR_OFFSET 0x0234
+#define PIC32MZ_EMAC1_IPGRSET_OFFSET 0x0238
+#define PIC32MZ_EMAC1_IPGRINV_OFFSET 0x023c
+
+#define PIC32MZ_EMAC1_CLRT_OFFSET 0x0240 /* Ethernet Controller MAC Collision Window/Retry Limit Register */
+#define PIC32MZ_EMAC1_CLRTCLR_OFFSET 0x0244
+#define PIC32MZ_EMAC1_CLRTSET_OFFSET 0x0248
+#define PIC32MZ_EMAC1_CLRTINV_OFFSET 0x024c
+
+#define PIC32MZ_EMAC1_MAXF_OFFSET 0x0250 /* Ethernet Controller MAC Maximum Frame Length Register */
+#define PIC32MZ_EMAC1_MAXFCLR_OFFSET 0x0254
+#define PIC32MZ_EMAC1_MAXFSET_OFFSET 0x0258
+#define PIC32MZ_EMAC1_MAXFINV_OFFSET 0x025c
+
+#define PIC32MZ_EMAC1_SUPP_OFFSET 0x0260 /* Ethernet Controller MAC PHY Support Register */
+#define PIC32MZ_EMAC1_SUPPCLR_OFFSET 0x0264
+#define PIC32MZ_EMAC1_SUPPSET_OFFSET 0x0268
+#define PIC32MZ_EMAC1_SUPPINV_OFFSET 0x026c
+
+#define PIC32MZ_EMAC1_TEST_OFFSET 0x0270 /* Ethernet Controller MAC Test Register */
+#define PIC32MZ_EMAC1_TESTCLR_OFFSET 0x0274
+#define PIC32MZ_EMAC1_TESTSET_OFFSET 0x0278
+#define PIC32MZ_EMAC1_TESTINV_OFFSET 0x027c
+
+#define PIC32MZ_EMAC1_SA0_OFFSET 0x0300 /* Ethernet Controller MAC Station Address 0 Register */
+#define PIC32MZ_EMAC1_SA0CLR_OFFSET 0x0304
+#define PIC32MZ_EMAC1_SA0SET_OFFSET 0x0308
+#define PIC32MZ_EMAC1_SA0INV_OFFSET 0x030c
+
+#define PIC32MZ_EMAC1_SA1_OFFSET 0x0310 /* Ethernet Controller MAC Station Address 1 Register */
+#define PIC32MZ_EMAC1_SA1CLR_OFFSET 0x0314
+#define PIC32MZ_EMAC1_SA1SET_OFFSET 0x0318
+#define PIC32MZ_EMAC1_SA1INV_OFFSET 0x031c
+
+#define PIC32MZ_EMAC1_SA2_OFFSET 0x0320 /* Ethernet Controller MAC Station Address 2 Register */
+#define PIC32MZ_EMAC1_SA2CLR_OFFSET 0x0324
+#define PIC32MZ_EMAC1_SA2SET_OFFSET 0x0328
+#define PIC32MZ_EMAC1_SA2INV_OFFSET 0x032c
+
+/* MII Management Registers */
+
+#define PIC32MZ_EMAC1_MCFG_OFFSET 0x0280 /* Ethernet Controller MAC MII Management Configuration Register */
+#define PIC32MZ_EMAC1_MCFGCLR_OFFSET 0x0284
+#define PIC32MZ_EMAC1_MCFGSET_OFFSET 0x0288
+#define PIC32MZ_EMAC1_MCFGINV_OFFSET 0x028c
+
+#define PIC32MZ_EMAC1_MCMD_OFFSET 0x0290 /* Ethernet Controller MAC MII Management Command Register */
+#define PIC32MZ_EMAC1_MCMDCLR_OFFSET 0x0294
+#define PIC32MZ_EMAC1_MCMDSET_OFFSET 0x0298
+#define PIC32MZ_EMAC1_MCMDINV_OFFSET 0x029c
+
+#define PIC32MZ_EMAC1_MADR_OFFSET 0x02a0 /* Ethernet Controller MAC MII Management Address Register */
+#define PIC32MZ_EMAC1_MADRCLR_OFFSET 0x02a4
+#define PIC32MZ_EMAC1_MADRSET_OFFSET 0x02a8
+#define PIC32MZ_EMAC1_MADRINV_OFFSET 0x02ac
+
+#define PIC32MZ_EMAC1_MWTD_OFFSET 0x02b0 /* Ethernet Controller MAC MII Management Write Data Register */
+#define PIC32MZ_EMAC1_MWTDCLR_OFFSET 0x02b4
+#define PIC32MZ_EMAC1_MWTDSET_OFFSET 0x02b8
+#define PIC32MZ_EMAC1_MWTDINV_OFFSET 0x02bc
+
+#define PIC32MZ_EMAC1_MRDD_OFFSET 0x02c0 /* Ethernet Controller MAC MII Management Read Data Register */
+#define PIC32MZ_EMAC1_MRDDCLR_OFFSET 0x02c4
+#define PIC32MZ_EMAC1_MRDDSET_OFFSET 0x02c8
+#define PIC32MZ_EMAC1_MRDDINV_OFFSET 0x02cc
+
+#define PIC32MZ_EMAC1_MIND_OFFSET 0x02d0 /* Ethernet Controller MAC MII Management Indicators Register */
+#define PIC32MZ_EMAC1_MINDCLR_OFFSET 0x02d4
+#define PIC32MZ_EMAC1_MINDSET_OFFSET 0x02d8
+#define PIC32MZ_EMAC1_MINDINV_OFFSET 0x02dc
+
+/* Register Addresses *******************************************************************************/
+
+/* Controller and DMA Engine Configuration/Status Registers */
+
+#define PIC32MZ_ETH_CON1 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON1_OFFSET)
+#define PIC32MZ_ETH_CON1CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON1CLR_OFFSET)
+#define PIC32MZ_ETH_CON1SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON1SET_OFFSET)
+#define PIC32MZ_ETH_CON1INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON1INV_OFFSET)
+
+#define PIC32MZ_ETH_CON2 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON2_OFFSET)
+#define PIC32MZ_ETH_CON2CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON2CLR_OFFSET)
+#define PIC32MZ_ETH_CON2SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON2SET_OFFSET)
+#define PIC32MZ_ETH_CON2INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_CON2INV_OFFSET)
+
+#define PIC32MZ_ETH_TXST (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_TXST_OFFSET)
+#define PIC32MZ_ETH_TXSTCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_TXSTCLR_OFFSET)
+#define PIC32MZ_ETH_TXSTSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_TXSTSET_OFFSET)
+#define PIC32MZ_ETH_TXSTINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_TXSTINV_OFFSET)
+
+#define PIC32MZ_ETH_RXST (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXST_OFFSET)
+#define PIC32MZ_ETH_RXSTCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXSTCLR_OFFSET)
+#define PIC32MZ_ETH_RXSTSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXSTSET_OFFSET)
+#define PIC32MZ_ETH_RXSTINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXSTINV_OFFSET)
+
+#define PIC32MZ_ETH_IEN (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IEN_OFFSET)
+#define PIC32MZ_ETH_IENCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IENCLR_OFFSET)
+#define PIC32MZ_ETH_IENSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IENSET_OFFSET)
+#define PIC32MZ_ETH_IENINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IENINV_OFFSET)
+
+#define PIC32MZ_ETH_IRQ (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IRQ_OFFSET)
+#define PIC32MZ_ETH_IRQCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IRQCLR_OFFSET)
+#define PIC32MZ_ETH_IRQSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IRQSET_OFFSET)
+#define PIC32MZ_ETH_IRQINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_IRQINV_OFFSET)
+
+#define PIC32MZ_ETH_STAT (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_STAT_OFFSET)
+
+/* RX Filtering Configuration Registers */
+
+#define PIC32MZ_ETH_RXFC (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXFC_OFFSET)
+#define PIC32MZ_ETH_RXFCCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXFCCLR_OFFSET)
+#define PIC32MZ_ETH_RXFCSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXFCSET_OFFSET)
+#define PIC32MZ_ETH_RXFCINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXFCINV_OFFSET)
+
+#define PIC32MZ_ETH_HT0 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT0_OFFSET)
+#define PIC32MZ_ETH_HT0CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT0CLR_OFFSET)
+#define PIC32MZ_ETH_HT0SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT0SET_OFFSET)
+#define PIC32MZ_ETH_HT0INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT0INV_OFFSET)
+
+#define PIC32MZ_ETH_HT1 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT1_OFFSET)
+#define PIC32MZ_ETH_HT1CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT1CLR_OFFSET)
+#define PIC32MZ_ETH_HT1SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT1SET_OFFSET)
+#define PIC32MZ_ETH_HT1INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_HT1INV_OFFSET)
+
+#define PIC32MZ_ETH_PMM0 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM0_OFFSET)
+#define PIC32MZ_ETH_PMM0CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM0CLR_OFFSET)
+#define PIC32MZ_ETH_PMM0SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM0SET_OFFSET)
+#define PIC32MZ_ETH_PMM0INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM0INV_OFFSET)
+
+#define PIC32MZ_ETH_PMM1 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM1_OFFSET)
+#define PIC32MZ_ETH_PMM1CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM1CLR_OFFSET)
+#define PIC32MZ_ETH_PMM1SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM1SET_OFFSET)
+#define PIC32MZ_ETH_PMM1INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMM1INV_OFFSET)
+
+#define PIC32MZ_ETH_PMCS (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMCS_OFFSET)
+#define PIC32MZ_ETH_PMCSCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMCSCLR_OFFSET)
+#define PIC32MZ_ETH_PMCSSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMCSSET_OFFSET)
+#define PIC32MZ_ETH_PMCSINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMCSINV_OFFSET)
+
+#define PIC32MZ_ETH_PMO (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMO_OFFSET)
+#define PIC32MZ_ETH_PMOCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMOCLR_OFFSET)
+#define PIC32MZ_ETH_PMOSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMOSET_OFFSET)
+#define PIC32MZ_ETH_PMOINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_PMOINV_OFFSET)
+
+/* Flow Control Configuring Register */
+
+#define PIC32MZ_ETH_RXWM (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXWM_OFFSET)
+#define PIC32MZ_ETH_RXWMCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXWMCLR_OFFSET)
+#define PIC32MZ_ETH_RXWMSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXWMSET_OFFSET)
+#define PIC32MZ_ETH_RXWMINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXWMINV_OFFSET)
+
+/* Ethernet Statistics Registers */
+
+#define PIC32MZ_ETH_RXOVFLOW (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXOVFLOW_OFFSET)
+#define PIC32MZ_ETH_RXOVFLOWCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXOVFLOWCLR_OFFSET)
+#define PIC32MZ_ETH_RXOVFLOWSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXOVFLOWSET_OFFSET)
+#define PIC32MZ_ETH_RXOVFLOWINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_RXOVFLOWINV_OFFSET)
+
+#define PIC32MZ_ETH_FRMTXOK (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMTXOK_OFFSET)
+#define PIC32MZ_ETH_FRMTXOKCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMTXOKCLR_OFFSET)
+#define PIC32MZ_ETH_FRMTXOKSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMTXOKSET_OFFSET)
+#define PIC32MZ_ETH_FRMTXOKINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMTXOKINV_OFFSET)
+
+#define PIC32MZ_ETH_SCOLFRM (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_SCOLFRM_OFFSET)
+#define PIC32MZ_ETH_SCOLFRMCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_SCOLFRMCLR_OFFSET)
+#define PIC32MZ_ETH_SCOLFRMSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_SCOLFRMSET_OFFSET)
+#define PIC32MZ_ETH_SCOLFRMINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_SCOLFRMINV_OFFSET)
+
+#define PIC32MZ_ETH_MCOLFRM (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_MCOLFRM_OFFSET)
+#define PIC32MZ_ETH_MCOLFRMCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_MCOLFRMCLR_OFFSET)
+#define PIC32MZ_ETH_MCOLFRMSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_MCOLFRMSET_OFFSET)
+#define PIC32MZ_ETH_MCOLFRMINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_MCOLFRMINV_OFFSET)
+
+#define PIC32MZ_ETH_FRMRXOK (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMRXOK_OFFSET)
+#define PIC32MZ_ETH_FRMRXOKCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMRXOKCLR_OFFSET)
+#define PIC32MZ_ETH_FRMRXOKSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMRXOKSET_OFFSET)
+#define PIC32MZ_ETH_FRMRXOKINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FRMRXOKINV_OFFSET)
+
+#define PIC32MZ_ETH_FCSERR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FCSERR_OFFSET)
+#define PIC32MZ_ETH_FCSERRCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FCSERRCLR_OFFSET)
+#define PIC32MZ_ETH_FCSERRSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FCSERRSET_OFFSET)
+#define PIC32MZ_ETH_FCSERRINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_FCSERRINV_OFFSET)
+
+#define PIC32MZ_ETH_ALGNERR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_ALGNERR_OFFSET)
+#define PIC32MZ_ETH_ALGNERRCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_ALGNERRCLR_OFFSET)
+#define PIC32MZ_ETH_ALGNERRSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_ALGNERRSET_OFFSET)
+#define PIC32MZ_ETH_ALGNERRINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_ETH_ALGNERRINV_OFFSET)
+
+/* MAC Configuration Registers */
+
+#define PIC32MZ_EMAC1_CFG1 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG1_OFFSET)
+#define PIC32MZ_EMAC1_CFG1CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG1CLR_OFFSET)
+#define PIC32MZ_EMAC1_CFG1SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG1SET_OFFSET)
+#define PIC32MZ_EMAC1_CFG1INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG1INV_OFFSET)
+
+#define PIC32MZ_EMAC1_CFG2 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG2_OFFSET)
+#define PIC32MZ_EMAC1_CFG2CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG2CLR_OFFSET)
+#define PIC32MZ_EMAC1_CFG2SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG2SET_OFFSET)
+#define PIC32MZ_EMAC1_CFG2INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CFG2INV_OFFSET)
+
+#define PIC32MZ_EMAC1_IPGT (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGT_OFFSET)
+#define PIC32MZ_EMAC1_IPGTCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGTCLR_OFFSET)
+#define PIC32MZ_EMAC1_IPGTSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGTSET_OFFSET)
+#define PIC32MZ_EMAC1_IPGTINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGTINV_OFFSET)
+
+#define PIC32MZ_EMAC1_IPGR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGR_OFFSET)
+#define PIC32MZ_EMAC1_IPGRCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGRCLR_OFFSET)
+#define PIC32MZ_EMAC1_IPGRSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGRSET_OFFSET)
+#define PIC32MZ_EMAC1_IPGRINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_IPGRINV_OFFSET)
+
+#define PIC32MZ_EMAC1_CLRT (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CLRT_OFFSET)
+#define PIC32MZ_EMAC1_CLRTCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CLRTCLR_OFFSET)
+#define PIC32MZ_EMAC1_CLRTSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CLRTSET_OFFSET)
+#define PIC32MZ_EMAC1_CLRTINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_CLRTINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MAXF (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MAXF_OFFSET)
+#define PIC32MZ_EMAC1_MAXFCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MAXFCLR_OFFSET)
+#define PIC32MZ_EMAC1_MAXFSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MAXFSET_OFFSET)
+#define PIC32MZ_EMAC1_MAXFINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MAXFINV_OFFSET)
+
+#define PIC32MZ_EMAC1_SUPP (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SUPP_OFFSET)
+#define PIC32MZ_EMAC1_SUPPCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SUPPCLR_OFFSET)
+#define PIC32MZ_EMAC1_SUPPSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SUPPSET_OFFSET)
+#define PIC32MZ_EMAC1_SUPPINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SUPPINV_OFFSET)
+
+#define PIC32MZ_EMAC1_TEST (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_TEST_OFFSET)
+#define PIC32MZ_EMAC1_TESTCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_TESTCLR_OFFSET)
+#define PIC32MZ_EMAC1_TESTSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_TESTSET_OFFSET)
+#define PIC32MZ_EMAC1_TESTINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_TESTINV_OFFSET)
+
+#define PIC32MZ_EMAC1_SA0 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA0_OFFSET)
+#define PIC32MZ_EMAC1_SA0CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA0CLR_OFFSET)
+#define PIC32MZ_EMAC1_SA0SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA0SET_OFFSET)
+#define PIC32MZ_EMAC1_SA0INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA0INV_OFFSET)
+
+#define PIC32MZ_EMAC1_SA1 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA1_OFFSET)
+#define PIC32MZ_EMAC1_SA1CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA1CLR_OFFSET)
+#define PIC32MZ_EMAC1_SA1SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA1SET_OFFSET)
+#define PIC32MZ_EMAC1_SA1INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA1INV_OFFSET)
+
+#define PIC32MZ_EMAC1_SA2 (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA2_OFFSET)
+#define PIC32MZ_EMAC1_SA2CLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA2CLR_OFFSET)
+#define PIC32MZ_EMAC1_SA2SET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA2SET_OFFSET)
+#define PIC32MZ_EMAC1_SA2INV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_SA2INV_OFFSET)
+
+/* MII Management Registers */
+
+#define PIC32MZ_EMAC1_MCFG (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCFG_OFFSET)
+#define PIC32MZ_EMAC1_MCFGCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCFGCLR_OFFSET)
+#define PIC32MZ_EMAC1_MCFGSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCFGSET_OFFSET)
+#define PIC32MZ_EMAC1_MCFGINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCFGINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MCMD (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCMD_OFFSET)
+#define PIC32MZ_EMAC1_MCMDCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCMDCLR_OFFSET)
+#define PIC32MZ_EMAC1_MCMDSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCMDSET_OFFSET)
+#define PIC32MZ_EMAC1_MCMDINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MCMDINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MADR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MADR_OFFSET)
+#define PIC32MZ_EMAC1_MADRCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MADRCLR_OFFSET)
+#define PIC32MZ_EMAC1_MADRSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MADRSET_OFFSET)
+#define PIC32MZ_EMAC1_MADRINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MADRINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MWTD (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MWTD_OFFSET)
+#define PIC32MZ_EMAC1_MWTDCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MWTDCLR_OFFSET)
+#define PIC32MZ_EMAC1_MWTDSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MWTDSET_OFFSET)
+#define PIC32MZ_EMAC1_MWTDINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MWTDINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MRDD (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MRDD_OFFSET)
+#define PIC32MZ_EMAC1_MRDDCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MRDDCLR_OFFSET)
+#define PIC32MZ_EMAC1_MRDDSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MRDDSET_OFFSET)
+#define PIC32MZ_EMAC1_MRDDINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MRDDINV_OFFSET)
+
+#define PIC32MZ_EMAC1_MIND (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MIND_OFFSET)
+#define PIC32MZ_EMAC1_MINDCLR (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MINDCLR_OFFSET)
+#define PIC32MZ_EMAC1_MINDSET (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MINDSET_OFFSET)
+#define PIC32MZ_EMAC1_MINDINV (PIC32MZ_ETHERNET_K1BASE+PIC32MZ_EMAC1_MINDINV_OFFSET)
+
+/* Register Bit-Field Definitions *******************************************************************/
+
+/* Controller and DMA Engine Configuration/Status Registers */
+/* Ethernet Controller Control 1 Register */
+
+#define ETH_CON1_BUFCDEC (1 << 0) /* Bit 0: : Descriptor Buffer Count Decrement bit */
+ /* Bit 1-3: Reserved */
+#define ETH_CON1_MANFC (1 << 4) /* Bit 4: Manual Flow Control bit */
+ /* Bit 5-6: Reserved */
+#define ETH_CON1_AUTOFC (1 << 7) /* Bit 7: Automatic Flow Control bit */
+#define ETH_CON1_RXEN (1 << 8) /* Bit 8: Receive Enable bit */
+#define ETH_CON1_TXRTS (1 << 9) /* Bit 9: Transmit Request to Send bit */
+ /* Bit 10-12: Reserved */
+#define ETH_CON1_SIDL (1 << 13) /* Bit 13: Ethernet Stop in Idle Mode bit */
+ /* Bit 14: Reserved */
+#define ETH_CON1_ON (1 << 15) /* Bit 15: Ethernet ON bit */
+#define ETH_CON1_PTV_SHIFT (16) /* Bits 16-31: PAUSE Timer Value bits */
+#define ETH_CON1_PTV_MASK (0xffff << ETH_CON1_PTV_SHIFT)
+
+/* Ethernet Controller Control 2 Register */
+ /* Bits 0-3: Reserved */
+#define ETH_CON2_RXBUFSZ_SHIFT (4) /* Bits 4-10: RX Data Buffer Size for All RX Descriptors */
+#define ETH_CON2_RXBUFSZ_MASK (0x7f << ETH_CON2_RXBUFSZ_SHIFT)
+# define ETH_CON2_RXBUFSZ(n) (((n) >> 4) << ETH_CON2_RXBUFSZ_SHIFT) /* n=16, 32, 48, ... 2032 */
+ /* Bits 11-31: Reserved */
+
+/* Ethernet Controller TX Packet Descriptor Start Address Register (32-bit address) */
+/* Ethernet Controller RX Packet Descriptor Start Address Register (32-bit address) */
+
+/* Ethernet Controller Interrupt Enable Register */
+/* Ethernet Controller Interrupt Request Register */
+
+#define ETH_INT_RXOVFLW (1 << 0) /* Bit 0: Receive FIFO overflow interrupt */
+#define ETH_INT_RXBUFNA (1 << 1) /* Bit 1: Receive buffer not available interrupt */
+#define ETH_INT_TXABORT (1 << 2) /* Bit 2: Transmitter abort interrupt */
+#define ETH_INT_TXDONE (1 << 3) /* Bit 3: Transmitter done interrupt */
+ /* Bit 4: Reserved */
+#define ETH_INT_RXACT (1 << 5) /* Bit 5: RX activity interrupt */
+#define ETH_INT_PKTPEND (1 << 6) /* Bit 6: Packet pending interrupt */
+#define ETH_INT_RXDONE (1 << 7) /* Bit 7: Receiver done interrupt */
+#define ETH_INT_FWMARK (1 << 8) /* Bit 8: Full watermark interrupt */
+#define ETH_INT_EWMARK (1 << 9) /* Bit 9: Empty watermark interrupt */
+ /* Bits 10-12: Reserved */
+#define ETH_INT_RXBUSE (1 << 13) /* Bit 13: Receive BVCI bus error interrupt */
+#define ETH_INT_TXBUSE (1 << 14) /* Bit 14: Transmit BVCI bus error interrupt */
+ /* Bits 15-31: Reserved */
+#define ETH_INT_ALLINTS (0x000063ef)
+
+/* Ethernet Controller Status Register */
+
+ /* Bits 0-4: Reserved */
+#define ETH_STAT_RXBUSY (1 << 5) /* Bit 5: Receive busy */
+#define ETH_STAT_TXBUSY (1 << 6) /* Bit 6: Transmit busy */
+#define ETH_STAT_ETHBUSY (1 << 7) /* Bit 7: Ethernet module busy */
+ /* Bits 8-15: Reserved */
+#define ETH_STAT_BUFCNT_SHIFT (18) /* Bits 16-23: Packet buffer count */
+#define ETH_STAT_BUFCNT_MASK (0xff << ETH_STAT_BUFCNT_SHIFT)
+ /* Bits 24-31: Reserved */
+
+/* RX Filtering Configuration Registers */
+/* Ethernet Controller Receive Filter Configuration Register */
+
+#define ETH_RXFC_BCEN (1 << 0) /* Bit 0: Broadcast filter enable */
+#define ETH_RXFC_MCEN (1 << 1) /* Bit 1: Multicast filter enable */
+#define ETH_RXFC_NOTMEEN (1 << 2) /* Bit 2: Not Me unicast filter enable */
+#define ETH_RXFC_UCEN (1 << 3) /* Bit 3: Unicast filter enable */
+#define ETH_RXFC_RUNTEN (1 << 4) /* Bit 4: Runt enable */
+#define ETH_RXFC_RUNTERREN (1 << 5) /* Bit 5: Runt error collection enable */
+#define ETH_RXFC_CRCOKEN (1 << 6) /* Bit 6: CRC OK enable enable */
+#define ETH_RXFC_CRCERREN (1 << 7) /* Bit 7: CRC error collection enable */
+#define ETH_RXFC_PMMODE_SHIFT (8) /* Bits 8-11: Pattern match mode */
+#define ETH_RXFC_PMMODE_MASK (15 << ETH_RXFC_PMMODE_SHIFT)
+# define ETH_RXFC_PMMODE_DISABLED (0 << ETH_RXFC_PMMODE_SHIFT) /* Pattern match is always unsuccessful */
+# define ETH_RXFC_PMMODE_PMCKSUM (1 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches */
+# define ETH_RXFC_PMMODE_DASTA (2 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches & DA==STA */
+/* #define ETH_RXFC_PMMODE_DASTA (3 << ETH_RXFC_PMMODE_SHIFT) PM checksum matches & DA==STA */
+# define ETH_RXFC_PMMODE_DAUCAST (4 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches & DA==Unicast address */
+/* #define ETH_RXFC_PMMODE_DAUCAST (5 << ETH_RXFC_PMMODE_SHIFT) PM checksum matches & DA==Unicast address */
+# define ETH_RXFC_PMMODE_DABCAST (6 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches & DA==Broadcast address */
+/* #define ETH_RXFC_PMMODE_DABCAST (7 << ETH_RXFC_PMMODE_SHIFT) PM checksum matches & DA==Broadcast address */
+# define ETH_RXFC_PMMODE_HASH (8 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches & Hash Table Filter match */
+# define ETH_RXFC_PMMODE_MAGIC (9 << ETH_RXFC_PMMODE_SHIFT) /* PM checksum matches & Packet = Magic Packet */
+#define ETH_RXFC_NOTPM (1 << 12) /* Bit 12: Pattern match inversion */
+ /* Bit 13: Reserved */
+#define ETH_RXFC_MPEN (1 << 14) /* Bit 14: Magic packet enable */
+#define ETH_RXFC_HTEN (1 << 15) /* Bit 15: Hash table filtering enable */
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller Hash Table 0 Register */
+
+#define ETH_HT0_BYTE0_SHIFT (0) /* Bits 0-7: Hash table byte 0, HT[0-7] */
+#define ETH_HT0_BYTE0_MASK (0xff << ETH_HT0_BYTE0_SHIFT)
+#define ETH_HT0_BYTE1_SHIFT (8) /* Bits 8-15: Hash table byte 1, HT[8-15] */
+#define ETH_HT0_BYTE1_MASK (0xff << ETH_HT0_BYTE1_SHIFT)
+#define ETH_HT0_BYTE2_SHIFT (16) /* Bits 16-23: Hash table byte 2, HT[16-23] */
+#define ETH_HT0_BYTE2_MASK (0xff << ETH_HT0_BYTE2_SHIFT)
+#define ETH_HT0_BYTE3_SHIFT (24) /* Bits 24-31: Hash table byte 3, HT[24-31] */
+#define ETH_HT0_BYTE3_MASK (0xff << ETH_HT0_BYTE3_SHIFT)
+
+/* Ethernet Controller Hash Table 1 Register */
+
+#define ETH_HT1_BYTE4_SHIFT (0) /* Bits 0-7: Hash table byte 4, HT[32-39] */
+#define ETH_HT1_BYTE4_MASK (0xff << ETH_HT1_BYTE4_SHIFT)
+#define ETH_HT1_BYTE5_SHIFT (8) /* Bits 8-15: Hash table byte 5, HT[40-47] */
+#define ETH_HT1_BYTE5_MASK (0xff << ETH_HT1_BYTE5_SHIFT)
+#define ETH_HT1_BYTE6_SHIFT (16) /* Bits 16-23: Hash table byte 6, HT[48-55] */
+#define ETH_HT1_BYTE6_MASK (0xff << ETH_HT1_BYTE6_SHIFT)
+#define ETH_HT1_BYTE7_SHIFT (24) /* Bits 24-31: Hash table byte 7, HT[56-63] */
+#define ETH_HT1_BYTE7_MASK (0xff << ETH_HT1_BYTE7_SHIFT)
+
+/* Ethernet Controller Pattern Match Mask 0 Register */
+
+#define ETH_PMM0_MASK0_SHIFT (0) /* Bits 0-7: Patch mask 0, PMM[0-7] */
+#define ETH_PMM0_MASK0_MASK (0xff << ETH_PMM0_MASK0_SHIFT)
+#define ETH_PMM0_MASK1_SHIFT (8) /* Bits 8-15: Patch mask 1, PMM[8-15] */
+#define ETH_PMM0_MASK1_MASK (0xff << ETH_PMM0_MASK1_SHIFT)
+#define ETH_PMM0_MASK2_SHIFT (16) /* Bits 16-23: Patch mask 2, PMM[16-23] */
+#define ETH_PMM0_MASK2_MASK (0xff << ETH_PMM0_MASK2_SHIFT)
+#define ETH_PMM0_MASK3_SHIFT (24) /* Bits 24-31: Patch mask 3, PMM[24-31] */
+#define ETH_PMM0_MASK3_MASK (0xff << ETH_PMM0_MASK3_SHIFT)
+
+/* Ethernet Controller Pattern Match Mask 1 Register */
+
+#define ETH_PMM1_MASK4_SHIFT (0) /* Bits 0-7: Patch mask 4, PMM[32-39] */
+#define ETH_PMM1_MASK4_MASK (0xff << ETH_PMM1_MASK4_SHIFT)
+#define ETH_PMM1_MASK5_SHIFT (8) /* Bits 8-15: Patch mask 5, PMM[40-47] */
+#define ETH_PMM1_MASK5_MASK (0xff << ETH_PMM1_MASK5_SHIFT)
+#define ETH_PMM1_MASK6_SHIFT (16) /* Bits 16-23: Patch mask 6, PMM[48-55] */
+#define ETH_PMM1_MASK6_MASK (0xff << ETH_PMM1_MASK6_SHIFT)
+#define ETH_PMM1_MASK7_SHIFT (24) /* Bits 24-31: Patch mask 7, PMM[56-63] */
+#define ETH_PMM1_MASK7_MASK (0xff << ETH_PMM1_MASK7_SHIFT)
+
+/* Ethernet Controller Pattern Match Checksum Register */
+
+#define ETH_PMCS_CKSM0_SHIFT (0) /* Bits 0-7: Pattern match checksum 0 bits, PMCS[0-7] */
+#define ETH_PMCS_CKSM0_MASK (0xff << ETH_PMCS_CKSM0_SHIFT)
+#define ETH_PMCS_CKSM1_SHIFT (8) /* Bits 8-15: Pattern match checksum 1 bits, PMCS[8-15] */
+#define ETH_PMCS_CKSM1_MASK (0xff << ETH_PMCS_CKSM1_SHIFT)
+
+/* Ethernet Controller Pattern Match Offset Register */
+
+#define ETH_PMO_MASK (0xffff)
+
+/* Flow Control Configuring Register */
+/* Ethernet Controller Receive Watermarks Register */
+
+#define ETH_RXWM_RXEWM_SHIFT (0) /* Bits 0-7: Receive empty watermark bits */
+#define ETH_RXWM_RXEWM_MASK (0xff << ETH_RXWM_RXEWM_SHIFT)
+#define ETH_RXWM_RXFWM_SHIFT (8) /* Bits 8-15: Receive full watermark bits */
+#define ETH_RXWM_RXFWM_MASK (0xff << ETH_RXWM_RXFWM_SHIFT)
+
+/* Ethernet Statistics Registers */
+/* Ethernet Controller Receive Overflow Statistics Register */
+
+#define ETH_RXOVFLOW_MASK (0xffff)
+
+/* Ethernet Controller Frames Transmitted OK Statistics Register */
+
+#define ETH_FRMTXOK_MASK (0xffff)
+
+/* Ethernet Controller Single Collision Frames Statistics Register */
+
+#define ETH_SCOLFRM_MASK (0xffff)
+
+/* Ethernet Controller Multiple Collision Frames Statistics Register */
+
+#define ETH_MCOLFRM_MASK (0xffff)
+
+/* Ethernet Controller Frames Received OK Statistics Register */
+
+#define ETH_FRMRXOK_MASK (0xffff)
+
+/* Ethernet Controller Frame Check Sequence Error Statistics Register */
+
+#define ETH_FCSERR_MASK (0xffff)
+
+/* Ethernet Controller Alignment Errors Statistics Register */
+
+#define ETH_ALGNERR_MASK (0xffff)
+
+/* MAC Configuration Registers */
+/* Ethernet Controller MAC Configuration 1 Register */
+
+#define EMAC1_CFG1_RXEN (1 << 0) /* Bit 0: MAC Receive enable */
+#define EMAC1_CFG1_PASSALL (1 << 1) /* Bit 1: MAC Pass all all receive frames */
+#define EMAC1_CFG1_RXPAUSE (1 << 2) /* Bit 2: MAC RX flow control bit */
+#define EMAC1_CFG1_TXPAUSE (1 << 3) /* Bit 3: MAC TX flow control */
+#define EMAC1_CFG1_LOOPBACK (1 << 4) /* Bit 4: MAC loopback mode */
+ /* Bits 5-7: Reserved */
+#define EMAC1_CFG1_TXRST (1 << 8) /* Bit 8: Reset TX function */
+#define EMAC1_CFG1_MCSTXRST (1 << 9) /* Bit 9: Reset MCS/TX */
+#define EMAC1_CFG1_RXRST (1 << 10) /* Bit 10: Reset RX */
+#define EMAC1_CFG1_MCSRXRST (1 << 11) /* Bit 11: Reset MCS/RX */
+ /* Bits 12-13: Reserved */
+#define EMAC1_CFG1_SIMRST (1 << 14) /* Bit 14: Simulation reset */
+#define EMAC1_CFG1_SOFTRST (1 << 15) /* Bit 15: Soft reset */
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC Configuration 2 Register */
+
+#define EMAC1_CFG2_FULLDPLX (1 << 0) /* Bit 0: Full duplex operation */
+#define EMAC1_CFG2_LENGTHCK (1 << 1) /* Bit 1: Frame length checking */
+#define EMAC1_CFG2_HUGEFRM (1 << 2) /* Bit 2: Huge frame enable */
+#define EMAC1_CFG2_DELAYCRC (1 << 3) /* Bit 3: Delayed CRC */
+#define EMAC1_CFG2_CRCEN (1 << 4) /* Bit 4: CRC enable */
+#define EMAC1_CFG2_PADCRCEN (1 << 5) /* Bit 5: Pad/CRC enable */
+#define EMAC1_CFG2_VLANPADEN (1 << 6) /* Bit 6: VLAN pad enable */
+#define EMAC1_CFG2_AUTOPADEN (1 << 7) /* Bit 7: Auto detect pad enable */
+#define EMAC1_CFG2_PUREPRE (1 << 8) /* Bit 8: Pure preamble enforcement */
+#define EMAC1_CFG2_LONGPRE (1 << 9) /* Bit 9: Long preamble enforcement */
+ /* Bits 10-11: Reserved */
+#define EMAC1_CFG2_NOBKOFF (1 << 12) /* Bit 12: No backoff */
+#define EMAC1_CFG2_BPNOBKOFF (1 << 13) /* Bit 13: Back pressure/no backoff */
+#define EMAC1_CFG2_EXCESSDFR (1 << 14) /* Bit 14: Excess defer */
+ /* Bits 15-31: Reserved */
+/* Ethernet Controller MAC Back-to-Back Interpacket Gap Register */
+
+#define EMAC1_IPGT_SHIFT (0) /* Bits 0-6 */
+#define EMAC1_IPGT_MASK (0x7f << EMAC1_IPGT_SHIFT)
+ /* Bits 7-31: Reserved */
+/* Ethernet Controller MAC Non-Back-to-Back Interpacket Gap Register */
+
+#define EMAC1_IPGR_GAP2_SHIFT (0) /* Bits 0-6: Gap part 2 */
+#define EMAC1_IPGR_GAP2_MASK (0x7f << EMAC1_IPGR_GAP2_SHIFT)
+ /* Bit 7: Reserved */
+#define EMAC1_IPGR_GAP1_SHIFT (8) /* Bits 8-18: Gap part 1 */
+#define EMAC1_IPGR_GAP1_MASK (0x7f << EMAC1_IPGR_GAP2_SHIFT)
+ /* Bits 15-31: Reserved */
+/* Ethernet Controller MAC Collision Window/Retry Limit Register */
+
+#define EMAC1_CLRT_RETX_SHIFT (0) /* Bits 0-3: Retransmission maximum */
+#define EMAC1_CLRT_RETX_MASK (15 << EMAC1_CLRT_RETX_SHIFT)
+ /* Bits 4-7: Reserved */
+#define EMAC1_CLRT_CWINDOW_SHIFT (8) /* Bits 8-13: Collision window */
+#define EMAC1_CLRT_CWINDOW_MASK (0x3f << EMAC1_CLRT_CWINDOW_SHIFT)
+ /* Bits 14-31: Reserved */
+/* Ethernet Controller MAC Maximum Frame Length Register */
+
+#define EMAC1_MAXF_SHIFT (0) /* Bits 0-15 */
+#define EMAC1_MAXF_MASK (0xffff << EMAC1_MAXF_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC PHY Support Register */
+ /* Bits 0-7: Reserved */
+#define EMAC1_SUPP_SPEEDRMII (1 << 8) /* Bit 8: RMII Speed0=10Bps 1=100Bps */
+ /* Bits 9-10: Reserved */
+#define EMAC1_SUPP_RESETRMII (1 << 11) /* Bit 11: Reset RMII Logic */
+ /* Bits 12-31: Reserved */
+/* Ethernet Controller MAC Test Register */
+
+#define EMAC1_TEST_SHRTQNTA (1 << 0) /* Bit 0: Shortcut pause quanta */
+#define EMAC1_TEST_TESTPAUSE (1 << 1) /* Bit 1: Test pause */
+#define EMAC1_TEST_TESTBP (1 << 2) /* Bit 2: Test packpressure */
+ /* Bits 3-31: Reserved */
+/* Ethernet Controller MAC Station Address 0 Register */
+
+#define EMAC1_SA0_STNADDR6_SHIFT (0) /* Bits 0-7: Station address 5th octet */
+#define EMAC1_SA0_STNADDR6_MASK (0xff << EMAC1_SA0_STNADDR6_SHIFT)
+#define EMAC1_SA0_STNADDR5_SHIFT (8) /* Bits 8-15: Station address 6th octet */
+#define EMAC1_SA0_STNADDR5_MASK (0xff << EMAC1_SA0_STNADDR5_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC Station Address 1 Register */
+
+#define EMAC1_SA1_STNADDR4_SHIFT (0) /* Bits 0-7: Station address 4th octet */
+#define EMAC1_SA1_STNADDR4_MASK (0xff << EMAC1_SA0_STNADDR4_SHIFT)
+#define EMAC1_SA1_STNADDR3_SHIFT (8) /* Bits 8-15: Station address 3rd octet */
+#define EMAC1_SA1_STNADDR3_MASK (0xff << EMAC1_SA0_STNADDR3_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC Station Address 2 Register */
+
+#define EMAC1_SA2_STNADDR2_SHIFT (0) /* Bits 0-7: Station address 2nd octet */
+#define EMAC1_SA2_STNADDR2_MASK (0xff << EMAC1_SA2_STNADDR2_SHIFT)
+#define EMAC1_SA2_STNADDR1_SHIFT (8) /* Bits 8-15: Station address 1st octet */
+#define EMAC1_SA2_STNADDR1_MASK (0xff << EMAC1_SA2_STNADDR1_SHIFT)
+ /* Bits 16-31: Reserved */
+/* MII Management Registers */
+
+/* Ethernet Controller MAC MII Management Configuration Register */
+
+#define EMAC1_MCFG_SCANINC (1 << 0) /* Bit 0: Scan increment */
+#define EMAC1_MCFG_NOPRE (1 << 1) /* Bit 1: Suppress preamble */
+#define EMAC1_MCFG_CLKSEL_SHIFT (2) /* Bits 2-5: Clock select */
+#define EMAC1_MCFG_CLKSEL_MASK (15 << EMAC1_MCFG_CLKSEL_SHIFT)
+# define EMAC1_MCFG_CLKSEL_DIV4 (0 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 4 */
+# define EMAC1_MCFG_CLKSEL_DIV6 (2 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 6 */
+# define EMAC1_MCFG_CLKSEL_DIV8 (3 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 8 */
+# define EMAC1_MCFG_CLKSEL_DIV10 (4 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 10 */
+# define EMAC1_MCFG_CLKSEL_DIV14 (5 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 14 */
+# define EMAC1_MCFG_CLKSEL_DIV20 (6 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 20 */
+# define EMAC1_MCFG_CLKSEL_DIV28 (7 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 28 */
+# define EMAC1_MCFG_CLKSEL_DIV40 (8 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 40 */
+# define EMAC1_MCFG_CLKSEL_DIV48 (9 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 48 */
+# define EMAC1_MCFG_CLKSEL_DIV50 (10 << EMAC1_MCFG_CLKSEL_SHIFT) /* PBCLK5 divided by 50 */
+ /* Bits 6-14: Reserved */
+#define EMAC1_MCFG_MGMTRST (1 << 15) /* Bit 15: Reset MII mgmt */
+ /* Bits 16-31: Reserved */
+
+/* Ethernet Controller MAC MII Management Command Register */
+
+#define EMAC1_MCMD_READ (1 << 0) /* Bit 0: Single read cycle */
+#define EMAC1_MCMD_SCAN (1 << 1) /* Bit 1: Continuous read cycles */
+ /* Bits 2-31: Reserved */
+#define EMAC1_MCMD_WRITE (0)
+
+/* Ethernet Controller MAC MII Management Address Register */
+
+#define EMAC1_MADR_REGADDR_SHIFT (0) /* Bits 0-4: Register address */
+#define EMAC1_MADR_REGADDR_MASK (31 << EMAC1_MADR_REGADDR_SHIFT)
+ /* Bits 7-5: Reserved */
+#define EMAC1_MADR_PHYADDR_SHIFT (8) /* Bits 8-12: PHY address */
+#define EMAC1_MADR_PHYADDR_MASK (31 << EMAC1_MADR_PHYADDR_SHIFT)
+ /* Bits 13-31: Reserved */
+/* Ethernet Controller MAC MII Management Write Data Register */
+
+#define EMAC1_MWTD_SHIFT (0) /* Bits 0-15 */
+#define EMAC1_MWTD_MASK (0xffff << EMAC1_MWTD_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC MII Management Read Data Register */
+
+#define EMAC1_MRDD_SHIFT (0) /* Bits 0-15 */
+#define EMAC1_MRDD_MASK (0xffff << EMAC1_MRDD_SHIFT)
+ /* Bits 16-31: Reserved */
+/* Ethernet Controller MAC MII Management Indicators Register */
+
+#define EMAC1_MIND_MIIMBUSY (1 << 0) /* Bit 0: Busy */
+#define EMAC1_MIND_SCAN (1 << 1) /* Bit 1: Scanning */
+#define EMAC1_MIND_NOTVALID (1 << 2) /* Bit 2: Not valid */
+#define EMAC1_MIND_LINKFAIL (1 << 3) /* Bit 3: MII link fail */
+ /* Bits 4-31: Reserved */
+
+/* Descriptors Offsets ******************************************************************************/
+
+/* Tx descriptor offsets. The NEXTED field is only present if NPV=1 */
+
+#define PIC32MZ_TXDESC_STATUS 0x00 /* Various status bits (32-bits) */
+#define PIC32MZ_TXDESC_ADDRESS 0x04 /* Data buffer address (32-bits) */
+#define PIC32MZ_TXDESC_TSV1 0x08 /* Transmit filter status vector 1 (32-bits) */
+#define PIC32MZ_TXDESC_TSV2 0x0c /* Transmit filter status vector 2 (32-bits) */
+#define PIC32MZ_TXLINEAR_SIZE 0x10 /* Size in bytes of one linear Tx descriptor */
+
+#define PIC32MZ_TXDESC_NEXTED 0x10 /* Next Ethernet Descriptor (ED) */
+#define PIC32MZ_TXLINKED_SIZE 0x14 /* Size in bytes of one linked Tx descriptor */
+
+/* Tx descriptor uint32_t* indices */
+
+#define TXDESC_STATUS 0 /* Various status bits (32-bits) */
+#define TXDESC_ADDRESS 1 /* Data buffer address (32-bits) */
+#define TXDESC_TSV1 2 /* Transmit filter status vector 1 (32-bits) */
+#define TXDESC_TSV2 3 /* Transmit filter status vector 2 (32-bits) */
+#define TXLINEAR_SIZE 4 /* Size in 32-bit words of one linear Tx descriptor */
+
+#define TXDESC_NEXTED 4 /* Next Ethernet Descriptor (ED) */
+#define TXLINKED_SIZE 5 /* Size in 32-bit words of one linked Tx descriptor */
+
+/* Rx descriptor offsets. The NEXTED field is only present if NPV=1 */
+
+#define PIC32MZ_RXDESC_STATUS 0x00 /* Various status bits (32-bits) */
+#define PIC32MZ_RXDESC_ADDRESS 0x04 /* Data buffer address (32-bits) */
+#define PIC32MZ_RXDESC_RSV1 0x08 /* Receive filter status vector 1 and checksum (32-bits) */
+#define PIC32MZ_RXDESC_RSV2 0x0c /* Receive filter status vector 2 (32-bits) */
+#define PIC32MZ_RXLINEAR_SIZE 0x10 /* Size in bytes of one linear Rx descriptor */
+
+#define PIC32MZ_RXDESC_NEXTED 0x10 /* Next Ethernet Descriptor (ED) */
+#define PIC32MZ_RXLINKED_SIZE 0x14 /* Size in bytes of one linked Rx descriptor */
+
+/* Rx descriptor offsets uint32_t* indices */
+
+#define RXDESC_STATUS 0 /* Various status bits (32-bits) */
+#define RXDESC_ADDRESS 1 /* Data buffer address (32-bits) */
+#define RXDESC_RSV1 2 /* Receive filter status vector 1 and checksum (32-bits) */
+#define RXDESC_RSV2 3 /* Receive filter status vector 2 (32-bits) */
+#define RXLINEAR_SIZE 4 /* Size in 32-bit words of one linear Rx descriptor */
+
+#define RXDESC_NEXTED 4 /* Next Ethernet Descriptor (ED) */
+#define RXLINKED_SIZE 5 /* Size in 32-bit words of one linked Rx descriptor */
+
+/* Descriptor Bit Definitions ***********************************************************************/
+/* Tx descriptor status bit definitions */
+ /* Bits 0-6: Reserved */
+#define TXDESC_STATUS_EOWN (1 << 7) /* Bit 7: 1=Ethernet controller owns */
+#define TXDESC_STATUS_SOWN (0) /* 0=Software owns */
+#define TXDESC_STATUS_NPV (1 << 8) /* Bit 8: Next ED pointer valid enable */
+#define TXDESC_STATUS_USER1_SHIFT (9) /* Bits 9-15: User-defined */
+#define TXDESC_STATUS_USER1_MASK (0x7f << TXDESC_STATUS_USER2_SHIFT)
+#define TXDESC_STATUS_BYTECOUNT_SHIFT (16) /* Bits 16-26: Byte Count */
+#define TXDESC_STATUS_BYTECOUNT_MASK (0x7ff << TXDESC_STATUS_BYTECOUNT_SHIFT)
+#define TXDESC_STATUS_USER2_SHIFT (27) /* Bits 27-29: User-defined */
+#define TXDESC_STATUS_USER2_MASK (7 << TXDESC_STATUS_USER1_SHIFT)
+#define TXDESC_STATUS_EOP (1 << 30) /* Bit 30: End of packet enable */
+#define TXDESC_STATUS_SOP (1 << 31) /* Bit 31: Start of packet enable */
+
+/* Tx descriptor Transmit filter status vector bit definitions */
+
+#define TXDESC_TSV1_BYTECOUNT_SHIFT (0) /* Bits 0-15: TSV[32-47] Total bytes transmitted */
+#define TXDESC_TSV1_BYTECOUNT_MASK (0xffff << TXDESC_TSV1_BYTECOUNT_SHIFT)
+#define TXDESC_TSV1_CONTROL (1 << 16) /* Bit 16: TSV48 Transmit Control Frame */
+#define TXDESC_TSV1_PAUSE (1 << 17) /* Bit 17: TSV49 Transmit PAUSE Control Frame */
+#define TXDESC_TSV1_BPAPPLIED (1 << 18) /* Bit 18: TSV50 Transmit Backpressure Applied */
+#define TXDESC_TSV1_VLAN (1 << 19) /* Bit 19: TSV51 Transmit VLAN Tagged Frame */
+ /* Bits 20-23: Reserved */
+#define TXDESC_TSV1_USER_SHIFT (24) /* Bits 24-31: User-defined */
+#define TXDESC_TSV1_USER_MASK (0xff << TXDESC_STATUS_USER1_SHIFT)
+
+#define TXDESC_TSV2_BYTECOUNT_SHIFT (0) /* Bits 0-15: TSV15:0 Transmit Byte Count */
+#define TXDESC_TSV2_BYTECOUNT_MASK (0xffff << TXDESC_TSV2_BYTECOUNT_SHIFT)
+#define TXDESC_TSV2_COLCOUNT_SHIFT (0) /* Bits 16-19: TSV16-19 Transmit Collision Count */
+#define TXDESC_TSV2_COLCOUNT_MASK (15 << TXDESC_TSV2_COLCOUNT_SHIFT)
+#define TXDESC_TSV2_TXCRCE (1 << 20) /* Bit 20: TSV20 Transmit CRC Error */
+#define TXDESC_TSV2_TXLCE (1 << 21) /* Bit 21: TSV21 Transmit Length Check Error */
+#define TXDESC_TSV2_TXOOR (1 << 22) /* Bit 22: TSV22 Transmit Length Out Of Range */
+#define TXDESC_TSV2_TXDONE (1 << 23) /* Bit 23: TSV23 Transmit Done */
+#define TXDESC_TSV2_MCAST (1 << 24) /* Bit 24: TSV24 Transmit Multicast */
+#define TXDESC_TSV2_BCAST (1 << 25) /* Bit 25: TSV25 Transmit Broadcast */
+#define TXDESC_TSV2_PKTDFR (1 << 26) /* Bit 26: TSV26 Transmit Packet Defer */
+#define TXDESC_TSV2_EXCESSDFR (1 << 27) /* Bit 27: TSV27 Transmit Excessive Defer */
+#define TXDESC_TSV2_MAXOL (1 << 28) /* Bit 28: TSV28 Transmit Maximum Collision */
+#define TXDESC_TSV2_TXLC (1 << 29) /* Bit 29: TSV29 Transmit Late Collision */
+#define TXDESC_TSV2_TXGIANT (1 << 30) /* Bit 30: TSV30 Transmit Giant */
+#define TXDESC_TSV2_TXUR (1 << 31) /* Bit 31: TSV31 Transmit Under-run */
+
+/* Rx descriptor status bit definitions */
+ /* Bits 0-6: Reserved */
+#define RXDESC_STATUS_EOWN (1 << 7) /* Bit 7: 1=Ethernet controller owns */
+#define RXDESC_STATUS_SOWN (0) /* 0=Software owns */
+#define RXDESC_STATUS_NPV (1 << 8) /* Bit 8: Next ED pointer valid enable */
+ /* Bits 9-15: Reserved */
+#define RXDESC_STATUS_BYTECOUNT_SHIFT (16) /* Bits 16-26: Byte Count */
+#define RXDESC_STATUS_BYTECOUNT_MASK (0x7ff << RXDESC_STATUS_BYTECOUNT_SHIFT)
+ /* Bits 27-29: Reserved */
+#define RXDESC_STATUS_EOP (1 << 30) /* Bit 30: End of packet enable */
+#define RXDESC_STATUS_SOP (1 << 31) /* Bit 31: Start of packet enable */
+
+/* Rx descriptor receive filter status vector bit definitions */
+
+#define RXDESC_RSV1_CHECKSUM_SHIFT (0) /* Bits 0-15: RX Packet Payload Checksum */
+#define RXDESC_RSV1_CHECKSUM_MASK (0xffff << RXDESC_RSV1_CHECKSUM_SHIFT)
+#define RXDESC_RSV1_USER_SHIFT (16) /* Bits 16-23: User defined */
+#define RXDESC_RSV1_USER_MASK (0xff << RXDESC_RSV1_USER_SHIFT)
+#define RXDESC_RSV1_RUNT (1 << 24) /* Bit 24: RXF_RSV0 Runt packet */
+#define RXDESC_RSV1_NOTANDNOT (1 << 25) /* Bit 25: RXF_RSV1 NOT (Unicast match) AND NOT (Multicast Match) */
+#define RXDESC_RSV1_HTMATCH (1 << 26) /* Bit 26: RXF_RSV2 Hash Table match */
+#define RXDESC_RSV1_MAGIC (1 << 27) /* Bit 27: RXF_RSV3 Magic Packet match */
+#define RXDESC_RSV1_PATMATCH (1 << 28) /* Bit 28: RXF_RSV4 Pattern Match match */
+#define RXDESC_RSV1_UCASTMATCH (1 << 29) /* Bit 29: RXF_RSV5 Unicast match */
+#define RXDESC_RSV1_BCASTMATCH (1 << 30) /* Bit 30: RXF_RSV6 Broadcast match */
+#define RXDESC_RSV1_MCASTMATCH (1 << 31) /* Bit 31: RXF_RSV7 Multicast match */
+
+#define RXDESC_RSV2_BYTECOUNT_SHIFT (0) /* Bits 0-15: RSV0-15 Received Byte Count */
+#define RXDESC_RSV2_BYTECOUNT_MASK (0xffff << RXDESC_RSV2_BYTECOUNT_SHIFT)
+#define RXDESC_RSV2_LONGDROP (1 << 16) /* Bit 16: RSV16 Long Event/Drop Event */
+#define RXDESC_RSV2_RXDVSEEN (1 << 17) /* Bit 17: RSV17 RXDV Event Previously Seen */
+#define RXDESC_RSV2_CARSEEN (1 << 18) /* Bit 18: RSV18 Carrier Event Previously Seen */
+#define RXDESC_RSV2_CODE (1 << 19) /* Bit 19: RSV19 Receive Code Violation */
+#define RXDESC_RSV2_CRCERR (1 << 20) /* Bit 20: RSV20 CRC Error */
+#define RXDESC_RSV2_LENCHK (1 << 21) /* Bit 21: RSV21 Length Check Error */
+#define RXDESC_RSV2_OOR (1 << 22) /* Bit 22: RSV22 Length Out of Range */
+#define RXDESC_RSV2_OK (1 << 23) /* Bit 23: RSV23 Received Ok */
+#define RXDESC_RSV2_MCAST (1 << 24) /* Bit 24: RSV24 Receive Multicast Packet */
+#define RXDESC_RSV2_BCAST (1 << 25) /* Bit 25: RSV25 Receive Broadcast Packet */
+#define RXDESC_RSV2_DRIBBLE (1 << 26) /* Bit 26: RSV26 Dribble Nibble */
+#define RXDESC_RSV2_CONTROL (1 << 27) /* Bit 27: RSV27 Receive Control Frame */
+#define RXDESC_RSV2_PAUSE (1 << 28) /* Bit 28: RSV28 Receive Pause Control Frame */
+#define RXDESC_RSV2_UNKNOWNOP (1 << 29) /* Bit 29: RSV29 Receive Unknown Op code */
+#define RXDESC_RSV2_VLAN (1 << 30) /* Bit 30: RSV30 Receive VLAN Type Detected */
+ /* Bit 31: RSV31 Reserved */
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* Descriptors as structures */
+
+/* Tx descriptor with NPV=0 */
+
+struct pic32mz_txlinear_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t tsv1; /* Transmit filter status vector 1 (32-bits) */
+ uint32_t tsv2; /* Transmit filter status vector 2 (32-bits) */
+};
+
+/* Tx descriptor with NPV=1 */
+
+struct pic32mz_txdesc_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t tsv1; /* Transmit filter status vector 1 (32-bits) */
+ uint32_t tsv2; /* Transmit filter status vector 2 (32-bits) */
+ uint32_t nexted; /* Next Ethernet Descriptor (ED) */
+};
+
+/* Rx descriptor with NPV=0 */
+
+struct pic32mz_rxlinear_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t rsv1; /* Receive filter status vector 1 and checksum (32-bits) */
+ uint32_t rsv2; /* Receive filter status vector 2 (32-bits) */
+};
+
+/* Rx descriptor with NPV=1 */
+
+struct pic32mz_rxdesc_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t rsv1; /* Receive filter status vector 1 and checksum (32-bits) */
+ uint32_t rsv2; /* Receive filter status vector 2 (32-bits) */
+ uint32_t nexted; /* Next Ethernet Descriptor (ED) */
+};
+
+/****************************************************************************************************
+ * Inline Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CHIP_NETHERNET > 0 */
+#endif /* __ARCH_MIPS_SRC_PIC32MZ_CHIP_PIC32MZ_ETHERNET_H */
diff --git a/nuttx/arch/mips/src/pic32mz/pic32mz_ethernet.c b/nuttx/arch/mips/src/pic32mz/pic32mz_ethernet.c
new file mode 100644
index 000000000..b8dd95ec3
--- /dev/null
+++ b/nuttx/arch/mips/src/pic32mz/pic32mz_ethernet.c
@@ -0,0 +1,3273 @@
+/****************************************************************************
+ * arch/arm/src/pic32mz/pic32mz_ethernet.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * This driver derives from the PIC32MZ Ethernet Driver
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_PIC32MZ_ETHERNET)
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <time.h>
+#include <string.h>
+#include <debug.h>
+#include <errno.h>
+#include <assert.h>
+
+#include <arpa/inet.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+#include <nuttx/wdog.h>
+#include <nuttx/net/mii.h>
+#include <nuttx/net/netconfig.h>
+#include <nuttx/net/arp.h>
+#include <nuttx/net/netdev.h>
+
+#ifdef CONFIG_NET_PKT
+# include <nuttx/net/pkt.h>
+#endif
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "pic32mz-config.h"
+#include "chip/pic32mz-ethernet.h"
+
+/* Does this chip have and Ethernet controller? */
+
+#if CHIP_NETHERNET > 0
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* CONFIG_PIC32MZ_NINTERFACES determines the number of physical interfaces
+ * that will be supported -- unless it is more than actually supported by the
+ * hardware!
+ */
+
+#if !defined(CONFIG_PIC32MZ_NINTERFACES) || CONFIG_PIC32MZ_NINTERFACES > CHIP_NETHERNET
+# undef CONFIG_PIC32MZ_NINTERFACES
+# define CONFIG_PIC32MZ_NINTERFACES CHIP_NETHERNET
+#endif
+
+/* The logic here has a few hooks for support for multiple interfaces, but
+ * that capability is not yet in place (and I won't worry about it until I get
+ * the first multi-interface PIC32MZ).
+ */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+# warning "Only a single ethernet controller is supported"
+# undef CONFIG_PIC32MZ_NINTERFACES
+# define CONFIG_PIC32MZ_NINTERFACES 1
+#endif
+
+/* CONFIG_NET_MULTIBUFFER is required */
+
+#ifndef CONFIG_NET_MULTIBUFFER
+# error "CONFIG_NET_MULTIBUFFER=y is required"
+#endif
+
+/* If IGMP is enabled, then accept multi-cast frames. */
+
+#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_MULTICAST)
+# define CONFIG_NET_MULTICAST 1
+#endif
+
+/* Use defaults if the number of discriptors is not provided */
+
+#ifndef CONFIG_NET_NTXDESC
+# define CONFIG_NET_NTXDESC 2
+#endif
+
+#if CONFIG_NET_NTXDESC > 255
+# error "The number of TX descriptors exceeds the range of a uint8_t index"
+#endif
+
+#ifndef CONFIG_NET_NRXDESC
+# define CONFIG_NET_NRXDESC 4
+#endif
+
+/* Make sure that the size of each buffer is a multiple of 4 bytes. This
+ * will force alignment of all buffers to 4-byte boundaries (this is needed
+ * by the queuing logic which will cast each buffer address to a pointer
+ * type).
+ */
+
+#define PIC32MZ_ALIGNED_BUFSIZE ((CONFIG_NET_ETH_MTU + 3) & ~3)
+
+/* The number of buffers will, then, be one for each descriptor plus one extra */
+
+#define PIC32MZ_NBUFFERS (CONFIG_NET_NRXDESC + CONFIG_NET_NTXDESC + 1)
+
+/* Debug Configuration *****************************************************/
+/* Register/Descriptor debug -- can only happen of CONFIG_DEBUG is selected.
+ * This will probably generate much more output than you care to see.
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_NET_REGDEBUG
+# undef CONFIG_NET_DESCDEBUG
+#endif
+
+/* CONFIG_NET_DUMPPACKET will dump the contents of each packet to the
+ * console.
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_NET_DUMPPACKET
+#endif
+
+#ifdef CONFIG_NET_DUMPPACKET
+# define pic32mz_dumppacket(m,a,n) lib_dumpbuffer(m,a,n)
+#else
+# define pic32mz_dumppacket(m,a,n)
+#endif
+
+/* Timing *******************************************************************/
+
+/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
+
+#define PIC32MZ_WDDELAY (1*CLK_TCK)
+#define PIC32MZ_POLLHSEC (1*2)
+
+/* TX timeout = 1 minute */
+
+#define PIC32MZ_TXTIMEOUT (60*CLK_TCK)
+
+/* PHY timout = 1 minute */
+
+#define PIC32MZ_MIITIMEOUT (666666)
+
+/* Ethernet MII clocking.
+ *
+ * The clock divider used to create the MII Management Clock (MDC). The MIIM
+ * module uses the SYSCLK as an input clock. According to the IEEE 802.3
+ * Specification this should be no faster than 2.5 MHz. However, some PHYs
+ * support clock rates up to 12.5 MHz.
+ *
+ * The board.h file provides the "ideal" divisor as BOARD_EMAC_MIIM_DIV. We
+ * pick the closest, actual divisor greater than or equal to this.
+ */
+
+#if BOARD_EMAC_MIIM_DIV <= 4
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV4
+#elif BOARD_EMAC_MIIM_DIV <= 6
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV6
+#elif BOARD_EMAC_MIIM_DIV <= 8
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV8
+#elif BOARD_EMAC_MIIM_DIV <= 10
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV10
+#elif BOARD_EMAC_MIIM_DIV <= 14
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV14
+#elif BOARD_EMAC_MIIM_DIV <= 20
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV20
+#elif BOARD_EMAC_MIIM_DIV <= 28
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV28
+#elif BOARD_EMAC_MIIM_DIV <= 40
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV40
+#elif BOARD_EMAC_MIIM_DIV <= 48
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV48
+#elif BOARD_EMAC_MIIM_DIV <= 50
+# define EMAC1_MCFG_CLKSEL_DIV EMAC1_MCFG_CLKSEL_DIV50
+#else
+# error "MIIM divider cannot be realized"
+#endif
+
+/* Interrupts ***************************************************************/
+
+#define ETH_RXINTS (ETH_INT_RXOVFLW | ETH_INT_RXBUFNA | ETH_INT_RXDONE | ETH_INT_RXBUSE)
+#define ETH_TXINTS (ETH_INT_TXABORT | ETH_INT_TXDONE | ETH_INT_TXBUSE)
+
+/* Misc. Helpers ***********************************************************/
+
+/* This is a helper pointer for accessing the contents of the Ethernet header */
+
+#define BUF ((struct eth_hdr_s *)priv->pd_dev.d_buf)
+
+/* PHYs *********************************************************************/
+/* Select PHY-specific values. Add more PHYs as needed. */
+
+#if defined(CONFIG_ETH0_PHY_KS8721)
+# define PIC32MZ_PHYNAME "KS8721"
+# define PIC32MZ_PHYID1 MII_PHYID1_KS8721
+# define PIC32MZ_PHYID2 MII_PHYID2_KS8721
+# define PIC32MZ_HAVE_PHY 1
+#elif defined(CONFIG_ETH0_PHY_DP83848C)
+# define PIC32MZ_PHYNAME "DP83848C"
+# define PIC32MZ_PHYID1 MII_PHYID1_DP83848C
+# define PIC32MZ_PHYID2 MII_PHYID2_DP83848C
+# define PIC32MZ_HAVE_PHY 1
+#elif defined(CONFIG_ETH0_PHY_LAN8720)
+# define PIC32MZ_PHYNAME "LAN8720"
+# define PIC32MZ_PHYID1 MII_PHYID1_LAN8720
+# define PIC32MZ_PHYID2 MII_PHYID2_LAN8720
+# define PIC32MZ_HAVE_PHY 1
+#else
+# warning "No PHY specified!"
+# undef PIC32MZ_HAVE_PHY
+#endif
+
+/* These definitions are used to remember the speed/duplex settings */
+
+#define PIC32MZ_SPEED_MASK 0x01
+#define PIC32MZ_SPEED_100 0x01
+#define PIC32MZ_SPEED_10 0x00
+
+#define PIC32MZ_DUPLEX_MASK 0x02
+#define PIC32MZ_DUPLEX_FULL 0x02
+#define PIC32MZ_DUPLEX_HALF 0x00
+
+#define PIC32MZ_10BASET_HD (PIC32MZ_SPEED_10 | PIC32MZ_DUPLEX_HALF)
+#define PIC32MZ_10BASET_FD (PIC32MZ_SPEED_10 | PIC32MZ_DUPLEX_FULL)
+#define PIC32MZ_100BASET_HD (PIC32MZ_SPEED_100 | PIC32MZ_DUPLEX_HALF)
+#define PIC32MZ_100BASET_FD (PIC32MZ_SPEED_100 | PIC32MZ_DUPLEX_FULL)
+
+#ifdef CONFIG_PHY_SPEED100
+# ifdef CONFIG_PHY_FDUPLEX
+# define PIC32MZ_MODE_DEFLT PIC32MZ_100BASET_FD
+# else
+# define PIC32MZ_MODE_DEFLT PIC32MZ_100BASET_HD
+# endif
+#else
+# ifdef CONFIG_PHY_FDUPLEX
+# define PIC32MZ_MODE_DEFLT PIC32MZ_10BASET_FD
+# else
+# define PIC32MZ_MODE_DEFLT PIC32MZ_10BASET_HD
+# endif
+#endif
+
+/* Misc Helper Macros *******************************************************/
+
+#define PHYS_ADDR(va) ((uint32_t)(va) & 0x1fffffff)
+#define VIRT_ADDR(pa) (KSEG1_BASE | (uint32_t)(pa))
+
+/* Ever-present MIN and MAX macros */
+
+#ifndef MIN
+# define MIN(a,b) (a < b ? a : b)
+#endif
+
+#ifndef MAX
+# define MAX(a,b) (a > b ? a : b)
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* EMAC statistics (debug only) */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
+struct pic32mz_statistics_s
+{
+ uint32_t rx_done; /* Rx done interrupts */
+ uint32_t rx_errors; /* Number of Rx error interrupts */
+ uint32_t rx_ovflw; /* Number of Rx overflow error interrupts */
+ uint32_t rx_bufna; /* Number of Rx buffer not available errors */
+ uint32_t rx_buse; /* Number of Rx BVCI bus errors */
+ uint32_t rx_packets; /* Number of packets received (sum of the following): */
+#ifdef CONFIG_NET_IPv4
+ uint32_t rx_ip; /* Number of Rx IPv4 packets received */
+#endif
+#ifdef CONFIG_NET_IPv6
+ uint32_t rx_ipv6; /* Number of Rx IPv6 packets received */
+#endif
+ uint32_t rx_arp; /* Number of Rx ARP packets received */
+ uint32_t rx_dropped; /* Number of dropped, unsupported Rx packets */
+ uint32_t rx_pkterr; /* Number of dropped, error in Rx descriptor */
+ uint32_t rx_pktsize; /* Number of dropped, too small or too big */
+ uint32_t rx_fragment; /* Number of dropped, packet fragments */
+ uint32_t tx_done; /* Tx done interrupts */
+ uint32_t tx_errors; /* Number of Tx error interrupts (OR of other errors) */
+ uint32_t tx_abort; /* Number of Tx abort interrupts */
+ uint32_t tx_buse; /* Number of Tx bus errors */
+ uint32_t tx_packets; /* Number of Tx packets queued */
+ uint32_t tx_pending; /* Number of Tx packets that had to wait for a TxDesc */
+ uint32_t tx_unpend; /* Number of pending Tx packets that were sent */
+ uint32_t tx_timeouts; /* Number of Tx timeout errors */
+};
+# define EMAC_STAT(priv,name) priv->pd_stat.name++
+#else
+# define EMAC_STAT(priv,name)
+#endif
+
+/* The pic32mz_driver_s encapsulates all state information for a single hardware
+ * interface
+ */
+
+struct pic32mz_driver_s
+{
+ /* The following fields would only be necessary on chips that support
+ * multiple Ethernet controllers.
+ */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ uint32_t pd_base; /* Ethernet controller base address */
+ int pd_irq; /* Ethernet controller IRQ vector number */
+ int pd_irqsrc; /* Ethernet controller IRQ source number */
+#endif
+
+ bool pd_ifup; /* true:ifup false:ifdown */
+ bool pd_txpending; /* There is a pending Tx in pd_dev */
+ bool pd_polling; /* Avoid concurrent attempts to poll */
+ uint8_t pd_mode; /* Speed/duplex */
+#ifdef PIC32MZ_HAVE_PHY
+ uint8_t pd_phyaddr; /* PHY device address */
+#endif
+ uint8_t pd_txnext; /* Index to the next Tx descriptor */
+ uint32_t pd_inten; /* Shadow copy of INTEN register */
+ WDOG_ID pd_txpoll; /* TX poll timer */
+ WDOG_ID pd_txtimeout; /* TX timeout timer */
+
+ sq_queue_t pd_freebuffers; /* The free buffer list */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
+ struct pic32mz_statistics_s pd_stat;
+#endif
+
+ /* This holds the information visible to uIP/NuttX */
+
+ struct net_driver_s pd_dev; /* Interface understood by uIP */
+
+ /* Descriptors and packet buffers */
+
+ struct pic32mz_rxdesc_s pd_rxdesc[CONFIG_NET_NRXDESC];
+ struct pic32mz_txdesc_s pd_txdesc[CONFIG_NET_NTXDESC];
+ uint8_t pd_buffers[PIC32MZ_NBUFFERS * PIC32MZ_ALIGNED_BUFSIZE];
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* Array of ethernet driver status structures */
+
+static struct pic32mz_driver_s g_ethdrvr[CONFIG_PIC32MZ_NINTERFACES];
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Register operations */
+
+#ifdef CONFIG_NET_REGDEBUG
+static void pic32mz_printreg(uint32_t addr, uint32_t val, bool iswrite);
+static void pic32mz_checkreg(uint32_t addr, uint32_t val, bool iswrite);
+static uint32_t pic32mz_getreg(uint32_t addr);
+static void pic32mz_putreg(uint32_t val, uint32_t addr);
+#else
+# define pic32mz_getreg(addr) getreg32(addr)
+# define pic32mz_putreg(val,addr) putreg32(val,addr)
+#endif
+
+/* Buffer and descriptor management */
+
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mz_dumptxdesc(struct pic32mz_txdesc_s *txdesc, const char *msg);
+static void pic32mz_dumprxdesc(struct pic32mz_rxdesc_s *rxdesc, const char *msg);
+#else
+# define pic32mz_dumptxdesc(txdesc,msg)
+# define pic32mz_dumprxdesc(rxdesc,msg)
+#endif
+
+static inline void pic32mz_bufferinit(struct pic32mz_driver_s *priv);
+static uint8_t *pic32mz_allocbuffer(struct pic32mz_driver_s *priv);
+static void pic32mz_freebuffer(struct pic32mz_driver_s *priv, uint8_t *buffer);
+
+static inline void pic32mz_txdescinit(struct pic32mz_driver_s *priv);
+static inline void pic32mz_rxdescinit(struct pic32mz_driver_s *priv);
+static inline struct pic32mz_txdesc_s *pic32mz_txdesc(struct pic32mz_driver_s *priv);
+static inline void pic32mz_txnext(struct pic32mz_driver_s *priv);
+static inline void pic32mz_rxreturn(struct pic32mz_rxdesc_s *rxdesc);
+static struct pic32mz_rxdesc_s *pic32mz_rxdesc(struct pic32mz_driver_s *priv);
+
+/* Common TX logic */
+
+static int pic32mz_transmit(struct pic32mz_driver_s *priv);
+static int pic32mz_txpoll(struct net_driver_s *dev);
+static void pic32mz_poll(struct pic32mz_driver_s *priv);
+static void pic32mz_timerpoll(struct pic32mz_driver_s *priv);
+
+/* Interrupt handling */
+
+static void pic32mz_response(struct pic32mz_driver_s *priv);
+static void pic32mz_rxdone(struct pic32mz_driver_s *priv);
+static void pic32mz_txdone(struct pic32mz_driver_s *priv);
+static int pic32mz_interrupt(int irq, void *context);
+
+/* Watchdog timer expirations */
+
+static void pic32mz_polltimer(int argc, uint32_t arg, ...);
+static void pic32mz_txtimeout(int argc, uint32_t arg, ...);
+
+/* NuttX callback functions */
+
+static int pic32mz_ifup(struct net_driver_s *dev);
+static int pic32mz_ifdown(struct net_driver_s *dev);
+static int pic32mz_txavail(struct net_driver_s *dev);
+#ifdef CONFIG_NET_IGMP
+static int pic32mz_addmac(struct net_driver_s *dev, const uint8_t *mac);
+static int pic32mz_rmmac(struct net_driver_s *dev, const uint8_t *mac);
+#endif
+
+/* PHY initialization functions */
+
+#ifdef PIC32MZ_HAVE_PHY
+# ifdef CONFIG_NET_REGDEBUG
+static void pic32mz_showmii(uint8_t phyaddr, const char *msg);
+# else
+# define pic32mz_showmii(phyaddr,msg)
+# endif
+
+static void pic32mz_phybusywait(void);
+static void pic32mz_phywrite(uint8_t phyaddr, uint8_t regaddr,
+ uint16_t phydata);
+static uint16_t pic32mz_phyread(uint8_t phyaddr, uint8_t regaddr);
+static inline int pic32mz_phyreset(uint8_t phyaddr);
+# ifdef CONFIG_PHY_AUTONEG
+static inline int pic32mz_phyautoneg(uint8_t phyaddr);
+# endif
+static int pic32mz_phymode(uint8_t phyaddr, uint8_t mode);
+static inline int pic32mz_phyinit(struct pic32mz_driver_s *priv);
+#else
+# define pic32mz_phyinit(priv)
+#endif
+
+/* EMAC Initialization functions */
+
+static void pic32mz_macmode(uint8_t mode);
+static void pic32mz_ethreset(struct pic32mz_driver_s *priv);
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/*******************************************************************************
+ * Name: pic32mz_printreg
+ *
+ * Description:
+ * Print the contents of an PIC32MZ register operation
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_NET_REGDEBUG
+static void pic32mz_printreg(uint32_t addr, uint32_t val, bool iswrite)
+{
+ lldbg("%08x%s%08x\n", addr, iswrite ? "<-" : "->", val);
+}
+#endif
+
+/*******************************************************************************
+ * Name: pic32mz_checkreg
+ *
+ * Description:
+ * Get the contents of an PIC32MZ register
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_NET_REGDEBUG
+static void pic32mz_checkreg(uint32_t addr, uint32_t val, bool iswrite)
+{
+ static uint32_t prevaddr = 0;
+ static uint32_t preval = 0;
+ static uint32_t count = 0;
+ static bool prevwrite = false;
+
+ /* Is this the same value that we read from/wrote to the same register last time?
+ * Are we polling the register? If so, suppress the output.
+ */
+
+ if (addr == prevaddr && val == preval && prevwrite == iswrite)
+ {
+ /* Yes.. Just increment the count */
+
+ count++;
+ }
+ else
+ {
+ /* No this is a new address or value or operation. Were there any
+ * duplicate accesses before this one?
+ */
+
+ if (count > 0)
+ {
+ /* Yes.. Just one? */
+
+ if (count == 1)
+ {
+ /* Yes.. Just one */
+
+ pic32mz_printreg(prevaddr, preval, prevwrite);
+ }
+ else
+ {
+ /* No.. More than one. */
+
+ lldbg("[repeats %d more times]\n", count);
+ }
+ }
+
+ /* Save the new address, value, count, and operation for next time */
+
+ prevaddr = addr;
+ preval = val;
+ count = 0;
+ prevwrite = iswrite;
+
+ /* Show the new register access */
+
+ pic32mz_printreg(addr, val, iswrite);
+ }
+}
+#endif
+
+/*******************************************************************************
+ * Name: pic32mz_getreg
+ *
+ * Description:
+ * Get the contents of an PIC32MZ register
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_NET_REGDEBUG
+static uint32_t pic32mz_getreg(uint32_t addr)
+{
+ /* Read the value from the register */
+
+ uint32_t val = getreg32(addr);
+
+ /* Check if we need to print this value */
+
+ pic32mz_checkreg(addr, val, false);
+ return val;
+}
+#endif
+
+/*******************************************************************************
+ * Name: pic32mz_putreg
+ *
+ * Description:
+ * Set the contents of an PIC32MZ register to a value
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_NET_REGDEBUG
+static void pic32mz_putreg(uint32_t val, uint32_t addr)
+{
+ /* Check if we need to print this value */
+
+ pic32mz_checkreg(addr, val, true);
+
+ /* Write the value */
+
+ putreg32(val, addr);
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_dumptxdesc
+ *
+ * Description:
+ * Dump the contents of the specified TX descriptor
+ *
+ * Parameters:
+ * txdesc - Pointer to the TX descriptor to dump
+ * msg - Annotation for the TX descriptor
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mz_dumptxdesc(struct pic32mz_txdesc_s *txdesc, const char *msg)
+{
+ lldbg("TX Descriptor [%p]: %s\n", txdesc, msg);
+ lldbg(" status: %08x\n", txdesc->status);
+ lldbg(" address: %08x [%08x]\n", txdesc->address, VIRT_ADDR(txdesc->address));
+ lldbg(" tsv1: %08x\n", txdesc->tsv1);
+ lldbg(" tsv2: %08x\n", txdesc->tsv2);
+ lldbg(" nexted: %08x [%08x]\n", txdesc->nexted, VIRT_ADDR(txdesc->nexted));
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_dumprxdesc
+ *
+ * Description:
+ * Dump the contents of the specified RX descriptor
+ *
+ * Parameters:
+ * txdesc - Pointer to the RX descriptor to dump
+ * msg - Annotation for the RX descriptor
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mz_dumprxdesc(struct pic32mz_rxdesc_s *rxdesc, const char *msg)
+{
+ lldbg("RX Descriptor [%p]: %s\n", rxdesc, msg);
+ lldbg(" status: %08x\n", rxdesc->status);
+ lldbg(" address: %08x [%08x]\n", rxdesc->address, VIRT_ADDR(rxdesc->address));
+ lldbg(" rsv1: %08x\n", rxdesc->rsv1);
+ lldbg(" rsv2: %08x\n", rxdesc->rsv2);
+ lldbg(" nexted: %08x [%08x]\n", rxdesc->nexted, VIRT_ADDR(rxdesc->nexted));
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_bufferinit
+ *
+ * Description:
+ * Initialize the buffers by placing them all in a free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void pic32mz_bufferinit(struct pic32mz_driver_s *priv)
+{
+ uint8_t *buffer;
+ int i;
+
+ for (i = 0, buffer = priv->pd_buffers; i < PIC32MZ_NBUFFERS; i++)
+ {
+ /* Add the buffer to the end of the list of free buffers */
+
+ sq_addlast((sq_entry_t*)buffer, &priv->pd_freebuffers);
+
+ /* Get the address of the next buffer */
+
+ buffer += PIC32MZ_ALIGNED_BUFSIZE;
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_allocbuffer
+ *
+ * Description:
+ * Allocate one buffer by removing it from the free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * Pointer to the allocated buffer (or NULL on failure)
+ *
+ ****************************************************************************/
+
+static uint8_t *pic32mz_allocbuffer(struct pic32mz_driver_s *priv)
+{
+ /* Return the next free buffer from the head of the free buffer list */
+
+ return (uint8_t*)sq_remfirst(&priv->pd_freebuffers);
+}
+
+/****************************************************************************
+ * Function: pic32mz_freebuffer
+ *
+ * Description:
+ * Free one buffer by returning it to the free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * Pointer to the allocated buffer (or NULL on failure)
+ *
+ ****************************************************************************/
+
+static void pic32mz_freebuffer(struct pic32mz_driver_s *priv, uint8_t *buffer)
+{
+ /* Add the buffer to the end of the free buffer list */
+
+ sq_addlast((sq_entry_t*)buffer, &priv->pd_freebuffers);
+}
+
+/****************************************************************************
+ * Function: pic32mz_txdescinit
+ *
+ * Description:
+ * Initialize the EMAC Tx descriptor table
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void pic32mz_txdescinit(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_txdesc_s *txdesc;
+ int i;
+
+ /* Assign a buffer to each TX descriptor. For now, just mark each TX
+ * descriptor as owned by softare andnot linked.
+ */
+
+ for (i = 0; i < CONFIG_NET_NTXDESC; i++)
+ {
+ /* Point to the next entry */
+
+ txdesc = &priv->pd_txdesc[i];
+
+ /* Initialize the buffer. It is idle, owned by software and has
+ * no buffer assigned to it.
+ */
+
+ txdesc->status = TXDESC_STATUS_SOWN | TXDESC_STATUS_NPV;
+ txdesc->address = 0;
+ txdesc->tsv1 = 0;
+ txdesc->tsv2 = 0;
+
+ /* Set the NEXTED pointer. If this is the last descriptor in the
+ * list, then set the NEXTED pointer back to the first entry,
+ * creating a ring.
+ */
+
+ if (i == (CONFIG_NET_NRXDESC-1))
+ {
+ txdesc->nexted = PHYS_ADDR(priv->pd_txdesc);
+ }
+ else
+ {
+ txdesc->nexted = PHYS_ADDR(&priv->pd_txdesc[i+1]);
+ }
+
+ pic32mz_dumptxdesc(txdesc, "Initial");
+ }
+
+ /* Position the Tx index to the first descriptor in the ring */
+
+ priv->pd_txnext = 0;
+
+ /* Update the ETHTXST register with the physical address of the head of
+ * the TX descriptors list.
+ */
+
+ pic32mz_putreg(PHYS_ADDR(priv->pd_txdesc), PIC32MZ_ETH_TXST);
+}
+
+/****************************************************************************
+ * Function: pic32mz_rxdescinit
+ *
+ * Description:
+ * Initialize the EMAC Rx descriptor table
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void pic32mz_rxdescinit(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_rxdesc_s *rxdesc;
+ int i;
+
+ /* Prepare a list of RX descriptors populated with valid buffers for
+ * messages to be received. Properly update the NPV, EOWN = 1 and
+ * DATA_BUFFER_ADDRESS fields in the RX descriptors. The
+ * DATA_BUFFER_ADDRESS should contain the physical address of the
+ * corresponding RX buffer.
+ */
+
+ for (i = 0; i < CONFIG_NET_NRXDESC; i++)
+ {
+ /* Point to the next entry */
+
+ rxdesc = &priv->pd_rxdesc[i];
+
+ /* Initialize the descriptor. Assign it a buffer and make it ready
+ * for reception.
+ */
+
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv2 = 0;
+ rxdesc->address = PHYS_ADDR(pic32mz_allocbuffer(priv));
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
+
+ /* Set the NEXTED pointer. If this is the last descriptor in the
+ * list, then set the NEXTED pointer back to the first entry,
+ * creating a ring.
+ */
+
+ if (i == (CONFIG_NET_NRXDESC-1))
+ {
+ rxdesc->nexted = PHYS_ADDR(priv->pd_rxdesc);
+ }
+ else
+ {
+ rxdesc->nexted = PHYS_ADDR(&priv->pd_rxdesc[i+1]);
+ }
+
+ pic32mz_dumprxdesc(rxdesc, "Initial");
+ }
+
+ /* Update the ETHRXST register with the physical address of the head of the
+ * RX descriptors list.
+ */
+
+ pic32mz_putreg(PHYS_ADDR(priv->pd_rxdesc), PIC32MZ_ETH_RXST);
+}
+
+/****************************************************************************
+ * Function: pic32mz_txdesc
+ *
+ * Description:
+ * Check if the next Tx descriptor is available.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * A pointer to the next available Tx descriptor on success; NULL if the
+ * next Tx dscriptor is not available.
+ *
+ ****************************************************************************/
+
+static inline struct pic32mz_txdesc_s *pic32mz_txdesc(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_txdesc_s *txdesc;
+
+ /* Get a reference to the next Tx descriptor in the ring */
+
+ txdesc = &priv->pd_txdesc[priv->pd_txnext];
+
+ /* Check if the EOWN bit is cleared. If it is, this descriptor is now under
+ * software control and the message has been transmitted.
+ *
+ * Also check that the buffer address is NULL. There is a race condition
+ * in that the hardware may have completed the transfer, but there may
+ * still be a valid buffer attached to the Tx descriptor because we have
+ * not yet processed the Tx done condition. We will know that the Tx
+ * done condition has been processed when the buffer has been freed and
+ * reset to zero.
+ */
+
+ if ((txdesc->status & TXDESC_STATUS_EOWN) == 0 && txdesc->address == 0)
+ {
+ /* Yes.. return a pointer to the descriptor */
+
+ return txdesc;
+ }
+
+ /* The next Tx descriptor is still owned by the Ethernet controller.. the
+ * Tx ring if full and cannot be used now. Return NULL.
+ */
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Function: pic32mz_txnext
+ *
+ * Description:
+ * After the next Tx descriptor has been given to the hardware, update the
+ * index to the next Tx descriptor in the ring.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+static inline void pic32mz_txnext(struct pic32mz_driver_s *priv)
+{
+ /* Increment the index to the next Tx descriptor in the ring */
+
+ int txnext = priv->pd_txnext + 1;
+
+ /* If the new index would go beyond the end of the allocated descriptors
+ * for the Tx ring, then reset to first descriptor.
+ */
+
+ if (txnext >= CONFIG_NET_NTXDESC)
+ {
+ txnext = 0;
+ }
+
+ /* Save the index to the next Tx descriptor */
+
+ priv->pd_txnext = txnext;
+}
+
+/****************************************************************************
+ * Function: pic32mz_rxreturn
+ *
+ * Description:
+ * Return an RX descriptor to the hardware.
+ *
+ * Parameters:
+ * rxdesc - Reference to the RX descriptor to be returned
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void pic32mz_rxreturn(struct pic32mz_rxdesc_s *rxdesc)
+{
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv2 = 0;
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
+ pic32mz_dumprxdesc(rxdesc, "Returned to hardware");
+}
+
+/****************************************************************************
+ * Function: pic32mz_rxdesc
+ *
+ * Description:
+ * Check if a RX descriptor is owned by the software.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * A pointer to the RX descriptor on success; NULL on failure
+ *
+ * Assumptions:
+ * May or may not be called from an interrupt handler. In either case,
+ * global interrupts are disabled, either explicitly or indirectly through
+ * interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static struct pic32mz_rxdesc_s *pic32mz_rxdesc(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_rxdesc_s *rxdesc;
+ int i;
+
+ /* Inspect the list of RX descriptors to see if the EOWN bit is cleared.
+ * If it is, this descriptor is now under software control and a message was
+ * received. Use SOP and EOP to extract the message, use BYTE_COUNT, RXF_RSV,
+ * RSV and PKT_CHECKSUM to get the message characteristics.
+ */
+
+ for (i = 0; i < CONFIG_NET_NRXDESC; i++)
+ {
+ /* Check if software owns this descriptor */
+
+ rxdesc = &priv->pd_rxdesc[i];
+ if ((rxdesc->status & RXDESC_STATUS_EOWN) == 0)
+ {
+ /* Yes.. return a pointer to the desciptor */
+
+ return rxdesc;
+ }
+ }
+
+ /* All descriptors are owned by the Ethernet controller.. return NULL */
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Function: pic32mz_transmit
+ *
+ * Description:
+ * Start hardware transmission. Called either from the txdone interrupt
+ * handling or from watchdog based polling.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * May or may not be called from an interrupt handler. In either case,
+ * global interrupts are disabled, either explicitly or indirectly through
+ * interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static int pic32mz_transmit(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_txdesc_s *txdesc;
+ uint32_t status;
+
+ /* Verify that the hardware is ready to send another packet. If we get
+ * here, then we are committed to sending a packet; Higher level logic
+ * must have assured that there is no transmission in progress.
+ */
+
+ DEBUGASSERT(priv->pd_dev.d_buf != NULL &&
+ priv->pd_dev.d_len < CONFIG_NET_ETH_MTU);
+
+ /* Increment statistics and dump the packet (if so configured) */
+
+ EMAC_STAT(priv, tx_packets);
+ pic32mz_dumppacket("Transmit packet", priv->pd_dev.d_buf, priv->pd_dev.d_len);
+
+ /* In order to transmit a message:
+ *
+ * The SOP, EOP, DATA_BUFFER_ADDRESS and BYTE_COUNT will be updated when a
+ * particular message has to be transmitted. The DATA_BUFFER_ADDRESS will
+ * contain the physical address of the message, the BYTE_COUNT message size.
+ * SOP and EOP are set depending on how many packets are needed to transmit
+ * the message.
+ */
+
+ /* Find the next available TX descriptor. We are guaranteed that is will
+ * not fail by upstream logic that assures that a TX packet is available
+ * before polling uIP.
+ */
+
+ txdesc = pic32mz_txdesc(priv);
+ DEBUGASSERT(txdesc != NULL);
+ pic32mz_dumptxdesc(txdesc, "Before transmit setup");
+
+ /* Remove the transmit buffer from the device structure and assign it to
+ * the TX descriptor.
+ */
+
+ txdesc->address = PHYS_ADDR(priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+
+ /* Set the BYTE_COUNT for in the TX descriptor with the number of bytes
+ * contained in the buffer.
+ */
+
+ status = ((uint32_t)priv->pd_dev.d_len << TXDESC_STATUS_BYTECOUNT_SHIFT);
+ priv->pd_dev.d_len = 0;
+
+ /* Set EOWN = 1 to indicate that the packet belongs to Ethernet and set both
+ * SOP and EOP to indicate that the packet both begins and ends with this
+ * frame.
+ */
+
+ status |= (TXDESC_STATUS_EOWN | TXDESC_STATUS_NPV |
+ TXDESC_STATUS_EOP | TXDESC_STATUS_SOP);
+ txdesc->status = status;
+ pic32mz_dumptxdesc(txdesc, "After transmit setup");
+
+ /* Update the index to the next descriptor to use in the Tx ring */
+
+ pic32mz_txnext(priv);
+
+ /* Enable the transmission of the message by setting the TXRTS bit (ETHCON1:9). */
+
+ pic32mz_putreg(ETH_CON1_TXRTS | ETH_CON1_ON, PIC32MZ_ETH_CON1SET);
+
+ /* Enable Tx interrupts */
+
+ priv->pd_inten |= ETH_TXINTS;
+ pic32mz_putreg(priv->pd_inten, PIC32MZ_ETH_IEN);
+
+ /* Setup the TX timeout watchdog (perhaps restarting the timer) */
+
+ (void)wd_start(priv->pd_txtimeout, PIC32MZ_TXTIMEOUT, pic32mz_txtimeout,
+ 1, (uint32_t)priv);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Function: pic32mz_txpoll
+ *
+ * Description:
+ * The transmitter is available, check if uIP has any outgoing packets ready
+ * to send. This is a callback from devif_poll(). devif_poll() may be called:
+ *
+ * 1. When the preceding TX packet send is complete,
+ * 2. When the preceding TX packet send timesout and the interface is reset
+ * 3. During normal TX polling
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * May or may not be called from an interrupt handler. In either case,
+ * global interrupts are disabled, either explicitly or indirectly through
+ * interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static int pic32mz_txpoll(struct net_driver_s *dev)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+ int ret = OK;
+
+ /* If the polling resulted in data that should be sent out on the network,
+ * the field d_len is set to a value > 0.
+ */
+
+ if (priv->pd_dev.d_len > 0)
+ {
+ /* Look up the destination MAC address and add it to the Ethernet
+ * header.
+ */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ if (IFF_IS_IPv4(priv->pd_dev.d_flags))
+#endif
+ {
+ arp_out(&priv->pd_dev);
+ }
+#endif /* CONFIG_NET_IPv4 */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ else
+#endif
+ {
+ neighbor_out(&priv->pd_dev);
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Send this packet. In this context, we know that there is space for
+ * at least one more packet in the descriptor list.
+ */
+
+ pic32mz_transmit(priv);
+
+ /* Check if the next TX descriptor is available. If not, return a
+ * non-zero value to terminate the poll.
+ */
+
+ if (pic32mz_txdesc(priv) == NULL)
+ {
+ /* There are no more TX descriptors/buffers available.. stop the poll */
+
+ return -EAGAIN;
+ }
+
+ /* Get the next Tx buffer needed in order to continue the poll */
+
+ priv->pd_dev.d_buf = pic32mz_allocbuffer(priv);
+ if (priv->pd_dev.d_buf == NULL)
+ {
+ /* We have no more buffers available for the nex Tx.. stop the poll */
+
+ return -ENOMEM;
+ }
+ }
+
+ /* If zero is returned, the polling will continue until all connections have
+ * been examined.
+ */
+
+ return ret;
+}
+
+/****************************************************************************
+ * Function: pic32mz_poll
+ *
+ * Description:
+ * Perform the uIP poll.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void pic32mz_poll(struct pic32mz_driver_s *priv)
+{
+ /* Is there already a poll in progress. This happens, for example, when
+ * debugging output is enabled. Interrupts may be re-enabled while debug
+ * output is performed and a timer expiration could attempt a concurrent
+ * poll.
+ */
+
+ if (!priv->pd_polling)
+ {
+ /* Assign a buffer for the poll */
+
+ DEBUGASSERT(priv->pd_dev.d_buf == NULL);
+ priv->pd_dev.d_buf = pic32mz_allocbuffer(priv);
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ /* And perform the poll */
+
+ priv->pd_polling = true;
+ (void)devif_poll(&priv->pd_dev, pic32mz_txpoll);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mz_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ priv->pd_polling = false;
+ }
+ }
+
+}
+
+/****************************************************************************
+ * Function: pic32mz_timerpoll
+ *
+ * Description:
+ * Perform the uIP timer poll.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void pic32mz_timerpoll(struct pic32mz_driver_s *priv)
+{
+ /* Is there already a poll in progress. This happens, for example, when
+ * debugging output is enabled. Interrupts may be re-enabled while debug
+ * output is performed and a timer expiration could attempt a concurrent
+ * poll.
+ */
+
+ if (!priv->pd_polling)
+ {
+ DEBUGASSERT(priv->pd_dev.d_buf == NULL);
+ priv->pd_dev.d_buf = pic32mz_allocbuffer(priv);
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ /* And perform the poll */
+
+ priv->pd_polling = true;
+ (void)devif_timer(&priv->pd_dev, pic32mz_txpoll, PIC32MZ_POLLHSEC);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mz_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ priv->pd_polling = false;
+ }
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_response
+ *
+ * Description:
+ * While processing an RxDone event, higher logic decides to send a packet,
+ * possibly a response to the incoming packet (but probably not, in reality).
+ * However, since the Rx and Tx operations are decoupled, there is no
+ * guarantee that there will be a Tx descriptor available at that time.
+ * This function will perform that check and, if no Tx descriptor is
+ * available, this function will (1) stop incoming Rx processing (bad), and
+ * (2) hold the outgoing packet in a pending state until the next Tx
+ * interrupt occurs.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static void pic32mz_response(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_txdesc_s *txdesc;
+
+ /* Check if the next TX descriptor is available. */
+
+ txdesc = pic32mz_txdesc(priv);
+ if (txdesc != NULL)
+ {
+ /* Yes.. queue the packet now. */
+
+ pic32mz_transmit(priv);
+ }
+ else
+ {
+ /* No.. mark the Tx as pending and halt further Rx interrupts */
+
+ DEBUGASSERT((priv->pd_inten & ETH_INT_TXDONE) != 0);
+
+ priv->pd_txpending = true;
+ priv->pd_inten &= ~ETH_RXINTS;
+ pic32mz_putreg(priv->pd_inten, PIC32MZ_ETH_IEN);
+ EMAC_STAT(priv, tx_pending);
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_rxdone
+ *
+ * Description:
+ * An interrupt was received indicating the availability of a new RX packet
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static void pic32mz_rxdone(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_rxdesc_s *rxdesc;
+
+ /* Loop while there are incoming packets to be processed, that is, while
+ * the producer index is not equal to the consumer index.
+ */
+
+ for (;;)
+ {
+ /* Check if any RX descriptor has the EOWN bit cleared meaning that the
+ * this descriptor is now under software control and a message was
+ * received.
+ */
+
+ rxdesc = pic32mz_rxdesc(priv);
+ if (rxdesc == NULL)
+ {
+ /* All RX descriptors are owned by the Ethernet controller... we
+ * are finished here.
+ */
+
+ return;
+ }
+ pic32mz_dumprxdesc(rxdesc, "RX Complete");
+
+ /* Update statistics */
+
+ EMAC_STAT(priv, rx_packets);
+
+ /* Get the packet length */
+
+ priv->pd_dev.d_len = (rxdesc->rsv2 & RXDESC_RSV2_BYTECOUNT_MASK) >> RXDESC_RSV2_BYTECOUNT_SHIFT;
+
+ /* Check for errors */
+
+ if ((rxdesc->rsv2 & RXDESC_RSV2_OK) == 0)
+ {
+ nlldbg("ERROR. rsv1: %08x rsv2: %08x\n", rxdesc->rsv1, rxdesc->rsv2);
+ EMAC_STAT(priv, rx_pkterr);
+ pic32mz_rxreturn(rxdesc);
+ }
+
+ /* If the packet length is greater then the buffer, then we cannot accept
+ * the packet. Also, since the DMA packet buffers are set up to
+ * be the same size as our max packet size, any fragments also
+ * imply that the packet is too big.
+ */
+
+ else if (priv->pd_dev.d_len > CONFIG_NET_ETH_MTU)
+ {
+ nlldbg("Too big. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
+ EMAC_STAT(priv, rx_pktsize);
+ pic32mz_rxreturn(rxdesc);
+ }
+
+ /* We don't have any logic here for reassembling packets from fragments. */
+
+ else if ((rxdesc->status & (RXDESC_STATUS_EOP|RXDESC_STATUS_SOP)) != (RXDESC_STATUS_EOP|RXDESC_STATUS_SOP))
+ {
+ nlldbg("Fragment. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
+ EMAC_STAT(priv, rx_fragment);
+ pic32mz_rxreturn(rxdesc);
+ }
+ else
+ {
+ uint8_t *rxbuffer;
+
+ /* Get the Rx buffer address from the Rx descriptor */
+
+ priv->pd_dev.d_buf = (uint8_t*)VIRT_ADDR(rxdesc->address);
+ DEBUGASSERT(priv->pd_dev.d_buf != NULL);
+
+ /* Replace the buffer in the RX descriptor with a new one */
+
+ rxbuffer = pic32mz_allocbuffer(priv);
+ DEBUGASSERT(rxbuffer != NULL);
+ rxdesc->address = PHYS_ADDR(rxbuffer);
+
+ /* And give the RX descriptor back to the hardware */
+
+ pic32mz_rxreturn(rxdesc);
+ pic32mz_dumppacket("Received packet",
+ priv->pd_dev.d_buf, priv->pd_dev.d_len);
+
+#ifdef CONFIG_NET_PKT
+ /* When packet sockets are enabled, feed the frame into the packet
+ * tap.
+ */
+
+ pkt_input(&priv->pd_dev);
+#endif
+
+ /* We only accept IP packets of the configured type and ARP packets */
+
+#ifdef CONFIG_NET_IPv4
+ if (BUF->type == HTONS(ETHTYPE_IP))
+ {
+ nllvdbg("IPv4 frame\n");
+
+ /* Handle ARP on input then give the IPv4 packet to the network
+ * layer
+ */
+
+ EMAC_STAT(priv, rx_ip);
+ arp_ipin(&priv->pd_dev);
+ ipv4_input(&priv->pd_dev);
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the field d_len will
+ * set to a value > 0.
+ */
+
+ if (priv->pd_dev.d_len > 0)
+ {
+ /* Update the Ethernet header with the correct MAC address */
+
+#ifdef CONFIG_NET_IPv6
+ if (IFF_IS_IPv4(priv->pd_dev.d_flags))
+#endif
+ {
+ arp_out(&priv->pd_dev);
+ }
+#ifdef CONFIG_NET_IPv6
+ else
+ {
+ neighbor_out(&priv->pd_dev);
+ }
+#endif
+
+ /* And send the packet */
+
+ pic32mz_response(priv);
+ }
+ }
+ else
+#endif
+#ifdef CONFIG_NET_IPv6
+ if (BUF->type == HTONS(ETHTYPE_IP6))
+ {
+ nllvdbg("Iv6 frame\n");
+
+ /* Give the IPv6 packet to the network layer */
+
+ EMAC_STAT(priv, rx_ipv6);
+ ipv6_input(&priv->pd_dev);
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the field d_len will
+ * set to a value > 0.
+ */
+
+ if (priv->pd_dev.d_len > 0)
+ {
+ /* Update the Ethernet header with the correct MAC address */
+
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv4(priv->pd_dev.d_flags))
+ {
+ arp_out(&priv->pd_dev);
+ }
+ else
+#endif
+#ifdef CONFIG_NET_IPv6
+ {
+ neighbor_out(&priv->pd_dev);
+ }
+#endif
+
+ /* And send the packet */
+
+ pic32mz_response(priv);
+ }
+ }
+ else
+#endif
+#ifdef CONFIG_NET_ARP
+ if (BUF->type == htons(ETHTYPE_ARP))
+ {
+ /* Handle the incoming ARP packet */
+
+ EMAC_STAT(priv, rx_arp);
+ arp_arpin(&priv->pd_dev);
+
+ /* If the above function invocation resulted in data that
+ * should be sent out on the network, the field d_len will
+ * set to a value > 0.
+ */
+
+ if (priv->pd_dev.d_len > 0)
+ {
+ pic32mz_response(priv);
+ }
+ }
+ else
+#endif
+ {
+ /* Unrecognized... drop it. */
+
+ nlldbg("Unrecognized packet type dropped: %04x\n", ntohs(BUF->type));
+ EMAC_STAT(priv, rx_dropped);
+ }
+
+ /* Discard any buffers still attached to the device structure */
+
+ priv->pd_dev.d_len = 0;
+ if (priv->pd_dev.d_buf)
+ {
+ pic32mz_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ }
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_txdone
+ *
+ * Description:
+ * An interrupt was received indicating that the last TX packet(s) is done
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static void pic32mz_txdone(struct pic32mz_driver_s *priv)
+{
+ struct pic32mz_txdesc_s *txdesc;
+ int i;
+
+ /* Cancel the pending Tx timeout */
+
+ wd_cancel(priv->pd_txtimeout);
+
+ /* Disable further Tx interrupts. Tx interrupts may be re-enabled again
+ * depending upon the result of the poll.
+ */
+
+ priv->pd_inten &= ~ETH_TXINTS;
+ pic32mz_putreg(priv->pd_inten, PIC32MZ_ETH_IEN);
+
+ /* Verify that the hardware is ready to send another packet. Since a Tx
+ * just completed, this must be the case.
+ */
+
+ DEBUGASSERT(pic32mz_txdesc(priv) != NULL);
+
+ /* Inspect the list of TX descriptors to see if the EOWN bit is cleared. If it
+ * is, this descriptor is now under software control and the message was
+ * transmitted. Use TSV to check for the transmission result.
+ */
+
+ for (i = 0; i < CONFIG_NET_NTXDESC; i++)
+ {
+ txdesc = &priv->pd_txdesc[i];
+
+ /* Check if software owns this descriptor */
+
+ if ((txdesc->status & TXDESC_STATUS_EOWN) == 0)
+ {
+ /* Yes.. Check if there is a buffer attached? */
+
+ if (txdesc->address != 0)
+ {
+ pic32mz_dumptxdesc(txdesc, "Freeing TX buffer");
+
+ /* Free the TX buffer */
+
+ pic32mz_freebuffer(priv, (uint8_t *)VIRT_ADDR(txdesc->address));
+ txdesc->address = 0;
+
+ /* Reset status */
+
+ txdesc->tsv1 = 0;
+ txdesc->tsv2 = 0;
+ txdesc->status = TXDESC_STATUS_SOWN | TXDESC_STATUS_NPV;
+ pic32mz_dumptxdesc(txdesc, "TX buffer freed");
+ }
+ }
+ }
+
+ /* Check if there is a pending Tx transfer that was deferred by Rx handling
+ * because there were no available Tx descriptors. If so, process that
+ * pending Tx now.
+ */
+
+ if (priv->pd_txpending)
+ {
+ /* Clear the pending condition, send the packet, and restore Rx interrupts */
+
+ priv->pd_txpending = false;
+ EMAC_STAT(priv, tx_unpend);
+
+ pic32mz_transmit(priv);
+
+ priv->pd_inten |= ETH_RXINTS;
+ pic32mz_putreg(priv->pd_inten, PIC32MZ_ETH_IEN);
+ }
+
+ /* Otherwise poll uIP for new XMIT data */
+
+ else
+ {
+ /* Perform the uIP poll */
+
+ pic32mz_poll(priv);
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_interrupt
+ *
+ * Description:
+ * Hardware interrupt handler
+ *
+ * Parameters:
+ * irq - Number of the IRQ that generated the interrupt
+ * context - Interrupt register state save info (architecture-specific)
+ *
+ * Returned Value:
+ * OK on success
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int pic32mz_interrupt(int irq, void *context)
+{
+ register struct pic32mz_driver_s *priv;
+ uint32_t status;
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+# error "A mechanism to associate and interface with an IRQ is needed"
+#else
+ priv = &g_ethdrvr[0];
+#endif
+
+ /* Get the interrupt status (zero means no interrupts pending). */
+
+ status = pic32mz_getreg(PIC32MZ_ETH_IRQ);
+ if (status != 0)
+ {
+ /* Clear all pending interrupts */
+
+ pic32mz_putreg(status, PIC32MZ_ETH_IRQCLR);
+
+ /* Handle each pending interrupt **************************************/
+ /* Receive Errors *****************************************************/
+ /* RXOVFLW: Receive FIFO Over Flow Error. RXOVFLW is set by the RXBM
+ * Logic for an RX FIFO Overflow condition. It is cleared by either a
+ * Reset or CPU write of a ‘1’ to the CLR register.
+ */
+
+ if ((status & ETH_INT_RXOVFLW) != 0)
+ {
+ nlldbg("RX Overrun. status: %08x\n", status);
+ EMAC_STAT(priv, rx_errors);
+ EMAC_STAT(priv, rx_ovflw);
+ }
+
+ /* RXBUFNA: Receive Buffer Not Available Interrupt. This bit is set by
+ * a RX Buffer Descriptor Overrun condition. It is cleared by either a
+ * Reset or a CPU write of a ‘1’ to the CLR register.
+ */
+
+ if ((status & ETH_INT_RXBUFNA) != 0)
+ {
+ nlldbg("RX buffer descriptor overrun. status: %08x\n", status);
+ EMAC_STAT(priv, rx_errors);
+ EMAC_STAT(priv, rx_bufna);
+ }
+
+ /* RXBUSE: Receive BVCI Bus Error Interrupt. This bit is set when the
+ * RX DMA encounters a BVCI Bus error during a memory access. It is
+ * cleared by either a Reset or CPU write of a ‘1’ to the CLR register.
+ */
+
+ if ((status & ETH_INT_RXBUSE) != 0)
+ {
+ nlldbg("RX BVCI bus error. status: %08x\n", status);
+ EMAC_STAT(priv, rx_errors);
+ EMAC_STAT(priv, rx_buse);
+ }
+
+ /* Receive Normal Events **********************************************/
+ /* RXACT: Receive Activity Interrupt. This bit is set whenever RX packet
+ * data is stored in the RXBM FIFO. It is cleared by either a Reset or CPU
+ * write of a ‘1’ to the CLR register.
+ */
+
+ /* PKTPEND: Packet Pending Interrupt. This bit is set when the BUFCNT
+ * counter has a value other than ‘0’. It is cleared by either a Reset
+ * or by writing the BUFCDEC bit to decrement the BUFCNT counter.
+ * Writing a ‘0’ or a ‘1’ has no effect.
+ */
+
+ /* RXDONE: Receive Done Interrupt. This bit is set whenever an RX packet
+ * is successfully received. It is cleared by either a Reset or CPU
+ * write of a ‘1’ to the CLR register.
+ */
+
+ if ((status & ETH_INT_RXDONE) != 0)
+ {
+ EMAC_STAT(priv, rx_done);
+
+ /* We have received at least one new incoming packet. */
+
+ pic32mz_rxdone(priv);
+ }
+
+ /* Transmit Errors ****************************************************/
+ /* TXABORT: Transmit Abort Condition Interrupt. This bit is set when
+ * the MAC aborts the transmission of a TX packet for one of the
+ * following reasons:
+ * - Jumbo TX packet abort
+ * - Underrun abort
+ * - Excessive defer abort
+ * - Late collision abort
+ * - Excessive collisions abort
+ * This bit is cleared by either a Reset or CPU write of a ‘1’ to the
+ * CLR register.
+ */
+
+ if ((status & ETH_INT_TXABORT) != 0)
+ {
+ nlldbg("TX abort. status: %08x\n", status);
+ EMAC_STAT(priv, tx_errors);
+ EMAC_STAT(priv, tx_abort);
+ }
+
+ /* TXBUSE: Transmit BVCI Bus Error Interrupt. This bit is set when the
+ * TX DMA encounters a BVCI Bus error during a memory access. It is
+ * cleared by either a Reset or CPU write of a ‘1’ to the CLR register.
+ */
+
+ if ((status & ETH_INT_TXBUSE) != 0)
+ {
+ nlldbg("TX BVCI bus error. status: %08x\n", status);
+ EMAC_STAT(priv, tx_errors);
+ EMAC_STAT(priv, tx_buse);
+ }
+
+ /* TXDONE: Transmit Done Interrupt. This bit is set when the currently
+ * transmitted TX packet completes transmission, and the Transmit
+ * Status Vector is loaded into the first descriptor used for the
+ * packet. It is cleared by either a Reset or CPU write of a ‘1’ to
+ * the CLR register.
+ */
+
+ if ((status & ETH_INT_TXDONE) != 0)
+ {
+ EMAC_STAT(priv, tx_done);
+
+ /* A packet transmission just completed */
+
+ pic32mz_txdone(priv);
+ }
+
+ /* Watermark Events ***************************************************/
+ /* EWMARK: Empty Watermark Interrupt. This bit is set when the RX
+ * Descriptor Buffer Count is less than or equal to the value in the
+ * RXEWM bit (ETHRXWM:0-7) value. It is cleared by BUFCNT bit
+ * (ETHSTAT:16-23) being incremented by hardware. Writing a ‘0’ or a ‘1’
+ * has no effect.
+ */
+
+ /* FWMARK: Full Watermark Interrupt. This bit is set when the RX
+ * escriptor Buffer Count is greater than or equal to the value in the
+ * RXFWM bit (ETHRXWM:16-23) field. It is cleared by writing the BUFCDEC
+ * (ETHCON1:0) bit to decrement the BUFCNT counter. Writing a ‘0’ or a
+ * ‘1’ has no effect.
+ */
+
+ }
+
+ /* Clear the pending interrupt */
+
+# if CONFIG_PIC32MZ_NINTERFACES > 1
+ up_clrpend_irq(priv->pd_irqsrc);
+# else
+ up_clrpend_irq(PIC32MZ_IRQSRC_ETH);
+# endif
+
+ return OK;
+}
+
+/****************************************************************************
+ * Function: pic32mz_txtimeout
+ *
+ * Description:
+ * Our TX watchdog timed out. Called from the timer interrupt handler.
+ * The last TX never completed. Reset the hardware and start again.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by the watchdog logic.
+ *
+ ****************************************************************************/
+
+static void pic32mz_txtimeout(int argc, uint32_t arg, ...)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)arg;
+
+ /* Increment statistics and dump debug info */
+
+ EMAC_STAT(priv, tx_timeouts);
+ if (priv->pd_ifup)
+ {
+ /* Then reset the hardware. ifup() will reset the interface, then bring
+ * it back up.
+ */
+
+ (void)pic32mz_ifup(&priv->pd_dev);
+
+ /* Then poll uIP for new XMIT data (We are guaranteed to have a free
+ * buffer here).
+ */
+
+ pic32mz_poll(priv);
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mz_polltimer
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by the watchdog logic.
+ *
+ ****************************************************************************/
+
+static void pic32mz_polltimer(int argc, uint32_t arg, ...)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)arg;
+
+ /* Check if the next Tx descriptor is available. We cannot perform the Tx
+ * poll if we are unable to accept another packet for transmission.
+ */
+
+ if (pic32mz_txdesc(priv) != NULL)
+ {
+ /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm..
+ * might be bug here. Does this mean if there is a transmit in progress,
+ * we will missing TCP time state updates?
+ */
+
+ pic32mz_timerpoll(priv);
+ }
+
+ /* Setup the watchdog poll timer again */
+
+ (void)wd_start(priv->pd_txpoll, PIC32MZ_WDDELAY, pic32mz_polltimer, 1, arg);
+}
+
+/****************************************************************************
+ * Function: pic32mz_ifup
+ *
+ * Description:
+ * NuttX Callback: Bring up the Ethernet interface when an IP address is
+ * provided
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int pic32mz_ifup(struct net_driver_s *dev)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+ uint32_t regval;
+ int ret;
+
+ ndbg("Bringing up: %d.%d.%d.%d\n",
+ dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
+ (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24);
+
+ /* Reset the Ethernet controller (again) */
+
+ pic32mz_ethreset(priv);
+
+ /* MAC Initialization *****************************************************/
+ /* Configuration:
+ * - Use the configuration fuse setting FETHIO bit (DEVCFG3:25) to detect
+ * the alternate/default I/O configuration
+ * - Use the configuration fuse setting FMIIEN (DEVCFG3:24) to detect the
+ * MII/RMII operation mode.
+ */
+
+ /* Pin Configuration:
+ *
+ * No GPIO pin configuration is required. Enabling the Ethernet Controller
+ * will configure the I/O pin direction as defined by the Ethernet Controller
+ * control bits. The port TRIS and LATCH registers will be overridden.
+ *
+ * I/O Pin MII RMII Pin Description
+ * Name Required Required Type
+ * EMDC Yes Yes O Ethernet MII Management Clock
+ * EMDIO Yes Yes I/O Ethernet MII Management IO
+ * ETXCLK Yes No I Ethernet MII TX Clock
+ * ETXEN Yes Yes O Ethernet Transmit Enable
+ * ETXD0 Yes Yes O Ethernet Data Transmit 0
+ * ETXD1 Yes Yes O Ethernet Data Transmit 1
+ * ETXD2 Yes No O Ethernet Data Transmit 2
+ * ETXD3 Yes No O Ethernet Data Transmit 3
+ * ETXERR Yes No O Ethernet Transmit Error
+ * ERXCLK Yes No I Ethernet MII RX Clock
+ * EREF_CLK No Yes I Ethernet RMII Ref Clock
+ * ERXDV Yes No I Ethernet MII Receive Data Valid
+ * ECRS_DV No Yes I Ethernet RMII Carrier Sense/Receive Data Valid
+ * ERXD0 Yes Yes I Ethernet Data Receive 0
+ * ERXD1 Yes Yes I Ethernet Data Receive 1
+ * ERXD2 Yes No I Ethernet Data Receive 2
+ * ERXD3 Yes No I Ethernet Data Receive 3
+ * ERXERR Yes Yes I Ethernet Receive Error
+ * ECRS Yes No I Ethernet Carrier Sense
+ * ECOL Yes No I Ethernet Collision Detected
+ *
+ * All that is required is to assure that the pins are initialized as
+ * digital (normally only those pins that have shared analog functionality
+ * need to be configured).
+ */
+
+ /* Initialize the MIIM interface
+ *
+ * If the RMII operation is selected, reset the RMII module by using the
+ * RESETRMII (EMAC1SUPP:11) bit and set the proper speed in the SPEEDRMII
+ * bit (EMAC1SUPP:8) bit.
+ */
+
+#if CONFIG_PIC32MZ_FMIIEN == 0
+ pic32mz_putreg(EMAC1_SUPP_RESETRMII, PIC32MZ_EMAC1_SUPPSET);
+ pic32mz_putreg((EMAC1_SUPP_RESETRMII | EMAC1_SUPP_SPEEDRMII), PIC32MZ_EMAC1_SUPPCLR);
+#endif
+
+ /* Issue an MIIM block reset, by setting the RESETMGMT (EMAC1MCFG:15) bit,
+ * and then clear the reset bit.
+ */
+
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_MCFG);
+ pic32mz_putreg(EMAC1_MCFG_MGMTRST, PIC32MZ_EMAC1_MCFGSET);
+
+ regval &= ~EMAC1_MCFG_MGMTRST;
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_MCFG);
+
+ /* Select a proper divider in the CLKSEL bit (EMAC1CFG:2-5) for the MIIM
+ * PHY communication based on the system running clock frequency and the
+ * external PHY supported clock.
+ *
+ * MII configuration: host clocked divider per board.h, no suppress
+ * preamble, no scan increment.
+ */
+
+ regval &= ~(EMAC1_MCFG_CLKSEL_MASK | EMAC1_MCFG_NOPRE | EMAC1_MCFG_SCANINC);
+ regval |= EMAC1_MCFG_CLKSEL_DIV;
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_MCFG);
+
+ /* PHY Initialization *****************************************************/
+ /* Initialize the PHY and wait for the link to be established */
+
+ ret = pic32mz_phyinit(priv);
+ if (ret != 0)
+ {
+ ndbg("pic32mz_phyinit failed: %d\n", ret);
+ return ret;
+ }
+
+ /* MAC Configuration ******************************************************/
+ /* Set other misc configuration-related registers to default values */
+
+ pic32mz_putreg(0, PIC32MZ_EMAC1_CFG2);
+ pic32mz_putreg(0, PIC32MZ_EMAC1_TEST);
+
+ /* Having available the Duplex and Speed settings, configure the MAC
+ * accordingly, using the following steps:
+ *
+ * Enable the RXENABLE bit (EMAC1CFG1:0), selecting both the TXPAUSE and
+ * RXPAUSE bit (EMAC1CFG1:2-3) (the PIC32 MAC supports both).
+ */
+
+ pic32mz_putreg(EMAC1_CFG1_RXEN | EMAC1_CFG1_RXPAUSE | EMAC1_CFG1_TXPAUSE,
+ PIC32MZ_EMAC1_CFG1SET);
+
+ /* Select the desired auto-padding and CRC capabilities, and the enabling
+ * of the huge frames and the Duplex type in the EMAC1CFG2 register.
+ * (This was done in the PHY initialization logic).
+ */
+
+ /* Program EMAC1IPGT with the back-to-back inter-packet gap */
+ /* Use EMAC1IPGR for setting the non back-to-back inter-packet gap */
+
+ pic32mz_putreg(((12 << EMAC1_IPGR_GAP1_SHIFT) | (12 << EMAC1_IPGR_GAP2_SHIFT)),
+ PIC32MZ_EMAC1_IPGR);
+
+ /* Set the collision window and the maximum number of retransmissions in
+ * EMAC1CLRT.
+ */
+
+ pic32mz_putreg(((15 << EMAC1_CLRT_RETX_SHIFT) | (55 << EMAC1_CLRT_CWINDOW_SHIFT)),
+ PIC32MZ_EMAC1_CLRT);
+
+ /* Set the maximum frame length in EMAC1MAXF. "This field resets to
+ * 0x05EE, which represents a maximum receive frame of 1518 octets. An
+ * untagged maximum size Ethernet frame is 1518 octets. A tagged frame adds
+ * four octets for a total of 1522 octets. If a shorter/longer maximum
+ * length restriction is desired, program this 16-bit field.
+ */
+
+ pic32mz_putreg(CONFIG_NET_ETH_MTU, PIC32MZ_EMAC1_MAXF);
+
+ /* Configure the MAC station address in the EMAC1SA0, EMAC1SA1 and
+ * EMAC1SA2 registers (these registers are loaded at reset from the
+ * factory preprogrammed station address).
+ */
+
+#if 0
+ regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[5] << 8 |
+ (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[4];
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_SA0);
+
+ regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[3] << 8 |
+ (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[2];
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_SA1);
+
+ regval = (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[1] << 8 |
+ (uint32_t)priv->pd_dev.d_mac.ether_addr_octet[0];
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_SA2);
+#else
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_SA0);
+ priv->pd_dev.d_mac.ether_addr_octet[4] = (uint32_t)(regval & 0xff);
+ priv->pd_dev.d_mac.ether_addr_octet[5] = (uint32_t)((regval >> 8) & 0xff);
+
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_SA1);
+ priv->pd_dev.d_mac.ether_addr_octet[2] = (uint32_t)(regval & 0xff);
+ priv->pd_dev.d_mac.ether_addr_octet[3] = (uint32_t)((regval >> 8) & 0xff);
+
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_SA2);
+ priv->pd_dev.d_mac.ether_addr_octet[0] = (uint32_t)(regval & 0xff);
+ priv->pd_dev.d_mac.ether_addr_octet[1] = (uint32_t)((regval >> 8) & 0xff);
+#endif
+
+ /* Continue Ethernet Controller Initialization ****************************/
+ /* If planning to turn on the flow control, update the PTV value
+ *(ETHCON1:16-31).
+ */
+
+ /* If using the auto-flow control, set the full and empty watermarks: RXFWM
+ * and RXEWM (ETHRXWM:16-23 and ETHRXWM:0-7).
+ */
+
+ /* If needed, enable the auto-flow control by setting AUTOFC (ETHCON1:7). */
+
+ /* Set the RX filters by updating the ETHHT0, ETHHT1, ETHPMM0, ETHPMM1,
+ * ETHPMCS and ETHRXFC registers.
+ *
+ * Set up RX filter and configure to accept broadcast addresses and multicast
+ * addresses (if so configured). NOTE: There is a selection
+ * CONFIG_NET_BROADCAST, but this enables receipt of UDP broadcast packets
+ * inside of the stack.
+ */
+
+ regval = ETH_RXFC_BCEN | ETH_RXFC_UCEN | ETH_RXFC_PMMODE_DISABLED;
+#ifdef CONFIG_NET_MULTICAST
+ regval |= ETH_RXFC_MCEN;
+#endif
+ pic32mz_putreg(regval, PIC32MZ_ETH_RXFC);
+
+ /* Set the size of the RX buffers in the RXBUFSZ bit (ETHCON2:4-10) (all
+ * receive descriptors use the same buffer size). Keep in mind that using
+ * packets that are too small leads to packet fragmentation and has a
+ * noticeable impact on the performance.
+ */
+
+ pic32mz_putreg(ETH_CON2_RXBUFSZ(CONFIG_NET_ETH_MTU), PIC32MZ_ETH_CON2);
+
+ /* Reset state varialbes */
+
+ priv->pd_polling = false;
+ priv->pd_txpending = false;
+
+ /* Initialize the buffer list */
+
+ pic32mz_bufferinit(priv);
+
+ /* Initialize the TX descriptor list */
+
+ pic32mz_txdescinit(priv);
+
+ /* Initialize the RX descriptor list */
+
+ pic32mz_rxdescinit(priv);
+
+ /* Enable the Ethernet Controller by setting the ON bit (ETHCON1:15).
+ * Enable the receiving of messages by setting the RXEN bit (ETHCON1:8).
+ */
+
+ pic32mz_putreg(ETH_CON1_RXEN | ETH_CON1_ON, PIC32MZ_ETH_CON1SET);
+
+ /* Initialize Ethernet interface for the PHY setup */
+
+ pic32mz_macmode(priv->pd_mode);
+
+ /* Configure to pass all received frames */
+
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_CFG1);
+ regval |= EMAC1_CFG1_PASSALL;
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_CFG1);
+
+ /* Clear any pending interrupts (shouldn't be any) */
+
+ pic32mz_putreg(0xffffffff, PIC32MZ_ETH_IRQCLR);
+
+ /* Configure interrupts. The Ethernet interrupt was attached during one-time
+ * initialization, so we only need to set the interrupt priority, configure
+ * interrupts, and enable them.
+ */
+
+ /* If the user provided an interrupt priority, then set the interrupt to that
+ * priority
+ */
+
+#if defined(CONFIG_NET_PRIORITY) && defined(CONFIG_ARCH_IRQPRIO)
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ (void)up_prioritize_irq(priv->pd_irq, CONFIG_NET_PRIORITY);
+#else
+ (void)up_prioritize_irq(PIC32MZ_IRQ_ETH, CONFIG_NET_PRIORITY);
+#endif
+#endif
+
+ /* Otherwise, enable all Rx interrupts. Tx interrupts, SOFTINT and WoL are
+ * excluded. Tx interrupts will not be enabled until there is data to be
+ * sent.
+ */
+
+ priv->pd_inten = ETH_RXINTS;
+ pic32mz_putreg(ETH_RXINTS, PIC32MZ_ETH_IENSET);
+
+ /* Set and activate a timer process */
+
+ (void)wd_start(priv->pd_txpoll, PIC32MZ_WDDELAY, pic32mz_polltimer, 1,
+ (uint32_t)priv);
+
+ /* Finally, enable the Ethernet interrupt at the interrupt controller */
+
+ priv->pd_ifup = true;
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ up_enable_irq(priv->pd_irqsrc);
+#else
+ up_enable_irq(PIC32MZ_IRQSRC_ETH);
+#endif
+ return OK;
+}
+
+/****************************************************************************
+ * Function: pic32mz_ifdown
+ *
+ * Description:
+ * NuttX Callback: Stop the interface.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int pic32mz_ifdown(struct net_driver_s *dev)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ /* Disable the Ethernet interrupt */
+
+ flags = irqsave();
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ up_disable_irq(priv->pd_irqsrc);
+#else
+ up_disable_irq(PIC32MZ_IRQSRC_ETH);
+#endif
+
+ /* Cancel the TX poll timer and TX timeout timers */
+
+ wd_cancel(priv->pd_txpoll);
+ wd_cancel(priv->pd_txtimeout);
+
+ /* Reset the device and mark it as down. */
+
+ pic32mz_ethreset(priv);
+ priv->pd_ifup = false;
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: pic32mz_txavail
+ *
+ * Description:
+ * Driver callback invoked when new TX data is available. This is a
+ * stimulus perform an out-of-cycle poll and, thereby, reduce the TX
+ * latency.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called in normal user mode
+ *
+ ****************************************************************************/
+
+static int pic32mz_txavail(struct net_driver_s *dev)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ /* Disable interrupts because this function may be called from interrupt
+ * level processing.
+ */
+
+ flags = irqsave();
+
+ /* Ignore the notification if the interface is not yet up */
+
+ if (priv->pd_ifup)
+ {
+ /* Check if the next Tx descriptor is available. */
+
+ if (pic32mz_txdesc(priv) != NULL)
+ {
+ /* If so, then poll uIP for new XMIT data. First allocate a buffer
+ * to perform the poll
+ */
+
+ pic32mz_poll(priv);
+ }
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: pic32mz_addmac
+ *
+ * Description:
+ * NuttX Callback: Add the specified MAC address to the hardware multicast
+ * address filtering
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ * mac - The MAC address to be added
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int pic32mz_addmac(struct net_driver_s *dev, const uint8_t *mac)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+
+ /* Add the MAC address to the hardware multicast routing table */
+
+#warning "Not implemented"
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_rmmac
+ *
+ * Description:
+ * NuttX Callback: Remove the specified MAC address from the hardware multicast
+ * address filtering
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ * mac - The MAC address to be removed
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int pic32mz_rmmac(struct net_driver_s *dev, const uint8_t *mac)
+{
+ struct pic32mz_driver_s *priv = (struct pic32mz_driver_s *)dev->d_private;
+
+ /* Add the MAC address to the hardware multicast routing table */
+
+#warning "Not implemented"
+ return OK;
+}
+#endif
+
+/*******************************************************************************
+ * Name: pic32mz_showmii
+ *
+ * Description:
+ * Dump PHY MII registers
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ *******************************************************************************/
+
+#if defined(CONFIG_NET_REGDEBUG) && defined(PIC32MZ_HAVE_PHY)
+static void pic32mz_showmii(uint8_t phyaddr, const char *msg)
+{
+ dbg("PHY " PIC32MZ_PHYNAME ": %s\n", msg);
+ dbg(" MCR: %04x\n", pic32mz_phyread(phyaddr, MII_MCR));
+ dbg(" MSR: %04x\n", pic32mz_phyread(phyaddr, MII_MSR));
+ dbg(" ADVERTISE: %04x\n", pic32mz_phyread(phyaddr, MII_ADVERTISE));
+ dbg(" LPA: %04x\n", pic32mz_phyread(phyaddr, MII_LPA));
+ dbg(" EXPANSION: %04x\n", pic32mz_phyread(phyaddr, MII_EXPANSION));
+#ifdef CONFIG_ETH0_PHY_KS8721
+ dbg(" 10BTCR: %04x\n", pic32mz_phyread(phyaddr, MII_KS8721_10BTCR));
+#endif
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phybusywait
+ *
+ * Description:
+ * Wait until the PHY is no longer busy
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void pic32mz_phybusywait(void)
+{
+ while ((pic32mz_getreg(PIC32MZ_EMAC1_MIND) & EMAC1_MIND_MIIMBUSY) != 0);
+}
+
+/****************************************************************************
+ * Function: pic32mz_phywrite
+ *
+ * Description:
+ * Write a value to an MII PHY register
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ * regaddr - The address of the PHY register to be written
+ * phydata - The data to write to the PHY register
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static void pic32mz_phywrite(uint8_t phyaddr, uint8_t regaddr, uint16_t phydata)
+{
+ uint32_t regval;
+
+ /* Make sure that the PHY is not still busy from the last command */
+
+ pic32mz_phybusywait();
+
+ /* Set PHY address and PHY register address */
+
+ regval = ((uint32_t)phyaddr << EMAC1_MADR_PHYADDR_SHIFT) |
+ ((uint32_t)regaddr << EMAC1_MADR_REGADDR_SHIFT);
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_MADR);
+
+ /* Write the register data to the PHY */
+
+ pic32mz_putreg((uint32_t)phydata, PIC32MZ_EMAC1_MWTD);
+
+ /* Two clock cycles until busy is set from the write operation */
+
+ __asm__ __volatile__ ("nop; nop;");
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phyread
+ *
+ * Description:
+ * Read a value from an MII PHY register
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ * regaddr - The address of the PHY register to be written
+ *
+ * Returned Value:
+ * Data read from the PHY register
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static uint16_t pic32mz_phyread(uint8_t phyaddr, uint8_t regaddr)
+{
+ uint32_t regval;
+
+ /* Make sure that the PHY is not still busy from the last command */
+
+ pic32mz_phybusywait();
+
+ /* Set PHY address and PHY register address */
+
+ regval = ((uint32_t)phyaddr << EMAC1_MADR_PHYADDR_SHIFT) |
+ ((uint32_t)regaddr << EMAC1_MADR_REGADDR_SHIFT);
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_MADR);
+
+ /* Set up to read */
+
+ pic32mz_putreg(EMAC1_MCMD_READ, PIC32MZ_EMAC1_MCMD);
+
+ /* Four clock cycles until busy is set from the write operation */
+
+ __asm__ __volatile__ ("nop; nop; nop; nop;");
+
+ /* Wait for the PHY command to complete */
+
+ pic32mz_phybusywait();
+ pic32mz_putreg(0, PIC32MZ_EMAC1_MCMD);
+
+ /* Return the PHY register data */
+
+ return (uint16_t)(pic32mz_getreg(PIC32MZ_EMAC1_MRDD) & EMAC1_MRDD_MASK);
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phyreset
+ *
+ * Description:
+ * Reset the PHY
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static inline int pic32mz_phyreset(uint8_t phyaddr)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Reset the PHY. Needs a minimal 50uS delay after reset. */
+
+ pic32mz_phywrite(phyaddr, MII_MCR, MII_MCR_RESET);
+
+ /* Wait for a minimum of 50uS no matter what */
+
+ up_udelay(50);
+
+ /* The MCR reset bit is self-clearing. Wait for it to be clear indicating
+ * that the reset is complete.
+ */
+
+ for (timeout = PIC32MZ_MIITIMEOUT; timeout > 0; timeout--)
+ {
+ phyreg = pic32mz_phyread(phyaddr, MII_MCR);
+ if ((phyreg & MII_MCR_RESET) == 0)
+ {
+ return OK;
+ }
+ }
+
+ ndbg("Reset failed. MCR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phyautoneg
+ *
+ * Description:
+ * Enable auto-negotiation.
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * The adverisement regiser has already been configured.
+ *
+ ****************************************************************************/
+
+#if defined(PIC32MZ_HAVE_PHY) && defined(CONFIG_PHY_AUTONEG)
+static inline int pic32mz_phyautoneg(uint8_t phyaddr)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Start auto-negotiation */
+
+ pic32mz_phywrite(phyaddr, MII_MCR, MII_MCR_ANENABLE | MII_MCR_ANRESTART);
+
+ /* Wait for autonegotiation to complete */
+
+ for (timeout = PIC32MZ_MIITIMEOUT; timeout > 0; timeout--)
+ {
+ /* Check if auto-negotiation has completed */
+
+ phyreg = pic32mz_phyread(phyaddr, MII_MSR);
+ if ((phyreg & MII_MSR_ANEGCOMPLETE) != 0)
+ {
+ /* Yes.. return success */
+
+ return OK;
+ }
+ }
+
+ ndbg("Auto-negotiation failed. MSR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phymode
+ *
+ * Description:
+ * Set the PHY to operate at a selected speed/duplex mode.
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ * mode - speed/duplex mode
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static int pic32mz_phymode(uint8_t phyaddr, uint8_t mode)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Disable auto-negotiation and set fixed Speed and Duplex settings:
+ *
+ * MII_MCR_UNIDIR 0=Disable unidirectional enable
+ * MII_MCR_SPEED1000 0=Reserved on 10/100
+ * MII_MCR_CTST 0=Disable collision test
+ * MII_MCR_FULLDPLX ?=Full duplex
+ * MII_MCR_ANRESTART 0=Don't restart auto negotiation
+ * MII_MCR_ISOLATE 0=Don't electronically isolate PHY from MII
+ * MII_MCR_PDOWN 0=Don't powerdown the PHY
+ * MII_MCR_ANENABLE 0=Disable auto negotiation
+ * MII_MCR_SPEED100 ?=Select 100Mbps
+ * MII_MCR_LOOPBACK 0=Disable loopback mode
+ * MII_MCR_RESET 0=No PHY reset
+ */
+
+ phyreg = 0;
+ if ((mode & PIC32MZ_SPEED_MASK) == PIC32MZ_SPEED_100)
+ {
+ phyreg = MII_MCR_SPEED100;
+ }
+
+ if ((mode & PIC32MZ_DUPLEX_MASK) == PIC32MZ_DUPLEX_FULL)
+ {
+ phyreg |= MII_MCR_FULLDPLX;
+ }
+
+ pic32mz_phywrite(phyaddr, MII_MCR, phyreg);
+
+ /* Then wait for the link to be established */
+
+ for (timeout = PIC32MZ_MIITIMEOUT; timeout > 0; timeout--)
+ {
+#ifdef CONFIG_ETH0_PHY_DP83848C
+ phyreg = pic32mz_phyread(phyaddr, MII_DP83848C_STS);
+ if ((phyreg & 0x0001) != 0)
+ {
+ /* Yes.. return success */
+
+ return OK;
+ }
+#else
+ phyreg = pic32mz_phyread(phyaddr, MII_MSR);
+ if ((phyreg & MII_MSR_LINKSTATUS) != 0)
+ {
+ /* Yes.. return success */
+
+ return OK;
+ }
+#endif
+ }
+
+ ndbg("Link failed. MSR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_phyinit
+ *
+ * Description:
+ * Initialize the PHY
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None directly. As a side-effect, it will initialize priv->pd_phyaddr
+ * and priv->pd_phymode.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static inline int pic32mz_phyinit(struct pic32mz_driver_s *priv)
+{
+ unsigned int phyaddr;
+ uint16_t phyreg;
+ uint32_t regval;
+ int ret;
+
+#if CONFIG_PIC32MZ_FMIIEN == 0
+ /* Set the RMII operation mode. This usually requires access to a vendor
+ * specific control register.
+ */
+
+#ifdef CONFIG_ETH0_PHY_DP83848C
+ /* The RMII/MII of operation can be selected by strap options or register
+ * control (using the RBR register). For RMII mode, it is required to use the
+ * strap option, since it requires a 50 MHz clock instead of the normal 25 MHz.
+ */
+#endif
+
+#else
+ /* Set the MII/ operation mode. This usually requires access to a vendor-
+ * specific control register.
+ */
+
+#ifdef CONFIG_ETH0_PHY_DP83848C
+# warning "Missing logic"
+#endif
+
+#endif
+
+ /* Find PHY Address. Because the controller has a pull-up and the
+ * PHY has pull-down resistors on RXD lines some times the PHY
+ * latches different at different addresses.
+ */
+
+ for (phyaddr = 0; phyaddr < 32; phyaddr++)
+ {
+ /* Clear any ongoing PHY command bits */
+
+ pic32mz_putreg(0, PIC32MZ_EMAC1_MCMD);
+
+ /* Reset the PHY (use Control Register 0). */
+
+ ret = pic32mz_phyreset(phyaddr);
+ if (ret < 0)
+ {
+ ndbg("Failed to reset PHY at address %d\n", phyaddr);
+ continue;
+ }
+
+ /* Set the normal, swapped or auto (preferred) MDIX. This usually
+ * requires access to a vendor-specific control register.
+ */
+
+ /* Check if we can see the selected device ID at this
+ * PHY address.
+ */
+
+ phyreg = (unsigned int)pic32mz_phyread(phyaddr, MII_PHYID1);
+ nvdbg("Addr: %d PHY ID1: %04x\n", phyaddr, phyreg);
+
+ if (phyreg == PIC32MZ_PHYID1)
+ {
+ phyreg = pic32mz_phyread(phyaddr, MII_PHYID2);
+ nvdbg("Addr: %d PHY ID2: %04x\n", phyaddr, phyreg);
+
+ if (phyreg == PIC32MZ_PHYID2)
+ {
+ break;
+ }
+ }
+ }
+
+ /* Check if the PHY device address was found */
+
+ if (phyaddr > 31)
+ {
+ /* Failed to find PHY at any location */
+
+ ndbg("No PHY detected\n");
+ return -ENODEV;
+ }
+ nvdbg("phyaddr: %d\n", phyaddr);
+
+ /* Save the discovered PHY device address */
+
+ priv->pd_phyaddr = phyaddr;
+
+ /* Reset the PHY */
+
+ ret = pic32mz_phyreset(phyaddr);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ pic32mz_showmii(phyaddr, "After reset");
+
+ /* Set the MII/RMII operation mode. This usually requires access to a
+ * vendor-specific control register.
+ */
+
+ /* Set the normal, swapped or auto (preferred) MDIX. This usually requires
+ * access to a vendor-specific control register.
+ */
+
+ /* Check the PHY capabilities by investigating the Status Register 1. */
+
+ /* Check for preamble suppression support */
+
+ phyreg = pic32mz_phyread(phyaddr, MII_MSR);
+ if ((phyreg & MII_MSR_MFRAMESUPPRESS) != 0)
+ {
+ /* The PHY supports preamble suppression */
+
+ regval = pic32mz_getreg(PIC32MZ_EMAC1_MCFG);
+ regval |= EMAC1_MCFG_NOPRE;
+ pic32mz_putreg(regval, PIC32MZ_EMAC1_MCFG);
+ }
+
+ /* Are we configured to do auto-negotiation?
+ *
+ * Preferably the auto-negotiation should be selected if the PHY supports
+ * it. Expose the supported capabilities: Half/Full Duplex, 10BaseT/100Base
+ * TX, etc. (Extended Register 4). Start the negotiation (Control Register
+ * 0) and wait for the negotiation complete and get the link partner
+ * capabilities (Extended Register 5) and negotiation result (vendor-
+ * specific register).
+ */
+
+#ifdef CONFIG_PHY_AUTONEG
+ /* Setup the Auto-negotiation advertisement: 100 or 10, and HD or FD */
+
+ pic32mz_phywrite(phyaddr, MII_ADVERTISE,
+ (MII_ADVERTISE_100BASETXFULL | MII_ADVERTISE_100BASETXHALF |
+ MII_ADVERTISE_10BASETXFULL | MII_ADVERTISE_10BASETXHALF |
+ MII_ADVERTISE_CSMA));
+
+ /* Then perform the auto-negotiation */
+
+ ret = pic32mz_phyautoneg(phyaddr);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#else
+ /* Set up the fixed PHY configuration
+ *
+ * If auto-negotiation is not supported/selected, update the PHY Duplex and
+ * Speed settings directly (use Control Register 0 and possibly some vendor-
+ * pecific registers).
+ */
+
+ ret = pic32mz_phymode(phyaddr, PIC32MZ_MODE_DEFLT);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
+ /* The link is established */
+
+ pic32mz_showmii(phyaddr, "After link established");
+
+ /* Check configuration */
+
+#if defined(CONFIG_ETH0_PHY_KS8721)
+ phyreg = pic32mz_phyread(phyaddr, MII_KS8721_10BTCR);
+
+ switch (phyreg & KS8721_10BTCR_MODE_MASK)
+ {
+ case KS8721_10BTCR_MODE_10BTHD: /* 10BASE-T half duplex */
+ priv->pd_mode = PIC32MZ_10BASET_HD;
+ break;
+ case KS8721_10BTCR_MODE_100BTHD: /* 100BASE-T half duplex */
+ priv->pd_mode = PIC32MZ_100BASET_HD;
+ break;
+ case KS8721_10BTCR_MODE_10BTFD: /* 10BASE-T full duplex */
+ priv->pd_mode = PIC32MZ_10BASET_FD;
+ break;
+ case KS8721_10BTCR_MODE_100BTFD: /* 100BASE-T full duplex */
+ priv->pd_mode = PIC32MZ_100BASET_FD;
+ break;
+ default:
+ ndbg("Unrecognized mode: %04x\n", phyreg);
+ return -ENODEV;
+ }
+#elif defined(CONFIG_ETH0_PHY_DP83848C)
+ phyreg = pic32mz_phyread(phyaddr, MII_DP83848C_STS);
+
+ /* Configure for full/half duplex mode and speed */
+
+ switch (phyreg & 0x0006)
+ {
+ case 0x0000:
+ priv->pd_mode = PIC32MZ_100BASET_HD;
+ break;
+ case 0x0002:
+ priv->pd_mode = PIC32MZ_10BASET_HD;
+ break;
+ case 0x0004:
+ priv->pd_mode = PIC32MZ_100BASET_FD;
+ break;
+ case 0x0006:
+ priv->pd_mode = PIC32MZ_10BASET_FD;
+ break;
+ default:
+ ndbg("Unrecognized mode: %04x\n", phyreg);
+ return -ENODEV;
+ }
+#elif defined(CONFIG_ETH0_PHY_LAN8720)
+ {
+ uint16_t advertise;
+ uint16_t lpa;
+
+ up_udelay(500);
+ advertise = pic32mz_phyread(phyaddr, MII_ADVERTISE);
+ lpa = pic32mz_phyread(phyaddr, MII_LPA);
+
+ /* Check for 100BASETX full duplex */
+
+ if ((advertise & MII_ADVERTISE_100BASETXFULL) != 0 &&
+ (lpa & MII_LPA_100BASETXFULL) != 0)
+ {
+ priv->pd_mode = PIC32MZ_100BASET_FD;
+ }
+
+ /* Check for 100BASETX half duplex */
+
+ else if ((advertise & MII_ADVERTISE_100BASETXHALF) != 0 &&
+ (lpa & MII_LPA_100BASETXHALF) != 0)
+ {
+ priv->pd_mode = PIC32MZ_100BASET_HD;
+ }
+
+ /* Check for 10BASETX full duplex */
+
+ else if ((advertise & MII_ADVERTISE_10BASETXFULL) != 0 &&
+ (lpa & MII_LPA_10BASETXFULL) != 0)
+ {
+ priv->pd_mode = PIC32MZ_10BASET_FD;
+ }
+
+ /* Check for 10BASETX half duplex */
+
+ else if ((advertise & MII_ADVERTISE_10BASETXHALF) != 0 &&
+ (lpa & MII_LPA_10BASETXHALF) != 0)
+ {
+ priv->pd_mode = PIC32MZ_10BASET_HD;
+ }
+ else
+ {
+ ndbg("Unrecognized mode: %04x\n", phyreg);
+ return -ENODEV;
+ }
+ }
+#else
+# warning "PHY Unknown: speed and duplex are bogus"
+#endif
+
+ ndbg("%dBase-T %s duplex\n",
+ (priv->pd_mode & PIC32MZ_SPEED_MASK) == PIC32MZ_SPEED_100 ? 100 : 10,
+ (priv->pd_mode & PIC32MZ_DUPLEX_MASK) == PIC32MZ_DUPLEX_FULL ?"full" : "half");
+
+ /* Disable auto-configuration. Set the fixed speed/duplex mode.
+ * (probably more than little redundant).
+ */
+
+ ret = pic32mz_phymode(phyaddr, priv->pd_mode);
+ pic32mz_showmii(phyaddr, "After final configuration");
+ return ret;
+}
+#else
+static inline int pic32mz_phyinit(struct pic32mz_driver_s *priv)
+{
+ priv->pd_mode = PIC32MZ_MODE_DEFLT;
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_macmode
+ *
+ * Description:
+ * Set the MAC to operate at a selected speed/duplex mode.
+ *
+ * Parameters:
+ * mode - speed/duplex mode
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef PIC32MZ_HAVE_PHY
+static void pic32mz_macmode(uint8_t mode)
+{
+ /* Set up for full or half duplex operation */
+
+ if ((mode & PIC32MZ_DUPLEX_MASK) == PIC32MZ_DUPLEX_FULL)
+ {
+ /* Set the back-to-back inter-packet gap */
+
+ pic32mz_putreg(21, PIC32MZ_EMAC1_IPGT);
+
+ /* Set MAC to operate in full duplex mode with CRC and Pad enabled */
+
+ pic32mz_putreg((EMAC1_CFG2_FULLDPLX | EMAC1_CFG2_CRCEN | EMAC1_CFG2_PADCRCEN),
+ PIC32MZ_EMAC1_CFG2SET);
+ }
+ else
+ {
+ /* Set the back-to-back inter-packet gap */
+
+ pic32mz_putreg(18, PIC32MZ_EMAC1_IPGT);
+
+ /* Set MAC to operate in half duplex mode with CRC and Pad enabled */
+
+ pic32mz_putreg(EMAC1_CFG2_FULLDPLX, PIC32MZ_EMAC1_CFG2CLR);
+ pic32mz_putreg((EMAC1_CFG2_CRCEN | EMAC1_CFG2_PADCRCEN), PIC32MZ_EMAC1_CFG2SET);
+ }
+
+ /* Set the RMII MAC speed. */
+
+#if CONFIG_PIC32MZ_FMIIEN == 0
+ if ((mode & PIC32MZ_SPEED_MASK) == PIC32MZ_SPEED_100)
+ {
+ pic32mz_putreg(EMAC1_SUPP_SPEEDRMII, PIC32MZ_EMAC1_SUPPSET);
+ }
+ else
+ {
+ pic32mz_putreg(EMAC1_SUPP_SPEEDRMII, PIC32MZ_EMAC1_SUPPCLR);
+ }
+#endif
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mz_ethreset
+ *
+ * Description:
+ * Configure and reset the Ethernet module, leaving it in a disabled state.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void pic32mz_ethreset(struct pic32mz_driver_s *priv)
+{
+ irqstate_t flags;
+
+ /* Reset the MAC */
+
+ flags = irqsave();
+
+ /* Ethernet Controller Initialization *************************************/
+ /* Disable Ethernet interrupts in the EVIC */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ up_disable_irq(priv->pd_irqsrc);
+#else
+ up_disable_irq(PIC32MZ_IRQSRC_ETH);
+#endif
+
+ /* Turn the Ethernet Controller off: Clear the ON, RXEN and TXRTS bits */
+
+ pic32mz_putreg(ETH_CON1_RXEN | ETH_CON1_TXRTS | ETH_CON1_ON, PIC32MZ_ETH_CON1CLR);
+
+ /* Wait activity abort by polling the ETHBUSY bit */
+
+ while ((pic32mz_getreg(PIC32MZ_ETH_STAT) & ETH_STAT_ETHBUSY) != 0);
+
+ /* Turn the Ethernet controller on. */
+
+ pic32mz_putreg(ETH_CON1_ON, PIC32MZ_ETH_CON1SET);
+
+ /* Clear the Ethernet STAT BUFCNT */
+
+ while ((pic32mz_getreg(PIC32MZ_ETH_STAT) & ETH_STAT_BUFCNT_MASK) != 0)
+ {
+ pic32mz_putreg(ETH_CON1_BUFCDEC, PIC32MZ_ETH_CON1SET);
+ }
+
+ /* Clear the Ethernet Interrupt Flag (ETHIF) bit in the Interrupts module */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ up_pending_irq(priv->pd_irqsrc);
+#else
+ up_pending_irq(PIC32MZ_IRQSRC_ETH);
+#endif
+
+ /* Disable any Ethernet Controller interrupt generation by clearing the IEN
+ * register.
+ */
+
+ pic32mz_putreg(ETH_INT_ALLINTS, PIC32MZ_ETH_IENCLR);
+
+ /* Clear the TX and RX start addresses by using ETHTXSTCLR and ETHRXSTCLR */
+
+ pic32mz_putreg(0xffffffff, PIC32MZ_ETH_TXSTCLR);
+ pic32mz_putreg(0xffffffff, PIC32MZ_ETH_RXSTCLR);
+
+ /* MAC Initialization *****************************************************/
+ /* Put the MAC into the reset state */
+
+ pic32mz_putreg((EMAC1_CFG1_TXRST | EMAC1_CFG1_MCSTXRST | EMAC1_CFG1_RXRST |
+ EMAC1_CFG1_MCSRXRST | EMAC1_CFG1_SIMRST | EMAC1_CFG1_SOFTRST),
+ PIC32MZ_EMAC1_CFG1);
+
+ /* Take the MAC out of the reset state */
+
+ up_udelay(50);
+ pic32mz_putreg(0, PIC32MZ_EMAC1_CFG1);
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: pic32mz_ethinitialize
+ *
+ * Description:
+ * Initialize one Ethernet controller and driver structure.
+ *
+ * Parameters:
+ * intf - Selects the interface to be initialized.
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+int pic32mz_ethinitialize(int intf)
+#else
+static inline int pic32mz_ethinitialize(int intf)
+#endif
+{
+ struct pic32mz_driver_s *priv;
+ int ret;
+
+ DEBUGASSERT(intf < CONFIG_PIC32MZ_NINTERFACES);
+ priv = &g_ethdrvr[intf];
+
+ /* Initialize the driver structure */
+
+ memset(priv, 0, sizeof(struct pic32mz_driver_s));
+ priv->pd_dev.d_ifup = pic32mz_ifup; /* I/F down callback */
+ priv->pd_dev.d_ifdown = pic32mz_ifdown; /* I/F up (new IP address) callback */
+ priv->pd_dev.d_txavail = pic32mz_txavail; /* New TX data callback */
+#ifdef CONFIG_NET_IGMP
+ priv->pd_dev.d_addmac = pic32mz_addmac; /* Add multicast MAC address */
+ priv->pd_dev.d_rmmac = pic32mz_rmmac; /* Remove multicast MAC address */
+#endif
+ priv->pd_dev.d_private = (void*)priv; /* Used to recover private state from dev */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+# error "A mechanism to associate base address an IRQ with an interface is needed"
+ priv->pd_base = ??; /* Ethernet controller base address */
+ priv->pd_irq = ??; /* Ethernet controller IRQ vector number */
+ priv->pd_irqsrc = ??; /* Ethernet controller IRQ source number */
+#endif
+
+ /* Create a watchdog for timing polling for and timing of transmisstions */
+
+ priv->pd_txpoll = wd_create(); /* Create periodic poll timer */
+ priv->pd_txtimeout = wd_create(); /* Create TX timeout timer */
+
+ /* Configure Ethernet peripheral pin selections */
+ /* Controlled by DEVCFG FMIIEN and FETHIO settings */
+
+ /* Reset the Ethernet controller and leave in the ifdown state. The
+ * Ethernet controller will be properly re-initialized each time
+ * pic32mz_ifup() is called.
+ */
+
+ pic32mz_ifdown(&priv->pd_dev);
+
+ /* Attach the IRQ to the driver */
+
+#if CONFIG_PIC32MZ_NINTERFACES > 1
+ ret = irq_attach(priv->pd_irq, pic32mz_interrupt);
+#else
+ ret = irq_attach(PIC32MZ_IRQ_ETH, pic32mz_interrupt);
+#endif
+ if (ret != 0)
+ {
+ /* We could not attach the ISR to the interrupt */
+
+ return -EAGAIN;
+ }
+
+ /* Register the device with the OS so that socket IOCTLs can be performed */
+
+ (void)netdev_register(&priv->pd_dev, NET_LL_ETHERNET);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_netinitialize
+ *
+ * Description:
+ * Initialize the first network interface. If there are more than one
+ * interface in the chip, then board-specific logic will have to provide
+ * this function to determine which, if any, Ethernet controllers should
+ * be initialized.
+ *
+ ****************************************************************************/
+
+#if CONFIG_PIC32MZ_NINTERFACES == 1
+void up_netinitialize(void)
+{
+ (void)pic32mz_ethinitialize(0);
+}
+#endif
+#endif /* CHIP_NETHERNET > 0 */
+#endif /* CONFIG_NET && CONFIG_PIC32MZ_ETHERNET */