AT91SAM7: add EMAC ethernet driver
authorarighi <arighi@38d2e660-2303-0410-9eaa-f027e97ec537>
Mon, 25 Oct 2010 11:09:22 +0000 (11:09 +0000)
committerarighi <arighi@38d2e660-2303-0410-9eaa-f027e97ec537>
Mon, 25 Oct 2010 11:09:22 +0000 (11:09 +0000)
git-svn-id: https://src.develer.com/svnoss/bertos/trunk@4458 38d2e660-2303-0410-9eaa-f027e97ec537

bertos/cpu/arm/drv/eth_at91.c [new file with mode: 0644]
bertos/cpu/arm/drv/eth_at91.h [new file with mode: 0644]
bertos/cpu/arm/io/at91_emac.h [new file with mode: 0644]
bertos/cpu/arm/io/at91sam7.h

diff --git a/bertos/cpu/arm/drv/eth_at91.c b/bertos/cpu/arm/drv/eth_at91.c
new file mode 100644 (file)
index 0000000..fbf3542
--- /dev/null
@@ -0,0 +1,425 @@
+/**
+  * \file
+  * <!--
+  * This file is part of BeRTOS.
+  *
+  * Bertos is free software; you can redistribute it and/or modify
+  * it under the terms of the GNU General Public License as published by
+  * the Free Software Foundation; either version 2 of the License, or
+  * (at your option) any later version.
+  *
+  * This program is distributed in the hope that it will be useful,
+  * but WITHOUT ANY WARRANTY; without even the implied warranty of
+  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+  * GNU General Public License for more details.
+  *
+  * You should have received a copy of the GNU General Public License
+  * along with this program; if not, write to the Free Software
+  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+  *
+  * As a special exception, you may use this file as part of a free software
+  * library without restriction.  Specifically, if other files instantiate
+  * templates or use macros or inline functions from this file, or you compile
+  * this file and link it with other files to produce an executable, this
+  * file does not by itself cause the resulting executable to be covered by
+  * the GNU General Public License.  This exception does not however
+  * invalidate any other reasons why the executable file might be covered by
+  * the GNU General Public License.
+  *
+  * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+  * All Rights Reserved.
+  * -->
+  *
+  * \brief EMAC driver for AT91SAM7X Family.
+  *
+  * \author Daniele Basile <asterix@develer.com>
+  * \author Andrea Righi <arighi@develer.com>
+  */
+
+#include "cfg/cfg_eth.h"
+
+#define LOG_LEVEL  ETH_LOG_LEVEL
+#define LOG_FORMAT ETH_LOG_FORMAT
+
+#include <cfg/log.h>
+
+#include <cfg/debug.h>
+#include <cfg/log.h>
+#include <cfg/macros.h>
+#include <cfg/compiler.h>
+
+#include <io/at91sam7.h>
+#include <io/arm.h>
+
+#include <cpu/power.h>
+#include <cpu/types.h>
+#include <cpu/irq.h>
+
+#include <drv/timer.h>
+#include <drv/eth.h>
+
+#include <mware/event.h>
+
+#include <string.h>
+
+#include "eth_at91.h"
+
+/*
+ * MAC address configuration (please change this in your project!).
+ *
+ * TODO: make this paramater user-configurable from the Wizard.
+ */
+uint8_t mac_addr[] = { 0x11, 0x22, 0x33, 0x44, 0x55, 0x66 };
+
+static volatile BufDescriptor tx_buf_tab[EMAC_TX_DESCRIPTORS];
+/*
+ * NOTE: this buffer should be declared as 'volatile' because it is read by the
+ * hardware. However, this is accessed only via memcpy() that should guarantee
+ * coherency when copying from/to buffers.
+ */
+static uint8_t tx_buf[EMAC_TX_BUFFERS * EMAC_TX_BUFSIZ] ALIGNED(8);
+static int tx_buf_idx = 0;
+
+static volatile BufDescriptor rx_buf_tab[EMAC_RX_DESCRIPTORS];
+/*
+ * NOTE: this buffer should be declared as 'volatile' because it is wrote by
+ * the hardware. However, this is accessed only via memcpy() that should
+ * guarantee coherency when copying from/to buffers.
+ */
+static uint8_t rx_buf[EMAC_RX_BUFFERS * EMAC_RX_BUFSIZ] ALIGNED(8);
+static int rx_buf_idx = 0;
+
+static Event recv_wait, send_wait;
+
+static DECLARE_ISR(emac_irqHandler)
+{
+       /* Read interrupt status and disable interrupts. */
+       uint32_t isr = EMAC_ISR;
+
+       /* Receiver interrupt */
+       if ((isr & EMAC_RX_INTS))
+       {
+               event_do(&recv_wait);
+               EMAC_RSR = EMAC_RX_INTS;
+       }
+       /* Transmitter interrupt */
+       if (isr & EMAC_TX_INTS)
+       {
+               event_do(&send_wait);
+               EMAC_TSR = EMAC_TX_INTS;
+       }
+       AIC_EOICR = 0;
+}
+
+/*
+ * \brief Read contents of PHY register.
+ *
+ * \param reg PHY register number.
+ *
+ * \return Contents of the specified register.
+ */
+static uint16_t phy_hw_read(reg8_t reg)
+{
+       // PHY read command.
+       EMAC_MAN = EMAC_SOF | EMAC_RW_READ | (NIC_PHY_ADDR << EMAC_PHYA_SHIFT)
+                       | ((reg  << EMAC_REGA_SHIFT) & EMAC_REGA) | EMAC_CODE;
+
+       // Wait until PHY logic completed.
+       while (!(EMAC_NSR & BV(EMAC_IDLE)))
+               cpu_relax();
+
+       // Get data from PHY maintenance register.
+       return (uint16_t)(EMAC_MAN & EMAC_DATA);
+}
+
+/*
+ * \brief Write value to PHY register.
+ *
+ * \param reg PHY register number.
+ * \param val Value to write.
+ */
+static void phy_hw_write(reg8_t reg, uint16_t val)
+{
+       // PHY write command.
+       EMAC_MAN = EMAC_SOF | EMAC_RW_WRITE | (NIC_PHY_ADDR << EMAC_PHYA_SHIFT)
+                       | ((reg  << EMAC_REGA_SHIFT) & EMAC_REGA) | EMAC_CODE | val;
+
+       // Wait until PHY logic completed.
+       while (!(EMAC_NSR & BV(EMAC_IDLE)))
+               cpu_relax();
+}
+
+static int emac_reset(void)
+{
+       uint16_t phy_cr;
+
+       // Enable devices
+       PMC_PCER = BV(PIOA_ID);
+       PMC_PCER = BV(PIOB_ID);
+       PMC_PCER = BV(EMAC_ID);
+
+       // Disable RMII and TESTMODE by disabling pull-ups.
+       PIOB_PUDR = BV(PHY_COL_RMII_BIT) | BV(PHY_RXDV_TESTMODE_BIT);
+
+       // Disable PHY power down.
+       PIOB_PER  = BV(PHY_PWRDN_BIT);
+       PIOB_OER  = BV(PHY_PWRDN_BIT);
+       PIOB_CODR = BV(PHY_PWRDN_BIT);
+
+       // Toggle external hardware reset pin.
+       RSTC_MR = RSTC_KEY | (1 << RSTC_ERSTL_SHIFT) | BV(RSTC_URSTEN);
+       RSTC_CR = RSTC_KEY | BV(RSTC_EXTRST);
+
+       while ((RSTC_SR & BV(RSTC_NRSTL)) == 0)
+               cpu_relax();
+
+       // Configure MII port.
+       PIOB_ASR = PHY_MII_PINS;
+       PIOB_BSR = 0;
+       PIOB_PDR = PHY_MII_PINS;
+
+       // Enable receive and transmit clocks.
+       EMAC_USRIO = BV(EMAC_CLKEN);
+
+       // Enable management port.
+       EMAC_NCR |= BV(EMAC_MPE);
+       EMAC_NCFGR |= EMAC_CLK_HCLK_32;
+
+       // Set local MAC address.
+       EMAC_SA1L = (mac_addr[3] << 24) | (mac_addr[2] << 16) |
+                               (mac_addr[1] << 8) | mac_addr[0];
+       EMAC_SA1H = (mac_addr[5] << 8) | mac_addr[4];
+
+       // Wait for PHY ready
+       timer_delay(255);
+
+       // Clear MII isolate.
+       phy_hw_read(NIC_PHY_BMCR);
+       phy_cr = phy_hw_read(NIC_PHY_BMCR);
+
+       phy_cr &= ~NIC_PHY_BMCR_ISOLATE;
+       phy_hw_write(NIC_PHY_BMCR, phy_cr);
+
+       phy_cr = phy_hw_read(NIC_PHY_BMCR);
+
+       LOG_INFO("%s: PHY ID %#04x %#04x\n",
+               __func__,
+               phy_hw_read(NIC_PHY_ID1), phy_hw_read(NIC_PHY_ID2));
+
+       // Wait for auto negotiation completed.
+       phy_hw_read(NIC_PHY_BMSR);
+       for (;;)
+       {
+               if (phy_hw_read(NIC_PHY_BMSR) & NIC_PHY_BMSR_ANCOMPL)
+                       break;
+               cpu_relax();
+       }
+
+       // Disable management port.
+       EMAC_NCR &= ~BV(EMAC_MPE);
+
+       return 0;
+}
+
+static int emac_start(void)
+{
+       uint32_t addr;
+       int i;
+
+       for (i = 0; i < EMAC_RX_DESCRIPTORS; i++)
+       {
+               addr = (uint32_t)(rx_buf + (i * EMAC_RX_BUFSIZ));
+               rx_buf_tab[i].addr = addr & BUF_ADDRMASK;
+       }
+       rx_buf_tab[EMAC_RX_DESCRIPTORS - 1].addr |= RXBUF_WRAP;
+
+       for (i = 0; i < EMAC_TX_DESCRIPTORS; i++)
+       {
+               addr = (uint32_t)(tx_buf + (i * EMAC_TX_BUFSIZ));
+               tx_buf_tab[i].addr = addr & BUF_ADDRMASK;
+               tx_buf_tab[i].stat = TXS_USED;
+       }
+       tx_buf_tab[EMAC_TX_DESCRIPTORS - 1].stat = TXS_USED | TXS_WRAP;
+
+       /* Tell the EMAC where to find the descriptors. */
+       EMAC_RBQP = (uint32_t)rx_buf_tab;
+       EMAC_TBQP = (uint32_t)tx_buf_tab;
+
+       /* Clear receiver status. */
+       EMAC_RSR = BV(EMAC_OVR) | BV(EMAC_REC) | BV(EMAC_BNA);
+
+       /* Copy all frames and discard FCS. */
+       EMAC_NCFGR |= BV(EMAC_CAF) | BV(EMAC_DRFCS);
+
+       /* Enable receiver, transmitter and statistics. */
+       EMAC_NCR |= BV(EMAC_TE) | BV(EMAC_RE) | BV(EMAC_WESTAT);
+
+       return 0;
+}
+
+ssize_t eth_send(const uint8_t *buf, size_t len)
+ {
+       size_t wr_len;
+       int idx;
+
+       if (UNLIKELY(!len))
+               return -1;
+       ASSERT(len <= sizeof(tx_buf));
+
+        /* Check if the transmit buffer is available */
+       idx = tx_buf_idx;
+        while (!(tx_buf_tab[idx].stat & TXS_USED))
+                event_wait(&send_wait);
+
+       if (++tx_buf_idx >= EMAC_TX_DESCRIPTORS)
+               tx_buf_idx = 0;
+
+        /* Copy the data into the buffer and prepare descriptor */
+        wr_len = MIN(len, (size_t)EMAC_TX_BUFSIZ);
+        memcpy((uint8_t *)tx_buf_tab[idx].addr, buf, wr_len);
+        tx_buf_tab[idx].stat = (wr_len & RXS_LENGTH_FRAME) |
+                       ((idx == EMAC_TX_DESCRIPTORS - 1) ?
+                               TXS_WRAP : 0) |
+                       TXS_LAST_BUFF;
+       EMAC_NCR |= BV(EMAC_TSTART);
+
+       return wr_len;
+}
+
+static size_t eth_getFrameLen(void)
+{
+       int idx, n = EMAC_RX_BUFFERS;
+
+       /* Skip empty buffers */
+       while ((n > 0) && !(rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP))
+       {
+               if (++rx_buf_idx >= EMAC_RX_BUFFERS)
+                       rx_buf_idx = 0;
+               n--;
+       }
+       if (UNLIKELY(!n))
+       {
+               LOG_INFO("no frame found\n");
+               return 0;
+       }
+       /* Search the start of frame and cleanup fragments */
+       while ((n > 0) && (rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP) &&
+                       !(rx_buf_tab[rx_buf_idx].stat & RXS_SOF))
+       {
+               rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
+               if (++rx_buf_idx >= EMAC_RX_BUFFERS)
+                       rx_buf_idx = 0;
+               n--;
+       }
+       if (UNLIKELY(!(rx_buf_tab[rx_buf_idx].stat & RXS_SOF)))
+       {
+               LOG_INFO("no SOF found\n");
+               return 0;
+       }
+       /* Search end of frame to evaluate the total frame size */
+       idx = rx_buf_idx;
+       while ((n > 0) && (rx_buf_tab[idx].addr & RXBUF_OWNERSHIP))
+       {
+               if (UNLIKELY((idx != rx_buf_idx) &&
+                               (rx_buf_tab[idx].stat & RXS_SOF)))
+               {
+                       /* Another start of frame found. Realign. */
+                       do {
+                               rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
+                               if (++rx_buf_idx >= EMAC_RX_BUFFERS)
+                                       rx_buf_idx = 0;
+                       } while (idx != rx_buf_idx);
+               }
+               if (rx_buf_tab[idx].stat & RXS_EOF)
+                       return rx_buf_tab[idx].stat & RXS_LENGTH_FRAME;
+               if (++idx >= EMAC_RX_BUFFERS)
+                       idx = 0;
+               n--;
+       }
+
+       LOG_INFO("no EOF found\n");
+       return 0;
+}
+
+ssize_t eth_recv(uint8_t *buf, size_t len)
+{
+       uint8_t *addr;
+       size_t rd_len = 0;
+
+       if (UNLIKELY(!len))
+               return -1;
+       ASSERT(len <= sizeof(tx_buf));
+
+       /* Check if there is at least one available frame in the buffer */
+       while (1)
+       {
+               size_t frame_len = MIN(len, eth_getFrameLen());
+               if (frame_len)
+               {
+                       len = frame_len;
+                       break;
+               }
+               /* Wait for RX interrupt */
+               event_wait(&recv_wait);
+       }
+
+       /* Copy data from the RX buffer */
+       addr = (uint8_t *)(rx_buf_tab[rx_buf_idx].addr & BUF_ADDRMASK);
+       if (addr + len > &rx_buf[countof(rx_buf)])
+       {
+               size_t count = &rx_buf[countof(rx_buf)] - addr;
+
+               memcpy(buf, addr, count);
+               memcpy(buf + count, rx_buf, len - count);
+       }
+       else
+       {
+               memcpy(buf, addr, len);
+       }
+       /* Update descriptors */
+       while (rd_len < len)
+       {
+               if (len - rd_len >= EMAC_RX_BUFSIZ)
+                       rd_len += EMAC_RX_BUFSIZ;
+               else
+                       rd_len += len - rd_len;
+               ASSERT(rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP);
+               rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
+               if (++rx_buf_idx >= EMAC_RX_DESCRIPTORS)
+                       rx_buf_idx = 0;
+       }
+       return rd_len;
+}
+
+int eth_init()
+{
+       cpu_flags_t flags;
+
+       emac_reset();
+       emac_start();
+
+       event_initGeneric(&recv_wait);
+       event_initGeneric(&send_wait);
+
+       // Register interrupt vector
+       IRQ_SAVE_DISABLE(flags);
+
+       /* Disable all emac interrupts */
+       EMAC_IDR = 0xFFFFFFFF;
+
+       /* Set the vector. */
+       AIC_SVR(EMAC_ID) = emac_irqHandler;
+       /* Initialize to edge triggered with defined priority. */
+       AIC_SMR(EMAC_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED;
+       /* Clear pending interrupt */
+       AIC_ICCR = BV(EMAC_ID);
+       /* Enable the system IRQ */
+       AIC_IECR = BV(EMAC_ID);
+
+       /* Enable interrupts */
+       EMAC_IER = EMAC_RX_INTS | EMAC_TX_INTS;
+
+       IRQ_RESTORE(flags);
+
+       return 0;
+}
diff --git a/bertos/cpu/arm/drv/eth_at91.h b/bertos/cpu/arm/drv/eth_at91.h
new file mode 100644 (file)
index 0000000..f779099
--- /dev/null
@@ -0,0 +1,168 @@
+/**
+  * \file
+  * <!--
+  * This file is part of BeRTOS.
+  *
+  * Bertos is free software; you can redistribute it and/or modify
+  * it under the terms of the GNU General Public License as published by
+  * the Free Software Foundation; either version 2 of the License, or
+  * (at your option) any later version.
+  *
+  * This program is distributed in the hope that it will be useful,
+  * but WITHOUT ANY WARRANTY; without even the implied warranty of
+  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+  * GNU General Public License for more details.
+  *
+  * You should have received a copy of the GNU General Public License
+  * along with this program; if not, write to the Free Software
+  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+  *
+  * As a special exception, you may use this file as part of a free software
+  * library without restriction.  Specifically, if other files instantiate
+  * templates or use macros or inline functions from this file, or you compile
+  * this file and link it with other files to produce an executable, this
+  * file does not by itself cause the resulting executable to be covered by
+  * the GNU General Public License.  This exception does not however
+  * invalidate any other reasons why the executable file might be covered by
+  * the GNU General Public License.
+  *
+  * Copyright 2009 Develer S.r.l. (http://www.develer.com/)
+  * All Rights Reserved.
+  * -->
+  *
+  * \brief EMAC driver for AT91SAM7X Family, interface.
+  *
+  * \author Daniele Basile <asterix@develer.com>
+  * \author Andrea Righi <arighi@develer.com>
+  */
+
+#ifndef ETH_AT91_H
+#define ETH_AT91_H
+
+// Settings and definition for DAVICOM 9161A
+// \{
+#define NIC_PHY_ADDR            31
+
+//Registry definition
+#define NIC_PHY_BMCR            0x00    //  Basic mode control register.
+#define NIC_PHY_BMCR_COLTEST    0x0080  //  Collision test.
+#define NIC_PHY_BMCR_FDUPLEX    0x0100  //  Full duplex mode.
+#define NIC_PHY_BMCR_ANEGSTART  0x0200  //  Restart auto negotiation.
+#define NIC_PHY_BMCR_ISOLATE    0x0400  //  Isolate from MII.
+#define NIC_PHY_BMCR_PWRDN      0x0800  //  Power-down.
+#define NIC_PHY_BMCR_ANEGENA    0x1000  //  Enable auto negotiation.
+#define NIC_PHY_BMCR_100MBPS    0x2000  //  Select 100 Mbps.
+#define NIC_PHY_BMCR_LOOPBACK   0x4000  //  Enable loopback mode.
+#define NIC_PHY_BMCR_RESET      0x8000  //  Software reset.
+
+#define NIC_PHY_BMSR            0x01    //  Basic mode status register.
+#define NIC_PHY_BMSR_ANCOMPL    0x0020  //  Auto negotiation complete.
+#define NIC_PHY_BMSR_ANEGCAPABLE 0x0008  // Able to do auto-negotiation
+#define NIC_PHY_BMSR_LINKSTAT   0x0004  //  Link status.
+
+#define NIC_PHY_ID1             0x02    //  PHY identifier register 1.
+#define NIC_PHY_ID2             0x03    //  PHY identifier register 2.
+#define NIC_PHY_ANAR            0x04    //  Auto negotiation advertisement register.
+#define NIC_PHY_ANLPAR          0x05    //  Auto negotiation link partner availability register.
+#define NIC_PHY_ANER            0x06    //  Auto negotiation expansion register.
+
+// Pin definition for DAVICOM 9161A
+// See schematic for at91sam7x-ek evalution board
+#define PHY_TXCLK_ISOLATE_BIT   0
+#define PHY_REFCLK_XT2_BIT      0
+#define PHY_TXEN_BIT            1
+#define PHY_TXD0_BIT            2
+#define PHY_TXD1_BIT            3
+#define PHY_CRS_AD4_BIT         4
+#define PHY_RXD0_AD0_BIT        5
+#define PHY_RXD1_AD1_BIT        6
+#define PHY_RXER_RXD4_RPTR_BIT  7
+#define PHY_MDC_BIT             8
+#define PHY_MDIO_BIT            9
+#define PHY_TXD2_BIT            10
+#define PHY_TXD3_BIT            11
+#define PHY_TXER_TXD4_BIT       12
+#define PHY_RXD2_AD2_BIT        13
+#define PHY_RXD3_AD3_BIT        14
+#define PHY_RXDV_TESTMODE_BIT   15
+#define PHY_COL_RMII_BIT        16
+#define PHY_RXCLK_10BTSER_BIT   17
+#define PHY_PWRDN_BIT           18
+#define PHY_MDINTR_BIT          26
+
+#define PHY_MII_PINS   BV(PHY_REFCLK_XT2_BIT) \
+       | BV(PHY_TXEN_BIT) \
+       | BV(PHY_TXD0_BIT) \
+       | BV(PHY_TXD1_BIT) \
+       | BV(PHY_CRS_AD4_BIT) \
+       | BV(PHY_RXD0_AD0_BIT) \
+       | BV(PHY_RXD1_AD1_BIT) \
+       | BV(PHY_RXER_RXD4_RPTR_BIT) \
+       | BV(PHY_MDC_BIT) \
+       | BV(PHY_MDIO_BIT) \
+       | BV(PHY_TXD2_BIT) \
+       | BV(PHY_TXD3_BIT) \
+       | BV(PHY_TXER_TXD4_BIT) \
+       | BV(PHY_RXD2_AD2_BIT) \
+       | BV(PHY_RXD3_AD3_BIT) \
+       | BV(PHY_RXDV_TESTMODE_BIT) \
+       | BV(PHY_COL_RMII_BIT) \
+       | BV(PHY_RXCLK_10BTSER_BIT)
+// \}
+
+#define EMAC_TX_BUFSIZ          1518
+#define EMAC_TX_BUFFERS         1
+#define EMAC_TX_DESCRIPTORS     EMAC_TX_BUFFERS
+
+#define EMAC_RX_BUFFERS         32
+#define EMAC_RX_BUFSIZ          128
+#define EMAC_RX_DESCRIPTORS    EMAC_RX_BUFFERS
+
+// Flag to manage local tx buffer
+#define TXS_USED            0x80000000  //Used buffer.
+#define TXS_WRAP            0x40000000  //Last descriptor.
+#define TXS_ERROR           0x20000000  //Retry limit exceeded.
+#define TXS_UNDERRUN        0x10000000  //Transmit underrun.
+#define TXS_NO_BUFFER       0x08000000  //Buffer exhausted.
+#define TXS_NO_CRC          0x00010000  //CRC not appended.
+#define TXS_LAST_BUFF       0x00008000  //Last buffer of frame.
+#define TXS_LENGTH_FRAME    0x000007FF  // Length of frame including FCS.
+
+// Flag to manage local rx buffer
+#define RXBUF_OWNERSHIP     0x00000001
+#define RXBUF_WRAP          0x00000002
+
+#define BUF_ADDRMASK        0xFFFFFFFC
+
+#define RXS_BROADCAST_ADDR  0x80000000  // Broadcast address detected.
+#define RXS_MULTICAST_HASH  0x40000000  // Multicast hash match.
+#define RXS_UNICAST_HASH    0x20000000  // Unicast hash match.
+#define RXS_EXTERNAL_ADDR   0x10000000  // External address match.
+#define RXS_SA1_ADDR        0x04000000  // Specific address register 1 match.
+#define RXS_SA2_ADDR        0x02000000  // Specific address register 2 match.
+#define RXS_SA3_ADDR        0x01000000  // Specific address register 3 match.
+#define RXS_SA4_ADDR        0x00800000  // Specific address register 4 match.
+#define RXS_TYPE_ID         0x00400000  // Type ID match.
+#define RXS_VLAN_TAG        0x00200000  // VLAN tag detected.
+#define RXS_PRIORITY_TAG    0x00100000  // Priority tag detected.
+#define RXS_VLAN_PRIORITY   0x000E0000  // VLAN priority.
+#define RXS_CFI_IND         0x00010000  // Concatenation format indicator.
+#define RXS_EOF             0x00008000  // End of frame.
+#define RXS_SOF             0x00004000  // Start of frame.
+#define RXS_RBF_OFFSET      0x00003000  // Receive buffer offset mask.
+#define RXS_LENGTH_FRAME    0x000007FF  // Length of frame including FCS.
+
+#define EMAC_RSR_BITS  (BV(EMAC_BNA) | BV(EMAC_REC) | BV(EMAC_OVR))
+#define EMAC_TSR_BITS  (BV(EMAC_UBR) | BV(EMAC_COL) | BV(EMAC_RLES) | \
+                       BV(EMAC_BEX) | BV(EMAC_COMP) | BV(EMAC_UND))
+
+#define EMAC_RX_INTS   (BV(EMAC_RCOMP) | BV(EMAC_ROVR) | BV(EMAC_RXUBR))
+#define EMAC_TX_INTS   (BV(EMAC_TCOMP))
+
+typedef struct BufDescriptor
+{
+       volatile uint32_t addr;
+       volatile uint32_t stat;
+} BufDescriptor;
+
+#endif /* ETH_AT91_H */
diff --git a/bertos/cpu/arm/io/at91_emac.h b/bertos/cpu/arm/io/at91_emac.h
new file mode 100644 (file)
index 0000000..2343238
--- /dev/null
@@ -0,0 +1,364 @@
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction.  Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License.  This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2009 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \author Daniele Basile <asterix@develer.com>
+ *
+ * AT91 Ethernet MAC 10/100 controller.
+ * This file is based on NUT/OS implementation. See license below.
+ */
+
+/*
+ * Copyright (C) 2005-2006 by egnite Software GmbH. All rights reserved.
+ *
+ * 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 of the copyright holders nor the names of
+ *    contributors may be used to endorse or promote products derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY EGNITE SOFTWARE GMBH 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 EGNITE
+ * SOFTWARE GMBH 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.
+ *
+ * For additional information see http://www.ethernut.de/
+ */
+
+#ifndef AT91_EMAC_H
+#define AT91_EMAC_H
+
+
+/**
+ *
+ * Network Control Register
+ *
+ */
+/* \{ */
+#define EMAC_NCR_OFF                0x00000000  ///< Network control register offset.
+#define EMAC_NCR    (*((reg32_t *)(EMAC_BASE +  EMAC_NCR_OFF)))  ///< Network Control register address.
+#define EMAC_LB                              0  ///< PHY loopback.
+#define EMAC_LLB                             1   ///< EMAC loopback.
+#define EMAC_RE                              2  ///< Receive enable.
+#define EMAC_TE                              3  ///< Transmit enable.
+#define EMAC_MPE                             4  ///< Management port enable.
+#define EMAC_CLRSTAT                         5  ///< Clear statistics registers.
+#define EMAC_INCSTAT                         6  ///< Increment statistics registers.
+#define EMAC_WESTAT                          7  ///< Write enable for statistics registers.
+#define EMAC_BP                              8  ///< Back pressure.
+#define EMAC_TSTART                          9  ///< Start Transmission.
+#define EMAC_THALT                          10  ///< Transmission halt.
+// Not in sam7x
+//#define EMAC_TPFR                           11  ///< Transmit pause frame.
+//#define EMAC_TZQ                            12  ///< Transmit zero quantum pause frame.
+/* \} */
+
+/**
+ * Network Configuration Register
+ *
+ */
+/* \{ */
+#define EMAC_NCFGR_OFF              0x00000004  ///< Network configuration register offset.
+#define EMAC_NCFGR   (*((reg32_t *)(EMAC_BASE +  EMAC_NCFGR_OFF))) ///< Network configuration register address.
+#define EMAC_SPD                             0  ///< Speed, set for 100Mb.
+#define EMAC_FD                              1  ///< Full duplex.
+#define EMAC_JFRAME                          3  ///< Jumbo Frames.
+#define EMAC_CAF                             4  ///< Copy all frames.
+#define EMAC_NBC                             5  ///< No broadcast.
+#define EMAC_MTI                             6  ///< Multicast hash event enable.
+#define EMAC_UNI                             7  ///< Unicast hash enable.
+#define EMAC_BIG                             8  ///< Receive 1522 bytes.
+// Not in sam7x
+//#define EMAC_EAE                           9  ///< External address match enable.
+#define EMAC_CLK                    0x00000C00  ///< Clock divider mask.
+#define EMAC_CLK_HCLK_8             0x00000000  ///< HCLK divided by 8.
+#define EMAC_CLK_HCLK_16            0x00000400  ///< HCLK divided by 16.
+#define EMAC_CLK_HCLK_32            0x00000800  ///< HCLK divided by 32.
+#define EMAC_CLK_HCLK_64            0x00000C00  ///< HCLK divided by 64.
+#define EMAC_RTY                            12  ///< Retry test.
+#define EMAC_PAE                            13  ///< Pause enable.
+#define EMAC_RBOF                   0x0000C000  ///< Receive buffer offset.
+#define EMAC_RBOF_OFFSET_0          0x00000000  ///< No offset from start of receive buffer.
+#define EMAC_RBOF_OFFSET_1          0x00004000  ///< One byte offset from start of receive buffer.
+#define EMAC_RBOF_OFFSET_2          0x00008000  ///< Two bytes offset from start of receive buffer.
+#define EMAC_RBOF_OFFSET_3          0x0000C000  ///< Three bytes offset from start of receive buffer.
+#define EMAC_RLCE                           16  ///< Receive length field checking enable.
+#define EMAC_DRFCS                          17  ///< Discard receive FCS.
+#define EMAC_EFRHD                          18  ///< Allow receive during transmit in half duplex.
+#define EMAC_IRXFCS                         19  ///< Ignore received FCS.
+/* \} */
+
+/**
+ * Network Status Register
+ *
+ */
+/* \{ */
+#define EMAC_NSR_OFF                0x00000008  ///< Network Status register offset.
+#define EMAC_NSR    (*((reg32_t *)(EMAC_BASE +  EMAC_NSR_OFF)))  ///< Network Status register address.
+// Not in sam7x
+//#define EMAC_LINKR                         0  ///< .
+#define EMAC_MDIO                            1  ///< Status of MDIO input pin.
+#define EMAC_IDLE                            2  ///< Set when PHY is running.
+/* \} */
+
+/**
+ * Transmit Status Register
+ */
+/* \{ */
+#define EMAC_TSR_OFF                0x00000014  ///< Transmit Status register offset.
+#define EMAC_TSR    (*((reg32_t *)(EMAC_BASE +  EMAC_TSR_OFF)))  ///< Transmit Status register address.
+
+#define EMAC_UBR                             0  ///< Used bit read.
+#define EMAC_COL                             1  ///< Collision occurred.
+#define EMAC_RLES                            2  ///< Retry limit exceeded.
+#define EMAC_TGO                             3  ///< Transmit active.
+#define EMAC_BEX                             4  ///< Buffers exhausted mid frame.
+#define EMAC_COMP                            5  ///< Transmit complete.
+#define EMAC_UND                             6  ///< Transmit underrun.
+/* \} */
+
+/**
+ * Buffer Queue Pointer Register
+ *
+ */
+/* \{ */
+#define EMAC_RBQP_OFF               0x00000018  ///< Receive buffer queue pointer.
+#define EMAC_RBQP   (*((reg32_t *)(EMAC_BASE +  EMAC_RBQP_OFF))) ///< Receive buffer queue pointer.
+#define EMAC_TBQP_OFF               0x0000001C  ///< Transmit buffer queue pointer.
+#define EMAC_TBQP   (*((reg32_t *)(EMAC_BASE +  EMAC_TBQP_OFF))) ///< Transmit buffer queue pointer.
+/* \} */
+
+/**
+ * Receive Status Register
+ */
+/* \{ */
+#define EMAC_RSR_OFF                0x00000020  ///< Receive status register offset.
+#define EMAC_RSR    (*((reg32_t *)(EMAC_BASE +  EMAC_RSR_OFF)))  ///< Receive status register address.
+#define EMAC_BNA                             0  ///< Buffer not available.
+#define EMAC_REC                             1  ///< Frame received.
+#define EMAC_OVR                             2  ///< Receive overrun.
+/* \} */
+
+/** Interrupt Registers */
+/* \{ */
+#define EMAC_ISR_OFF                0x00000024  ///< Status register offset.
+#define EMAC_ISR    (*((reg32_t *)(EMAC_BASE +  EMAC_ISR_OFF)))  ///< Status register address.
+#define EMAC_IER_OFF                0x00000028  ///< Enable register offset.
+#define EMAC_IER    (*((reg32_t *)(EMAC_BASE +  EMAC_IER_OFF)))  ///< Enable register address.
+#define EMAC_IDR_OFF                0x0000002C  ///< Disable register offset.
+#define EMAC_IDR    (*((reg32_t *)(EMAC_BASE +  EMAC_IDR_OFF)))  ///< Disable register address.
+#define EMAC_IMR_OFF                0x00000030  ///< Mask register offset.
+#define EMAC_IMR    (*((reg32_t *)(EMAC_BASE +  EMAC_IMR_OFF)))  ///< Mask register address.
+
+#define EMAC_MFD                             0  ///< Management frame done.
+#define EMAC_RCOMP                           1  ///< Receive complete.
+#define EMAC_RXUBR                           2  ///< Receive used bit read.
+#define EMAC_TXUBR                           3  ///< Transmit used bit read.
+#define EMAC_TUND                            4  ///< Ethernet transmit buffer underrun.
+#define EMAC_RLEX                            5  ///< Retry limit exceeded.
+#define EMAC_TXERR                           6  ///< Transmit error.
+#define EMAC_TCOMP                           7  ///< Transmit complete.
+//Not in sam7x
+//#define EMAC_LINK                          8  ///< .
+#define EMAC_ROVR                           10  ///< Receive overrun.
+#define EMAC_HRESP                          11  ///< DMA bus error.
+#define EMAC_PFR                            12  ///< Pause frame received.
+#define EMAC_PTZ                            13  ///< Pause time zero.
+/* \} */
+
+/**
+ * PHY Maintenance Register
+ *
+ */
+/* \{ */
+#define EMAC_MAN_OFF                0x00000034  ///< PHY maintenance register offset.
+#define EMAC_MAN    (*((reg32_t *)(EMAC_BASE +  EMAC_MAN_OFF)))  ///< PHY maintenance register address.
+#define EMAC_DATA                   0x0000FFFF  ///< PHY data mask.
+#define EMAC_CODE                   0x00020000  ///< Fixed value.
+#define EMAC_REGA                   0x007C0000  ///< PHY register address mask.
+#define EMAC_REGA_SHIFT                     18  ///< PHY register address mask.
+#define EMAC_PHYA                   0x0F800000  ///< PHY address mask.
+#define EMAC_PHYA_SHIFT                     23  ///< PHY address mask.
+#define EMAC_RW                     0x30000000  ///< PHY read/write command mask.
+#define EMAC_RW_READ                0x20000000  ///< PHY read command.
+#define EMAC_RW_WRITE               0x10000000  ///< PHY write command.
+#define EMAC_SOF                    0x40000000  ///< Fixed value.
+/* \} */
+
+/**
+ * Pause Time Register
+ *
+ */
+/* \{ */
+#define EMAC_PTR_OFF                0x00000038  ///< Pause time register offset.
+#define EMAC_PTR    (*((reg32_t *)(EMAC_BASE +  EMAC_PTR_OFF)))  ///< Pause time register address.
+#define EMAC_PTIME                  0x0000FFFF  ///< Pause time mask.
+/* \} */
+
+/**
+ * Statistics Registers
+ */
+/* \{ */
+#define EMAC_PFRR_OFF               0x0000003C  ///< Pause frames received register offset.
+#define EMAC_PFRR  (*((reg32_t *)(EMAC_BASE +  EMAC_PFRR_OFF)))  ///< Pause frames received register address.
+#define EMAC_FTO_OFF                0x00000040  ///< Frames transmitted OK register offset.
+#define EMAC_FTO    (*((reg32_t *)(EMAC_BASE +  EMAC_FTO_OFF)))  ///< Frames transmitted OK register address.
+#define EMAC_SCF_OFF                0x00000044  ///< Single collision frame register offset.
+#define EMAC_SCF    (*((reg32_t *)(EMAC_BASE +  EMAC_SCF_OFF)))  ///< Single collision frame register address.
+#define EMAC_MCF_OFF                0x00000048  ///< Multiple collision frame register offset.
+#define EMAC_MCF    (*((reg32_t *)(EMAC_BASE +  EMAC_MCF_OFF)))  ///< Multiple collision frame register address.
+#define EMAC_FRO_OFF                0x0000004C  ///< Frames received OK register offset.
+#define EMAC_FRO    (*((reg32_t *)(EMAC_BASE +  EMAC_FRO_OFF)))  ///< Frames received OK register address.
+#define EMAC_FCSE_OFF               0x00000050  ///< Frame check sequence error register offset.
+#define EMAC_FCSE   (*((reg32_t *)(EMAC_BASE +  EMAC_FCSE_OFF))) ///< Frame check sequence error register address.
+#define EMAC_ALE_OFF                0x00000054  ///< Alignment error register offset.
+#define EMAC_ALE    (*((reg32_t *)(EMAC_BASE +  EMAC_ALE_OFF)))  ///< Alignment error register address.
+#define EMAC_DTF_OFF                0x00000058  ///< Deferred transmission frame register offset.
+#define EMAC_DTF    (*((reg32_t *)(EMAC_BASE +  EMAC_DTF_OFF)))  ///< Deferred transmission frame register address.
+#define EMAC_LCOL_OFF               0x0000005C  ///< Late collision register offset.
+#define EMAC_LCOL   (*((reg32_t *)(EMAC_BASE +  EMAC_LCOL_OFF))) ///< Late collision register address.
+#define EMAC_ECOL_OFF               0x00000060  ///< Excessive collision register offset.
+#define EMAC_ECOL   (*((reg32_t *)(EMAC_BASE +  EMAC_ECOL_OFF))) ///< Excessive collision register address.
+#define EMAC_TUNDR_OFF              0x00000064  ///< Transmit underrun error register offset.
+#define EMAC_TUNDR (*((reg32_t *)(EMAC_BASE +  EMAC_TUNDR_OFF))) ///< Transmit underrun error register address.
+#define EMAC_CSE_OFF                0x00000068  ///< Carrier sense error register offset.
+#define EMAC_CSE    (*((reg32_t *)(EMAC_BASE +  EMAC_CSE_OFF)))  ///< Carrier sense error register address.
+#define EMAC_RRE_OFF                0x0000006C  ///< Receive resource error register offset.
+#define EMAC_RRE    (*((reg32_t *)(EMAC_BASE +  EMAC_RRE_OFF)))  ///< Receive resource error register address.
+#define EMAC_ROV_OFF                0x00000070  ///< Receive overrun errors register offset.
+#define EMAC_ROV    (*((reg32_t *)(EMAC_BASE +  EMAC_ROV_OFF)))  ///< Receive overrun errors register address.
+#define EMAC_RSE_OFF                0x00000074  ///< Receive symbol errors register offset.
+#define EMAC_RSE    (*((reg32_t *)(EMAC_BASE +  EMAC_RSE_OFF)))  ///< Receive symbol errors register address.
+#define EMAC_ELE_OFF                0x00000078  ///< Excessive length errors register offset.
+#define EMAC_ELE    (*((reg32_t *)(EMAC_BASE +  EMAC_ELE_OFF)))  ///< Excessive length errors register address.
+#define EMAC_RJA_OFF                0x0000007C  ///< Receive jabbers register offset.
+#define EMAC_RJA    (*((reg32_t *)(EMAC_BASE +  EMAC_RJA_OFF)))  ///< Receive jabbers register address.
+#define EMAC_USF_OFF                0x00000080  ///< Undersize frames register offset.
+#define EMAC_USF    (*((reg32_t *)(EMAC_BASE +  EMAC_USF_OFF)))  ///< Undersize frames register address.
+#define EMAC_STE_OFF                0x00000084  ///< SQE test error register offset.
+#define EMAC_STE    (*((reg32_t *)(EMAC_BASE +  EMAC_STE_OFF)))  ///< SQE test error register address.
+#define EMAC_RLE_OFF                0x00000088  ///< Receive length field mismatch register offset.
+#define EMAC_RLE    (*((reg32_t *)(EMAC_BASE +  EMAC_RLE_OFF)))  ///< Receive length field mismatch register address.
+// Not in sam7x
+//#define EMAC_TPF_OFF                0x0000008C  ///< Transmitted pause frames register offset.
+//#define EMAC_TPF    (*((reg32_t *)(EMAC_BASE +  EMAC_TPF_OFF)  ///< Transmitted pause frames register address.
+/* \} */
+
+/**
+ * MAC Adressing Registers
+ *
+ */
+/* \{ */
+#define EMAC_HRB_OFF                0x00000090  ///< Hash address bottom[31:0].
+#define EMAC_HRB    (*((reg32_t *)(EMAC_BASE +  EMAC_HRB_OFF)))  ///< Hash address bottom[31:0].
+#define EMAC_HRT_OFF                0x00000094  ///< Hash address top[63:32].
+#define EMAC_HRT    (*((reg32_t *)(EMAC_BASE +  EMAC_HRT_OFF)))  ///< Hash address top[63:32].
+#define EMAC_SA1L_OFF               0x00000098  ///< Specific address 1 bottom, first 4 bytes.
+#define EMAC_SA1L   (*((reg32_t *)(EMAC_BASE +  EMAC_SA1L_OFF))) ///< Specific address 1 bottom, first 4 bytes.
+#define EMAC_SA1H_OFF               0x0000009C  ///< Specific address 1 top, last 2 bytes.
+#define EMAC_SA1H   (*((reg32_t *)(EMAC_BASE +  EMAC_SA1H_OFF))) ///< Specific address 1 top, last 2 bytes.
+#define EMAC_SA2L_OFF               0x000000A0  ///< Specific address 2 bottom, first 4 bytes.
+#define EMAC_SA2L   (*((reg32_t *)(EMAC_BASE +  EMAC_SA2L_OFF))) ///< Specific address 2 bottom, first 4 bytes.
+#define EMAC_SA2H_OFF               0x000000A4  ///< Specific address 2 top, last 2 bytes.
+#define EMAC_SA2H   (*((reg32_t *)(EMAC_BASE +  EMAC_SA2H_OFF))) ///< Specific address 2 top, last 2 bytes.
+#define EMAC_SA3L_OFF               0x000000A8  ///< Specific address 3 bottom, first 4 bytes.
+#define EMAC_SA3L   (*((reg32_t *)(EMAC_BASE +  EMAC_SA3L_OFF))) ///< Specific address 3 bottom, first 4 bytes.
+#define EMAC_SA3H_OFF               0x000000AC  ///< Specific address 3 top, last 2 bytes.
+#define EMAC_SA3H   (*((reg32_t *)(EMAC_BASE +  EMAC_SA3H_OFF))) ///< Specific address 3 top, last 2 bytes.
+#define EMAC_SA4L_OFF               0x000000B0  ///< Specific address 4 bottom, first 4 bytes.
+#define EMAC_SA4L   (*((reg32_t *)(EMAC_BASE +  EMAC_SA4L_OFF))) ///< Specific address 4 bottom, first 4 bytes.
+#define EMAC_SA4H_OFF               0x000000B4  ///< Specific address 4 top, last 2 bytes.
+#define EMAC_SA4H   (*((reg32_t *)(EMAC_BASE +  EMAC_SA4H_OFF))) ///< Specific address 4 top, last 2 bytes.
+/* \} */
+
+/**
+ * Type ID Register
+ *
+ */
+/* \{ */
+#define EMAC_TID_OFF                0x000000B8  ///< Type ID checking register offset.
+#define EMAC_TID    (*((reg32_t *)(EMAC_BASE +  EMAC_TID_OFF))) ///< Type ID checking register address.
+// Not in sam7x
+//#define EMAC_TPQ_OFF                0x000000BC  ///< Transmit pause quantum register offset.
+//#define EMAC_TPQ    (*((reg32_t *)(EMAC_BASE +  EMAC_TPQ_OFF)))  ///< Transmit pause quantum register address.
+/* \} */
+
+/**
+ * User Input/Output Register
+ *
+ */
+/* \{ */
+#define EMAC_USRIO_OFF              0x000000C0  ///< User input/output register offset.
+#define EMAC_USRIO (*((reg32_t *)(EMAC_BASE +  EMAC_USRIO_OFF))) ///< User input/output register address.
+
+#define EMAC_RMII                            0  ///< Enable reduced MII.
+#define EMAC_CLKEN                           1  ///< Enable tranceiver input clock.
+/* \} */
+
+// Not in sam7x
+/*
+ * Wake On LAN Register
+ *
+ *
+* \{ *
+#define EMAC_WOL_OFF                0x000000C4  ///< Wake On LAN register offset.
+#define EMAC_WOL    (*((reg32_t *)(EMAC_BASE +  EMAC_WOL_OFF)  ///< Wake On LAN register address.
+#define EMAC_IP                     0x0000FFFF  ///< ARP request IP address mask.
+#define EMAC_MAG                    0x00010000  ///< Magic packet event enable.
+#define EMAC_ARP                    0x00020000  ///< ARP request event enable.
+#define EMAC_SA1                    0x00040000  ///< Specific address register 1 event enable.
+* \} *
+
+** Revision Register *
+* \{ *
+#define EMAC_REV_OFF                0x000000FC  ///< Revision register offset.
+#define EMAC_REV    (*((reg32_t *)(EMAC_BASE +  EMAC_REV_OFF)  ///< Revision register address.
+#define EMAC_REVREF                 0x0000FFFF  ///< Revision.
+#define EMAC_PARTREF                0xFFFF0000  ///< Part.
+* \} *
+*/
+
+#endif /* AT91_EMAC_H */
index 0bf835f630c0c2bfe66b2d2a1476150b332a1d6a..5388df0a214cd499847b4ffece7105d4bc7037d0 100644 (file)
 #include "at91_spi.h"
 #include "at91_twi.h"
 #include "at91_ssc.h"
+#include "at91_emac.h"
 //TODO: add other peripherals
 
 /**