summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-04-27 03:52:56 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-04-27 03:52:56 +0000
commita93a76bd76b69717c5adc252665bcfde94a0436f (patch)
treeab5d407c7f4ba82c34e92ade00bc0cf2339550be /nuttx
parentf4a23d64426f170d5e932aa3c30564c36a27258e (diff)
downloadpx4-nuttx-a93a76bd76b69717c5adc252665bcfde94a0436f.tar.gz
px4-nuttx-a93a76bd76b69717c5adc252665bcfde94a0436f.tar.bz2
px4-nuttx-a93a76bd76b69717c5adc252665bcfde94a0436f.zip
Big time name changes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2634 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/drivers/net/enc28j60.c90
-rwxr-xr-xnuttx/drivers/net/enc28j60.h256
2 files changed, 175 insertions, 171 deletions
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 24aa884b2..5f439b352 100755
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -104,23 +104,23 @@
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
-#define ENC28J60_WDDELAY (1*CLK_TCK)
-#define ENC28J60_POLLHSEC (1*2)
+#define ENC_WDDELAY (1*CLK_TCK)
+#define ENC_POLLHSEC (1*2)
/* TX timeout = 1 minute */
-#define ENC28J60_TXTIMEOUT (60*CLK_TCK)
+#define ENC_TXTIMEOUT (60*CLK_TCK)
/* Misc. Helper Macros ******************************************************/
#define enc_rdgreg(priv,ctrlreg) \
- enc_rdgreg2(priv, ENC28J60_RCR | GETADDR(ctrlreg))
+ enc_rdgreg2(priv, ENC_RCR | GETADDR(ctrlreg))
#define enc_wdgreg(priv,ctrlreg,wrdata) \
- enc_wdgreg2(priv, ENC28J60_WCR | GETADDR(ctrlreg), wrdata)
-#define enc_clrglobal(priv,ctrlreg,clrbits) \
- enc_wdgreg2(priv, ENC28J60_BFC | GETADDR(ctrlreg), clrbits)
-#define enc_setglobal(priv,ctrlreg,setbits) \
- enc_wdgreg2(priv, ENC28J60_BFS | GETADDR(ctrlreg), setbits)
+ enc_wdgreg2(priv, ENC_WCR | GETADDR(ctrlreg), wrdata)
+#define enc_bfcgreg(priv,ctrlreg,clrbits) \
+ enc_wdgreg2(priv, ENC_BFC | GETADDR(ctrlreg), clrbits)
+#define enc_bfsgreg(priv,ctrlreg,setbits) \
+ enc_wdgreg2(priv, ENC_BFS | GETADDR(ctrlreg), setbits)
/* This is a helper pointer for accessing the contents of the Ethernet header */
@@ -418,13 +418,13 @@ static void enc_setbank(FAR struct enc_driver_s *priv, uint8_t bank)
{
/* Select bank 0 (just so that all of the bits are cleared) */
- enc_clrglobal(priv, ECON1, ECON1_BSEL_MASK);
+ enc_bfcgreg(priv, ENC_ECON1, ECON1_BSEL_MASK);
/* Then OR in bits to get the correct bank */
if (bank != 0)
{
- enc_setglobal(priv, ECON1, (bank << ECON1_BSEL_SHIFT));
+ enc_bfsgreg(priv, ENC_ECON1, (bank << ECON1_BSEL_SHIFT));
}
/* Then remember the bank setting */
@@ -459,7 +459,7 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
/* Send the read command and collect the return data. */
- rddata = SPI_SEND(spi, ENC28J60_RCR | GETADDR(ctrlreg));
+ rddata = SPI_SEND(spi, ENC_RCR | GETADDR(ctrlreg));
/* De-select ENC28J60 chip */
@@ -495,7 +495,7 @@ static uint8_t enc_rdphymac(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
/* Send the read command (discarding the return data) */
- (void)SPI_SEND(spi, ENC28J60_RCR | GETADDR(ctrlreg));
+ (void)SPI_SEND(spi, ENC_RCR | GETADDR(ctrlreg));
/* Do an extra transfer to get the data from the MAC or PHY */
@@ -533,7 +533,7 @@ static void enc_rwrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
/* Send the write command */
- (void)SPI_SEND(spi, ENC28J60_WCR | GETADDR(ctrlreg));
+ (void)SPI_SEND(spi, ENC_WCR | GETADDR(ctrlreg));
/* Send the data byte */
@@ -566,7 +566,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
/* Send the read buffer memory command (ignoring the response) */
- (void)SPI_SEND(spi, ENC28J60_RBM);
+ (void)SPI_SEND(spi, ENC_RBM);
/* Then read the buffer data */
@@ -599,7 +599,7 @@ static void enc_wrbuffer(FAR struct enc_driver_s *priv,
/* Send the write buffer memory command (ignoring the response) */
- (void)SPI_SEND(spi, ENC28J60_WBM);
+ (void)SPI_SEND(spi, ENC_WBM);
/* Then send the buffer */
@@ -641,7 +641,7 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
/* Setup the TX timeout watchdog (perhaps restarting the timer) */
- (void)wd_start(priv->txtimeout, ENC28J60_TXTIMEOUT, enc_txtimeout, 1, (uint32_t)priv);
+ (void)wd_start(priv->txtimeout, ENC_TXTIMEOUT, enc_txtimeout, 1, (uint32_t)priv);
return OK;
}
@@ -728,7 +728,7 @@ static void enc_txif(FAR struct enc_driver_s *priv)
#ifdef CONFIG_ENC28J60_STATS
priv->txifs++;
- if (enc_rdgreg(priv, ESTAT) & ESTAT_TXABRT)
+ if (enc_rdgreg(priv, ENC_ESTAT) & ESTAT_TXABRT)
{
priv->txabrts++;
}
@@ -736,7 +736,7 @@ static void enc_txif(FAR struct enc_driver_s *priv)
/* Clear the request to send bit */
- enc_clrglobal(priv, ECON1, ECON1_TXRTS);
+ enc_bfcgreg(priv, ENC_ECON1, ECON1_TXRTS);
/* If no further xmits are pending, then cancel the TX timeout */
@@ -771,16 +771,20 @@ static void enc_txerif(FAR struct enc_driver_s *priv)
priv->txerifs++;
#endif
- /* Here we really should read the TSV and determine if we should re-transmit
- * the packet by resetting TXRTS... maybe someday.
- */
-
- enc_clrglobal(priv, ECON1, ECON1_TXRTS);
-
/* Reset TX */
- enc_setglobal(priv, ECON1, ECON1_TXRST);
- enc_clrglobal(priv, ECON1, ECON1_TXRST);
+ enc_bfsgreg(priv, ENC_ECON1, ECON1_TXRST);
+ enc_bfcgreg(priv, ENC_ECON1, ECON1_TXRST | ECON1_TXRTS);
+
+ /* Here we really should re-transmit:
+ *
+ * 1. Read the TSV:
+ * - Read ETXNDL to get the end pointer
+ * - Read 7 bytes from that pointer + 1 using ENC_RMB.
+ * 2. Determine if we need to retransmit. Check the LATE COLLISION bit, if
+ * set, then we need to transmit.
+ * 3. Retranmit by resetting ECON1_TXRTS.
+ */
}
/****************************************************************************
@@ -900,14 +904,14 @@ static void enc_worker(FAR void *arg)
/* Disable further interrupts by clearing the global interrup enable bit */
- enc_clrglobal(priv, EIE, EIE_INTIE);
+ enc_bfcgreg(priv, ENC_EIE, EIE_INTIE);
/* Loop until all interrupts have been processed (EIR==0). Note that
* there is no infinite loop check... if there are always pending interrupts,
* we are just broken.
*/
- while ((eir = enc_rdgreg(priv, EIR) & EIR_ALLINTS) != 0)
+ while ((eir = enc_rdgreg(priv, ENC_EIR) & EIR_ALLINTS) != 0)
{
/* Handle interrupts according to interrupt register register bit
* settings
@@ -923,7 +927,7 @@ static void enc_worker(FAR void *arg)
{
/* Not used by this driver. Just clear the interrupt request. */
- enc_clrglobal(priv, EIR, EIR_DMAIF);
+ enc_bfcgreg(priv, ENC_EIR, EIR_DMAIF);
}
/* LINKIF: The LINKIF indicates that the link status has changed.
@@ -944,8 +948,8 @@ static void enc_worker(FAR void *arg)
if ((eir & EIR_LINKIF) != 0) /* Link change interrupt */
{
- enc_linkstatus(priv); /* Get current link status */
- enc_rdphy(priv, PHIR); /* Clear the LINKIF interrupt */
+ enc_linkstatus(priv); /* Get current link status */
+ enc_rdphy(priv, ENC_PHIR); /* Clear the LINKIF interrupt */
}
/* TXIF: The Transmit Interrupt Flag (TXIF) is used to indicate that
@@ -960,8 +964,8 @@ static void enc_worker(FAR void *arg)
if ((eir & EIR_TXIF) != 0) /* Transmit interrupt */
{
- enc_txif(priv); /* Handle TX completion */
- enc_clrglobal(priv, EIR, EIR_TXIF); /* Clear the TXIF interrupt */
+ enc_txif(priv); /* Handle TX completion */
+ enc_bfcgreg(priv, ENC_EIR, EIR_TXIF); /* Clear the TXIF interrupt */
}
/* TXERIF: The Transmit Error Interrupt Flag (TXERIF) is used to
@@ -1005,8 +1009,8 @@ static void enc_worker(FAR void *arg)
if ((eir & EIR_TXERIF) != 0) /* Transmit Error Interrupts */
{
- enc_txerif(priv); /* Handle the TX error */
- enc_clrglobal(priv, EIR, EIR_TXERIF); /* Clear the TXERIF interrupt */
+ enc_txerif(priv); /* Handle the TX error */
+ enc_bfcgreg(priv, ENC_EIR, EIR_TXERIF); /* Clear the TXERIF interrupt */
}
/* PKTIF The Receive Packet Pending Interrupt Flag (PKTIF) is used to
@@ -1026,7 +1030,7 @@ static void enc_worker(FAR void *arg)
/* Ignore PKTIF because is unreliable. Use EPKTCNT instead */
/* if ((eir & EIR_PKTIF) != 0) */
{
- uint8_t pktcnt = enc_rdbreg(priv, EPKTCNT);
+ uint8_t pktcnt = enc_rdbreg(priv, ENC_EPKTCNT);
if (pktcnt > 0)
{
#ifdef CONFIG_ENC28J60_STATS
@@ -1063,8 +1067,8 @@ static void enc_worker(FAR void *arg)
if ((eir & EIR_RXERIF) != 0) /* Receive Errror Interrupts */
{
- enc_rxerif(priv); /* Handle the RX error */
- enc_clrglobal(priv, EIR, EIR_RXERIF); /* Clear the RXERIF interrupt */
+ enc_rxerif(priv); /* Handle the RX error */
+ enc_bfcgreg(priv, ENC_EIR, EIR_RXERIF); /* Clear the RXERIF interrupt */
}
}
@@ -1073,7 +1077,7 @@ static void enc_worker(FAR void *arg)
* there are no pending transmissions.
*/
- enc_setglobal(priv, EIE, EIE_INTIE);
+ enc_bfsgreg(priv, ENC_EIE, EIE_INTIE);
}
/****************************************************************************
@@ -1175,11 +1179,11 @@ static void enc_polltimer(int argc, uint32_t arg, ...)
/* If so, update TCP timing states and poll uIP for new XMIT data */
- (void)uip_timer(&priv->dev, enc_uiptxpoll, ENC28J60_POLLHSEC);
+ (void)uip_timer(&priv->dev, enc_uiptxpoll, ENC_POLLHSEC);
/* Setup the watchdog poll timer again */
- (void)wd_start(priv->txpoll, ENC28J60_WDDELAY, enc_polltimer, 1, arg);
+ (void)wd_start(priv->txpoll, ENC_WDDELAY, enc_polltimer, 1, arg);
}
/****************************************************************************
@@ -1211,7 +1215,7 @@ static int enc_ifup(struct uip_driver_s *dev)
/* Set and activate a timer process */
- (void)wd_start(priv->txpoll, ENC28J60_WDDELAY, enc_polltimer, 1, (uint32_t)priv);
+ (void)wd_start(priv->txpoll, ENC_WDDELAY, enc_polltimer, 1, (uint32_t)priv);
/* Enable the Ethernet interrupt */
diff --git a/nuttx/drivers/net/enc28j60.h b/nuttx/drivers/net/enc28j60.h
index b160f4b49..f0e00687a 100755
--- a/nuttx/drivers/net/enc28j60.h
+++ b/nuttx/drivers/net/enc28j60.h
@@ -55,19 +55,19 @@
* dddddddd is one or more bytes of data that may accompany the command.
*/
-#define ENC28J60_RCR (0x00) /* Read Control Register
+#define ENC_RCR (0x00) /* Read Control Register
* 000 | aaaaa | (Registe value returned)) */
-#define ENC28J60_RBM (0x3a) /* Read Buffer Memory
+#define ENC_RBM (0x3a) /* Read Buffer Memory
* 001 | 11010 | (Read buffer data follows) */
-#define ENC28J60_WCR (0x40) /* Write Control Register
+#define ENC_WCR (0x40) /* Write Control Register
* 010 | aaaaa | dddddddd */
-#define ENC28J60_WBM (0x7a) /* Write Buffer Memory
+#define ENC_WBM (0x7a) /* Write Buffer Memory
* 011 | 11010 | (Write buffer data follows) */
-#define ENC28J60_BFS (0x80) /* Bit Field Set
+#define ENC_BFS (0x80) /* Bit Field Set
* 100 | aaaaa | dddddddd */
-#define ENC28J60_BFC (0xa0) /* Bit Field Clear
+#define ENC_BFC (0xa0) /* Bit Field Clear
* 101 | aaaaa | dddddddd */
-#define ENC28J60_SRC (0xff) /* System Reset
+#define ENC_SRC (0xff) /* System Reset
* 111 | 11111 | (No data) */
/* Global Control Registers *************************************************/
@@ -87,11 +87,11 @@
* registers prefixed with MI belong to the MII group.
*/
-#define EIE (0x1b) /* Ethernet Interrupt Enable Register */
-#define EIR (0x1c) /* Ethernet Interupt Request Register */
-#define ESTAT (0x1d) /* Ethernet Status Register */
-#define ECON2 (0x1e) /* Ethernet Control 2 Register */
-#define ECON1 (0x1f) /* Ethernet Control 1 Register */
+#define ENC_EIE (0x1b) /* Ethernet Interrupt Enable Register */
+#define ENC_EIR (0x1c) /* Ethernet Interupt Request Register */
+#define ENC_ESTAT (0x1d) /* Ethernet Status Register */
+#define ENC_ECON2 (0x1e) /* Ethernet Control 2 Register */
+#define ENC_ECON1 (0x1f) /* Ethernet Control 1 Register */
/* Ethernet Interrupt Enable Register Bit Definitions */
@@ -156,135 +156,135 @@
* address together to keep the design simpler.
*/
-#define ENC28J60_ADDR_SHIFT (0) /* Bits 0-4: Register address */
-#define ENC28J60_ADDR_MASK (0x1f << ENC28J60_ADDR_SHIFT)
-#define ENC28J60_BANK_SHIFT (5) /* Bits 5-6: Bank number */
-#define ENC28J60_BANK_MASK (3 << ENC28J60_BSEL_SHIFT)
-# define ENC28J60_BANK0 (0 << ENC28J60_BSEL_SHIFT)
-# define ENC28J60_BANK1 (1 << ENC28J60_BSEL_SHIFT)
-# define ENC28J60_BANK2 (2 << ENC28J60_BSEL_SHIFT)
-# define ENC28J60_BANK3 (3 << ENC28J60_BSEL_SHIFT)
+#define ENC_ADDR_SHIFT (0) /* Bits 0-4: Register address */
+#define ENC_ADDR_MASK (0x1f << ENC_ADDR_SHIFT)
+#define ENC_BANK_SHIFT (5) /* Bits 5-6: Bank number */
+#define ENC_BANK_MASK (3 << ENC_BSEL_SHIFT)
+# define ENC_BANK0 (0 << ENC_BSEL_SHIFT)
+# define ENC_BANK1 (1 << ENC_BSEL_SHIFT)
+# define ENC_BANK2 (2 << ENC_BSEL_SHIFT)
+# define ENC_BANK3 (3 << ENC_BSEL_SHIFT)
-#define REGADDR(a,b) ((b) << ENC28J60_BANK_SHIFT | (a))
-#define GETADDR(a) ((a) & ENC28J60_ADDR_MASK)
-#define GETBANK(a) (((a) >> ENC28J60_BANK_SHIFT) & 3)
+#define REGADDR(a,b) ((b) << ENC_BANK_SHIFT | (a))
+#define GETADDR(a) ((a) & ENC_ADDR_MASK)
+#define GETBANK(a) (((a) >> ENC_BANK_SHIFT) & 3)
/* Bank 0 Control Register Addresses */
-#define ERDPTL REGADDR(0x00, 0) /* Read Pointer Low Byte (ERDPT<7:0> */
-#define ERDPTH REGADDR(0x01, 0) /* Read Pointer High Byte (ERDPT<12:8>) */
-#define EWRPTL REGADDR(0x02, 0) /* Write Pointer Low Byte (EWRPT<7:0>) */
-#define EWRPTH REGADDR(0x03, 0) /* Write Pointer High Byte (EWRPT<12:8>) */
-#define ETXSTL REGADDR(0x04, 0) /* TX Start Low Byte (ETXST<7:0>) */
-#define ETXSTH REGADDR(0x05, 0) /* TX Start High Byte (ETXST<12:8>) */
-#define ETXNDL REGADDR(0x06, 0) /* TX End Low Byte (ETXND<7:0>) */
-#define ETXNDH REGADDR(0x07, 0) /* TX End High Byte (ETXND<12:8>) */
-#define ERXSTL REGADDR(0x08, 0) /* RX Start Low Byte (ERXST<7:0>) */
-#define ERXSTH REGADDR(0x09, 0) /* RX Start High Byte (ERXST<12:8>) */
-#define ERXNDL REGADDR(0x0a, 0) /* RX End Low Byte (ERXND<7:0>) */
-#define ERXNDH REGADDR(0x0b, 0) /* RX End High Byte (ERXND<12:8>) */
-#define ERXRDPTL REGADDR(0x0c, 0) /* RX RD Pointer Low Byte (ERXRDPT<7:0>) */
-#define ERXRDPTH REGADDR(0x0d, 0) /* RX RD Pointer High Byte (ERXRDPT<12:8>) */
-#define ERXWRPTL REGADDR(0x0e, 0) /* RX WR Pointer Low Byte (ERXWRPT<7:0>) */
-#define ERXWRPTH REGADDR(0x0f, 0) /* RX WR Pointer High Byte (ERXWRPT<12:8>) */
-#define EDMASTL REGADDR(0x10, 0) /* DMA Start Low Byte (EDMAST<7:0>) */
-#define EDMASTH REGADDR(0x11, 0) /* DMA Start High Byte (EDMAST<12:8>) */
-#define EDMANDL REGADDR(0x12, 0) /* DMA End Low Byte (EDMAND<7:0>) */
-#define EDMANDH REGADDR(0x13, 0) /* DMA End High Byte (EDMAND<12:8>) */
-#define EDMADSTL REGADDR(0x14, 0) /* DMA Destination Low Byte (EDMADST<7:0>) */
-#define EDMADSTH REGADDR(0x15, 0) /* DMA Destination High Byte (EDMADST<12:8>) */
-#define EDMACSL REGADDR(0x16, 0) /* DMA Checksum Low Byte (EDMACS<7:0>) */
-#define EDMACSH REGADDR(0x17, 0) /* DMA Checksum High Byte (EDMACS<15:8>) */
- /* 0x18-0x1a: Reserved */
- /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
+#define ENC_ERDPTL REGADDR(0x00, 0) /* Read Pointer Low Byte (ERDPT<7:0> */
+#define ENC_ERDPTH REGADDR(0x01, 0) /* Read Pointer High Byte (ERDPT<12:8>) */
+#define ENC_EWRPTL REGADDR(0x02, 0) /* Write Pointer Low Byte (EWRPT<7:0>) */
+#define ENC_EWRPTH REGADDR(0x03, 0) /* Write Pointer High Byte (EWRPT<12:8>) */
+#define ENC_ETXSTL REGADDR(0x04, 0) /* TX Start Low Byte (ETXST<7:0>) */
+#define ENC_ETXSTH REGADDR(0x05, 0) /* TX Start High Byte (ETXST<12:8>) */
+#define ENC_ETXNDL REGADDR(0x06, 0) /* TX End Low Byte (ETXND<7:0>) */
+#define ENC_ETXNDH REGADDR(0x07, 0) /* TX End High Byte (ETXND<12:8>) */
+#define ENC_ERXSTL REGADDR(0x08, 0) /* RX Start Low Byte (ERXST<7:0>) */
+#define ENC_ERXSTH REGADDR(0x09, 0) /* RX Start High Byte (ERXST<12:8>) */
+#define ENC_ERXNDL REGADDR(0x0a, 0) /* RX End Low Byte (ERXND<7:0>) */
+#define ENC_ERXNDH REGADDR(0x0b, 0) /* RX End High Byte (ERXND<12:8>) */
+#define ENC_ERXRDPTL REGADDR(0x0c, 0) /* RX RD Pointer Low Byte (ERXRDPT<7:0>) */
+#define ENC_ERXRDPTH REGADDR(0x0d, 0) /* RX RD Pointer High Byte (ERXRDPT<12:8>) */
+#define ENC_ERXWRPTL REGADDR(0x0e, 0) /* RX WR Pointer Low Byte (ERXWRPT<7:0>) */
+#define ENC_ERXWRPTH REGADDR(0x0f, 0) /* RX WR Pointer High Byte (ERXWRPT<12:8>) */
+#define ENC_EDMASTL REGADDR(0x10, 0) /* DMA Start Low Byte (EDMAST<7:0>) */
+#define ENC_EDMASTH REGADDR(0x11, 0) /* DMA Start High Byte (EDMAST<12:8>) */
+#define ENC_EDMANDL REGADDR(0x12, 0) /* DMA End Low Byte (EDMAND<7:0>) */
+#define ENC_EDMANDH REGADDR(0x13, 0) /* DMA End High Byte (EDMAND<12:8>) */
+#define ENC_EDMADSTL REGADDR(0x14, 0) /* DMA Destination Low Byte (EDMADST<7:0>) */
+#define ENC_EDMADSTH REGADDR(0x15, 0) /* DMA Destination High Byte (EDMADST<12:8>) */
+#define ENC_EDMACSL REGADDR(0x16, 0) /* DMA Checksum Low Byte (EDMACS<7:0>) */
+#define ENC_EDMACSH REGADDR(0x17, 0) /* DMA Checksum High Byte (EDMACS<15:8>) */
+ /* 0x18-0x1a: Reserved */
+ /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
/* Bank 1 Control Register Addresses */
-#define EHT0 REGADDR(0x00, 1) /* Hash Table Byte 0 (EHT<7:0>) */
-#define EHT1 REGADDR(0x01, 1) /* Hash Table Byte 1 (EHT<15:8>) */
-#define EHT2 REGADDR(0x02, 1) /* Hash Table Byte 2 (EHT<23:16>) */
-#define EHT3 REGADDR(0x03, 1) /* Hash Table Byte 3 (EHT<31:24>) */
-#define EHT4 REGADDR(0x04, 1) /* Hash Table Byte 4 (EHT<39:32>) */
-#define EHT5 REGADDR(0x05, 1) /* Hash Table Byte 5 (EHT<47:40>) */
-#define EHT6 REGADDR(0x06, 1) /* Hash Table Byte 6 (EHT<55:48>) */
-#define EHT7 REGADDR(0x07, 1) /* Hash Table Byte 7 (EHT<63:56>) */
-#define EPMM0 REGADDR(0x08, 1) /* Pattern Match Mask Byte 0 (EPMM<7:0>) */
-#define EPMM1 REGADDR(0x09, 1) /* Pattern Match Mask Byte 1 (EPMM<15:8>) */
-#define EPMM2 REGADDR(0x0a, 1) /* Pattern Match Mask Byte 2 (EPMM<23:16>) */
-#define EPMM3 REGADDR(0x0b, 1) /* Pattern Match Mask Byte 3 (EPMM<31:24>) */
-#define EPMM4 REGADDR(0x0c, 1) /* Pattern Match Mask Byte 4 (EPMM<39:32>) */
-#define EPMM5 REGADDR(0x0d, 1) /* Pattern Match Mask Byte 5 (EPMM<47:40>) */
-#define EPMM6 REGADDR(0x0e, 1) /* Pattern Match Mask Byte 6 (EPMM<55:48>) */
-#define EPMM7 REGADDR(0x0f, 1) /* Pattern Match Mask Byte 7 (EPMM<63:56>) */
-#define EPMCSL REGADDR(0x10, 1) /* Pattern Match Checksum Low Byte (EPMCS<7:0>) */
-#define EPMCSH REGADDR(0x11, 1) /* Pattern Match Checksum High Byte (EPMCS<15:0>) */
- /* 0x12-0x13: Reserved */
-#define EPMOL REGADDR(0x14, 1) /* Pattern Match Offset Low Byte (EPMO<7:0>) */
-#define EPMOH REGADDR(0x15, 1) /* Pattern Match Offset High Byte (EPMO<12:8>) */
- /* 0x16-0x17: Reserved */
-#define ERXFCON REGADDR(0x18, 1) /* Receive Filter Configuration */
-#define EPKTCNT REGADDR(0x19, 1) /* Ethernet Packet Count */
- /* 0x1a: Reserved */
- /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
+#define ENC_EHT0 REGADDR(0x00, 1) /* Hash Table Byte 0 (EHT<7:0>) */
+#define ENC_EHT1 REGADDR(0x01, 1) /* Hash Table Byte 1 (EHT<15:8>) */
+#define ENC_EHT2 REGADDR(0x02, 1) /* Hash Table Byte 2 (EHT<23:16>) */
+#define ENC_EHT3 REGADDR(0x03, 1) /* Hash Table Byte 3 (EHT<31:24>) */
+#define ENC_EHT4 REGADDR(0x04, 1) /* Hash Table Byte 4 (EHT<39:32>) */
+#define ENC_EHT5 REGADDR(0x05, 1) /* Hash Table Byte 5 (EHT<47:40>) */
+#define ENC_EHT6 REGADDR(0x06, 1) /* Hash Table Byte 6 (EHT<55:48>) */
+#define ENC_EHT7 REGADDR(0x07, 1) /* Hash Table Byte 7 (EHT<63:56>) */
+#define ENC_EPMM0 REGADDR(0x08, 1) /* Pattern Match Mask Byte 0 (EPMM<7:0>) */
+#define ENC_EPMM1 REGADDR(0x09, 1) /* Pattern Match Mask Byte 1 (EPMM<15:8>) */
+#define ENC_EPMM2 REGADDR(0x0a, 1) /* Pattern Match Mask Byte 2 (EPMM<23:16>) */
+#define ENC_EPMM3 REGADDR(0x0b, 1) /* Pattern Match Mask Byte 3 (EPMM<31:24>) */
+#define ENC_EPMM4 REGADDR(0x0c, 1) /* Pattern Match Mask Byte 4 (EPMM<39:32>) */
+#define ENC_EPMM5 REGADDR(0x0d, 1) /* Pattern Match Mask Byte 5 (EPMM<47:40>) */
+#define ENC_EPMM6 REGADDR(0x0e, 1) /* Pattern Match Mask Byte 6 (EPMM<55:48>) */
+#define ENC_EPMM7 REGADDR(0x0f, 1) /* Pattern Match Mask Byte 7 (EPMM<63:56>) */
+#define ENC_EPMCSL REGADDR(0x10, 1) /* Pattern Match Checksum Low Byte (EPMCS<7:0>) */
+#define ENC_EPMCSH REGADDR(0x11, 1) /* Pattern Match Checksum High Byte (EPMCS<15:0>) */
+ /* 0x12-0x13: Reserved */
+#define ENC_EPMOL REGADDR(0x14, 1) /* Pattern Match Offset Low Byte (EPMO<7:0>) */
+#define ENC_EPMOH REGADDR(0x15, 1) /* Pattern Match Offset High Byte (EPMO<12:8>) */
+ /* 0x16-0x17: Reserved */
+#define ENC_ERXFCON REGADDR(0x18, 1) /* Receive Filter Configuration */
+#define ENC_EPKTCNT REGADDR(0x19, 1) /* Ethernet Packet Count */
+ /* 0x1a: Reserved */
+ /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
/* Bank 2 Control Register Addresses */
-#define MACON1 REGADDR(0x00, 2) /* MAC control 1 */
-#define MACON2 REGADDR(0x01, 2) /* MAC control 2 */
-#define MACON3 REGADDR(0x02, 2) /* MAC control 3 */
-#define MACON4 REGADDR(0x03, 2) /* MAC control 4 */
-#define MABBIPG REGADDR(0x04, 2) /* Back-to-Back Inter-Packet Gap (BBIPG<6:0>) */
- /* 0x05: Reserved */
-#define MAIPGL REGADDR(0x06, 2) /* Non-Back-to-Back Inter-Packet Gap Low Byte (MAIPGL<6:0>) */
-#define MAIPGH REGADDR(0x07, 2) /* Non-Back-to-Back Inter-Packet Gap High Byte (MAIPGH<6:0>) */
-#define MACLCON1 REGADDR(0x08, 2) /* MAC Collision Control 1 */
-#define MACLCON2 REGADDR(0x09, 2) /* MAC Collision Control 2 */
-#define MAMXFLL REGADDR(0x0a, 2) /* Maximum Frame Length Low Byte (MAMXFL<7:0>) */
-#define MAMXFLH REGADDR(0x0b, 2) /* Maximum Frame Length High Byte (MAMXFL<15:8>) */
- /* 0x0c-0x11: Reserved */
-#define MICMD REGADDR(0x12, 2) /* MII Command Register */
- /* 0x13: Reserved */
-#define MIREGADR REGADDR(0x14, 2) /* MII Register Address */
- /* 0x15: Reserved */
-#define MIWRL REGADDR(0x16, 2) /* MII Write Data Low Byte (MIWR<7:0>) */
-#define MIWRH REGADDR(0x17, 2) /* MII Write Data High Byte (MIWR<15:8>) */
-#define MIRDL REGADDR(0x18, 2) /* MII Read Data Low Byte (MIRD<7:0>) */
-#define MIRDH REGADDR(0x19, 2) /* MII Read Data High Byte(MIRD<15:8>) */
- /* 0x1a: Reserved */
- /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
+#define ENC_MACON1 REGADDR(0x00, 2) /* MAC control 1 */
+#define ENC_MACON2 REGADDR(0x01, 2) /* MAC control 2 */
+#define ENC_MACON3 REGADDR(0x02, 2) /* MAC control 3 */
+#define ENC_MACON4 REGADDR(0x03, 2) /* MAC control 4 */
+#define ENC_MABBIPG REGADDR(0x04, 2) /* Back-to-Back Inter-Packet Gap (BBIPG<6:0>) */
+ /* 0x05: Reserved */
+#define ENC_MAIPGL REGADDR(0x06, 2) /* Non-Back-to-Back Inter-Packet Gap Low Byte (MAIPGL<6:0>) */
+#define ENC_MAIPGH REGADDR(0x07, 2) /* Non-Back-to-Back Inter-Packet Gap High Byte (MAIPGH<6:0>) */
+#define ENC_MACLCON1 REGADDR(0x08, 2) /* MAC Collision Control 1 */
+#define ENC_MACLCON2 REGADDR(0x09, 2) /* MAC Collision Control 2 */
+#define ENC_MAMXFLL REGADDR(0x0a, 2) /* Maximum Frame Length Low Byte (MAMXFL<7:0>) */
+#define ENC_MAMXFLH REGADDR(0x0b, 2) /* Maximum Frame Length High Byte (MAMXFL<15:8>) */
+ /* 0x0c-0x11: Reserved */
+#define ENC_MICMD REGADDR(0x12, 2) /* MII Command Register */
+ /* 0x13: Reserved */
+#define ENC_MIREGADR REGADDR(0x14, 2) /* MII Register Address */
+ /* 0x15: Reserved */
+#define ENC_MIWRL REGADDR(0x16, 2) /* MII Write Data Low Byte (MIWR<7:0>) */
+#define ENC_MIWRH REGADDR(0x17, 2) /* MII Write Data High Byte (MIWR<15:8>) */
+#define ENC_MIRDL REGADDR(0x18, 2) /* MII Read Data Low Byte (MIRD<7:0>) */
+#define ENC_MIRDH REGADDR(0x19, 2) /* MII Read Data High Byte(MIRD<15:8>) */
+ /* 0x1a: Reserved */
+ /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
/* Bank 3 Control Register Addresses */
-#define MAADR5 REGADDR(0x00, 3) /* MAC Address Byte 5 (MAADR<15:8>) */
-#define MAADR6 REGADDR(0x01, 3) /* MAC Address Byte 6 (MAADR<7:0>) */
-#define MAADR3 REGADDR(0x02, 3) /* MAC Address Byte 3 (MAADR<31:24>), OUI Byte 3 */
-#define MAADR4 REGADDR(0x03, 3) /* MAC Address Byte 4 (MAADR<23:16>) */
-#define MAADR1 REGADDR(0x04, 3) /* MAC Address Byte 1 (MAADR<47:40>), OUI Byte 1 */
-#define MAADR2 REGADDR(0x05, 3) /* MAC Address Byte 2 (MAADR<39:32>), OUI Byte */
-#define EBSTSD REGADDR(0x06, 3) /* Built-in Self-Test Fill Seed (EBSTSD<7:0>) */
-#define EBSTCON REGADDR(0x07, 3) /* Built-in Self-Test Control */
-#define EBSTCSL REGADDR(0x08, 3) /* Built-in Self-Test Checksum Low Byte (EBSTCS<7:0>) */
-#define EBSTCSH REGADDR(0x09, 3) /* Built-in Self-Test Checksum High Byte (EBSTCS<15:8>) */
-#define MISTAT REGADDR(0x0a, 3) /* MII Status Register */
- /* 0x0b-0x11: Reserved */
-#define EREVID REGADDR(0x12, 3) /* Ethernet Revision ID */
- /* 0x13-0x14: Reserved */
-#define ECOCON REGADDR(0x15, 3) /* Clock Output Control */
- /* 0x16: Reserved */
-#define EFLOCON REGADDR(0x17, 3) /* Ethernet Flow Control */
-#define EPAUSL REGADDR(0x18, 3) /* Pause Timer Value Low Byte (EPAUS<7:0>) */
-#define EPAUSH REGADDR(0x19, 3) /* Pause Timer Value High Byte (EPAUS<15:8>) */
- /* 0x1a: Reserved */
- /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
+#define ENC_MAADR5 REGADDR(0x00, 3) /* MAC Address Byte 5 (MAADR<15:8>) */
+#define ENC_MAADR6 REGADDR(0x01, 3) /* MAC Address Byte 6 (MAADR<7:0>) */
+#define ENC_MAADR3 REGADDR(0x02, 3) /* MAC Address Byte 3 (MAADR<31:24>), OUI Byte 3 */
+#define ENC_MAADR4 REGADDR(0x03, 3) /* MAC Address Byte 4 (MAADR<23:16>) */
+#define ENC_MAADR1 REGADDR(0x04, 3) /* MAC Address Byte 1 (MAADR<47:40>), OUI Byte 1 */
+#define ENC_MAADR2 REGADDR(0x05, 3) /* MAC Address Byte 2 (MAADR<39:32>), OUI Byte */
+#define ENC_EBSTSD REGADDR(0x06, 3) /* Built-in Self-Test Fill Seed (EBSTSD<7:0>) */
+#define ENC_EBSTCON REGADDR(0x07, 3) /* Built-in Self-Test Control */
+#define ENC_EBSTCSL REGADDR(0x08, 3) /* Built-in Self-Test Checksum Low Byte (EBSTCS<7:0>) */
+#define ENC_EBSTCSH REGADDR(0x09, 3) /* Built-in Self-Test Checksum High Byte (EBSTCS<15:8>) */
+#define ENC_MISTAT REGADDR(0x0a, 3) /* MII Status Register */
+ /* 0x0b-0x11: Reserved */
+#define ENC_EREVID REGADDR(0x12, 3) /* Ethernet Revision ID */
+ /* 0x13-0x14: Reserved */
+#define ENC_ECOCON REGADDR(0x15, 3) /* Clock Output Control */
+ /* 0x16: Reserved */
+#define ENC_EFLOCON REGADDR(0x17, 3) /* Ethernet Flow Control */
+#define ENC_EPAUSL REGADDR(0x18, 3) /* Pause Timer Value Low Byte (EPAUS<7:0>) */
+#define ENC_EPAUSH REGADDR(0x19, 3) /* Pause Timer Value High Byte (EPAUS<15:8>) */
+ /* 0x1a: Reserved */
+ /* 0x1b-0x1f: EIE, EIR, ESTAT, ECON2, ECON1 */
/* PHY Registers ************************************************************/
-#define PHCON1 (0x00) /* PHY Control Register 1 */
-#define PHSTAT1 (0x01) /* PHY Status 1 */
-#define PHID1 (0x02) /* PHY ID Register 1 */
-#define PHID2 (0x03) /* PHY ID Register 2 */
-#define PHCON2 (0x10) /* PHY Control Register 2 */
-#define PHSTAT2 (0x11) /* PHY Status 2 */
-#define PHIE (0x12) /* PHY Interrupt Enable Register */
-#define PHIR (0x13)
-#define PHLCON (0x14)
+#define ENC_PHCON1 (0x00) /* PHY Control Register 1 */
+#define ENC_PHSTAT1 (0x01) /* PHY Status 1 */
+#define ENC_PHID1 (0x02) /* PHY ID Register 1 */
+#define ENC_PHID2 (0x03) /* PHY ID Register 2 */
+#define ENC_PHCON2 (0x10) /* PHY Control Register 2 */
+#define ENC_PHSTAT2 (0x11) /* PHY Status 2 */
+#define ENC_PHIE (0x12) /* PHY Interrupt Enable Register */
+#define ENC_PHIR (0x13)
+#define ENC_PHLCON (0x14)
/* PHY Control Register 1 Register Bit Definitions */