From 903d775d32042e666f0266039ad63403e17b5fb9 Mon Sep 17 00:00:00 2001 From: Juergen Beisert Date: Thu, 8 Nov 2007 16:24:51 +0100 Subject: adding first clean mx27 only fec driver --- board/phycore_pcm038/pcm038.c | 6 +- drivers/net/Kconfig | 7 +- drivers/net/Makefile | 1 + drivers/net/fec_imx27.c | 654 +++++++++++++++++++++++++++++++++++++ drivers/net/fec_imx27.h | 336 +++++++++++++++++++ include/asm-ppc/arch-mpc5200/fec.h | 14 - include/fec.h | 44 +++ 7 files changed, 1044 insertions(+), 18 deletions(-) create mode 100644 drivers/net/fec_imx27.c create mode 100644 drivers/net/fec_imx27.h delete mode 100644 include/asm-ppc/arch-mpc5200/fec.h create mode 100644 include/fec.h diff --git a/board/phycore_pcm038/pcm038.c b/board/phycore_pcm038/pcm038.c index 9b1f0e3761..99cbc5eec4 100644 --- a/board/phycore_pcm038/pcm038.c +++ b/board/phycore_pcm038/pcm038.c @@ -24,7 +24,7 @@ #include #include #include -#include +#include #include #include #include @@ -48,12 +48,12 @@ static struct device_d sdram_dev = { .type = DEVICE_TYPE_DRAM, }; -static struct mpc5xxx_fec_platform_data fec_info = { +static struct fec_platform_data fec_info = { .xcv_type = MII100, }; static struct device_d fec_dev = { - .name = "fec_mpc5xxx", + .name = "fec_imx27", .id = "eth0", .map_base = 0x1002b000, .platform_data = &fec_info, diff --git a/drivers/net/Kconfig b/drivers/net/Kconfig index 0c88ef0053..372f02dc12 100644 --- a/drivers/net/Kconfig +++ b/drivers/net/Kconfig @@ -49,7 +49,12 @@ config DRIVER_NET_AT91_ETHER config DRIVER_NET_MPC5200 bool "MPC5200 Ethernet driver" - depends on ARCH_MPC5200 || ARCH_IMX27 + depends on ARCH_MPC5200 + select MIIPHY + +config DRIVER_NET_IMX27 + bool "i.MX27 Ethernet driver" + depends on ARCH_IMX27 select MIIPHY config DRIVER_NET_TAP diff --git a/drivers/net/Makefile b/drivers/net/Makefile index b5e1b76258..cc48a27e52 100644 --- a/drivers/net/Makefile +++ b/drivers/net/Makefile @@ -4,5 +4,6 @@ obj-$(CONFIG_DRIVER_NET_DM9000) += dm9000.o obj-$(CONFIG_DRIVER_NET_NETX) += netx_eth.o obj-$(CONFIG_DRIVER_NET_AT91_ETHER) += at91_ether.o obj-$(CONFIG_DRIVER_NET_MPC5200) += fec_mpc5200.o +obj-$(CONFIG_DRIVER_NET_IMX27) += fec_imx27.o obj-$(CONFIG_DRIVER_NET_TAP) += tap.o obj-$(CONFIG_MIIPHY) += miiphy.o diff --git a/drivers/net/fec_imx27.c b/drivers/net/fec_imx27.c new file mode 100644 index 0000000000..2a9368f806 --- /dev/null +++ b/drivers/net/fec_imx27.c @@ -0,0 +1,654 @@ +/* + * (C) Copyright 2007 Pengutronix, Sascha Hauer + * (C) Copyright 2007 Pengutronix, Juergen Beisert + * + * This program 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., 59 Temple Place, Suite 330, Boston, + * MA 02111-1307 USA + */ + +#define DEBUG + +#include +#include +#include +#include +#include +#include +#include +#include +#include "fec_imx27.h" + +#include +#include +#include +#include +#include + +#define CONFIG_PHY_ADDR 1 /* FIXME */ + +typedef struct { + uint8_t data[1500]; /* actual data */ + int length; /* actual length */ + int used; /* buffer in use or not */ + uint8_t head[16]; /* MAC header(6 + 6 + 2) + 2(aligned) */ +} NBUF; + +/* + * MII-interface related functions + */ +static int fec_miiphy_read(struct miiphy_device *mdev, uint8_t phyAddr, + uint8_t regAddr, uint16_t * retVal) +{ + struct eth_device *edev = mdev->edev; + fec_priv *fec = (fec_priv *)edev->priv; + + uint32_t reg; /* convenient holder for the PHY register */ + uint32_t phy; /* convenient holder for the PHY */ + uint64_t start; + + /* + * reading from any PHY's register is done by properly + * programming the FEC's MII data register. + */ + writel(FEC_IEVENT_MII, &fec->eth->ievent); + reg = regAddr << FEC_MII_DATA_RA_SHIFT; + phy = phyAddr << FEC_MII_DATA_PA_SHIFT; + + writel(FEC_MII_DATA_ST | FEC_MII_DATA_OP_RD | FEC_MII_DATA_TA | phy | reg, &fec->eth->mii_data); + + /* + * wait for the related interrupt + */ + start = get_time_ns(); + while (!(readl(&fec->eth->ievent) & FEC_IEVENT_MII)) { + if (is_timeout(start, MSECOND)) { + printf("Read MDIO failed...\n"); + return -1; + } + } + + /* + * clear mii interrupt bit + */ + writel(FEC_IEVENT_MII, &fec->eth->ievent); + + /* + * it's now safe to read the PHY's register + */ + *retVal = readl(&fec->eth->mii_data); + + return 0; +} + +static int fec_miiphy_write(struct miiphy_device *mdev, uint8_t phyAddr, + uint8_t regAddr, uint16_t data) +{ + struct eth_device *edev = mdev->edev; + fec_priv *fec = (fec_priv *)edev->priv; + + uint32_t reg; /* convenient holder for the PHY register */ + uint32_t phy; /* convenient holder for the PHY */ + uint64_t start; + + reg = regAddr << FEC_MII_DATA_RA_SHIFT; + phy = phyAddr << FEC_MII_DATA_PA_SHIFT; + + writel(FEC_MII_DATA_ST | FEC_MII_DATA_OP_WR | + FEC_MII_DATA_TA | phy | reg | data, &fec->eth->mii_data); + + /* + * wait for the MII interrupt + */ + start = get_time_ns(); + while (!(readl(&fec->eth->ievent) & FEC_IEVENT_MII)) { + if (is_timeout(start, MSECOND)) { + printf("Write MDIO failed...\n"); + return -1; + } + } + + /* + * clear MII interrupt bit + */ + writel(FEC_IEVENT_MII, &fec->eth->ievent); + + return 0; +} + +static int fec_rx_task_enable(fec_priv *fec) +{ + writel(1 << 24, &fec->eth->r_des_active); + return 0; +} + +static int fec_rx_task_disable(fec_priv *fec) +{ + return 0; +} + +static int fec_tx_task_enable(fec_priv *fec) +{ + writel(1 << 24, &fec->eth->x_des_active); + return 0; +} + +static int fec_tx_task_disable(fec_priv *fec) +{ + return 0; +} + +/** + * Initialize receive task's buffer descriptors + * @param[in] fec all we know about the device yet + * @param[in] count receive buffer count to be allocated + * @param[in] size size of each receive buffer + * @return 0 on success + * + * For this task we need additional memory for the data buffers. And each + * data buffer requires some alignment. Thy must be aligned to a specific + * boundary each (4 byte). + */ +static int fec_rbd_init(fec_priv *fec, int count, int size) +{ + int ix; + static int once = 0; + uint32_t p=0; + + if (!once) { + /* reserve data memory and consider alignment */ + p = (uint32_t)xzalloc(size * count + 0x04) + 0x03; + p &= ~0x03; + } + + for (ix = 0; ix < count; ix++) { + if (!once) { + writel(p, &fec->rbd_base[ix].data_pointer); + p += size; + } + writew(FEC_RBD_EMPTY, &fec->rbd_base[ix].status); + writew(0, &fec->rbd_base[ix].data_length); + } + once = 1; /* malloc done now (and once) */ + /* + * mark the last RBD to close the ring + */ + writew(FEC_RBD_WRAP | FEC_RBD_EMPTY, &fec->rbd_base[ix - 1].status); + fec->rbd_index = 0; + + return 0; +} + +/** + * Initialize transmit task's buffer descriptors + * @param[in] fec all we know about the device yet + * + * Transmit buffers are created externally. We only have to init the BDs here. + * Note: There is a race condition in the hardware. When only one BD is in + * use it must be marked with the WRAP bit to use it for every transmitt. + * This bit in combination with the READY bit results into double transmit + * of each data buffer. It seems the state machine checks READY earlier then + * resetting it after the first transfer. + * Using two BDs solves this issue. + */ +static void fec_tbd_init(fec_priv *fec) +{ + writew(0x0000, &fec->tbd_base[0].status); + writew(FEC_TBD_WRAP, &fec->tbd_base[1].status); + fec->tbd_index = 0; +} + +/** + * Mark the given read buffer descriptor as free + * @param[in] last 1 if this is the last buffer descriptor in the chain, else 0 + * @param[in] pRbd buffer descriptor to mark free again + */ +static void fec_rbd_clean(int last, FEC_BD *pRbd) +{ + /* + * Reset buffer descriptor as empty + */ + if (last) + writew(FEC_RBD_WRAP | FEC_RBD_EMPTY, &pRbd->status); + else + writew(FEC_RBD_EMPTY, &pRbd->status); + /* + * no data in it + */ + writew(0, &pRbd->data_length); +} + +static int fec_get_hwaddr(struct eth_device *dev, unsigned char *mac) +{ + /* no eeprom */ + return -1; +} + +static int fec_set_hwaddr(struct eth_device *dev, unsigned char *mac) +{ + fec_priv *fec = (fec_priv *)dev->priv; +//#define WTF_IS_THIS +#ifdef WTF_IS_THIS + uint32_t crc = 0xffffffff; /* initial value */ + uint8_t currByte; /* byte for which to compute the CRC */ + int byte; /* loop - counter */ + int bit; /* loop - counter */ + + /* + * The algorithm used is the following: + * we loop on each of the six bytes of the provided address, + * and we compute the CRC by left-shifting the previous + * value by one position, so that each bit in the current + * byte of the address may contribute the calculation. If + * the latter and the MSB in the CRC are different, then + * the CRC value so computed is also ex-ored with the + * "polynomium generator". The current byte of the address + * is also shifted right by one bit at each iteration. + * This is because the CRC generatore in hardware is implemented + * as a shift-register with as many ex-ores as the radixes + * in the polynomium. This suggests that we represent the + * polynomiumm itself as a 32-bit constant. + */ + for (byte = 0; byte < 6; byte++) { + currByte = mac[byte]; + for (bit = 0; bit < 8; bit++) { + if ((currByte & 0x01) ^ (crc & 0x01)) { + crc >>= 1; + crc = crc ^ 0xedb88320; + } else { + crc >>= 1; + } + currByte >>= 1; + } + } + + crc = crc >> 26; + + /* + * Set individual hash table register + */ + if (crc >= 32) { + fec->eth->iaddr1 = (1 << (crc - 32)); + fec->eth->iaddr2 = 0; + } else { + fec->eth->iaddr1 = 0; + fec->eth->iaddr2 = (1 << crc); + } +#else + writel(0, &fec->eth->iaddr1); + writel(0, &fec->eth->iaddr2); + writel(0, &fec->eth->gaddr1); + writel(0, &fec->eth->gaddr2); +#endif + /* + * Set physical address + */ + writel((mac[0] << 24) + (mac[1] << 16) + (mac[2] << 8) + mac[3], &fec->eth->paddr1); + writel((mac[4] << 24) + (mac[5] << 16) + 0x8808, &fec->eth->paddr2); + + return 0; +} + +static int fec_init(struct eth_device *dev) +{ + fec_priv *fec = (fec_priv *)dev->priv; + + /* + * Initialize RxBD/TxBD rings + */ + fec_rbd_init(fec, FEC_RBD_NUM, FEC_MAX_PKT_SIZE); + fec_tbd_init(fec); + + /* + * Clear FEC-Lite interrupt event register(IEVENT) + */ + writel(0xffffffff, &fec->eth->ievent); + + /* + * Set interrupt mask register + */ + writel(0x00000000, &fec->eth->imask); + + /* + * Set FEC-Lite receive control register(R_CNTRL): + */ + if (fec->xcv_type == SEVENWIRE) { + /* + * Frame length=1518; 7-wire mode + */ + writel(0x05ee0020, &fec->eth->r_cntrl); /* FIXME 0x05ee0000 */ + } else { + /* + * Frame length=1518; MII mode; + */ + writel(0x05ee0024, &fec->eth->r_cntrl); /* FIXME 0x05ee0004 */ + + /* + * Set MII_SPEED = (1/(mii_speed * 2)) * System Clock + * and do not drop the Preamble. + */ + writel(((imx_get_ahbclk() >> 20) / 5) << 1, &fec->eth->mii_speed); /* No MII for 7-wire mode */ + } + + /* + * Set Opcode/Pause Duration Register + */ + writel(0x00010020, &fec->eth->op_pause); /* FIXME 0xffff0020; */ + + writel(0x2, &fec->eth->x_wmrk); + + /* + * Set multicast address filter + */ + writel(0x00000000, &fec->eth->gaddr1); + writel(0x00000000, &fec->eth->gaddr2); + + /* size of each buffer */ + writel(2048-16, &fec->eth->emrbr); /* ???????????????????? */ + + if (fec->xcv_type != SEVENWIRE) + miiphy_restart_aneg(&fec->miiphy); + + return 0; +} + +/** + * Start the FEC engine + * @param[in] dev Our device to handle + */ +static int fec_open(struct eth_device *edev) +{ + fec_priv *fec = (fec_priv *)edev->priv; + + writel(1 << 2, &fec->eth->x_cntrl); /* full-duplex, heartbeat disabled */ + + fec->rbd_index = 0; + + /* + * Enable FEC-Lite controller + */ + writel(FEC_ECNTRL_ETHER_EN, &fec->eth->ecntrl); + /* + * Enable SmartDMA receive task + */ + fec_rx_task_enable(fec); + + if (fec->xcv_type != SEVENWIRE) { + miiphy_wait_aneg(&fec->miiphy); + miiphy_print_status(&fec->miiphy); + } + + return 0; +} + +/** + * Halt the FEC engine + * @param[in] dev Our device to handle + */ +static void fec_halt(struct eth_device *dev) +{ + fec_priv *fec = (fec_priv *)dev->priv; + int counter = 0xffff; + + /* + * issue graceful stop command to the FEC transmitter if necessary + */ + writel(FEC_ECNTRL_RESET | readl(&fec->eth->x_cntrl), &fec->eth->x_cntrl); + + /* + * wait for graceful stop to register + */ + while ((counter--) && (!(readl(&fec->eth->ievent) & FEC_IEVENT_GRA))) + ; /* FIXME ensure time */ + + /* + * Disable SmartDMA tasks + */ + fec_tx_task_disable(fec); + fec_rx_task_disable(fec); + + /* + * Disable the Ethernet Controller + * Note: this will also reset the BD index counter! + */ + writel(0, &fec->eth->ecntrl); + fec->rbd_index = 0; + fec->tbd_index = 0; +} + +/** + * Transmit one frame + * @param[in] dev Our ethernet device to handle + * @param[in] eth_data Pointer to the data to be transmitted + * @param[in] data_length Data count in bytes + * @return 0 on success + */ +static int fec_send(struct eth_device *dev, void *eth_data, int data_length) +{ + unsigned int status; + + /* + * This routine transmits one frame. This routine only accepts + * 6-byte Ethernet addresses. + */ + fec_priv *fec = (fec_priv *)dev->priv; + + /* + * Check for valid length of data. + */ + if ((data_length > 1500) || (data_length <= 0)) { + printf("Payload (%d) to large!\n"); + return -1; + } + + if ((uint32_t)eth_data & 0x0F) { + printf("%s: Warning: Transmitt data not aligned!\n", __FUNCTION__); + } + /* + * Setup the transmitt buffer + * Note: We are always using the first buffer for transmission, + * the second will be empty and only used to stop the DMA engine + */ + writew(data_length, &fec->tbd_base[fec->tbd_index].data_length); + writel((uint32_t)eth_data, &fec->tbd_base[fec->tbd_index].data_pointer); + /* + * update BD's status now + * This block: + * - is always the last in a chain (means no chain) + * - should transmitt the CRC + * - might be the last BD in the list, so the address counter should + * wrap (-> keep the WRAP flag) + */ + status = readw(&fec->tbd_base[fec->tbd_index].status) & FEC_TBD_WRAP; + status |= FEC_TBD_LAST | FEC_TBD_TC | FEC_TBD_READY; + writew(status, &fec->tbd_base[fec->tbd_index].status); + /* + * Enable SmartDMA transmit task + */ + fec_tx_task_enable(fec); + + /* + * wait until frame is sent . + */ + while (readw(&fec->tbd_base[fec->tbd_index].status) & FEC_TBD_READY) { + /* FIXME: Timeout */ + } + + /* for next transmission use the other buffer */ + if (fec->tbd_index) + fec->tbd_index = 0; + else + fec->tbd_index = 1; + + return 0; +} + +/** + * Pull one frame from the card + * @param[in] dev Our ethernet device to handle + * @return Length of packet read + */ +static int fec_recv(struct eth_device *dev) +{ + fec_priv *fec = (fec_priv *)dev->priv; + FEC_BD *rbd = &fec->rbd_base[fec->rbd_index]; + unsigned long ievent; + int frame_length, len = 0; + NBUF *frame; + uint16_t bd_status; + uchar buff[FEC_MAX_PKT_SIZE]; + + /* + * Check if any critical events have happened + */ + ievent = readl(&fec->eth->ievent); + writel(ievent, &fec->eth->ievent); + if (ievent & (FEC_IEVENT_BABT | FEC_IEVENT_XFIFO_ERROR | + FEC_IEVENT_RFIFO_ERROR)) { + /* BABT, Rx/Tx FIFO errors */ + fec_halt(dev); + fec_init(dev); + printf("some error: 0x%08x\n", ievent); + return 0; + } + if (ievent & FEC_IEVENT_HBERR) { + /* Heartbeat error */ + writel(0x00000001 | readl(&fec->eth->x_cntrl), &fec->eth->x_cntrl); + } + if (ievent & FEC_IEVENT_GRA) { + /* Graceful stop complete */ + if (readl(&fec->eth->x_cntrl) & 0x00000001) { + fec_halt(dev); + writel(~0x00000001 & readl(&fec->eth->x_cntrl), &fec->eth->x_cntrl); + fec_init(dev); + } + } + + /* + * ensure reading the right buffer status + */ + bd_status = readw(&rbd->status); + + if (!(bd_status & FEC_RBD_EMPTY)) { + if ((bd_status & FEC_RBD_LAST) && !(bd_status & FEC_RBD_ERR) && + ((readw(&rbd->data_length) - 4) > 14)) { + /* + * Get buffer address and size + */ + frame = (NBUF *)readl(&rbd->data_pointer); + frame_length = readw(&rbd->data_length) - 4; + /* + * Fill the buffer and pass it to upper layers + */ + memcpy(buff, frame->data, frame_length); + NetReceive(buff, frame_length); + len = frame_length; + } else { + if (bd_status & FEC_RBD_ERR) { + printf("error frame: 0x%08x 0x%08x\n", rbd, bd_status); + } + } + /* + * free the current buffer, restart the engine + * and move forward to the next buffer + */ + fec_rbd_clean(fec->rbd_index == (FEC_RBD_NUM - 1) ? 1 : 0, rbd); + fec_rx_task_enable(fec); + fec->rbd_index = (fec->rbd_index + 1) % FEC_RBD_NUM; + } + + return len; +} + +int fec_probe(struct device_d *dev) +{ + struct fec_platform_data *pdata = (struct fec_platform_data *)dev->platform_data; + struct eth_device *edev; + fec_priv *fec; + uint32_t base; + + PCCR0 |= PCCR0_FEC_EN; + edev = (struct eth_device *)malloc(sizeof(struct eth_device)); + dev->type_data = edev; + fec = (fec_priv*)malloc(sizeof(*fec)); + edev->priv = fec; + edev->dev = dev; + edev->open = fec_open, + edev->init = fec_init, + edev->send = fec_send, + edev->recv = fec_recv, + edev->halt = fec_halt, + edev->get_ethaddr = fec_get_hwaddr, + edev->set_ethaddr = fec_set_hwaddr, + + fec->eth = (ethernet_regs *)dev->map_base; + + /* Reset chip. */ + writel(FEC_ECNTRL_RESET, &fec->eth->ecntrl); + while(readl(&fec->eth->ecntrl) & 1) { + udelay(10); + } + + /* + * reserve memory for both buffer descriptor chains at once + * Datasheet forces the startaddress of each chain is 16 byte aligned + */ + base = (uint32_t)xzalloc( (2 + FEC_RBD_NUM) * sizeof(FEC_BD) + 0x20 ); + base += 0x0f; + base &= ~0x0f; + fec->rbd_base = (FEC_BD*)base; + base += FEC_RBD_NUM * sizeof(FEC_BD) + 0x0f; + base &= ~0x0f; + fec->tbd_base = (FEC_BD*)base; + + writel((uint32_t)fec->tbd_base, &fec->eth->etdsr); + writel((uint32_t)fec->rbd_base, &fec->eth->erdsr); + + fec->xcv_type = pdata->xcv_type; + + sprintf(dev->name, "FEC ETHERNET"); + + if (fec->xcv_type != SEVENWIRE) { + fec->miiphy.read = fec_miiphy_read; + fec->miiphy.write = fec_miiphy_write; + fec->miiphy.address = CONFIG_PHY_ADDR; + fec->miiphy.flags = pdata->xcv_type == MII10 ? MIIPHY_FORCE_10 : 0; + fec->miiphy.edev = edev; + + miiphy_register(&fec->miiphy); + } + + eth_register(edev); + return 0; +} + +static struct driver_d imx27_driver = { + .name = "fec_imx27", + .probe = fec_probe, + .type = DEVICE_TYPE_ETHER, +}; + +static int fec_register(void) +{ + register_driver(&imx27_driver); + return 0; +} + +device_initcall(fec_register); + +/** + * @file + * @brief Network driver for FreeScale's FEC implementation. + * This type of hardware can be found on i.MX27 CPUs + */ diff --git a/drivers/net/fec_imx27.h b/drivers/net/fec_imx27.h new file mode 100644 index 0000000000..b2c4436e1f --- /dev/null +++ b/drivers/net/fec_imx27.h @@ -0,0 +1,336 @@ +/* + * (C) Copyright 2003 + * Wolfgang Denk, DENX Software Engineering, wd@denx.de. + * + * This file is based on mpc4200fec.h + * (C) Copyright Motorola, Inc., 2000 + * + * odin ethernet header file + */ + +#ifndef __IMX27_FEC_H +#define __IMX27_FEC_H + +/* +typedef unsigned long uint32_t; +typedef unsigned short uint16_t; +typedef unsigned char uint8_t; +*/ + +/** + * Layout description of the FEC + */ +typedef struct ethernet_register_set { + +/* [10:2]addr = 00 */ + +/* Control and status Registers (offset 000-1FF) */ + + uint32_t fec_id; /* MBAR_ETH + 0x000 */ + uint32_t ievent; /* MBAR_ETH + 0x004 */ + uint32_t imask; /* MBAR_ETH + 0x008 */ + + uint32_t RES0[1]; /* MBAR_ETH + 0x00C */ + uint32_t r_des_active; /* MBAR_ETH + 0x010 */ + uint32_t x_des_active; /* MBAR_ETH + 0x014 */ + uint32_t r_des_active_cl; /* MBAR_ETH + 0x018 */ + uint32_t x_des_active_cl; /* MBAR_ETH + 0x01C */ + uint32_t ivent_set; /* MBAR_ETH + 0x020 */ + uint32_t ecntrl; /* MBAR_ETH + 0x024 */ + + uint32_t RES1[6]; /* MBAR_ETH + 0x028-03C */ + uint32_t mii_data; /* MBAR_ETH + 0x040 */ + uint32_t mii_speed; /* MBAR_ETH + 0x044 */ + uint32_t mii_status; /* MBAR_ETH + 0x048 */ + + uint32_t RES2[5]; /* MBAR_ETH + 0x04C-05C */ + uint32_t mib_data; /* MBAR_ETH + 0x060 */ + uint32_t mib_control; /* MBAR_ETH + 0x064 */ + + uint32_t RES3[6]; /* MBAR_ETH + 0x068-7C */ + uint32_t r_activate; /* MBAR_ETH + 0x080 */ + uint32_t r_cntrl; /* MBAR_ETH + 0x084 */ + uint32_t r_hash; /* MBAR_ETH + 0x088 */ + uint32_t r_data; /* MBAR_ETH + 0x08C */ + uint32_t ar_done; /* MBAR_ETH + 0x090 */ + uint32_t r_test; /* MBAR_ETH + 0x094 */ + uint32_t r_mib; /* MBAR_ETH + 0x098 */ + uint32_t r_da_low; /* MBAR_ETH + 0x09C */ + uint32_t r_da_high; /* MBAR_ETH + 0x0A0 */ + + uint32_t RES4[7]; /* MBAR_ETH + 0x0A4-0BC */ + uint32_t x_activate; /* MBAR_ETH + 0x0C0 */ + uint32_t x_cntrl; /* MBAR_ETH + 0x0C4 */ + uint32_t backoff; /* MBAR_ETH + 0x0C8 */ + uint32_t x_data; /* MBAR_ETH + 0x0CC */ + uint32_t x_status; /* MBAR_ETH + 0x0D0 */ + uint32_t x_mib; /* MBAR_ETH + 0x0D4 */ + uint32_t x_test; /* MBAR_ETH + 0x0D8 */ + uint32_t fdxfc_da1; /* MBAR_ETH + 0x0DC */ + uint32_t fdxfc_da2; /* MBAR_ETH + 0x0E0 */ + uint32_t paddr1; /* MBAR_ETH + 0x0E4 */ + uint32_t paddr2; /* MBAR_ETH + 0x0E8 */ + uint32_t op_pause; /* MBAR_ETH + 0x0EC */ + + uint32_t RES5[4]; /* MBAR_ETH + 0x0F0-0FC */ + uint32_t instr_reg; /* MBAR_ETH + 0x100 */ + uint32_t context_reg; /* MBAR_ETH + 0x104 */ + uint32_t test_cntrl; /* MBAR_ETH + 0x108 */ + uint32_t acc_reg; /* MBAR_ETH + 0x10C */ + uint32_t ones; /* MBAR_ETH + 0x110 */ + uint32_t zeros; /* MBAR_ETH + 0x114 */ + uint32_t iaddr1; /* MBAR_ETH + 0x118 */ + uint32_t iaddr2; /* MBAR_ETH + 0x11C */ + uint32_t gaddr1; /* MBAR_ETH + 0x120 */ + uint32_t gaddr2; /* MBAR_ETH + 0x124 */ + uint32_t random; /* MBAR_ETH + 0x128 */ + uint32_t rand1; /* MBAR_ETH + 0x12C */ + uint32_t tmp; /* MBAR_ETH + 0x130 */ + + uint32_t RES6[3]; /* MBAR_ETH + 0x134-13C */ + uint32_t fifo_id; /* MBAR_ETH + 0x140 */ + uint32_t x_wmrk; /* MBAR_ETH + 0x144 */ + uint32_t fcntrl; /* MBAR_ETH + 0x148 */ + uint32_t r_bound; /* MBAR_ETH + 0x14C */ + uint32_t r_fstart; /* MBAR_ETH + 0x150 */ + uint32_t r_count; /* MBAR_ETH + 0x154 */ + uint32_t r_lag; /* MBAR_ETH + 0x158 */ + uint32_t r_read; /* MBAR_ETH + 0x15C */ + uint32_t r_write; /* MBAR_ETH + 0x160 */ + uint32_t x_count; /* MBAR_ETH + 0x164 */ + uint32_t x_lag; /* MBAR_ETH + 0x168 */ + uint32_t x_retry; /* MBAR_ETH + 0x16C */ + uint32_t x_write; /* MBAR_ETH + 0x170 */ + uint32_t x_read; /* MBAR_ETH + 0x174 */ + + uint32_t RES7[2]; /* MBAR_ETH + 0x178-17C */ + uint32_t fm_cntrl; /* MBAR_ETH + 0x180 */ +#define erdsr fm_cntrl + uint32_t rfifo_data; /* MBAR_ETH + 0x184 */ +#define etdsr rfifo_data + uint32_t rfifo_status; /* MBAR_ETH + 0x188 */ +#define emrbr rfifo_status + uint32_t rfifo_cntrl; /* MBAR_ETH + 0x18C */ + uint32_t rfifo_lrf_ptr; /* MBAR_ETH + 0x190 */ + uint32_t rfifo_lwf_ptr; /* MBAR_ETH + 0x194 */ + uint32_t rfifo_alarm; /* MBAR_ETH + 0x198 */ + uint32_t rfifo_rdptr; /* MBAR_ETH + 0x19C */ + uint32_t rfifo_wrptr; /* MBAR_ETH + 0x1A0 */ + uint32_t tfifo_data; /* MBAR_ETH + 0x1A4 */ + uint32_t tfifo_status; /* MBAR_ETH + 0x1A8 */ + uint32_t tfifo_cntrl; /* MBAR_ETH + 0x1AC */ + uint32_t tfifo_lrf_ptr; /* MBAR_ETH + 0x1B0 */ + uint32_t tfifo_lwf_ptr; /* MBAR_ETH + 0x1B4 */ + uint32_t tfifo_alarm; /* MBAR_ETH + 0x1B8 */ + uint32_t tfifo_rdptr; /* MBAR_ETH + 0x1BC */ + uint32_t tfifo_wrptr; /* MBAR_ETH + 0x1C0 */ + + uint32_t reset_cntrl; /* MBAR_ETH + 0x1C4 */ + uint32_t xmit_fsm; /* MBAR_ETH + 0x1C8 */ + + uint32_t RES8[3]; /* MBAR_ETH + 0x1CC-1D4 */ + uint32_t rdes_data0; /* MBAR_ETH + 0x1D8 */ + uint32_t rdes_data1; /* MBAR_ETH + 0x1DC */ + uint32_t r_length; /* MBAR_ETH + 0x1E0 */ + uint32_t x_length; /* MBAR_ETH + 0x1E4 */ + uint32_t x_addr; /* MBAR_ETH + 0x1E8 */ + uint32_t cdes_data; /* MBAR_ETH + 0x1EC */ + uint32_t status; /* MBAR_ETH + 0x1F0 */ + uint32_t dma_control; /* MBAR_ETH + 0x1F4 */ + uint32_t des_cmnd; /* MBAR_ETH + 0x1F8 */ + uint32_t data; /* MBAR_ETH + 0x1FC */ + +/* MIB COUNTERS (Offset 200-2FF) */ + + uint32_t rmon_t_drop; /* MBAR_ETH + 0x200 */ + uint32_t rmon_t_packets; /* MBAR_ETH + 0x204 */ + uint32_t rmon_t_bc_pkt; /* MBAR_ETH + 0x208 */ + uint32_t rmon_t_mc_pkt; /* MBAR_ETH + 0x20C */ + uint32_t rmon_t_crc_align; /* MBAR_ETH + 0x210 */ + uint32_t rmon_t_undersize; /* MBAR_ETH + 0x214 */ + uint32_t rmon_t_oversize; /* MBAR_ETH + 0x218 */ + uint32_t rmon_t_frag; /* MBAR_ETH + 0x21C */ + uint32_t rmon_t_jab; /* MBAR_ETH + 0x220 */ + uint32_t rmon_t_col; /* MBAR_ETH + 0x224 */ + uint32_t rmon_t_p64; /* MBAR_ETH + 0x228 */ + uint32_t rmon_t_p65to127; /* MBAR_ETH + 0x22C */ + uint32_t rmon_t_p128to255; /* MBAR_ETH + 0x230 */ + uint32_t rmon_t_p256to511; /* MBAR_ETH + 0x234 */ + uint32_t rmon_t_p512to1023; /* MBAR_ETH + 0x238 */ + uint32_t rmon_t_p1024to2047; /* MBAR_ETH + 0x23C */ + uint32_t rmon_t_p_gte2048; /* MBAR_ETH + 0x240 */ + uint32_t rmon_t_octets; /* MBAR_ETH + 0x244 */ + uint32_t ieee_t_drop; /* MBAR_ETH + 0x248 */ + uint32_t ieee_t_frame_ok; /* MBAR_ETH + 0x24C */ + uint32_t ieee_t_1col; /* MBAR_ETH + 0x250 */ + uint32_t ieee_t_mcol; /* MBAR_ETH + 0x254 */ + uint32_t ieee_t_def; /* MBAR_ETH + 0x258 */ + uint32_t ieee_t_lcol; /* MBAR_ETH + 0x25C */ + uint32_t ieee_t_excol; /* MBAR_ETH + 0x260 */ + uint32_t ieee_t_macerr; /* MBAR_ETH + 0x264 */ + uint32_t ieee_t_cserr; /* MBAR_ETH + 0x268 */ + uint32_t ieee_t_sqe; /* MBAR_ETH + 0x26C */ + uint32_t t_fdxfc; /* MBAR_ETH + 0x270 */ + uint32_t ieee_t_octets_ok; /* MBAR_ETH + 0x274 */ + + uint32_t RES9[2]; /* MBAR_ETH + 0x278-27C */ + uint32_t rmon_r_drop; /* MBAR_ETH + 0x280 */ + uint32_t rmon_r_packets; /* MBAR_ETH + 0x284 */ + uint32_t rmon_r_bc_pkt; /* MBAR_ETH + 0x288 */ + uint32_t rmon_r_mc_pkt; /* MBAR_ETH + 0x28C */ + uint32_t rmon_r_crc_align; /* MBAR_ETH + 0x290 */ + uint32_t rmon_r_undersize; /* MBAR_ETH + 0x294 */ + uint32_t rmon_r_oversize; /* MBAR_ETH + 0x298 */ + uint32_t rmon_r_frag; /* MBAR_ETH + 0x29C */ + uint32_t rmon_r_jab; /* MBAR_ETH + 0x2A0 */ + + uint32_t rmon_r_resvd_0; /* MBAR_ETH + 0x2A4 */ + + uint32_t rmon_r_p64; /* MBAR_ETH + 0x2A8 */ + uint32_t rmon_r_p65to127; /* MBAR_ETH + 0x2AC */ + uint32_t rmon_r_p128to255; /* MBAR_ETH + 0x2B0 */ + uint32_t rmon_r_p256to511; /* MBAR_ETH + 0x2B4 */ + uint32_t rmon_r_p512to1023; /* MBAR_ETH + 0x2B8 */ + uint32_t rmon_r_p1024to2047; /* MBAR_ETH + 0x2BC */ + uint32_t rmon_r_p_gte2048; /* MBAR_ETH + 0x2C0 */ + uint32_t rmon_r_octets; /* MBAR_ETH + 0x2C4 */ + uint32_t ieee_r_drop; /* MBAR_ETH + 0x2C8 */ + uint32_t ieee_r_frame_ok; /* MBAR_ETH + 0x2CC */ + uint32_t ieee_r_crc; /* MBAR_ETH + 0x2D0 */ + uint32_t ieee_r_align; /* MBAR_ETH + 0x2D4 */ + uint32_t r_macerr; /* MBAR_ETH + 0x2D8 */ + uint32_t r_fdxfc; /* MBAR_ETH + 0x2DC */ + uint32_t ieee_r_octets_ok; /* MBAR_ETH + 0x2E0 */ + + uint32_t RES10[6]; /* MBAR_ETH + 0x2E4-2FC */ + + uint32_t RES11[64]; /* MBAR_ETH + 0x300-3FF */ +} ethernet_regs; + +#define FEC_IEVENT_HBERR 0x80000000 +#define FEC_IEVENT_BABR 0x40000000 +#define FEC_IEVENT_BABT 0x20000000 +#define FEC_IEVENT_GRA 0x10000000 +#define FEC_IEVENT_TFINT 0x08000000 +#define FEC_IEVENT_MII 0x00800000 +#define FEC_IEVENT_LATE_COL 0x00200000 +#define FEC_IEVENT_COL_RETRY_LIM 0x00100000 +#define FEC_IEVENT_XFIFO_UN 0x00080000 +#define FEC_IEVENT_XFIFO_ERROR 0x00040000 +#define FEC_IEVENT_RFIFO_ERROR 0x00020000 + +#define FEC_IMASK_HBERR 0x80000000 +#define FEC_IMASK_BABR 0x40000000 +#define FEC_IMASK_BABT 0x20000000 +#define FEC_IMASK_GRA 0x10000000 +#define FEC_IMASK_MII 0x00800000 +#define FEC_IMASK_LATE_COL 0x00200000 +#define FEC_IMASK_COL_RETRY_LIM 0x00100000 +#define FEC_IMASK_XFIFO_UN 0x00080000 +#define FEC_IMASK_XFIFO_ERROR 0x00040000 +#define FEC_IMASK_RFIFO_ERROR 0x00020000 + +#define FEC_RCNTRL_MAX_FL_SHIFT 16 +#define FEC_RCNTRL_LOOP 0x01 +#define FEC_RCNTRL_DRT 0x02 +#define FEC_RCNTRL_MII_MODE 0x04 +#define FEC_RCNTRL_PROM 0x08 +#define FEC_RCNTRL_BC_REJ 0x10 +#define FEC_RCNTRL_FCE 0x20 + +#define FEC_TCNTRL_GTS 0x00000001 +#define FEC_TCNTRL_HBC 0x00000002 +#define FEC_TCNTRL_FDEN 0x00000004 +#define FEC_TCNTRL_TFC_PAUSE 0x00000008 +#define FEC_TCNTRL_RFC_PAUSE 0x00000010 + +#define FEC_ECNTRL_RESET 0x00000001 +#define FEC_ECNTRL_ETHER_EN 0x00000002 + +/** + * Receive & Transmit Buffer Descriptor definitions + * Little endian layout + */ +typedef struct buffer_descriptor { + uint16_t data_length; + uint16_t status; + uint32_t data_pointer; +} FEC_BD; + +/** + * private structure + */ +typedef struct { + ethernet_regs *eth; + xceiver_type xcv_type; /** transceiver type */ + FEC_BD *rbd_base; /** RBD ring */ + int rbd_index; /** next receive BD to read */ + FEC_BD *tbd_base; /** TBD ring */ + int tbd_index; /** next transmit BD to write */ + struct miiphy_device miiphy; +} fec_priv; + +/** + * buffer alignment on request + */ +#define RDB_ALIGNMENT 16 + +/* Ethernet parameter area */ +#define FEC_TBD_BASE (FEC_PARAM_BASE + 0x00) +#define FEC_TBD_NEXT (FEC_PARAM_BASE + 0x04) +#define FEC_RBD_BASE (FEC_PARAM_BASE + 0x08) +#define FEC_RBD_NEXT (FEC_PARAM_BASE + 0x0c) + +/** + * Numbers of buffer descriptos for receiving + */ +#define FEC_RBD_NUM 64 /* The user can adjust this value */ + +/** + * define the packet size limit + */ +#define FEC_MAX_PKT_SIZE 1536 + +/* RBD bits definitions */ +#define FEC_RBD_EMPTY 0x8000 /* Buffer is empty */ +#define FEC_RBD_WRAP 0x2000 /* Last BD in ring */ +#define FEC_RBD_INT 0x1000 /* Interrupt */ +#define FEC_RBD_LAST 0x0800 /* Buffer is last in frame(useless) */ +#define FEC_RBD_MISS 0x0100 /* Miss bit for prom mode */ +#define FEC_RBD_BC 0x0080 /* The received frame is broadcast frame */ +#define FEC_RBD_MC 0x0040 /* The received frame is multicast frame */ +#define FEC_RBD_LG 0x0020 /* Frame length violation */ +#define FEC_RBD_NO 0x0010 /* Nonoctet align frame */ +#define FEC_RBD_SH 0x0008 /* Short frame */ +#define FEC_RBD_CR 0x0004 /* CRC error */ +#define FEC_RBD_OV 0x0002 /* Receive FIFO overrun */ +#define FEC_RBD_TR 0x0001 /* Frame is truncated */ +#define FEC_RBD_ERR (FEC_RBD_LG | FEC_RBD_NO | FEC_RBD_CR | \ + FEC_RBD_OV | FEC_RBD_TR) + +/* TBD bits definitions */ +#define FEC_TBD_READY 0x8000 /* Buffer is ready */ +#define FEC_TBD_WRAP 0x2000 /* Last BD in ring */ +#define FEC_TBD_INT 0x1000 /* Interrupt */ +#define FEC_TBD_LAST 0x0800 /* Buffer is last in frame */ +#define FEC_TBD_TC 0x0400 /* Transmit the CRC */ +#define FEC_TBD_ABC 0x0200 /* Append bad CRC */ + +/* MII-related definitios */ +#define FEC_MII_DATA_ST 0x40000000 /* Start of frame delimiter */ +#define FEC_MII_DATA_OP_RD 0x20000000 /* Perform a read operation */ +#define FEC_MII_DATA_OP_WR 0x10000000 /* Perform a write operation */ +#define FEC_MII_DATA_PA_MSK 0x0f800000 /* PHY Address field mask */ +#define FEC_MII_DATA_RA_MSK 0x007c0000 /* PHY Register field mask */ +#define FEC_MII_DATA_TA 0x00020000 /* Turnaround */ +#define FEC_MII_DATA_DATAMSK 0x0000ffff /* PHY data field */ + +#define FEC_MII_DATA_RA_SHIFT 18 /* MII Register address bits */ +#define FEC_MII_DATA_PA_SHIFT 23 /* MII PHY address bits */ + +#endif /* __IMX27_FEC_H */ + +/** + * @file + * @brief Definitions for the FEC driver (i.MX27) + */ diff --git a/include/asm-ppc/arch-mpc5200/fec.h b/include/asm-ppc/arch-mpc5200/fec.h deleted file mode 100644 index a3e04b4e9d..0000000000 --- a/include/asm-ppc/arch-mpc5200/fec.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef __INCLUDE_ASM_ARCH_FEC_H -#define __INCLUDE_ASM_ARCH_FEC_H - -struct mpc5xxx_fec_platform_data { - ulong xcv_type; -}; - -typedef enum { - SEVENWIRE, /* 7-wire */ - MII10, /* MII 10Mbps */ - MII100 /* MII 100Mbps */ -} xceiver_type; - -#endif /* __INCLUDE_ASM_ARCH_FEC_H */ diff --git a/include/fec.h b/include/fec.h new file mode 100644 index 0000000000..89f0fba2c1 --- /dev/null +++ b/include/fec.h @@ -0,0 +1,44 @@ +/* + * (C) Copyright 2007 Pengutronix, Sascha Hauer + * (C) Copyright 2007 Pengutronix, Juergen Beisert + * + * This program 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., 59 Temple Place, Suite 330, Boston, + * MA 02111-1307 USA + */ + +/** + * @file + * @brief Shared structures and constants between i.MX27's and MPC52xx's FEC + */ +#ifndef __INCLUDE_NETWORK_FEC_H +#define __INCLUDE_NETWORK_FEC_H + +/** + * Define the phy connected externally + */ +struct fec_platform_data { + ulong xcv_type; +}; + +/** + * Supported phy types on this platform + */ +typedef enum { + SEVENWIRE, /** 7-wire */ + MII10, /** MII 10Mbps */ + MII100 /** MII 100Mbps */ +} xceiver_type; + +#endif /* __INCLUDE_NETWORK_FEC_H */ -- cgit v1.2.3