summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorVijay Kumar Banerjee <vijay@rtems.org>2021-02-16 16:41:54 -0700
committerVijay Kumar Banerjee <vijay@rtems.org>2021-03-02 14:32:11 -0700
commit22f3e3c64addcefee992eed572d758a6eab2313b (patch)
tree8a3f58d7ac48836a0e5d127e5fdff6f2a196d3fa
parentaf6b0e296605c82d710385f41117396a54d4d625 (diff)
Add support for building bsp specific net drivers
-rw-r--r--bsp_drivers.py54
-rw-r--r--bsps/arm/atsam/if_atsam.c1255
-rw-r--r--bsps/arm/csb336/net/lan91c11x.c261
-rw-r--r--bsps/arm/csb336/net/lan91c11x.h229
-rw-r--r--bsps/arm/csb336/net/network.c708
-rw-r--r--bsps/arm/csb337/net/network.c864
-rw-r--r--bsps/arm/edb7312/net/network.c126
-rw-r--r--bsps/arm/gumstix/net/rtl8019.c1197
-rw-r--r--bsps/arm/gumstix/net/wd80x3.h303
-rw-r--r--bsps/arm/rtl22xx/net/network.c126
-rw-r--r--bsps/bfin/bf537Stamp/net/ethernet.c880
-rw-r--r--bsps/bfin/bf537Stamp/net/networkconfig.c69
-rw-r--r--bsps/i386/pc386/net/3c509.c1538
-rw-r--r--bsps/i386/pc386/net/3c509.h436
-rw-r--r--bsps/i386/pc386/net/elink.c82
-rw-r--r--bsps/i386/pc386/net/elink.h49
-rw-r--r--bsps/i386/pc386/net/ne2000.c1310
-rw-r--r--bsps/i386/pc386/net/wd8003.c647
-rw-r--r--bsps/include/libchip/cs8900.h761
-rw-r--r--bsps/include/libchip/greth.h152
-rw-r--r--bsps/include/libchip/open_eth.h173
-rw-r--r--bsps/include/libchip/smc91111exp.h26
-rw-r--r--bsps/include/libchip/sonic.h458
-rw-r--r--bsps/lm32/shared/net/dp83848phy.h186
-rw-r--r--bsps/lm32/shared/net/network.c319
-rw-r--r--bsps/lm32/shared/net/network.h31
-rw-r--r--bsps/lm32/shared/net/tsmac.c821
-rw-r--r--bsps/lm32/shared/net/tsmac.h172
-rw-r--r--bsps/m68k/av5282/net/network.c940
-rw-r--r--bsps/m68k/csb360/net/network.c984
-rw-r--r--bsps/m68k/gen68360/net/network.c1062
-rw-r--r--bsps/m68k/genmcf548x/net/network.c1696
-rw-r--r--bsps/m68k/mcf5235/net/network.c879
-rw-r--r--bsps/m68k/mcf5329/net/network.c857
-rw-r--r--bsps/m68k/mvme167/net/network.c3098
-rw-r--r--bsps/m68k/mvme167/net/uti596.h369
-rw-r--r--bsps/m68k/uC5282/net/network.c1013
-rw-r--r--bsps/mips/csb350/net/network.c909
-rw-r--r--bsps/powerpc/beatnik/net/if_em/LICENSE31
-rw-r--r--bsps/powerpc/beatnik/net/if_em/README332
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em.c3847
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em.h493
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em_hw.c6620
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em_hw.h2678
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em_osdep.h146
-rw-r--r--bsps/powerpc/beatnik/net/if_em/if_em_rtems.c106
-rw-r--r--bsps/powerpc/beatnik/net/if_em/rtemscompat_defs.h198
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/gtethreg.h854
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/gtvar.h170
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/if_gfe.c2648
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/if_gfe_rtems.c129
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/if_gfevar.h225
-rw-r--r--bsps/powerpc/beatnik/net/if_gfe/rtemscompat_defs.h161
-rw-r--r--bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c3318
-rw-r--r--bsps/powerpc/beatnik/net/if_mve/mve_smallbuf_tst.c145
-rw-r--r--bsps/powerpc/beatnik/net/if_mve/testing.c324
-rw-r--r--bsps/powerpc/beatnik/net/porting/LICENSE51
-rw-r--r--bsps/powerpc/beatnik/net/porting/Makefile.template84
-rw-r--r--bsps/powerpc/beatnik/net/porting/README104
-rw-r--r--bsps/powerpc/beatnik/net/porting/if_xxx.modini.c34
-rw-r--r--bsps/powerpc/beatnik/net/porting/if_xxx_rtems.c500
-rw-r--r--bsps/powerpc/beatnik/net/porting/pcireg.h405
-rw-r--r--bsps/powerpc/beatnik/net/porting/rtemscompat.h454
-rw-r--r--bsps/powerpc/beatnik/net/porting/rtemscompat1.h219
-rw-r--r--bsps/powerpc/beatnik/net/porting/rtemscompat_defs.h.template97
-rw-r--r--bsps/powerpc/beatnik/net/support/bsp_attach.c468
-rw-r--r--bsps/powerpc/beatnik/net/support/early_link_status.c40
-rw-r--r--bsps/powerpc/gen5200/net/network.c1580
-rw-r--r--bsps/powerpc/gen83xx/net/network.c255
-rw-r--r--bsps/powerpc/haleakala/net/network.c1249
-rw-r--r--bsps/powerpc/mpc55xxevb/net/if_smc.c161
-rw-r--r--bsps/powerpc/mpc55xxevb/net/smsc9218i.c2124
-rw-r--r--bsps/powerpc/mpc8260ads/net/README55
-rw-r--r--bsps/powerpc/mpc8260ads/net/if_hdlcsubr.c349
-rw-r--r--bsps/powerpc/mpc8260ads/net/if_hdlcsubr.h34
-rw-r--r--bsps/powerpc/mpc8260ads/net/network.c969
-rw-r--r--bsps/powerpc/mvme3100/net/tsec.c3208
-rw-r--r--bsps/powerpc/mvme5500/net/if_100MHz/GT64260eth.c1574
-rw-r--r--bsps/powerpc/mvme5500/net/if_1GHz/if_wm.c1765
-rw-r--r--bsps/powerpc/mvme5500/net/if_1GHz/pci_map.c135
-rw-r--r--bsps/powerpc/psim/net/README141
-rw-r--r--bsps/powerpc/psim/net/gdb-6.8-psim-hw_ethtap.diff15893
-rw-r--r--bsps/powerpc/psim/net/if_sim.c504
-rw-r--r--bsps/powerpc/qoriq/net/if_intercom.c296
-rw-r--r--bsps/powerpc/qoriq/net/network.c135
-rw-r--r--bsps/powerpc/tqm8xx/net/network_fec.c1248
-rw-r--r--bsps/powerpc/tqm8xx/net/network_scc.c1049
-rw-r--r--bsps/powerpc/virtex/net/xiltemac.c961
-rw-r--r--bsps/riscv/griscv/net/griscv_greth.c59
-rw-r--r--bsps/sparc/erc32/net/erc32sonic.c123
-rw-r--r--bsps/sparc/leon2/net/leon_open_eth.c64
-rw-r--r--bsps/sparc/leon2/net/leon_smc91111.c69
-rw-r--r--bsps/sparc/leon3/net/leon_greth.c58
-rw-r--r--bsps/sparc/leon3/net/leon_open_eth.c75
-rw-r--r--bsps/sparc/leon3/net/leon_smc91111.c89
-rw-r--r--lnetworking.py47
-rw-r--r--wscript4
97 files changed, 84185 insertions, 9 deletions
diff --git a/bsp_drivers.py b/bsp_drivers.py
new file mode 100644
index 0000000..910dcde
--- /dev/null
+++ b/bsp_drivers.py
@@ -0,0 +1,54 @@
+#
+# RTEMS Project (https://www.rtems.org/)
+#
+# Copyright (c) 2021 Vijay Kumar Banerjee <vijay@rtems.org>.
+# 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.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+from rtems_waf import rtems
+import os
+import waflib.Options
+import waflib.ConfigSet
+
+def bsp_files(bld):
+ source_files = {}
+ include_dirs = {}
+ bsp_archs = {}
+ include_files = []
+
+ bsp_list = bld.env.RTEMS_ARCH_BSP_LIST
+
+ for bl in bsp_list:
+ bsp = bl.split('-')[-1]
+ arch = bl.split('-')[0]
+ bsp_archs[bsp] = bl
+ for root, dirs, files in os.walk(os.path.join('./bsps', arch, bsp)):
+ include_dirs[bsp] = []
+ source_files[bsp] = []
+ for name in files:
+ if name[-2:] == '.c':
+ source_files[bsp].append(os.path.join(root, name))
+ if name[-2:] == '.h':
+ if root not in include_dirs[bsp]:
+ include_dirs[bsp].append(root)
+ return (include_dirs, source_files, bsp_archs)
diff --git a/bsps/arm/atsam/if_atsam.c b/bsps/arm/atsam/if_atsam.c
new file mode 100644
index 0000000..9665aa1
--- /dev/null
+++ b/bsps/arm/atsam/if_atsam.c
@@ -0,0 +1,1255 @@
+/*
+ * Copyright (c) 2016 embedded brains GmbH. All rights reserved.
+ *
+ * embedded brains GmbH
+ * Dornierstr. 4
+ * 82178 Puchheim
+ * Germany
+ * <info@embedded-brains.de>
+ *
+ * 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.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <libchip/chip.h>
+#include <libchip/include/gmacd.h>
+#include <libchip/include/pio.h>
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <bsp/irq.h>
+
+#include <stdio.h>
+
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+
+#include <sys/types.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+#include <net/if_var.h>
+#include <net/if_types.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <dev/mii/mii.h>
+
+/*
+ * Number of interfaces supported by the driver
+ */
+#define NIFACES 1
+
+/** Enable/Disable CopyAllFrame */
+#define GMAC_CAF_DISABLE 0
+#define GMAC_CAF_ENABLE 1
+
+/** Enable/Disable NoBroadCast */
+#define GMAC_NBC_DISABLE 0
+#define GMAC_NBC_ENABLE 1
+
+/** The PIN list of PIO for GMAC */
+#define BOARD_GMAC_PINS \
+ { (PIO_PD0A_GTXCK | PIO_PD1A_GTXEN | PIO_PD2A_GTX0 | PIO_PD3A_GTX1 \
+ | PIO_PD4A_GRXDV | PIO_PD5A_GRX0 | PIO_PD6A_GRX1 \
+ | PIO_PD7A_GRXER \
+ | PIO_PD8A_GMDC | PIO_PD9A_GMDIO), PIOD, ID_PIOD, PIO_PERIPH_A, \
+ PIO_DEFAULT }
+/** The runtime pin configure list for GMAC */
+#define BOARD_GMAC_RUN_PINS BOARD_GMAC_PINS
+
+/** The PIN list of PIO for GMAC */
+#define BOARD_GMAC_RESET_PIN \
+ { PIO_PC10, PIOC, ID_PIOC, \
+ PIO_OUTPUT_1, \
+ PIO_PULLUP }
+
+/** Multicast Enable */
+#define GMAC_MC_ENABLE (1u << 6)
+#define HASH_INDEX_AMOUNT 6
+#define HASH_ELEMENTS_PER_INDEX 8
+#define MAC_ADDR_MASK 0x0000FFFFFFFFFFFF
+#define MAC_IDX_MASK (1u << 0)
+
+/** Promiscuous Mode Enable */
+#define GMAC_PROM_ENABLE (1u << 4)
+
+/** RX Defines */
+#define GMAC_RX_BUFFER_SIZE 1536
+#define GMAC_RX_BUF_DESC_ADDR_MASK 0xFFFFFFFC
+#define GMAC_RX_SET_OFFSET (1u << 15)
+#define GMAC_RX_SET_USED_WRAP ((1u << 1) | (1u << 0))
+#define GMAC_RX_SET_WRAP (1u << 1)
+#define GMAC_RX_SET_USED (1u << 0)
+/** TX Defines */
+#define GMAC_TX_SET_EOF (1u << 15)
+#define GMAC_TX_SET_WRAP (1u << 30)
+#define GMAC_TX_SET_USED (1u << 31)
+
+#define GMAC_DESCRIPTOR_ALIGNMENT 8
+
+/** Events */
+#define ATSAMV7_ETH_RX_EVENT_INTERRUPT RTEMS_EVENT_1
+#define ATSAMV7_ETH_TX_EVENT_INTERRUPT RTEMS_EVENT_2
+#define ATSAMV7_ETH_START_TRANSMIT_EVENT RTEMS_EVENT_3
+
+#define ATSAMV7_ETH_RX_DATA_OFFSET 2
+
+#define WATCHDOG_TIMEOUT 5
+
+/** The PINs for GMAC */
+static const Pin gmacPins[] = { BOARD_GMAC_RUN_PINS };
+
+static const Pin gmacResetPin = BOARD_GMAC_RESET_PIN;
+
+typedef struct if_atsam_gmac {
+ /** The GMAC driver instance */
+ sGmacd gGmacd;
+ uint32_t retries;
+ uint8_t phy_address;
+} if_atsam_gmac;
+
+typedef struct ring_buffer {
+ unsigned tx_bd_used;
+ unsigned tx_bd_free;
+ size_t length;
+} ring_buffer;
+
+/*
+ * Per-device data
+ */
+typedef struct if_atsam_softc {
+ /*
+ * Data
+ */
+ struct arpcom arpcom;
+ if_atsam_gmac Gmac_inst;
+ struct rtems_mdio_info mdio;
+ uint8_t GMacAddress[6];
+ rtems_id rx_daemon_tid;
+ rtems_id tx_daemon_tid;
+ rtems_vector_number interrupt_number;
+ struct mbuf **rx_mbuf;
+ struct mbuf **tx_mbuf;
+ volatile sGmacTxDescriptor *tx_bd_base;
+ uint32_t anlpar;
+ size_t rx_bd_fill_idx;
+ size_t amount_rx_buf;
+ size_t amount_tx_buf;
+ ring_buffer tx_ring;
+
+ /*
+ * Statistics
+ */
+ unsigned rx_overrun_errors;
+ unsigned rx_interrupts;
+ unsigned tx_complete_int;
+ unsigned tx_tur_errors;
+ unsigned tx_rlex_errors;
+ unsigned tx_tfc_errors;
+ unsigned tx_hresp_errors;
+ unsigned tx_interrupts;
+} if_atsam_softc;
+
+static struct if_atsam_softc if_atsam_softc_inst;
+
+static struct mbuf *if_atsam_new_mbuf(struct ifnet *ifp)
+{
+ struct mbuf *m;
+
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if (m != NULL) {
+ MCLGET(m, M_DONTWAIT);
+ if ((m->m_flags & M_EXT) != 0) {
+ m->m_pkthdr.rcvif = ifp;
+ m->m_data = mtod(m, char *);
+ rtems_cache_invalidate_multiple_data_lines(mtod(m, void *),
+ GMAC_RX_BUFFER_SIZE);
+ } else {
+ m_free(m);
+ m = NULL;
+ }
+ }
+ return (m);
+}
+
+
+static uint8_t if_atsam_wait_phy(Gmac *pHw, uint32_t retry)
+{
+ volatile uint32_t retry_count = 0;
+
+ while (!GMAC_IsIdle(pHw)) {
+ if (retry == 0) {
+ continue;
+ }
+ retry_count++;
+
+ if (retry_count >= retry) {
+ return (1);
+ }
+ rtems_task_wake_after(1);
+ }
+
+ return (0);
+}
+
+
+static uint8_t
+if_atsam_write_phy(Gmac *pHw, uint8_t PhyAddress, uint8_t Address,
+ uint32_t Value, uint32_t retry)
+{
+ GMAC_PHYMaintain(pHw, PhyAddress, Address, 0, (uint16_t)Value);
+ if (if_atsam_wait_phy(pHw, retry) == 1) {
+ return (1);
+ }
+ return (0);
+}
+
+
+static uint8_t
+if_atsam_read_phy(Gmac *pHw,
+ uint8_t PhyAddress, uint8_t Address, uint32_t *pvalue, uint32_t retry)
+{
+ GMAC_PHYMaintain(pHw, PhyAddress, Address, 1, 0);
+ if (if_atsam_wait_phy(pHw, retry) == 1) {
+ return (1);
+ }
+ *pvalue = GMAC_PHYData(pHw);
+ return (0);
+}
+
+
+static void atsamv7_find_valid_phy(if_atsam_gmac *gmac_inst)
+{
+ Gmac *pHw = gmac_inst->gGmacd.pHw;
+ uint32_t value = 0;
+ uint8_t phy_address;
+ int i;
+
+ if (gmac_inst->phy_address != 0xFF) {
+ return;
+ }
+
+ /* Find another one */
+ phy_address = 0xFF;
+
+ for (i = 31; i >= 0; --i) {
+ int rv;
+
+ rv = if_atsam_read_phy(pHw, (uint8_t)i, MII_PHYIDR1,
+ &value, gmac_inst->retries);
+ if (rv == 0 && value != 0 && value < 0xffff) {
+ phy_address = (uint8_t)i;
+ break;
+ }
+ }
+
+ if (phy_address != 0xFF) {
+ if_atsam_read_phy(pHw, phy_address, MII_PHYIDR1, &value,
+ gmac_inst->retries);
+ if_atsam_read_phy(pHw, phy_address, MII_PHYIDR2, &value,
+ gmac_inst->retries);
+ gmac_inst->phy_address = phy_address;
+ }
+}
+
+
+static uint8_t if_atsam_reset_phy(if_atsam_gmac *gmac_inst)
+{
+ uint32_t retry_max;
+ uint32_t bmcr;
+ uint8_t phy_address;
+ uint32_t timeout = 10;
+ uint8_t ret = 0;
+
+ Gmac *pHw = gmac_inst->gGmacd.pHw;
+
+ phy_address = gmac_inst->phy_address;
+ retry_max = gmac_inst->retries;
+
+ bmcr = BMCR_RESET;
+ if_atsam_write_phy(pHw, phy_address, MII_BMCR, bmcr, retry_max);
+ do {
+ if_atsam_read_phy(pHw, phy_address, MII_BMCR, &bmcr,
+ retry_max);
+ timeout--;
+ } while ((bmcr & BMCR_RESET) && timeout);
+
+ if (!timeout) {
+ ret = 1;
+ }
+ return (ret);
+}
+
+
+static uint8_t
+if_atsam_init_phy(if_atsam_gmac *gmac_inst, uint32_t mck,
+ const Pin *pResetPins, uint32_t nbResetPins, const Pin *pGmacPins,
+ uint32_t nbGmacPins)
+{
+ uint8_t rc = 1;
+ Gmac *pHw = gmac_inst->gGmacd.pHw;
+
+ /* Perform RESET */
+ if (pResetPins) {
+ /* Configure PINS */
+ PIO_Configure(pResetPins, nbResetPins);
+ PIO_Clear(pResetPins);
+ rtems_task_wake_after(1);
+ PIO_Set(pResetPins);
+ }
+ /* Configure GMAC runtime pins */
+ if (rc) {
+ PIO_Configure(pGmacPins, nbGmacPins);
+ rc = GMAC_SetMdcClock(pHw, mck);
+
+ if (!rc) {
+ return (0);
+ }
+ if_atsam_reset_phy(gmac_inst);
+ }
+ return (rc);
+}
+
+static bool if_atsam_is_valid_phy(int phy)
+{
+ return phy >= 0 && phy <= 31;
+}
+
+static int if_atsam_mdio_read(int phy, void *arg, unsigned reg, uint32_t *pval)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+
+ if (!if_atsam_is_valid_phy(phy)) {
+ return (EINVAL);
+ }
+
+ return (if_atsam_read_phy(sc->Gmac_inst.gGmacd.pHw,
+ (uint8_t)phy, (uint8_t)reg, pval, sc->Gmac_inst.retries));
+}
+
+
+static int if_atsam_mdio_write(int phy, void *arg, unsigned reg, uint32_t pval)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+
+ if (!if_atsam_is_valid_phy(phy)) {
+ return (EINVAL);
+ }
+
+ return if_atsam_write_phy(sc->Gmac_inst.gGmacd.pHw,
+ (uint8_t)phy, (uint8_t)reg, pval, sc->Gmac_inst.retries);
+}
+
+
+/*
+ * Interrupt Handler for the network driver
+ */
+static void if_atsam_interrupt_handler(void *arg)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+ uint32_t irq_status_val;
+ rtems_event_set rx_event = 0;
+ rtems_event_set tx_event = 0;
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ /* Get interrupt status */
+ irq_status_val = GMAC_GetItStatus(pHw, 0);
+
+ /* Check receive interrupts */
+ if ((irq_status_val & GMAC_IER_ROVR) != 0) {
+ ++sc->rx_overrun_errors;
+ rx_event = ATSAMV7_ETH_RX_EVENT_INTERRUPT;
+ }
+ if ((irq_status_val & GMAC_IER_RCOMP) != 0) {
+ rx_event = ATSAMV7_ETH_RX_EVENT_INTERRUPT;
+ }
+ /* Send events to receive task and switch off rx interrupts */
+ if (rx_event != 0) {
+ ++sc->rx_interrupts;
+ /* Erase the interrupts for RX completion and errors */
+ GMAC_DisableIt(pHw, GMAC_IER_RCOMP | GMAC_IER_ROVR, 0);
+ (void)rtems_bsdnet_event_send(sc->rx_daemon_tid, rx_event);
+ }
+ if ((irq_status_val & GMAC_IER_TUR) != 0) {
+ ++sc->tx_tur_errors;
+ tx_event = ATSAMV7_ETH_TX_EVENT_INTERRUPT;
+ }
+ if ((irq_status_val & GMAC_IER_RLEX) != 0) {
+ ++sc->tx_rlex_errors;
+ tx_event = ATSAMV7_ETH_TX_EVENT_INTERRUPT;
+ }
+ if ((irq_status_val & GMAC_IER_TFC) != 0) {
+ ++sc->tx_tfc_errors;
+ tx_event = ATSAMV7_ETH_TX_EVENT_INTERRUPT;
+ }
+ if ((irq_status_val & GMAC_IER_HRESP) != 0) {
+ ++sc->tx_hresp_errors;
+ tx_event = ATSAMV7_ETH_TX_EVENT_INTERRUPT;
+ }
+ if ((irq_status_val & GMAC_IER_TCOMP) != 0) {
+ ++sc->tx_complete_int;
+ tx_event = ATSAMV7_ETH_TX_EVENT_INTERRUPT;
+ }
+ /* Send events to transmit task and switch off tx interrupts */
+ if (tx_event != 0) {
+ ++sc->tx_interrupts;
+ /* Erase the interrupts for TX completion and errors */
+ GMAC_DisableIt(pHw, GMAC_INT_TX_BITS, 0);
+ (void)rtems_bsdnet_event_send(sc->tx_daemon_tid, tx_event);
+ }
+}
+/*
+ * Receive daemon
+ */
+static void if_atsam_rx_daemon(void *arg)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+ rtems_event_set events = 0;
+ void *rx_bd_base;
+ struct mbuf *m;
+ struct mbuf *n;
+ volatile sGmacRxDescriptor *buffer_desc;
+ int frame_len;
+ struct ether_header *eh;
+ uint32_t tmp_rx_bd_address;
+
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ /* Allocate memory space for priority queue descriptor list */
+ rx_bd_base = rtems_cache_coherent_allocate(sizeof(sGmacRxDescriptor),
+ GMAC_DESCRIPTOR_ALIGNMENT, 0);
+ assert(rx_bd_base != NULL);
+
+ buffer_desc = (sGmacRxDescriptor *)rx_bd_base;
+ buffer_desc->addr.val = GMAC_RX_SET_USED_WRAP;
+ buffer_desc->status.val = 0;
+
+ GMAC_SetRxQueue(pHw, (uint32_t)buffer_desc, 1);
+ GMAC_SetRxQueue(pHw, (uint32_t)buffer_desc, 2);
+
+ /* Allocate memory space for buffer descriptor list */
+ rx_bd_base = rtems_cache_coherent_allocate(
+ sc->amount_rx_buf * sizeof(sGmacRxDescriptor),
+ GMAC_DESCRIPTOR_ALIGNMENT, 0);
+ assert(rx_bd_base != NULL);
+ buffer_desc = (sGmacRxDescriptor *)rx_bd_base;
+
+ /* Create descriptor list and mark as empty */
+ for (sc->rx_bd_fill_idx = 0; sc->rx_bd_fill_idx < sc->amount_rx_buf;
+ ++sc->rx_bd_fill_idx) {
+ m = if_atsam_new_mbuf(&sc->arpcom.ac_if);
+ assert(m != NULL);
+ sc->rx_mbuf[sc->rx_bd_fill_idx] = m;
+ buffer_desc->addr.val = ((uint32_t)m->m_data) &
+ GMAC_RX_BUF_DESC_ADDR_MASK;
+ buffer_desc->status.val = 0;
+ if (sc->rx_bd_fill_idx == (sc->amount_rx_buf - 1)) {
+ buffer_desc->addr.bm.bWrap = 1;
+ } else {
+ buffer_desc++;
+ }
+ }
+ buffer_desc = (sGmacRxDescriptor *)rx_bd_base;
+
+ /* Set 2 Byte Receive Buffer Offset */
+ pHw->GMAC_NCFGR |= GMAC_RX_SET_OFFSET;
+
+ /* Write Buffer Queue Base Address Register */
+ GMAC_ReceiveEnable(pHw, 0);
+ GMAC_SetRxQueue(pHw, (uint32_t)buffer_desc, 0);
+
+ /* Set address for address matching */
+ GMAC_SetAddress(pHw, 0, sc->GMacAddress);
+
+ /* Enable Receiving of data */
+ GMAC_ReceiveEnable(pHw, 1);
+
+ /* Setup the interrupts for RX completion and errors */
+ GMAC_EnableIt(pHw, GMAC_IER_RCOMP | GMAC_IER_ROVR, 0);
+
+ sc->rx_bd_fill_idx = 0;
+
+ while (true) {
+ /* Wait for events */
+ rtems_bsdnet_event_receive(ATSAMV7_ETH_RX_EVENT_INTERRUPT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Check for all packets with a set ownership bit
+ */
+ while (buffer_desc->addr.bm.bOwnership == 1) {
+ if (buffer_desc->status.bm.bEof == 1) {
+ m = sc->rx_mbuf[sc->rx_bd_fill_idx];
+
+ /* New mbuf for desc */
+ n = if_atsam_new_mbuf(&sc->arpcom.ac_if);
+ if (n != NULL) {
+ frame_len = (int)
+ (buffer_desc->status.bm.len);
+
+ /* Discard Ethernet header */
+ int sz = frame_len - ETHER_HDR_LEN;
+
+ /* Update mbuf */
+ eh = (struct ether_header *)
+ (mtod(m, char *) + 2);
+ m->m_len = sz;
+ m->m_pkthdr.len = sz;
+ m->m_data = (void *)(eh + 1);
+ ether_input(&sc->arpcom.ac_if, eh, m);
+ m = n;
+ } else {
+ (void)rtems_bsdnet_event_send(
+ sc->tx_daemon_tid, ATSAMV7_ETH_START_TRANSMIT_EVENT);
+ }
+ sc->rx_mbuf[sc->rx_bd_fill_idx] = m;
+ tmp_rx_bd_address = (uint32_t)m->m_data &
+ GMAC_RX_BUF_DESC_ADDR_MASK;
+
+ /* Switch pointer to next buffer descriptor */
+ if (sc->rx_bd_fill_idx ==
+ (sc->amount_rx_buf - 1)) {
+ tmp_rx_bd_address |= GMAC_RX_SET_WRAP;
+ sc->rx_bd_fill_idx = 0;
+ } else {
+ ++sc->rx_bd_fill_idx;
+ }
+
+ /*
+ * Give ownership to GMAC for further processing
+ */
+ tmp_rx_bd_address &= ~GMAC_RX_SET_USED;
+ _ARM_Data_synchronization_barrier();
+ buffer_desc->addr.val = tmp_rx_bd_address;
+
+ buffer_desc = (sGmacRxDescriptor *)rx_bd_base
+ + sc->rx_bd_fill_idx;
+ }
+ }
+ /* Setup the interrupts for RX completion and errors */
+ GMAC_EnableIt(pHw, GMAC_IER_RCOMP | GMAC_IER_ROVR, 0);
+ }
+}
+
+/*
+ * Update of current transmit buffer position.
+ */
+static void if_atsam_tx_bd_pos_update(size_t *pos, size_t amount_tx_buf)
+{
+ *pos = (*pos + 1) % amount_tx_buf;
+}
+
+/*
+ * Is RingBuffer empty
+ */
+static bool if_atsam_ring_buffer_empty(ring_buffer *ring_buffer)
+{
+ return (ring_buffer->tx_bd_used == ring_buffer->tx_bd_free);
+}
+
+/*
+ * Is RingBuffer full
+ */
+static bool if_atsam_ring_buffer_full(ring_buffer *ring_buffer)
+{
+ size_t tx_bd_used_next = ring_buffer->tx_bd_used;
+
+ if_atsam_tx_bd_pos_update(&tx_bd_used_next, ring_buffer->length);
+ return (tx_bd_used_next == ring_buffer->tx_bd_free);
+}
+
+/*
+ * Cleanup transmit file descriptors by freeing mbufs which are not needed any
+ * longer due to correct transmission.
+ */
+static void if_atsam_tx_bd_cleanup(if_atsam_softc *sc)
+{
+ struct mbuf *m;
+ volatile sGmacTxDescriptor *cur;
+ bool eof_needed = false;
+
+ while (!if_atsam_ring_buffer_empty(&sc->tx_ring)){
+ cur = sc->tx_bd_base + sc->tx_ring.tx_bd_free;
+ if (((cur->status.bm.bUsed == 1) && !eof_needed) || eof_needed) {
+ eof_needed = true;
+ cur->status.val |= GMAC_TX_SET_USED;
+ m = sc->tx_mbuf[sc->tx_ring.tx_bd_free];
+ m_free(m);
+ sc->tx_mbuf[sc->tx_ring.tx_bd_free] = 0;
+ if_atsam_tx_bd_pos_update(&sc->tx_ring.tx_bd_free,
+ sc->tx_ring.length);
+ if (cur->status.bm.bLastBuffer) {
+ eof_needed = false;
+ }
+ } else {
+ break;
+ }
+ }
+}
+
+/*
+ * Prepare Ethernet frame to start transmission.
+ */
+static bool if_atsam_send_packet(if_atsam_softc *sc, struct mbuf *m)
+{
+ volatile sGmacTxDescriptor *cur;
+ volatile sGmacTxDescriptor *start_packet_tx_bd = 0;
+ int pos = 0;
+ uint32_t tmp_val = 0;
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+ bool success;
+
+ if_atsam_tx_bd_cleanup(sc);
+ /* Wait for interrupt in case no buffer descriptors are available */
+ /* Wait for events */
+ while (true) {
+ if (if_atsam_ring_buffer_full(&sc->tx_ring)) {
+ /* Setup the interrupts for TX completion and errors */
+ GMAC_EnableIt(pHw, GMAC_INT_TX_BITS, 0);
+ success = false;
+ break;
+ }
+
+ /*
+ * Get current mbuf for data fill
+ */
+ cur = &sc->tx_bd_base[sc->tx_ring.tx_bd_used];
+ /* Set the transfer data */
+ if (m->m_len) {
+ uintptr_t cache_adjustment = mtod(m, uintptr_t) % 32;
+
+ rtems_cache_flush_multiple_data_lines(
+ mtod(m, const char *) - cache_adjustment,
+ (size_t)(m->m_len + cache_adjustment));
+
+ cur->addr = mtod(m, uint32_t);
+ tmp_val = (uint32_t)m->m_len | GMAC_TX_SET_USED;
+ if (sc->tx_ring.tx_bd_used == (sc->tx_ring.length - 1)) {
+ tmp_val |= GMAC_TX_SET_WRAP;
+ }
+ if (pos == 0) {
+ start_packet_tx_bd = cur;
+ }
+ sc->tx_mbuf[sc->tx_ring.tx_bd_used] = m;
+ m = m->m_next;
+ if_atsam_tx_bd_pos_update(&sc->tx_ring.tx_bd_used,
+ sc->tx_ring.length);
+ } else {
+ /* Discard empty mbufs */
+ m = m_free(m);
+ }
+
+ /*
+ * Send out the buffer once the complete mbuf_chain has been
+ * processed
+ */
+ if (m == NULL) {
+ tmp_val |= GMAC_TX_SET_EOF;
+ tmp_val &= ~GMAC_TX_SET_USED;
+ _ARM_Data_synchronization_barrier();
+ cur->status.val = tmp_val;
+ start_packet_tx_bd->status.val &= ~GMAC_TX_SET_USED;
+ _ARM_Data_synchronization_barrier();
+ GMAC_TransmissionStart(pHw);
+ success = true;
+ break;
+ } else {
+ if (pos > 0) {
+ tmp_val &= ~GMAC_TX_SET_USED;
+ }
+ pos++;
+ cur->status.val = tmp_val;
+ }
+ }
+ return success;
+}
+
+
+/*
+ * Transmit daemon
+ */
+static void if_atsam_tx_daemon(void *arg)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+ rtems_event_set events = 0;
+ sGmacTxDescriptor *buffer_desc;
+ int bd_number;
+ void *tx_bd_base;
+ struct mbuf *m;
+ bool success;
+
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ GMAC_TransmitEnable(pHw, 0);
+
+ /* Allocate memory space for priority queue descriptor list */
+ tx_bd_base = rtems_cache_coherent_allocate(sizeof(sGmacTxDescriptor),
+ GMAC_DESCRIPTOR_ALIGNMENT, 0);
+ assert(tx_bd_base != NULL);
+
+ buffer_desc = (sGmacTxDescriptor *)tx_bd_base;
+ buffer_desc->addr = 0;
+ buffer_desc->status.val = GMAC_TX_SET_USED | GMAC_TX_SET_WRAP;
+
+ GMAC_SetTxQueue(pHw, (uint32_t)buffer_desc, 1);
+ GMAC_SetTxQueue(pHw, (uint32_t)buffer_desc, 2);
+
+ /* Allocate memory space for buffer descriptor list */
+ tx_bd_base = rtems_cache_coherent_allocate(
+ sc->amount_tx_buf * sizeof(sGmacTxDescriptor),
+ GMAC_DESCRIPTOR_ALIGNMENT, 0);
+ assert(tx_bd_base != NULL);
+ buffer_desc = (sGmacTxDescriptor *)tx_bd_base;
+
+ /* Create descriptor list and mark as empty */
+ for (bd_number = 0; bd_number < sc->amount_tx_buf; bd_number++) {
+ buffer_desc->addr = 0;
+ buffer_desc->status.val = GMAC_TX_SET_USED;
+ if (bd_number == (sc->amount_tx_buf - 1)) {
+ buffer_desc->status.bm.bWrap = 1;
+ } else {
+ buffer_desc++;
+ }
+ }
+ buffer_desc = (sGmacTxDescriptor *)tx_bd_base;
+
+ /* Write Buffer Queue Base Address Register */
+ GMAC_SetTxQueue(pHw, (uint32_t)buffer_desc, 0);
+
+ /* Enable Transmission of data */
+ GMAC_TransmitEnable(pHw, 1);
+
+ /* Set variables in context */
+ sc->tx_bd_base = tx_bd_base;
+
+ while (true) {
+ /* Wait for events */
+ rtems_bsdnet_event_receive(ATSAMV7_ETH_START_TRANSMIT_EVENT | ATSAMV7_ETH_TX_EVENT_INTERRUPT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+ //printf("TX Transmit Event received\n");
+
+ /*
+ * Send packets till queue is empty
+ */
+ while (true) {
+ /*
+ * Get the mbuf chain to transmit
+ */
+ if_atsam_tx_bd_cleanup(sc);
+ IF_DEQUEUE(&sc->arpcom.ac_if.if_snd, m);
+ if (!m) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ break;
+ }
+ success = if_atsam_send_packet(sc, m);
+ if (!success){
+ break;
+ }
+ }
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void if_atsam_enet_start(struct ifnet *ifp)
+{
+ if_atsam_softc *sc = (if_atsam_softc *)ifp->if_softc;
+
+ ifp->if_flags |= IFF_OACTIVE;
+ rtems_bsdnet_event_send(sc->tx_daemon_tid,
+ ATSAMV7_ETH_START_TRANSMIT_EVENT);
+}
+
+
+/*
+ * Attach a watchdog for autonegotiation to the system
+ */
+static void if_atsam_interface_watchdog(struct ifnet *ifp)
+{
+ uint32_t anlpar;
+ uint8_t speed = GMAC_SPEED_100M;
+ uint8_t full_duplex = GMAC_DUPLEX_FULL;
+
+ if_atsam_softc *sc = (if_atsam_softc *)ifp->if_softc;
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+ uint8_t phy = sc->Gmac_inst.phy_address;
+ uint32_t retries = sc->Gmac_inst.retries;
+
+ if (if_atsam_read_phy(pHw, phy, MII_ANLPAR, &anlpar, retries)) {
+ anlpar = 0;
+ }
+ if (sc->anlpar != anlpar) {
+ /* Set up the GMAC link speed */
+ if (anlpar & ANLPAR_TX_FD) {
+ /* Set MII for 100BaseTx and Full Duplex */
+ speed = GMAC_SPEED_100M;
+ full_duplex = GMAC_DUPLEX_FULL;
+ } else if (anlpar & ANLPAR_10_FD) {
+ /* Set MII for 10BaseTx and Full Duplex */
+ speed = GMAC_SPEED_10M;
+ full_duplex = GMAC_DUPLEX_FULL;
+ } else if (anlpar & ANLPAR_TX) {
+ /* Set MII for 100BaseTx and half Duplex */
+ speed = GMAC_SPEED_100M;
+ full_duplex = GMAC_DUPLEX_HALF;
+ } else if (anlpar & ANLPAR_10) {
+ /* Set MII for 10BaseTx and half Duplex */
+ speed = GMAC_SPEED_10M;
+ full_duplex = GMAC_DUPLEX_HALF;
+ } else {
+ /* Set MII for 100BaseTx and Full Duplex */
+ speed = GMAC_SPEED_100M;
+ full_duplex = GMAC_DUPLEX_FULL;
+ }
+ GMAC_SetLinkSpeed(pHw, speed, full_duplex);
+ sc->anlpar = anlpar;
+ }
+ ifp->if_timer = WATCHDOG_TIMEOUT;
+}
+
+
+/*
+ * Sets up the hardware and chooses the interface to be used
+ */
+static void if_atsam_init(void *arg)
+{
+ rtems_status_code status;
+
+ if_atsam_softc *sc = (if_atsam_softc *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ uint32_t dmac_cfg = 0;
+ uint32_t gmii_val = 0;
+
+ if (sc->arpcom.ac_if.if_flags & IFF_RUNNING) {
+ return;
+ }
+ sc->arpcom.ac_if.if_flags |= IFF_RUNNING;
+ sc->interrupt_number = GMAC_IRQn;
+
+ /* Enable Peripheral Clock */
+ if ((PMC->PMC_PCSR1 & (1u << 7)) != (1u << 7)) {
+ PMC->PMC_PCER1 = 1 << 7;
+ }
+ /* Setup interrupts */
+ NVIC_ClearPendingIRQ(GMAC_IRQn);
+ NVIC_EnableIRQ(GMAC_IRQn);
+
+ GMACD_Init(&sc->Gmac_inst.gGmacd, GMAC, ID_GMAC, GMAC_CAF_ENABLE,
+ GMAC_NBC_DISABLE);
+
+ /* Enable MDIO interface */
+ GMAC_EnableMdio(sc->Gmac_inst.gGmacd.pHw);
+
+ /* PHY initialize */
+ if_atsam_init_phy(&sc->Gmac_inst, BOARD_MCK, &gmacResetPin, 1,
+ gmacPins, PIO_LISTSIZE(gmacPins));
+ /* Find valid Phy */
+ atsamv7_find_valid_phy(&sc->Gmac_inst);
+
+ /* Set Link Speed */
+ sc->anlpar = 0xFFFFFFFF;
+ if_atsam_interface_watchdog(ifp);
+
+ /* Enable autonegotation */
+ if_atsam_read_phy(sc->Gmac_inst.gGmacd.pHw, sc->Gmac_inst.phy_address,
+ MII_BMCR, &gmii_val, sc->Gmac_inst.retries);
+ if_atsam_write_phy(sc->Gmac_inst.gGmacd.pHw, sc->Gmac_inst.phy_address,
+ MII_BMCR, (gmii_val | BMCR_AUTOEN), sc->Gmac_inst.retries);
+
+ /* Configuration of DMAC */
+ dmac_cfg = (GMAC_DCFGR_DRBS(GMAC_RX_BUFFER_SIZE >> 6)) |
+ GMAC_DCFGR_RXBMS(3) | GMAC_DCFGR_TXPBMS | GMAC_DCFGR_FBLDO_INCR16;
+ GMAC_SetDMAConfig(sc->Gmac_inst.gGmacd.pHw, dmac_cfg, 0);
+
+ /* Shut down Transmit and Receive */
+ GMAC_ReceiveEnable(sc->Gmac_inst.gGmacd.pHw, 0);
+ GMAC_TransmitEnable(sc->Gmac_inst.gGmacd.pHw, 0);
+
+ GMAC_StatisticsWriteEnable(sc->Gmac_inst.gGmacd.pHw, 1);
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rx_mbuf = malloc(sc->amount_rx_buf * sizeof *sc->rx_mbuf,
+ M_MBUF, M_NOWAIT);
+ sc->tx_mbuf = malloc(sc->amount_tx_buf * sizeof *sc->tx_mbuf,
+ M_MBUF, M_NOWAIT);
+
+ /* Install interrupt handler */
+ status = rtems_interrupt_handler_install(sc->interrupt_number,
+ "Ethernet",
+ RTEMS_INTERRUPT_UNIQUE,
+ if_atsam_interrupt_handler,
+ sc);
+ assert(status == RTEMS_SUCCESSFUL);
+
+ /*
+ * Start driver tasks
+ */
+ sc->rx_daemon_tid = rtems_bsdnet_newproc("SCrx", 4096,
+ if_atsam_rx_daemon, sc);
+ sc->tx_daemon_tid = rtems_bsdnet_newproc("SCtx", 4096,
+ if_atsam_tx_daemon, sc);
+
+ /* Start Watchdog Timer */
+ ifp->if_timer = 1;
+}
+
+
+/*
+ * Stop the device
+ */
+static void if_atsam_stop(struct if_atsam_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /* Disable MDIO interface and TX/RX */
+ pHw->GMAC_NCR &= ~(GMAC_NCR_RXEN | GMAC_NCR_TXEN);
+ pHw->GMAC_NCR &= ~GMAC_NCR_MPE;
+}
+
+
+/*
+ * Show interface statistics
+ */
+static void if_atsam_stats(struct if_atsam_softc *sc)
+{
+ int eno = EIO;
+ int media = 0;
+ Gmac *pHw;
+
+ media = (int)IFM_MAKEWORD(0, 0, 0, sc->Gmac_inst.phy_address);
+ eno = rtems_mii_ioctl(&sc->mdio, sc, SIOCGIFMEDIA, &media);
+
+ rtems_bsdnet_semaphore_release();
+
+ if (eno == 0) {
+ rtems_ifmedia2str(media, NULL, 0);
+ printf("\n");
+ }
+ pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ printf("\n** Context Statistics **\n");
+ printf("Rx interrupts: %u\n", sc->rx_interrupts);
+ printf("Tx interrupts: %u\n", sc->tx_interrupts);
+ printf("Error Tur Tx interrupts: %u\n\n", sc->tx_tur_errors);
+ printf("Error Rlex Tx interrupts: %u\n\n", sc->tx_rlex_errors);
+ printf("Error Tfc Tx interrupts: %u\n\n", sc->tx_tfc_errors);
+ printf("Error Hresp Tx interrupts: %u\n\n", sc->tx_hresp_errors);
+ printf("Tx complete interrupts: %u\n\n", sc->tx_complete_int);
+ printf("\n** Statistics **\n");
+ printf("Octets Transmitted Low: %lu\n", pHw->GMAC_OTLO);
+ printf("Octets Transmitted High: %lu\n", pHw->GMAC_OTHI);
+ printf("Frames Transmitted: %lu\n", pHw->GMAC_FT);
+ printf("Broadcast Frames Transmitted: %lu\n", pHw->GMAC_BCFT);
+ printf("Multicast Frames Transmitted: %lu\n", pHw->GMAC_MFT);
+ printf("Pause Frames Transmitted: %lu\n", pHw->GMAC_PFT);
+ printf("64 Byte Frames Transmitted: %lu\n", pHw->GMAC_BFT64);
+ printf("65 to 127 Byte Frames Transmitted: %lu\n", pHw->GMAC_TBFT127);
+ printf("128 to 255 Byte Frames Transmitted: %lu\n", pHw->GMAC_TBFR255);
+ printf("256 to 511 Byte Frames Transmitted: %lu\n", pHw->GMAC_TBFT511);
+ printf("512 to 1023 Byte Frames Transmitted: %lu\n",
+ pHw->GMAC_TBFT1023);
+ printf("1024 to 1518 Byte Frames Transmitted: %lu\n",
+ pHw->GMAC_TBFT1518);
+ printf("Greater Than 1518 Byte Frames Transmitted: %lu\n",
+ pHw->GMAC_GTBFT1518);
+ printf("Transmit Underruns: %lu\n", pHw->GMAC_TUR);
+ printf("Single Collision Frames: %lu\n", pHw->GMAC_SCF);
+ printf("Multiple Collision Frames: %lu\n", pHw->GMAC_MCF);
+ printf("Excessive Collisions: %lu\n", pHw->GMAC_EC);
+ printf("Late Collisions: %lu\n", pHw->GMAC_LC);
+ printf("Deferred Transmission Frames: %lu\n", pHw->GMAC_DTF);
+ printf("Carrier Sense Errors: %lu\n", pHw->GMAC_CSE);
+ printf("Octets Received Low: %lu\n", pHw->GMAC_ORLO);
+ printf("Octets Received High: %lu\n", pHw->GMAC_ORHI);
+ printf("Frames Received: %lu\n", pHw->GMAC_FR);
+ printf("Broadcast Frames Received: %lu\n", pHw->GMAC_BCFR);
+ printf("Multicast Frames Received: %lu\n", pHw->GMAC_MFR);
+ printf("Pause Frames Received: %lu\n", pHw->GMAC_PFR);
+ printf("64 Byte Frames Received: %lu\n", pHw->GMAC_BFR64);
+ printf("65 to 127 Byte Frames Received: %lu\n", pHw->GMAC_TBFR127);
+ printf("128 to 255 Byte Frames Received: %lu\n", pHw->GMAC_TBFR255);
+ printf("256 to 511 Byte Frames Received: %lu\n", pHw->GMAC_TBFR511);
+ printf("512 to 1023 Byte Frames Received: %lu\n", pHw->GMAC_TBFR1023);
+ printf("1024 to 1518 Byte Frames Received: %lu\n", pHw->GMAC_TBFR1518);
+ printf("1519 to Maximum Byte Frames Received: %lu\n",
+ pHw->GMAC_TBFR1518);
+ printf("Undersize Frames Received: %lu\n", pHw->GMAC_UFR);
+ printf("Oversize Frames Received: %lu\n", pHw->GMAC_OFR);
+ printf("Jabbers Received: %lu\n", pHw->GMAC_JR);
+ printf("Frame Check Sequence Errors: %lu\n", pHw->GMAC_FCSE);
+ printf("Length Field Frame Errors: %lu\n", pHw->GMAC_LFFE);
+ printf("Receive Symbol Errors: %lu\n", pHw->GMAC_RSE);
+ printf("Alignment Errors: %lu\n", pHw->GMAC_AE);
+ printf("Receive Resource Errors: %lu\n", pHw->GMAC_RRE);
+ printf("Receive Overrun: %lu\n", pHw->GMAC_ROE);
+ printf("IP Header Checksum Errors: %lu\n", pHw->GMAC_IHCE);
+ printf("TCP Checksum Errors: %lu\n", pHw->GMAC_TCE);
+ printf("UDP Checksum Errors: %lu\n", pHw->GMAC_UCE);
+
+ rtems_bsdnet_semaphore_obtain();
+}
+
+
+/*
+ * Calculates the index that is to be sent into the hash registers
+ */
+static void if_atsam_get_hash_index(uint64_t addr, uint32_t *val)
+{
+ uint64_t tmp_val;
+ uint8_t i, j;
+ uint64_t idx;
+ int offset = 0;
+
+ addr &= MAC_ADDR_MASK;
+
+ for (i = 0; i < HASH_INDEX_AMOUNT; ++i) {
+ tmp_val = 0;
+ offset = 0;
+ for (j = 0; j < HASH_ELEMENTS_PER_INDEX; j++) {
+ idx = (addr >> (offset + i)) & MAC_IDX_MASK;
+ tmp_val ^= idx;
+ offset += HASH_INDEX_AMOUNT;
+ }
+ if (tmp_val > 0) {
+ *val |= (1u << i);
+ }
+ }
+}
+
+
+/*
+ * Dis/Enable promiscuous Mode
+ */
+static void if_atsam_promiscuous_mode(if_atsam_softc *sc, bool enable)
+{
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ if (enable) {
+ pHw->GMAC_NCFGR |= GMAC_PROM_ENABLE;
+ } else {
+ pHw->GMAC_NCFGR &= ~GMAC_PROM_ENABLE;
+ }
+}
+
+
+/*
+ * Multicast handler
+ */
+static int
+if_atsam_multicast_control(bool add, struct ifreq *ifr, if_atsam_softc *sc)
+{
+ int eno = 0;
+ struct arpcom *ac = &sc->arpcom;
+ Gmac *pHw = sc->Gmac_inst.gGmacd.pHw;
+
+ /* Switch off Multicast Hashing */
+ pHw->GMAC_NCFGR &= ~GMAC_MC_ENABLE;
+
+ if (add) {
+ eno = ether_addmulti(ifr, ac);
+ } else {
+ eno = ether_delmulti(ifr, ac);
+ }
+
+ if (eno == ENETRESET) {
+ struct ether_multistep step;
+ struct ether_multi *enm;
+
+ eno = 0;
+
+ pHw->GMAC_HRB = 0;
+ pHw->GMAC_HRT = 0;
+
+ ETHER_FIRST_MULTI(step, ac, enm);
+ while (enm != NULL) {
+ uint64_t addrlo = 0;
+ uint64_t addrhi = 0;
+ uint32_t val = 0;
+
+ memcpy(&addrlo, enm->enm_addrlo, ETHER_ADDR_LEN);
+ memcpy(&addrhi, enm->enm_addrhi, ETHER_ADDR_LEN);
+ while (addrlo <= addrhi) {
+ if_atsam_get_hash_index(addrlo, &val);
+ if (val < 32) {
+ pHw->GMAC_HRB |= (1u << val);
+ } else {
+ pHw->GMAC_HRT |= (1u << (val - 32));
+ }
+ ++addrlo;
+ }
+ ETHER_NEXT_MULTI(step, enm);
+ }
+ }
+ /* Switch on Multicast Hashing */
+ pHw->GMAC_NCFGR |= GMAC_MC_ENABLE;
+ return (eno);
+}
+
+
+/*
+ * Driver ioctl handler
+ */
+static int
+if_atsam_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct if_atsam_softc *sc = (if_atsam_softc *)ifp->if_softc;
+ struct ifreq *ifr = (struct ifreq *)data;
+ int rv = 0;
+ bool prom_enable;
+
+ switch (command) {
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ rtems_mii_ioctl(&sc->mdio, sc, command, &ifr->ifr_media);
+ break;
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+ case SIOCSIFFLAGS:
+ if (ifp->if_flags & IFF_UP) {
+ if (ifp->if_flags & IFF_RUNNING) {
+ /* Don't do anything */
+ } else {
+ if_atsam_init(sc);
+ }
+ prom_enable = ((ifp->if_flags & IFF_PROMISC) != 0);
+ if_atsam_promiscuous_mode(sc, prom_enable);
+ } else {
+ if (ifp->if_flags & IFF_RUNNING) {
+ if_atsam_stop(sc);
+ }
+ }
+ break;
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ if_atsam_multicast_control(command == SIOCADDMULTI, ifr, sc);
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ if_atsam_stats(sc);
+ break;
+ default:
+ rv = EINVAL;
+ break;
+ }
+ return (rv);
+}
+
+
+/*
+ * Attach an SAMV71 driver to the system
+ */
+static int if_atsam_driver_attach(struct rtems_bsdnet_ifconfig *config)
+{
+ if_atsam_softc *sc = &if_atsam_softc_inst;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ const if_atsam_config *conf = config->drv_ctrl;
+ int unitNumber;
+ char *unitName;
+
+ if (conf != NULL) {
+ sc->Gmac_inst.retries = conf->mdio_retries;
+ sc->Gmac_inst.phy_address = conf->phy_addr;
+ } else {
+ sc->Gmac_inst.retries = 10;
+ sc->Gmac_inst.phy_address = 0xFF;
+ }
+
+ /* The MAC address used */
+ memcpy(sc->GMacAddress, config->hardware_address, ETHER_ADDR_LEN);
+ memcpy(sc->arpcom.ac_enaddr, sc->GMacAddress, ETHER_ADDR_LEN);
+
+ /*
+ * Parse driver name
+ */
+ unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName);
+ assert(unitNumber == 0);
+
+ assert(ifp->if_softc == NULL);
+
+ /* MDIO */
+ sc->mdio.mdio_r = if_atsam_mdio_read;
+ sc->mdio.mdio_w = if_atsam_mdio_write;
+ sc->mdio.has_gmii = 1;
+
+ if (config->rbuf_count > 0) {
+ sc->amount_rx_buf = config->rbuf_count;
+ } else {
+ sc->amount_rx_buf = 8;
+ }
+
+ if (config->xbuf_count > 0) {
+ sc->amount_tx_buf = config->xbuf_count;
+ } else {
+ sc->amount_tx_buf = 64;
+ }
+
+ sc->tx_ring.tx_bd_used = 0;
+ sc->tx_ring.tx_bd_free = 0;
+ sc->tx_ring.length = sc->amount_tx_buf;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = (short int)unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = ETHERMTU;
+ ifp->if_init = if_atsam_init;
+ ifp->if_ioctl = if_atsam_ioctl;
+ ifp->if_start = if_atsam_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = if_atsam_interface_watchdog;
+ ifp->if_flags = IFF_MULTICAST | IFF_BROADCAST | IFF_SIMPLEX;
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ ifp->if_timer = 0;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ return (1);
+}
+
+
+int if_atsam_attach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ (void)attaching;
+ return (if_atsam_driver_attach(config));
+}
diff --git a/bsps/arm/csb336/net/lan91c11x.c b/bsps/arm/csb336/net/lan91c11x.c
new file mode 100644
index 0000000..779fbdc
--- /dev/null
+++ b/bsps/arm/csb336/net/lan91c11x.c
@@ -0,0 +1,261 @@
+/**
+ * @file
+ *
+ * @ingroup RTEMSBSPsARMCSB336
+ *
+ * @brief Helper functions for SMSC LAN91C11x
+ */
+
+/*
+ * Helper functions for SMSC LAN91C11x
+ *
+ * Copyright (c) 2004 by Cogent Computer Systems
+ * Written by Jay Monkman <jtm@lopingdog.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <sys/types.h>
+#include <rtems.h>
+#include "lan91c11x.h"
+
+uint16_t lan91c11x_read_reg(int reg)
+{
+ volatile uint16_t *ptr = (uint16_t *)LAN91C11X_BASE_ADDR;
+ uint16_t old_bank;
+ uint16_t val;
+ rtems_interrupt_level level;
+
+ rtems_interrupt_disable(level);
+
+ /* save the bank register */
+ old_bank = ptr[7] & 0x7;
+
+ /* set the bank register */
+ ptr[7] = (reg >> 4) & 0x7;
+
+ val = ptr[((reg & 0xf) >> 1)];
+
+ /* restore the bank register */
+ ptr[7] = old_bank;
+
+ rtems_interrupt_enable(level);
+ return val;
+}
+
+void lan91c11x_write_reg(int reg, uint16_t value)
+{
+ volatile uint16_t *ptr = (uint16_t *)LAN91C11X_BASE_ADDR;
+ uint16_t old_bank;
+ rtems_interrupt_level level;
+
+ rtems_interrupt_disable(level);
+
+ /* save the bank register */
+ old_bank = ptr[7] & 0x7;
+
+ /* set the bank register */
+ ptr[7] = (reg >> 4) & 0x7;
+
+ ptr[((reg & 0xf) >> 1)] = value;
+
+ /* restore the bank register */
+ ptr[7] = old_bank;
+
+ rtems_interrupt_enable(level);
+}
+
+uint16_t lan91c11x_read_reg_fast(int reg)
+{
+ volatile uint16_t *ptr = (uint16_t *)LAN91C11X_BASE_ADDR;
+ uint16_t val;
+
+ val = ptr[((reg & 0xf) >> 1)];
+
+ return val;
+}
+
+void lan91c11x_write_reg_fast(int reg, uint16_t value)
+{
+ volatile uint16_t *ptr = (uint16_t *)LAN91C11X_BASE_ADDR;
+
+ ptr[((reg & 0xf) >> 1)] = value;
+}
+
+
+uint16_t lan91c11x_read_phy_reg(int reg)
+{
+ int i;
+ uint16_t mask;
+ uint16_t bits[64];
+ int clk_idx = 0;
+ int input_idx = 0;
+ uint16_t phydata;
+
+ /* 32 consecutive ones on MDO to establish sync */
+ for (i = 0; i < 32; ++i) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ }
+
+ /* Start code <01> */
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+
+ /* Read command <10> */
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+
+ /* Output the PHY address, msb first - Internal PHY is address 0 */
+ for (i = 0; i < 5; ++i) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ }
+
+ /* Output the phy register number, msb first */
+ mask = 0x10;
+ for (i = 0; i < 5; ++i) {
+ if (reg & mask) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ } else {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ }
+
+
+ /* Shift to next lowest bit */
+ mask >>= 1;
+ }
+
+ /* 1 bit time for turnaround */
+ bits[clk_idx++] = 0;
+
+ /* Input starts at this bit time */
+ input_idx = clk_idx;
+
+ /* Will input 16 bits */
+ for (i = 0; i < 16; ++i) {
+ bits[clk_idx++] = 0;
+ }
+
+ /* Final clock bit */
+ bits[clk_idx++] = 0;
+
+ /* Turn off all MII Interface bits */
+ lan91c11x_write_reg(LAN91C11X_MGMT,
+ lan91c11x_read_reg(LAN91C11X_MGMT) & 0xfff0);
+
+ /* Clock all 64 cycles */
+ for (i = 0; i < sizeof bits; ++i) {
+ /* Clock Low - output data */
+ lan91c11x_write_reg(LAN91C11X_MGMT, bits[i]);
+ rtems_task_wake_after(1);
+
+ /* Clock Hi - input data */
+ lan91c11x_write_reg(LAN91C11X_MGMT, bits[i] | LAN91C11X_MGMT_MCLK);
+ rtems_task_wake_after(1);
+ bits[i] |= lan91c11x_read_reg(LAN91C11X_MGMT) & LAN91C11X_MGMT_MDI;
+ }
+
+ /* Return to idle state */
+ /* Set clock to low, data to low, and output tristated */
+ lan91c11x_write_reg(LAN91C11X_MGMT, lan91c11x_read_reg(LAN91C11X_MGMT) & 0xfff0);
+ rtems_task_wake_after(1);
+
+ /* Recover input data */
+ phydata = 0;
+ for (i = 0; i < 16; ++i) {
+ phydata <<= 1;
+
+ if (bits[input_idx++] & LAN91C11X_MGMT_MDI) {
+ phydata |= 0x0001;
+ }
+ }
+
+ return phydata;
+}
+
+
+
+void lan91c11x_write_phy_reg(int reg, uint16_t phydata)
+{
+ int i;
+ ushort mask;
+ ushort bits[64];
+ int clk_idx = 0;
+
+ /* 32 consecutive ones on MDO to establish sync */
+ for (i = 0; i < 32; ++i) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ }
+
+ /* Start code <01> */
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+
+ /* Write command <01> */
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+
+ /* Output the PHY address, msb first - Internal PHY is address 0 */
+ for (i = 0; i < 5; ++i) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ }
+
+ /* Output the phy register number, msb first */
+ mask = 0x10;
+ for (i = 0; i < 5; ++i) {
+ if (reg & mask) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ } else {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ }
+
+ /* Shift to next lowest bit */
+ mask >>= 1;
+ }
+
+ /* 2 extra bit times for turnaround */
+ bits[clk_idx++] = 0;
+ bits[clk_idx++] = 0;
+
+ /* Write out 16 bits of data, msb first */
+ mask = 0x8000;
+ for (i = 0; i < 16; ++i) {
+ if (phydata & mask) {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE | LAN91C11X_MGMT_MDO;
+ } else {
+ bits[clk_idx++] = LAN91C11X_MGMT_MDOE;
+ }
+
+ /* Shift to next lowest bit */
+ mask >>= 1;
+ }
+
+ /* Turn off all MII Interface bits */
+ lan91c11x_write_reg(LAN91C11X_MGMT,
+ lan91c11x_read_reg(LAN91C11X_MGMT) & 0xfff0);
+
+ /* Clock all 64 cycles */
+ for (i = 0; i < sizeof bits; ++i) {
+ /* Clock Low - output data */
+ lan91c11x_write_reg(LAN91C11X_MGMT, bits[i]);
+ rtems_task_wake_after(1);
+
+ /* Clock Hi - input data */
+ lan91c11x_write_reg(LAN91C11X_MGMT, bits[i] | LAN91C11X_MGMT_MCLK);
+ rtems_task_wake_after(1);
+ bits[i] |= lan91c11x_read_reg(LAN91C11X_MGMT) & LAN91C11X_MGMT_MDI;
+ }
+
+ /* Return to idle state */
+ /* Set clock to low, data to low, and output tristated */
+ lan91c11x_write_reg(LAN91C11X_MGMT,
+ lan91c11x_read_reg(LAN91C11X_MGMT) & 0xfff0);
+ rtems_task_wake_after(1);
+
+}
+
+
+
diff --git a/bsps/arm/csb336/net/lan91c11x.h b/bsps/arm/csb336/net/lan91c11x.h
new file mode 100644
index 0000000..c1181bd
--- /dev/null
+++ b/bsps/arm/csb336/net/lan91c11x.h
@@ -0,0 +1,229 @@
+/**
+ * @file
+ *
+ * @ingroup RTEMSBSPsARMCSB336
+ *
+ * @brief SMSC LAN91C11x ethernet devices definitions.
+ */
+
+/**
+ * @defgroup arm_csb336_lan91c11x SMSC LAN91C11x
+ *
+ * @ingroup RTEMSBSPsARMCSB336
+ *
+ * @brief SMSC LAN91C11x ethernet devices definitions.
+ */
+
+/*
+ * Header file for SMSC LAN91C11x ethernet devices
+ *
+ * Copyright (c) 2004 by Cogent Computer Systems
+ * Written by Jay Monkman <jtm@lopingdog.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+#ifndef __LAN91C11X_H__
+#define __LAN91C11X_H__
+
+#include <rtems.h>
+#include <bsp.h>
+
+uint16_t lan91c11x_read_reg(int);
+void lan91c11x_write_reg(int, uint16_t);
+uint16_t lan91c11x_read_reg_fast(int);
+void lan91c11x_write_reg_fast(int, uint16_t);
+void lan91c11x_write_phy_reg(int , uint16_t);
+uint16_t lan91c11x_read_phy_reg(int);
+void lan91c11x_unlock(void);
+void lan91c11x_lock(void);
+
+#define LAN91C11X_BASE_ADDR 0x12000000
+
+#define LAN91C11X_REG(_b_, _r_) ((((_b_) & 0xf) << 4) | ((_r_) & 0xf))
+
+
+#define LAN91C11X_TCR (LAN91C11X_REG(0, 0x0))
+#define LAN91C11X_EPHSTAT (LAN91C11X_REG(0, 0x2))
+#define LAN91C11X_RCR (LAN91C11X_REG(0, 0x4))
+#define LAN91C11X_CNTR (LAN91C11X_REG(0, 0x6))
+#define LAN91C11X_MIR (LAN91C11X_REG(0, 0x8))
+#define LAN91C11X_RPCR (LAN91C11X_REG(0, 0xa))
+#define LAN91C11X_BANK (LAN91C11X_REG(0, 0xe))
+#define LAN91C11X_CONFIG (LAN91C11X_REG(1, 0x0))
+#define LAN91C11X_BASE (LAN91C11X_REG(1, 0x2))
+#define LAN91C11X_IA0 (LAN91C11X_REG(1, 0x4))
+#define LAN91C11X_IA2 (LAN91C11X_REG(1, 0x6))
+#define LAN91C11X_IA4 (LAN91C11X_REG(1, 0x8))
+#define LAN91C11X_GNRL (LAN91C11X_REG(1, 0xa))
+#define LAN91C11X_CTRL (LAN91C11X_REG(1, 0xc))
+#define LAN91C11X_MMUCMD (LAN91C11X_REG(2, 0x0))
+#define LAN91C11X_PNR (LAN91C11X_REG(2, 0x2))
+#define LAN91C11X_FIFO (LAN91C11X_REG(2, 0x4))
+#define LAN91C11X_PTR (LAN91C11X_REG(2, 0x6))
+#define LAN91C11X_DATA (LAN91C11X_REG(2, 0x8))
+#define LAN91C11X_INT (LAN91C11X_REG(2, 0xc))
+#define LAN91C11X_MT0 (LAN91C11X_REG(3, 0x0))
+#define LAN91C11X_MT2 (LAN91C11X_REG(3, 0x2))
+#define LAN91C11X_MT4 (LAN91C11X_REG(3, 0x4))
+#define LAN91C11X_MT6 (LAN91C11X_REG(3, 0x6))
+#define LAN91C11X_MGMT (LAN91C11X_REG(3, 0x8))
+#define LAN91C11X_REV (LAN91C11X_REG(3, 0xa))
+#define LAN91C11X_ERCV (LAN91C11X_REG(3, 0xc))
+
+
+#define LAN91C11X_TCR_TXENA (bit(0))
+#define LAN91C11X_TCR_LOOP (bit(1))
+#define LAN91C11X_TCR_FORCOL (bit(2))
+#define LAN91C11X_TCR_PADEN (bit(7))
+#define LAN91C11X_TCR_NOCRC (bit(8))
+#define LAN91C11X_TCR_MONCSN (bit(10))
+#define LAN91C11X_TCR_FDUPLX (bit(11))
+#define LAN91C11X_TCR_STPSQET (bit(12))
+#define LAN91C11X_TCR_EPHLOOP (bit(13))
+#define LAN91C11X_TCR_SWFDUP (bit(15))
+
+#define LAN91C11X_EPHSTAT_TXSUC (bit(0))
+#define LAN91C11X_EPHSTAT_SNGLCOL (bit(1))
+#define LAN91C11X_EPHSTAT_MULCOL (bit(2))
+#define LAN91C11X_EPHSTAT_LTXMUL (bit(3))
+#define LAN91C11X_EPHSTAT_16COL (bit(4))
+#define LAN91C11X_EPHSTAT_SQET (bit(5))
+#define LAN91C11X_EPHSTAT_LTXBRD (bit(6))
+#define LAN91C11X_EPHSTAT_TXDFR (bit(7))
+#define LAN91C11X_EPHSTAT_LATCOL (bit(9))
+#define LAN91C11X_EPHSTAT_LOST (bit(10))
+#define LAN91C11X_EPHSTAT_EXCDEF (bit(11))
+#define LAN91C11X_EPHSTAT_CTRROL (bit(12))
+#define LAN91C11X_EPHSTAT_LINK (bit(14))
+#define LAN91C11X_EPHSTAT_TXUNRN (bit(15))
+
+#define LAN91C11X_RCR_RXABT (bit(0))
+#define LAN91C11X_RCR_PRMS (bit(1))
+#define LAN91C11X_RCR_ALMUL (bit(2))
+#define LAN91C11X_RCR_RXEN (bit(8))
+#define LAN91C11X_RCR_STRIP (bit(9))
+#define LAN91C11X_RCR_ABTENB (bit(13))
+#define LAN91C11X_RCR_FILT (bit(14))
+#define LAN91C11X_RCR_RST (bit(15))
+
+#define LAN91C11X_RPCR_LS0B (bit(2))
+#define LAN91C11X_RPCR_LS1B (bit(3))
+#define LAN91C11X_RPCR_LS2B (bit(4))
+#define LAN91C11X_RPCR_LS0A (bit(5))
+#define LAN91C11X_RPCR_LS1A (bit(6))
+#define LAN91C11X_RPCR_LS2A (bit(7))
+#define LAN91C11X_RPCR_ANEG (bit(11))
+#define LAN91C11X_RPCR_DPLX (bit(12))
+#define LAN91C11X_RPCR_SPEED (bit(13))
+
+#define LAN91C11X_CONFIG_EXTPHY (bit(9))
+#define LAN91C11X_CONFIG_GPCTRL (bit(10))
+#define LAN91C11X_CONFIG_NOWAIT (bit(12))
+#define LAN91C11X_CONFIG_PWR (bit(15))
+
+#define LAN91C11X_CTRL_STORE (bit(0))
+#define LAN91C11X_CTRL_RELOAD (bit(1))
+#define LAN91C11X_CTRL_EEPROM (bit(2))
+#define LAN91C11X_CTRL_TEEN (bit(5))
+#define LAN91C11X_CTRL_CREN (bit(6))
+#define LAN91C11X_CTRL_LEEN (bit(7))
+#define LAN91C11X_CTRL_AUTO (bit(11))
+#define LAN91C11X_CTRL_RCVBAD (bit(14))
+
+#define LAN91C11X_MMUCMD_BUSY (bit(0))
+#define LAN91C11X_MMUCMD_NOOP (0 << 5)
+#define LAN91C11X_MMUCMD_ALLOCTX (1 << 5)
+#define LAN91C11X_MMUCMD_RESETMMU (2 << 5)
+#define LAN91C11X_MMUCMD_REMFRM (3 << 5)
+#define LAN91C11X_MMUCMD_REMTOP (4 << 5)
+#define LAN91C11X_MMUCMD_RELEASE (5 << 5)
+#define LAN91C11X_MMUCMD_ENQUEUE (6 << 5)
+#define LAN91C11X_MMUCMD_RESETTX (7 << 5)
+
+#define LAN91C11X_PTR_MASK (0x7ff)
+#define LAN91C11X_PTR_NE (bit(11))
+#define LAN91C11X_PTR_ETEN (bit(12))
+#define LAN91C11X_PTR_READ (bit(13))
+#define LAN91C11X_PTR_AUTOINC (bit(14))
+#define LAN91C11X_PTR_RCV (bit(15))
+
+#define LAN91C11X_INT_RX (bit(0))
+#define LAN91C11X_INT_TX (bit(1))
+#define LAN91C11X_INT_TXE (bit(2))
+#define LAN91C11X_INT_ALLOC (bit(3))
+#define LAN91C11X_INT_RXOV (bit(4))
+#define LAN91C11X_INT_EPH (bit(5))
+#define LAN91C11X_INT_ERX (bit(6))
+#define LAN91C11X_INT_MD (bit(7))
+#define LAN91C11X_INT_RXMASK (bit(8))
+#define LAN91C11X_INT_TXMASK (bit(9))
+#define LAN91C11X_INT_TXEMASK (bit(10))
+#define LAN91C11X_INT_ALLOCMASK (bit(11))
+#define LAN91C11X_INT_RXOVMASK (bit(12))
+#define LAN91C11X_INT_EPHMASK (bit(13))
+#define LAN91C11X_INT_ERXMASK (bit(14))
+#define LAN91C11X_INT_MDMASK (bit(15))
+
+#define LAN91C11X_MGMT_MDO (bit(0))
+#define LAN91C11X_MGMT_MDI (bit(1))
+#define LAN91C11X_MGMT_MCLK (bit(2))
+#define LAN91C11X_MGMT_MDOE (bit(3))
+#define LAN91C11X_MGMT_MSKCRS100 (bit(14))
+
+
+#define LAN91C11X_PKT_CTRL_CRC (bit(4))
+#define LAN91C11X_PKT_CTRL_ODD (bit(5))
+
+
+/* PHY Registers */
+#define PHY_CTRL 0x00 /* PHY Control */
+#define PHY_STAT 0x01 /* PHY Status */
+#define PHY_ID1 0x02 /* PHY Identifier 1 */
+#define PHY_ID2 0x03 /* PHY Identifier 2 */
+#define PHY_AD 0x04 /* PHY Auto-negotiate Control */
+#define PHY_RMT 0x05 /* PHY Auto-neg Remote End Cap Register */
+#define PHY_CFG1 0x10 /* PHY Configuration 1 */
+#define PHY_CFG2 0x11 /* PHY Configuration 2 */
+#define PHY_INT 0x12 /* Status Output (Interrupt Status) */
+#define PHY_MASK 0x13 /* Interrupt Mask */
+
+/* PHY Control Register Bit Defines */
+#define PHY_CTRL_RST 0x8000 /* PHY Reset */
+#define PHY_CTRL_LPBK 0x4000 /* PHY Loopback */
+#define PHY_CTRL_SPEED 0x2000 /* 100Mbps, 0=10Mpbs */
+#define PHY_CTRL_ANEGEN 0x1000 /* Enable Auto negotiation */
+#define PHY_CTRL_PDN 0x0800 /* PHY Power Down mode */
+#define PHY_CTRL_MIIDIS 0x0400 /* MII 4 bit interface disabled */
+#define PHY_CTRL_ANEGRST 0x0200 /* Reset Auto negotiate */
+#define PHY_CTRL_DPLX 0x0100 /* Full Duplex, 0=Half Duplex */
+#define PHY_CTRL_COLTST 0x0080 /* MII Colision Test */
+
+#define PHY_STAT_CAPT4 0x8000
+#define PHY_STAT_CAPTXF 0x4000
+#define PHY_STAT_CAPTXH 0x2000
+#define PHY_STAT_CAPTF 0x1000
+#define PHY_STAT_CAPTH 0x0800
+#define PHY_STAT_CAPSUPR 0x0040
+#define PHY_STAT_ANEGACK 0x0020
+#define PHY_STAT_REMFLT 0x0010
+#define PHY_STAT_CAPANEG 0x0008
+#define PHY_STAT_LINK 0x0004
+#define PHY_STAT_JAB 0x0002
+#define PHY_STAT_EXREG 0x0001
+
+#define PHY_ADV_NP 0x8000
+#define PHY_ADV_ACK 0x4000
+#define PHY_ADV_RF 0x2000
+#define PHY_ADV_T4 0x0200
+#define PHY_ADV_TXFDX 0x0100
+#define PHY_ADV_TXHDX 0x0080
+#define PHY_ADV_10FDX 0x0040
+#define PHY_ADV_10HDX 0x0020
+#define PHY_ADV_CSMA 0x0001
+
+
+
+
+#endif /* __LAN91C11X_H__ */
diff --git a/bsps/arm/csb336/net/network.c b/bsps/arm/csb336/net/network.c
new file mode 100644
index 0000000..ddc671a
--- /dev/null
+++ b/bsps/arm/csb336/net/network.c
@@ -0,0 +1,708 @@
+/*
+ * MC9323MXL Ethernet driver
+ *
+ * Copyright (c) 2004 by Cogent Computer Systems
+ * Written by Jay Monkman <jtm@lopingdog.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <mc9328mxl.h>
+#include "lan91c11x.h"
+
+#include <stdio.h>
+#include <string.h>
+
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/bspIo.h>
+#include <assert.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <bsp/irq.h>
+
+/* RTEMS event used by interrupt handler to start receive daemon. */
+#define START_RECEIVE_EVENT RTEMS_EVENT_1
+
+/* RTEMS event used to start transmit daemon. */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+static void enet_isr(void *);
+static void enet_isr_on(void);
+
+typedef struct {
+ unsigned long rx_packets; /* total packets received */
+ unsigned long tx_packets; /* total packets transmitted */
+ unsigned long rx_bytes; /* total bytes received */
+ unsigned long tx_bytes; /* total bytes transmitted */
+ unsigned long interrupts; /* total number of interrupts */
+ unsigned long rx_interrupts; /* total number of rx interrupts */
+ unsigned long tx_interrupts; /* total number of tx interrupts */
+ unsigned long txerr_interrupts; /* total number of tx error interrupts */
+
+} eth_stats_t;
+
+/*
+ * Hardware-specific storage
+ */
+typedef struct
+{
+ /*
+ * Connection to networking code
+ * This entry *must* be the first in the sonic_softc structure.
+ */
+ struct arpcom arpcom;
+
+ int accept_bcast;
+
+ /* Tasks waiting for interrupts */
+ rtems_id rx_task;
+ rtems_id tx_task;
+
+ eth_stats_t stats;
+
+} mc9328mxl_enet_softc_t;
+
+static mc9328mxl_enet_softc_t softc;
+
+
+/* function prototypes */
+int rtems_mc9328mxl_enet_attach(struct rtems_bsdnet_ifconfig *config,
+ void *chip);
+void mc9328mxl_enet_init(void *arg);
+void mc9328mxl_enet_init_hw(mc9328mxl_enet_softc_t *sc);
+void mc9328mxl_enet_start(struct ifnet *ifp);
+void mc9328mxl_enet_stop (mc9328mxl_enet_softc_t *sc);
+void mc9328mxl_enet_tx_task (void *arg);
+void mc9328mxl_enet_sendpacket (struct ifnet *ifp, struct mbuf *m);
+void mc9328mxl_enet_rx_task(void *arg);
+void mc9328mxl_enet_stats(mc9328mxl_enet_softc_t *sc);
+static int mc9328mxl_enet_ioctl(struct ifnet *ifp,
+ ioctl_command_t command, caddr_t data);
+
+
+int rtems_mc9328mxl_enet_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ void *chip /* only one ethernet, so no chip number */
+ )
+{
+ struct ifnet *ifp;
+ int mtu;
+ int unitnumber;
+ char *unitname;
+ int tmp;
+
+ /*
+ * Parse driver name
+ */
+ unitnumber = rtems_bsdnet_parse_driver_name(config, &unitname);
+ if (unitnumber < 0) {
+ return 0;
+ }
+
+ /*
+ * Is driver free?
+ */
+ if (unitnumber != 0) {
+ printf ("Bad MC9328MXL unit number.\n");
+ return 0;
+ }
+
+ ifp = &softc.arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf ("Driver already in use.\n");
+ return 0;
+ }
+
+ /* zero out the control structure */
+ memset( &softc, 0, sizeof(softc) );
+
+
+ /* set the MAC address */
+ tmp = lan91c11x_read_reg(LAN91C11X_IA0);
+ softc.arpcom.ac_enaddr[0] = tmp & 0xff;
+ softc.arpcom.ac_enaddr[1] = (tmp >> 8) & 0xff;
+
+ tmp = lan91c11x_read_reg(LAN91C11X_IA2);
+ softc.arpcom.ac_enaddr[2] = tmp & 0xff;
+ softc.arpcom.ac_enaddr[3] = (tmp >> 8) & 0xff;
+
+ tmp = lan91c11x_read_reg(LAN91C11X_IA4);
+ softc.arpcom.ac_enaddr[4] = tmp & 0xff;
+ softc.arpcom.ac_enaddr[5] = (tmp >> 8) & 0xff;
+
+ if (config->mtu) {
+ mtu = config->mtu;
+ } else {
+ mtu = ETHERMTU;
+ }
+
+ softc.accept_bcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = &softc;
+ ifp->if_unit = unitnumber;
+ ifp->if_name = unitname;
+ ifp->if_mtu = mtu;
+ ifp->if_init = mc9328mxl_enet_init;
+ ifp->if_ioctl = mc9328mxl_enet_ioctl;
+ ifp->if_start = mc9328mxl_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST;
+ if (ifp->if_snd.ifq_maxlen == 0) {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+
+ /* Attach the interface */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+}
+
+void mc9328mxl_enet_init(void *arg)
+{
+ mc9328mxl_enet_softc_t *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ /*
+ *This is for stuff that only gets done once (mc9328mxl_enet_init()
+ * gets called multiple times
+ */
+ if (sc->tx_task == 0)
+ {
+ /* Set up ENET hardware */
+ mc9328mxl_enet_init_hw(sc);
+
+ /* Start driver tasks */
+ sc->rx_task = rtems_bsdnet_newproc("ENrx",
+ 4096,
+ mc9328mxl_enet_rx_task,
+ sc);
+ sc->tx_task = rtems_bsdnet_newproc("ENtx",
+ 4096,
+ mc9328mxl_enet_tx_task,
+ sc);
+ } /* if tx_task */
+
+
+ /* Configure for promiscuous if needed */
+ if (ifp->if_flags & IFF_PROMISC) {
+ lan91c11x_write_reg(LAN91C11X_RCR,
+ (lan91c11x_read_reg(LAN91C11X_RCR) |
+ LAN91C11X_RCR_PRMS));
+ }
+
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /* Enable TX/RX */
+ lan91c11x_write_reg(LAN91C11X_TCR,
+ (lan91c11x_read_reg(LAN91C11X_TCR) |
+ LAN91C11X_TCR_TXENA));
+
+ lan91c11x_write_reg(LAN91C11X_RCR,
+ (lan91c11x_read_reg(LAN91C11X_RCR) |
+ LAN91C11X_RCR_RXEN));
+
+
+} /* mc9328mxl_enet_init() */
+
+void mc9328mxl_enet_init_hw(mc9328mxl_enet_softc_t *sc)
+{
+ uint16_t stat;
+ uint16_t my = 0;
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+
+ lan91c11x_write_reg(LAN91C11X_RCR, LAN91C11X_RCR_RST);
+ lan91c11x_write_reg(LAN91C11X_RCR, 0);
+ rtems_task_wake_after(1);
+
+ /* Reset the PHY */
+ lan91c11x_write_phy_reg(PHY_CTRL, PHY_CTRL_RST);
+ while(lan91c11x_read_phy_reg(PHY_CTRL) & PHY_CTRL_RST) {
+ rtems_task_wake_after(1);
+ }
+
+
+ stat = lan91c11x_read_phy_reg(PHY_STAT);
+
+ if(stat & PHY_STAT_CAPT4) {
+ my |= PHY_ADV_T4;
+ }
+/* 100Mbs doesn't work, so we won't advertise it */
+
+ if(stat & PHY_STAT_CAPTXF) {
+ my |= PHY_ADV_TXFDX;
+ }
+ if(stat & PHY_STAT_CAPTXH) {
+ my |= PHY_ADV_TXHDX;
+ }
+
+ if(stat & PHY_STAT_CAPTF) {
+ my |= PHY_ADV_10FDX;
+ }
+
+ if(stat & PHY_STAT_CAPTH) {
+ my |= PHY_ADV_10HDX;
+ }
+
+ my |= PHY_ADV_CSMA;
+
+ lan91c11x_write_phy_reg(PHY_AD, my);
+
+
+ /* Enable Autonegotiation */
+#if 0
+ lan91c11x_write_phy_reg(PHY_CTRL,
+ (PHY_CTRL_ANEGEN | PHY_CTRL_ANEGRST));
+#endif
+
+ /* Enable full duplex, let MAC take care
+ * of padding and CRC.
+ */
+ lan91c11x_write_reg(LAN91C11X_TCR,
+ (LAN91C11X_TCR_PADEN |
+ LAN91C11X_TCR_SWFDUP));
+
+ /* Disable promisc, don'tstrip CRC */
+ lan91c11x_write_reg(LAN91C11X_RCR, 0);
+
+ /* Enable auto-negotiation, LEDA is link, LEDB is traffic */
+ lan91c11x_write_reg(LAN91C11X_RPCR,
+ (LAN91C11X_RPCR_ANEG |
+ LAN91C11X_RPCR_LS2B));
+
+ /* Don't add wait states, enable PHY power */
+ lan91c11x_write_reg(LAN91C11X_CONFIG,
+ (LAN91C11X_CONFIG_NOWAIT |
+ LAN91C11X_CONFIG_PWR));
+
+ /* Disable error interrupts, enable auto release */
+ lan91c11x_write_reg(LAN91C11X_CTRL, LAN91C11X_CTRL_AUTO);
+
+ /* Reset MMU */
+ lan91c11x_write_reg(LAN91C11X_MMUCMD,
+ LAN91C11X_MMUCMD_RESETMMU );
+
+
+ rtems_task_wake_after(100);
+ /* Enable Autonegotiation */
+ lan91c11x_write_phy_reg(PHY_CTRL, 0x3000);
+ rtems_task_wake_after(100);
+
+ /* Enable Interrupts for RX */
+ lan91c11x_write_reg(LAN91C11X_INT, LAN91C11X_INT_RXMASK);
+
+ /* Enable interrupts on GPIO Port A3 */
+ /* Make pin 3 an input */
+ MC9328MXL_GPIOA_DDIR &= ~bit(3);
+
+ /* Use GPIO function for pin 3 */
+ MC9328MXL_GPIOA_GIUS |= bit(3);
+
+ /* Set for active high, level triggered interupt */
+ MC9328MXL_GPIOA_ICR1 = ((MC9328MXL_GPIOA_ICR1 & ~(3 << 6)) |
+ (2 << 6));
+
+ /* Enable GPIO port A3 interrupt */
+ MC9328MXL_GPIOA_IMR |= bit(3);
+
+ /* Install the interrupt handler */
+ status = rtems_interrupt_handler_install(
+ BSP_INT_GPIO_PORTA,
+ "Network",
+ RTEMS_INTERRUPT_UNIQUE,
+ enet_isr,
+ (void *)BSP_INT_GPIO_PORTA
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+ enet_isr_on();
+
+} /* mc9328mxl_enet_init_hw() */
+
+void mc9328mxl_enet_start(struct ifnet *ifp)
+{
+ mc9328mxl_enet_softc_t *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->tx_task, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+void mc9328mxl_enet_stop (mc9328mxl_enet_softc_t *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+
+ /* Stop the transmitter and receiver. */
+ lan91c11x_write_reg(LAN91C11X_TCR,
+ (lan91c11x_read_reg(LAN91C11X_TCR) &
+ ~LAN91C11X_TCR_TXENA));
+
+ lan91c11x_write_reg(LAN91C11X_RCR,
+ (lan91c11x_read_reg(LAN91C11X_RCR) &
+ ~LAN91C11X_RCR_RXEN));
+
+}
+
+/*
+ * Driver transmit daemon
+ */
+void mc9328mxl_enet_tx_task(void *arg)
+{
+ mc9328mxl_enet_softc_t *sc = (mc9328mxl_enet_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;)
+ {
+ rtems_bsdnet_event_receive(
+ START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Send packets till queue is empty */
+ for (;;)
+ {
+ /* Get the next mbuf chain to transmit. */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m) {
+ break;
+ }
+ mc9328mxl_enet_sendpacket (ifp, m);
+ softc.stats.tx_packets++;
+
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/* Send packet */
+void mc9328mxl_enet_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct mbuf *l = NULL;
+ int size = 0;
+ int tmp;
+ int i;
+ int start;
+ uint16_t d;
+
+ /* How big is the packet ? */
+ l = m;
+ do {
+ size += l->m_len;
+ l = l->m_next;
+ } while (l != NULL);
+
+ /* Allocate a TX buffer */
+ lan91c11x_write_reg(LAN91C11X_MMUCMD,
+ (LAN91C11X_MMUCMD_ALLOCTX |
+ (size >> 8)));
+
+ /* Wait for the allocation */
+ while ((lan91c11x_read_reg(LAN91C11X_INT) & LAN91C11X_INT_ALLOC) == 0) {
+ continue;
+ }
+
+ tmp = lan91c11x_read_reg(LAN91C11X_PNR);
+ lan91c11x_write_reg(LAN91C11X_PNR, ((tmp >> 8) & 0xff));
+
+ /* Set the data pointer for auto increment */
+ lan91c11x_write_reg(LAN91C11X_PTR, LAN91C11X_PTR_AUTOINC);
+
+ /* A delay is needed between pointer and data access ?!? */
+ for (i = 0; i < 10; i++) {
+ continue;
+ }
+
+ /* Write status word */
+ lan91c11x_write_reg(LAN91C11X_DATA, 0);
+
+ /* Write byte count */
+ if (size & 1) {
+ size++;
+ }
+ lan91c11x_write_reg(LAN91C11X_DATA, size + 6);
+
+ lan91c11x_lock();
+
+ /* Copy the mbuf */
+ l = m;
+ start = 0;
+ d = 0;
+ while (l != NULL)
+ {
+ uint8_t *data;
+
+ data = mtod(l, uint8_t *);
+
+ for (i = start; i < l->m_len; i++) {
+ if ((i & 1) == 0) {
+ d = data[i] << 8;
+ } else {
+ d = d | data[i];
+ lan91c11x_write_reg_fast(LAN91C11X_DATA, htons(d));
+ }
+ }
+
+ /* If everything is 2 byte aligned, i will be even */
+ start = (i & 1);
+
+ l = l->m_next;
+ }
+
+ /* write control byte */
+ if (i & 1) {
+ lan91c11x_write_reg_fast(LAN91C11X_DATA,
+ htons(LAN91C11X_PKT_CTRL_ODD | d));
+ } else {
+ lan91c11x_write_reg_fast(LAN91C11X_DATA, 0);
+ }
+
+ lan91c11x_unlock();
+
+ /* Enable TX interrupts */
+ lan91c11x_write_reg(LAN91C11X_INT,
+ (lan91c11x_read_reg(LAN91C11X_INT) |
+ LAN91C11X_INT_TXMASK |
+ LAN91C11X_INT_TXEMASK));
+
+ /* Enqueue it */
+ lan91c11x_write_reg(LAN91C11X_MMUCMD,
+ LAN91C11X_MMUCMD_ENQUEUE);
+
+ /* free the mbuf chain we just copied */
+ m_freem(m);
+
+} /* mc9328mxl_enet_sendpacket () */
+
+
+/* reader task */
+void mc9328mxl_enet_rx_task(void *arg)
+{
+ mc9328mxl_enet_softc_t *sc = (mc9328mxl_enet_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ struct ether_header *eh;
+ rtems_event_set events;
+ int pktlen;
+ uint16_t rsw;
+ uint16_t bc;
+ uint16_t cbyte;
+ int i;
+ uint16_t int_reg;
+
+ /* Input packet handling loop */
+ while (1) {
+ rtems_bsdnet_event_receive(
+ START_RECEIVE_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Configure for reads from RX data area */
+ lan91c11x_write_reg(LAN91C11X_PTR,
+ (LAN91C11X_PTR_AUTOINC |
+ LAN91C11X_PTR_RCV |
+ LAN91C11X_PTR_READ));
+
+ /* read the receive status word */
+ rsw = lan91c11x_read_reg(LAN91C11X_DATA);
+ /* TBD: Need to check rsw here */
+
+ /* read the byte count */
+ bc = lan91c11x_read_reg(LAN91C11X_DATA);
+ pktlen = (bc & 0x7ff) - 6;
+
+ /* get an mbuf for this packet */
+ MGETHDR(m, M_WAIT, MT_DATA);
+
+ /* now get a cluster pointed to by the mbuf */
+ /* since an mbuf by itself is too small */
+ MCLGET(m, M_WAIT);
+
+ lan91c11x_lock();
+
+ /* Copy the received packet into an mbuf */
+ for (i = 0; i < (pktlen / 2); i++) {
+ ((uint16_t*)m->m_ext.ext_buf)[i] =
+ lan91c11x_read_reg_fast(LAN91C11X_DATA);
+ }
+
+ cbyte = lan91c11x_read_reg_fast(LAN91C11X_DATA);
+ if (cbyte & LAN91C11X_PKT_CTRL_ODD) {
+ ((uint16_t*)m->m_ext.ext_buf)[i] = cbyte;
+ pktlen++;
+ }
+ lan91c11x_unlock();
+
+ /* Release the packets memory */
+ lan91c11x_write_reg(LAN91C11X_MMUCMD,
+ LAN91C11X_MMUCMD_REMTOP);
+
+ /* set the receiving interface */
+ m->m_pkthdr.rcvif = ifp;
+ m->m_nextpkt = 0;
+
+ /* set the length of the mbuf */
+ m->m_len = pktlen - (sizeof(struct ether_header));
+ m->m_pkthdr.len = m->m_len;
+
+ /* strip off the ethernet header from the mbuf */
+ /* but save the pointer to it */
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+
+
+ softc.stats.rx_packets++;
+
+ /* give all this stuff to the stack */
+ ether_input(ifp, eh, m);
+
+ /* renable RX interrupts */
+ int_reg = lan91c11x_read_reg(LAN91C11X_INT);
+ int_reg |= LAN91C11X_INT_RXMASK;
+ lan91c11x_write_reg(LAN91C11X_INT, int_reg);
+
+ }
+} /* mc9328mxl_enet_rx_task */
+
+
+/* Show interface statistics */
+void mc9328mxl_enet_stats (mc9328mxl_enet_softc_t *sc)
+{
+ printf (" Total Interrupts:%-8lu", sc->stats.interrupts);
+ printf (" Rx Interrupts:%-8lu", sc->stats.rx_interrupts);
+ printf (" Tx Interrupts:%-8lu\n", sc->stats.tx_interrupts);
+ printf (" Tx Error Interrupts:%-8lu\n", sc->stats.txerr_interrupts);
+ printf (" Rx Packets:%-8lu", sc->stats.rx_packets);
+ printf (" Tx Packets:%-8lu\n", sc->stats.tx_packets);
+}
+
+
+/* Enables mc9328mxl_enet interrupts. */
+static void enet_isr_on(void)
+{
+ /* Enable interrupts */
+ MC9328MXL_AITC_INTENNUM = MC9328MXL_INT_GPIO_PORTA;
+
+ return;
+}
+
+/* Driver ioctl handler */
+static int
+mc9328mxl_enet_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ mc9328mxl_enet_softc_t *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+ case IFF_RUNNING:
+ mc9328mxl_enet_stop (sc);
+ break;
+
+ case IFF_UP:
+ mc9328mxl_enet_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ mc9328mxl_enet_stop (sc);
+ mc9328mxl_enet_init (sc);
+ break;
+
+ default:
+ break;
+ } /* switch (if_flags) */
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ mc9328mxl_enet_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ } /* switch (command) */
+ return error;
+}
+
+/* interrupt handler */
+static void enet_isr(void * unused)
+{
+ uint16_t int_reg;
+
+ softc.stats.interrupts++;
+ /* get the ISR status and determine RX or TX */
+ int_reg = lan91c11x_read_reg(LAN91C11X_INT);
+
+ /* Handle RX interrupts */
+ if ((int_reg & LAN91C11X_INT_RX) && (int_reg & LAN91C11X_INT_RXMASK)) {
+ softc.stats.rx_interrupts++;
+
+ /* Disable the interrupt */
+ int_reg &= ~LAN91C11X_INT_RXMASK;
+
+ rtems_bsdnet_event_send (softc.rx_task, START_RECEIVE_EVENT);
+ }
+
+ /* Handle TX Empty interrupts */
+ if ((int_reg & LAN91C11X_INT_TXE) && (int_reg & LAN91C11X_INT_TXEMASK)) {
+ softc.stats.tx_interrupts++;
+
+ /* Disable the interrupt */
+ int_reg &= ~LAN91C11X_INT_TXEMASK;
+
+ /* Acknowledge the interrupt */
+ int_reg |= LAN91C11X_INT_TXE;
+
+ rtems_bsdnet_event_send(softc.tx_task, START_TRANSMIT_EVENT);
+
+ }
+
+ /* Handle interrupts for transmit errors */
+ if ((int_reg & LAN91C11X_INT_TX) && (int_reg & LAN91C11X_INT_TXMASK)) {
+ softc.stats.txerr_interrupts++;
+ printk("Caught TX interrupt - error on transmission\n");
+ }
+
+ /* Update the interrupt register on the 91c11x */
+ lan91c11x_write_reg(LAN91C11X_INT, int_reg);
+
+ /* clear GPIO Int. status */
+ MC9328MXL_GPIOA_ISR |= bit(3);
+}
+
diff --git a/bsps/arm/csb337/net/network.c b/bsps/arm/csb337/net/network.c
new file mode 100644
index 0000000..b795cf4
--- /dev/null
+++ b/bsps/arm/csb337/net/network.c
@@ -0,0 +1,864 @@
+/*
+ * AT91RM9200 ethernet driver
+ *
+ * Copyright (c) 2003 by Cogent Computer Systems
+ * Written by Mike Kelly <mike@cogcomp.com>
+ * and Jay Monkman <jtm@lopingdog.com>
+ *
+ *
+ * July 2009: Joel Sherrill merged csb637 PHY differences from
+ * MicroMonitor 1.17.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/bspIo.h>
+#include <at91rm9200.h>
+#include <at91rm9200_emac.h>
+#include <at91rm9200_gpio.h>
+#include <at91rm9200_pmc.h>
+
+#include <stdio.h>
+#include <string.h>
+
+#include <errno.h>
+#include <rtems/error.h>
+#include <assert.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <bsp/irq.h>
+#include <bspopts.h>
+
+/* enable debugging of the PHY code */
+#define PHY_DBG
+
+/* enable debugging of the EMAC code */
+/* #define EMAC_DBG */
+
+#if csb637
+ /* Bit defines for the PHY Status Register #1 (phy address 0x01) */
+ /* 1 = PHY able to perform 100BASE-T4 */
+ #define PHY_STAT_100BASE_T4 BIT15
+ /* 1 = PHY able to perform full-duplex 100BASE-X */
+ #define PHY_STAT_100BASE_X_FDX BIT14
+ /* 1 = PHY able to perform half-duplex 100BASE-X */
+ #define PHY_STAT_100BASE_X_HDX BIT13
+ /* 1 = PHY able to operate at 10 Mbps in full-duplex mode */
+ #define PHY_STAT_10BASE_FDX BIT12
+ /* 1 = PHY able to operate at 10 Mbps in half-duplex mode */
+ #define PHY_STAT_10BASE_HDX BIT11
+ /* 1 = PHY will accept management frames with preamble suppressed */
+ #define PHY_STAT_MF_PREAMBLE BIT6
+ /* 1 = Auto-negotiation complete */
+ #define PHY_STAT_AUTO_NEG_DONE BIT5
+ /* 1 = Remote fault condition detected */
+ #define PHY_STAT_REM_FLT BIT4
+ /* 1 = PHY is able to perform Auto-Negotiation */
+ #define PHY_STAT_AUTO_NEG_ABLE BIT3
+ /* 1 = Link is up */
+ #define PHY_STAT_LINK_UP BIT2
+ /* 1 = Jabber condition detected */
+ #define PHY_STAT_JABBER BIT1
+ /* 1 = Extended register capabilities */
+ #define PHY_STAT_EXT_REG BIT0
+
+ /* Bit defines for the Auxillary Mode 3 register */
+ #define PHY_AUX_MODE2_TRAFFIC_LED BIT6
+#endif
+
+ /* interrupt stuff */
+ #define EMAC_INT_PRIORITY 0 /* lowest priority */
+
+ /* RTEMS event used by interrupt handler to start receive daemon. */
+ #define START_RECEIVE_EVENT RTEMS_EVENT_1
+
+ /* RTEMS event used to start transmit daemon. */
+ #define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+static void at91rm9200_emac_isr (void *);
+static void at91rm9200_emac_isr_on(void);
+
+/* use the values defined in linkcmds for our use of SRAM */
+extern void * at91rm9200_emac_rxbuf_hdrs;
+extern void * at91rm9200_emac_txbuf;
+extern void * at91rm9200_emac_rxbufs;
+
+/* Set up EMAC hardware */
+/* Number of Receive and Transmit Buffers and Buffer Descriptors */
+#define NUM_RXBDS 8
+#define NUM_TXBDS 1
+#define RX_BUFFER_SIZE 0x600
+
+/* use internal SRAM for buffers and descriptors
+ * also insure that the receive descriptors
+ * start on a 64byte boundary
+ * Receive Buffer Descriptor Header
+ */
+
+typedef struct
+{
+ unsigned long address;
+ unsigned long status;
+} RXBUF_HDR;
+
+RXBUF_HDR *rxbuf_hdrs;
+unsigned char *txbuf;
+unsigned char *rxbuf;
+
+int delay_cnt;
+
+/*
+ * Hardware-specific storage
+ */
+typedef struct
+{
+ /*
+ * Connection to networking code
+ * This entry *must* be the first in the sonic_softc structure.
+ */
+ struct arpcom arpcom;
+
+ /*
+ * Interrupt vector
+ */
+ rtems_vector_number vector;
+
+ /*
+ * Indicates configuration
+ */
+ int acceptBroadcast;
+
+ /*
+ * Task waiting for interrupts
+ */
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * current receive header
+ */
+ int rx_buf_idx;
+
+
+
+ /*
+ * Statistics
+ */
+ unsigned long Interrupts;
+ unsigned long rxInterrupts;
+ unsigned long rxMissed;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxBadCRC;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txSingleCollision;
+ unsigned long txMultipleCollision;
+ unsigned long txCollision;
+ unsigned long txDeferred;
+ unsigned long txUnderrun;
+ unsigned long txLateCollision;
+ unsigned long txExcessiveCollision;
+ unsigned long txExcessiveDeferral;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+} at91rm9200_emac_softc_t;
+
+static at91rm9200_emac_softc_t softc;
+
+
+/* The AT91RM9200 ethernet fifos are very undersized. Therefore
+ * we use the internal SRAM to hold 4 receive packets and one
+ * transmit packet. Note that the AT91RM9200 can only queue
+ * one transmit packet at a time.
+ */
+
+/* function prototypes */
+int rtems_at91rm9200_emac_attach (struct rtems_bsdnet_ifconfig *config,
+ void *chip);
+void at91rm9200_emac_init(void *arg);
+void at91rm9200_emac_init_hw(at91rm9200_emac_softc_t *sc);
+void at91rm9200_emac_start(struct ifnet *ifp);
+void at91rm9200_emac_stop (at91rm9200_emac_softc_t *sc);
+void at91rm9200_emac_txDaemon (void *arg);
+void at91rm9200_emac_sendpacket (struct ifnet *ifp, struct mbuf *m);
+void at91rm9200_emac_rxDaemon(void *arg);
+void at91rm9200_emac_stats (at91rm9200_emac_softc_t *sc);
+static int at91rm9200_emac_ioctl (struct ifnet *ifp,
+ ioctl_command_t command,
+ caddr_t data);
+
+#if csb637
+/*
+ * phyread(): Read the PHY
+ */
+static uint32_t phyread(uint8_t reg)
+{
+ EMAC_REG(EMAC_MAN) = (0x01 << 30 /* Start of Frame Delimiter */
+ | 0x02 << 28 /* Operation, 0x01 = Write, 0x02 = Read */
+ | 0x00 << 23 /* Phy Number, 0 as we only have one */
+ | reg << 18 /* Phy Register */
+ | 0x02 << 16); /* must be 0x02 for turn around field */
+
+ /* wait for phy read to complete (was udelay(5000)) */
+ rtems_task_wake_after(1);
+
+ #if defined(EMAC_DBG)
+ printk(
+ "EMAC: Phy 0, Reg %d, Read 0x%04lx.\n",
+ reg,
+ (EMAC_REG(EMAC_MAN) & 0xffff)
+ );
+ #endif
+
+ return EMAC_REG(EMAC_MAN) & 0xffff;
+}
+#endif
+
+/*
+ * phywrite(): Write the PHY
+ */
+static void phywrite(uint8_t reg, uint16_t data)
+{
+ EMAC_REG(EMAC_MAN) = (0x01 << 30 /* Start of Frame Delimiter */
+ | 0x01 << 28 /* Operation, 0x01 = Write, 0x02 = Read */
+ | 0x00 << 23 /* Phy Number, BCM5221 is address 0 */
+ | reg << 18 /* Phy Register */
+ | 0x02 << 16 /* must be 0x02 for turn around field */
+ | data);
+ #if defined(EMAC_DBG)
+ printk("EMAC: Phy 0, Reg %d, Write 0x%04x.\n", reg, data);
+ #endif
+
+ /* wait for phy write to complete (was udelay(5000)) */
+ rtems_task_wake_after(1);
+}
+
+
+int rtems_at91rm9200_emac_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ void *chip /* only one ethernet, so no chip number */
+ )
+{
+ struct ifnet *ifp;
+ int mtu;
+ int unitnumber;
+ char *unitname;
+ void *p;
+
+ /* an array of receive buffer descriptors -- avoid type punned warning */
+ p = (void *)&at91rm9200_emac_rxbuf_hdrs;
+ rxbuf_hdrs = (RXBUF_HDR *)p;
+
+ /* one transmit buffer, 1536 bytes maximum */
+ txbuf = (unsigned char *)&at91rm9200_emac_txbuf;
+
+ /* receive buffers starting address */
+ rxbuf = (unsigned char *)&at91rm9200_emac_rxbufs;
+ /*
+ * Parse driver name
+ */
+ if ((unitnumber = rtems_bsdnet_parse_driver_name (config, &unitname)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if (unitnumber != 0) {
+ printk ("Bad AT91RM9200 EMAC unit number.\n");
+ return 0;
+ }
+ ifp = &softc.arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printk ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * zero out the control structure
+ */
+
+ memset( &softc, 0, sizeof(softc) );
+
+
+ /* get the MAC address from the chip */
+ softc.arpcom.ac_enaddr[0] = (EMAC_REG(EMAC_SA1L) >> 0) & 0xff;
+ softc.arpcom.ac_enaddr[1] = (EMAC_REG(EMAC_SA1L) >> 8) & 0xff;
+ softc.arpcom.ac_enaddr[2] = (EMAC_REG(EMAC_SA1L) >> 16) & 0xff;
+ softc.arpcom.ac_enaddr[3] = (EMAC_REG(EMAC_SA1L) >> 24) & 0xff;
+ softc.arpcom.ac_enaddr[4] = (EMAC_REG(EMAC_SA1H) >> 0) & 0xff;
+ softc.arpcom.ac_enaddr[5] = (EMAC_REG(EMAC_SA1H) >> 8) & 0xff;
+
+ #if 0
+ printk( "MAC=%02x:%02x:%02x:%02x:%02x:%02x\n",
+ softc.arpcom.ac_enaddr[0],
+ softc.arpcom.ac_enaddr[1],
+ softc.arpcom.ac_enaddr[2],
+ softc.arpcom.ac_enaddr[3],
+ softc.arpcom.ac_enaddr[4],
+ softc.arpcom.ac_enaddr[5]
+ );
+ #endif
+
+ if (config->mtu) {
+ mtu = config->mtu;
+ } else {
+ mtu = ETHERMTU;
+ }
+
+ softc.acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = &softc;
+ ifp->if_unit = unitnumber;
+ ifp->if_name = unitname;
+ ifp->if_mtu = mtu;
+ ifp->if_init = at91rm9200_emac_init;
+ ifp->if_ioctl = at91rm9200_emac_ioctl;
+ ifp->if_start = at91rm9200_emac_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST;
+ if (ifp->if_snd.ifq_maxlen == 0) {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+
+ softc.rx_buf_idx = 0;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+}
+
+void at91rm9200_emac_init(void *arg)
+{
+ at91rm9200_emac_softc_t *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+
+ /*
+ *This is for stuff that only gets done once (at91rm9200_emac_init()
+ * gets called multiple times
+ */
+ if (sc->txDaemonTid == 0) {
+ /* Set up EMAC hardware */
+ at91rm9200_emac_init_hw(sc);
+
+ /* Start driver tasks */
+ sc->rxDaemonTid = rtems_bsdnet_newproc("ENrx",
+ 4096,
+ at91rm9200_emac_rxDaemon,
+ sc);
+ sc->txDaemonTid = rtems_bsdnet_newproc("ENtx",
+ 4096,
+ at91rm9200_emac_txDaemon,
+ sc);
+ } /* if txDaemonTid */
+
+ /* set our priority in the AIC */
+ AIC_SMR_REG(AIC_SMR_EMAC) = AIC_SMR_PRIOR(EMAC_INT_PRIORITY);
+
+ /* install the interrupt handler */
+ status = rtems_interrupt_handler_install(
+ AT91RM9200_INT_EMAC,
+ "Network",
+ RTEMS_INTERRUPT_UNIQUE,
+ at91rm9200_emac_isr,
+ NULL
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+ at91rm9200_emac_isr_on();
+
+ /* EMAC doesn't support promiscuous, so ignore requests */
+ if (ifp->if_flags & IFF_PROMISC) {
+ printk ("Warning - AT91RM9200 Ethernet driver"
+ " doesn't support Promiscuous Mode!\n");
+ }
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /* Enable TX/RX and clear the statistics counters */
+ EMAC_REG(EMAC_CTL) = (EMAC_CTL_TE | EMAC_CTL_RE | EMAC_CTL_CSR);
+
+ /* clear any pending interrupts */
+ EMAC_REG(EMAC_TSR) = 0xffffffff;
+ EMAC_REG(EMAC_RSR) = 0xffffffff;
+
+} /* at91rm9200_emac_init() */
+
+void at91rm9200_emac_init_hw(at91rm9200_emac_softc_t *sc)
+{
+ int i;
+
+ /* Configure shared pins for Ethernet, not GPIO */
+ PIOA_REG(PIO_PDR) = ( BIT7 | /* tx clock */
+ BIT8 | /* tx enable */
+ BIT9 | /* tx data 0 */
+ BIT10 | /* tx data 1 */
+ BIT11 | /* carrier sense */
+ BIT12 | /* rx data 0 */
+ BIT13 | /* rx data 1 */
+ BIT14 | /* rx error */
+ BIT15 | /* MII clock */
+ BIT16 ); /* MII data */
+
+ PIOB_REG(PIO_PDR) = ( BIT12 | /* tx data 2 */
+ BIT13 | /* tx data 3 */
+ BIT14 | /* tx error */
+ BIT15 | /* rx data 2 */
+ BIT16 | /* rx data 3 */
+ BIT17 | /* rx data valid */
+ BIT18 | /* rx collistion */
+ BIT19 ); /* rx clock */
+
+ PIOB_REG(PIO_BSR) = ( BIT12 | /* tx data 2 */
+ BIT13 | /* tx data 3 */
+ BIT14 | /* tx error */
+ BIT15 | /* rx data 2 */
+ BIT16 | /* rx data 3 */
+ BIT17 | /* rx data valid */
+ BIT18 | /* rx collistion */
+ BIT19 ); /* rx clock */
+
+
+ /* Enable the clock to the EMAC */
+ PMC_REG(PMC_PCER) |= PMC_PCR_PID_EMAC;
+
+ /* initialize our receive buffer descriptors */
+ for (i = 0; i < NUM_RXBDS-1; i++) {
+ rxbuf_hdrs[i].address = (unsigned long)(&rxbuf[i * RX_BUFFER_SIZE]);
+ rxbuf_hdrs[i].status = 0x00000000;
+ }
+
+ /* last one needs the wrapbit set as well */
+ rxbuf_hdrs[i].address = ((unsigned long)(&rxbuf[i * RX_BUFFER_SIZE]) |
+ RXBUF_ADD_WRAP);
+ rxbuf_hdrs[i].status = 0x00000000;
+
+ /* point to our receive buffer queue */
+ EMAC_REG(EMAC_RBQP) = (unsigned long)rxbuf_hdrs;
+
+ /* clear any left over status bits */
+ EMAC_REG(EMAC_RSR) &= ~(EMAC_RSR_OVR | EMAC_RSR_REC | EMAC_RSR_BNA);
+
+ /* set the MII clock divder to MCK/64 */
+ EMAC_REG(EMAC_CFG) &= EMAC_CFG_CLK_MASK;
+ EMAC_REG(EMAC_CFG) = (EMAC_CFG_CLK_64 | EMAC_CFG_BIG | EMAC_CFG_FD);
+
+ /* enable the MII interface */
+ EMAC_REG(EMAC_CTL) = EMAC_CTL_MPE;
+
+ #if csb637
+ {
+ int timeout;
+ uint32_t emac_link_status;
+
+ #if defined(PHY_DBG)
+ printk("EMAC: Getting Link Status.\n");
+ #endif
+ /* read the PHY ID registers */
+ emac_link_status = phyread(0x02);
+ emac_link_status = phyread(0x03);
+
+ /* Get the link status - wait for done with a timeout */
+ for (timeout = 10000 ; timeout ; ) {
+ for (i = 0; i < 100; i++)
+ ;
+ emac_link_status = phyread(0x01);
+ if (!(emac_link_status & PHY_STAT_AUTO_NEG_ABLE)) {
+ #if defined(PHY_DBG)
+ printk("EMAC: PHY is unable to Auto-Negotatiate!\n");
+ #endif
+ timeout = 0;
+ break;
+ }
+ if (emac_link_status & PHY_STAT_AUTO_NEG_DONE) {
+ #if defined(PHY_DBG)
+ printk("EMAC: Auto-Negotiate Complete, Link = ");
+ #endif
+ break;
+ }
+ timeout-- ;
+ }
+ if (!timeout) {
+ #if defined(PHY_DBG)
+ printk(
+ "EMAC: Auto-Negotatiate Failed, Status = 0x%04lx!\n"
+ "EMAC: Initialization Halted.\n",
+ emac_link_status
+ );
+ #endif
+ /* if autonegotiation fails, just force to 10HD... */
+ emac_link_status = PHY_STAT_10BASE_HDX;
+ }
+
+ /* Set SPD and FD based on the return link status */
+ if (emac_link_status & (PHY_STAT_100BASE_X_FDX | PHY_STAT_100BASE_X_HDX)){
+ EMAC_REG(EMAC_CFG) |= EMAC_CFG_SPD;
+ #if defined(PHY_DBG)
+ printk("100MBIT, ");
+ #endif
+ } else {
+ EMAC_REG(EMAC_CFG) &= ~EMAC_CFG_SPD;
+ #if defined(PHY_DBG)
+ printk("10MBIT, ");
+ #endif
+ }
+
+ if (emac_link_status & (PHY_STAT_100BASE_X_FDX | PHY_STAT_10BASE_FDX)) {
+ EMAC_REG(EMAC_CFG) |= EMAC_CFG_FD;
+ #if defined(PHY_DBG)
+ printk("Full Duplex.\n");
+ #endif
+ } else {
+ EMAC_REG(EMAC_CFG) &= ~EMAC_CFG_FD;
+ #if defined(PHY_DBG)
+ printk("Half Duplex.\n");
+ #endif
+ }
+
+ /* Set PHY LED modes. Traffic Meter Mode for ACTLED
+ * Set Bit 6 - Traffic Mode on
+ */
+ phywrite(0x1b, PHY_AUX_MODE2_TRAFFIC_LED);
+ }
+ #else
+ /* must be csb337 */
+ /* Set PHY LED2 to combined Link/Activity and enable pulse stretching */
+ phywrite( 18, 0x0d0a );
+ #endif
+
+ #if 0
+ EMAC_REG(EMAC_MAN) = (0x01 << 30 | /* Start of Frame Delimiter */
+ 0x01 << 28 | /* Operation, 0x01 = Write */
+ 0x00 << 23 | /* Phy Number */
+ 0x14 << 18 | /* Phy Register */
+ 0x02 << 16 | /* must be 0x02 */
+ 0x0D0A); /* Write data (0x0000 if read) */
+ #endif
+
+} /* at91rm9200_emac_init_hw() */
+
+void at91rm9200_emac_start(struct ifnet *ifp)
+{
+ at91rm9200_emac_softc_t *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+void at91rm9200_emac_stop (at91rm9200_emac_softc_t *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Stop the transmitter and receiver.
+ */
+ EMAC_REG(EMAC_CTL) &= ~(EMAC_CTL_TE | EMAC_CTL_RE);
+}
+
+/*
+ * Driver transmit daemon
+ */
+void at91rm9200_emac_txDaemon (void *arg)
+{
+ at91rm9200_emac_softc_t *sc = (at91rm9200_emac_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;)
+ {
+ /* turn on TX interrupt, then wait for one */
+ EMAC_REG(EMAC_IER) = EMAC_INT_TCOM; /* Transmit complete */
+
+ rtems_bsdnet_event_receive(
+ START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Send packets till queue is empty */
+ for (;;)
+ {
+ /* Get the next mbuf chain to transmit. */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ at91rm9200_emac_sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/* Send packet */
+void at91rm9200_emac_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct mbuf *l = NULL;
+ unsigned int pkt_offset = 0;
+ delay_cnt = 0;
+ /* printk("at91rm9200_emac_sendpacket %p\n", m); */
+
+ /* Wait for EMAC Transmit Queue to become available. */
+ while (((EMAC_REG(EMAC_TSR) & EMAC_TSR_COMP) == 0) &&
+ ((EMAC_REG(EMAC_TSR) & EMAC_TSR_TXIDLE) == 0))
+
+ {
+ delay_cnt++;
+/* sleep(0); make sure we don't hog the cpu */
+ continue;
+ }
+
+ /* copy the mbuf chain into the transmit buffer */
+ l = m;
+ while (l != NULL) {
+ memcpy(((char *)txbuf + pkt_offset), /* offset into pkt for mbuf */
+ (char *)mtod(l, void *), /* cast to void */
+ l->m_len); /* length of this mbuf */
+
+ pkt_offset += l->m_len; /* update offset */
+ l = l->m_next; /* get next mbuf, if any */
+ }
+
+ /* free the mbuf chain we just copied */
+ m_freem(m);
+
+ /* clear any pending status */
+ EMAC_REG(EMAC_TSR) = (EMAC_TSR_OVR | EMAC_TSR_COL | EMAC_TSR_RLE
+ | EMAC_TSR_COMP | EMAC_TSR_UND);
+
+ /* tell the EMAC about our buffer */
+ EMAC_REG(EMAC_TAR) = (unsigned long)txbuf;
+ EMAC_REG(EMAC_TCR) = (unsigned long)pkt_offset;
+} /* at91rm9200_emac_sendpacket () */
+
+
+/* SONIC reader task */
+void at91rm9200_emac_rxDaemon(void *arg)
+{
+ at91rm9200_emac_softc_t *sc = (at91rm9200_emac_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ struct ether_header *eh;
+ rtems_event_set events;
+ int pktlen;
+
+ /* Input packet handling loop */
+ for (;;) {
+ /* turn on RX interrupts, then wait for one */
+ EMAC_REG(EMAC_IER) = (EMAC_INT_RCOM | /* Receive complete */
+ EMAC_INT_RBNA | /* Receive buf not available */
+ EMAC_INT_ROVR); /* Receive overrun */
+
+ rtems_bsdnet_event_receive(
+ START_RECEIVE_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ if (EMAC_REG(EMAC_RSR) & EMAC_RSR_BNA) {
+ printk("1: EMAC_BNA\n");
+ }
+
+ if (EMAC_REG(EMAC_RSR) & EMAC_RSR_OVR) {
+ printk("1: EMAC_OVR\n");
+ }
+
+ /* clear the receive status as we do not use it anyway */
+ EMAC_REG(EMAC_RSR) = (EMAC_RSR_REC | EMAC_RSR_OVR | EMAC_RSR_BNA);
+
+ /* scan the buffer descriptors looking for any with data in them */
+ while (rxbuf_hdrs[sc->rx_buf_idx].address & RXBUF_ADD_OWNED) {
+ pktlen = rxbuf_hdrs[sc->rx_buf_idx].status & RXBUF_STAT_LEN_MASK;
+
+ /* get an mbuf this packet */
+ MGETHDR(m, M_WAIT, MT_DATA);
+
+ /* now get a cluster pointed to by the mbuf */
+ /* since an mbuf by itself is too small */
+ MCLGET(m, M_WAIT);
+
+ /* set the type of mbuf to ifp (ethernet I/F) */
+ m->m_pkthdr.rcvif = ifp;
+ m->m_nextpkt = 0;
+
+ /* copy the packet into the cluster pointed to by the mbuf */
+ memcpy((char *)m->m_ext.ext_buf,
+ (char *)(rxbuf_hdrs[sc->rx_buf_idx].address & 0xfffffffc),
+ pktlen);
+
+ /* Release the buffer ASAP back to the EMAC */
+ rxbuf_hdrs[sc->rx_buf_idx].address &= ~RXBUF_ADD_OWNED;
+
+ /* set the length of the mbuf */
+ m->m_len = pktlen - (sizeof(struct ether_header) + 4);
+ m->m_pkthdr.len = m->m_len;
+
+ /* strip off the ethernet header from the mbuf */
+ /* but save the pointer to it */
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+
+ /* increment the buffer index */
+ sc->rx_buf_idx++;
+ if (sc->rx_buf_idx >= NUM_RXBDS) {
+ sc->rx_buf_idx = 0;
+ }
+
+ /* give all this stuff to the stack */
+ ether_input(ifp, eh, m);
+
+ } /* while ADD_OWNED = 0 */
+
+ if (EMAC_REG(EMAC_RSR) & EMAC_RSR_BNA) {
+ printk("2:EMAC_BNA\n");
+ }
+ if (EMAC_REG(EMAC_RSR) & EMAC_RSR_OVR) {
+ printk("2:EMAC_OVR\n");
+ }
+
+
+ } /* for (;;) */
+} /* at91rm9200_emac_rxDaemon() */
+
+
+/* Show interface statistics */
+void at91rm9200_emac_stats (at91rm9200_emac_softc_t *sc)
+{
+ printf (" Total Interrupts:%-8lu", sc->Interrupts);
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Collision:%-8lu", sc->rxCollision);
+ printf (" Missed:%-8lu\n", sc->rxMissed);
+
+ printf ( " Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf ( " Deferred:%-8lu", sc->txDeferred);
+ printf (" Lost Carrier:%-8lu\n", sc->txLostCarrier);
+ printf ( "Single Collisions:%-8lu", sc->txSingleCollision);
+ printf ( "Multiple Collisions:%-8lu", sc->txMultipleCollision);
+ printf ("Excessive Collisions:%-8lu\n", sc->txExcessiveCollision);
+ printf ( " Total Collisions:%-8lu", sc->txCollision);
+ printf ( " Late Collision:%-8lu", sc->txLateCollision);
+ printf (" Underrun:%-8lu\n", sc->txUnderrun);
+ printf ( " Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+
+/* Enables at91rm9200_emac interrupts. */
+static void at91rm9200_emac_isr_on(void)
+{
+ /* Enable various TX/RX interrupts */
+ EMAC_REG(EMAC_IER) = (EMAC_INT_RCOM | /* Receive complete */
+ EMAC_INT_RBNA | /* Receive buffer not available */
+ EMAC_INT_TCOM | /* Transmit complete */
+ EMAC_INT_ROVR | /* Receive overrun */
+ EMAC_INT_ABT); /* Abort on DMA transfer */
+
+ return;
+}
+
+/* Driver ioctl handler */
+static int
+at91rm9200_emac_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ at91rm9200_emac_softc_t *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+ case IFF_RUNNING:
+ at91rm9200_emac_stop (sc);
+ break;
+
+ case IFF_UP:
+ at91rm9200_emac_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ at91rm9200_emac_stop (sc);
+ at91rm9200_emac_init (sc);
+ break;
+
+ default:
+ break;
+ } /* switch (if_flags) */
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ at91rm9200_emac_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ } /* switch (command) */
+ return error;
+}
+
+/* interrupt handler */
+static void at91rm9200_emac_isr (void * unused)
+{
+ unsigned long status32;
+
+ /* get the ISR status and determine RX or TX */
+ status32 = EMAC_REG(EMAC_ISR);
+
+ if (status32 & EMAC_INT_ABT) {
+ EMAC_REG(EMAC_IDR) = EMAC_INT_ABT; /* disable it */
+ rtems_panic("AT91RM9200 Ethernet MAC has received an Abort.\n");
+ }
+
+ if (status32 & (EMAC_INT_RCOM | /* Receive complete */
+ EMAC_INT_RBNA | /* Receive buffer not available */
+ EMAC_INT_ROVR)) { /* Receive overrun */
+
+ /* disable the RX interrupts */
+ EMAC_REG(EMAC_IDR) = (EMAC_INT_RCOM | /* Receive complete */
+ EMAC_INT_RBNA | /* Receive buf not available */
+ EMAC_INT_ROVR); /* Receive overrun */
+
+ rtems_bsdnet_event_send (softc.rxDaemonTid, START_RECEIVE_EVENT);
+ }
+
+ if (status32 & EMAC_INT_TCOM) { /* Transmit buffer register empty */
+
+ /* disable the TX interrupts */
+ EMAC_REG(EMAC_IDR) = EMAC_INT_TCOM;
+
+ rtems_bsdnet_event_send (softc.txDaemonTid, START_TRANSMIT_EVENT);
+ }
+}
+
diff --git a/bsps/arm/edb7312/net/network.c b/bsps/arm/edb7312/net/network.c
new file mode 100644
index 0000000..9a83229
--- /dev/null
+++ b/bsps/arm/edb7312/net/network.c
@@ -0,0 +1,126 @@
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <bsp/irq.h>
+#include <libchip/cs8900.h>
+#include <assert.h>
+
+#define CS8900_BASE 0x20000300
+unsigned int bsp_cs8900_io_base = 0;
+unsigned int bsp_cs8900_memory_base = 0;
+static void cs8900_isr(void *);
+
+char g_enetbuf[1520];
+
+static void cs8900_isr(void *arg)
+{
+ cs8900_interrupt(BSP_EINT3, arg);
+}
+
+/* cs8900_io_set_reg - set one of the I/O addressed registers */
+void cs8900_io_set_reg (cs8900_device *cs, unsigned short reg, unsigned short data)
+{
+ /* works the same for all values of dev */
+/*
+ printf("cs8900_io_set_reg: reg: %#6x, val %#6x\n",
+ CS8900_BASE + reg,
+ data);
+*/
+ *(unsigned short *)(CS8900_BASE + reg) = data;
+}
+
+/* cs8900_io_get_reg - reads one of the I/O addressed registers */
+unsigned short cs8900_io_get_reg (cs8900_device *cs, unsigned short reg)
+{
+ unsigned short val;
+ /* works the same for all values of dev */
+ val = *(unsigned short *)(CS8900_BASE + reg);
+/*
+ printf("cs8900_io_get_reg: reg: %#6x, val %#6x\n", reg, val);
+*/
+ return val;
+}
+
+/* cs8900_mem_set_reg - sets one of the registers mapped through
+ * PacketPage
+ */
+void cs8900_mem_set_reg (cs8900_device *cs, unsigned long reg, unsigned short data)
+{
+ /* works the same for all values of dev */
+ cs8900_io_set_reg(cs, CS8900_IO_PACKET_PAGE_PTR, reg);
+ cs8900_io_set_reg(cs, CS8900_IO_PP_DATA_PORT0, data);
+}
+
+/* cs8900_mem_get_reg - reads one of the registers mapped through
+ * PacketPage
+ */
+unsigned short cs8900_mem_get_reg (cs8900_device *cs, unsigned long reg)
+{
+ /* works the same for all values of dev */
+ cs8900_io_set_reg(cs, CS8900_IO_PACKET_PAGE_PTR, reg);
+ return cs8900_io_get_reg(cs, CS8900_IO_PP_DATA_PORT0);
+}
+
+void cs8900_attach_interrupt (cs8900_device *cs)
+{
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+
+ status = rtems_interrupt_handler_install(
+ BSP_EINT3,
+ "Network",
+ RTEMS_INTERRUPT_UNIQUE,
+ cs8900_isr,
+ cs
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+void cs8900_detach_interrupt (cs8900_device *cs)
+{
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+
+ status = rtems_interrupt_handler_remove(
+ BSP_EINT3,
+ cs8900_isr,
+ cs
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+unsigned short cs8900_get_data_block (cs8900_device *cs, unsigned char *data)
+{
+ int len;
+ int i;
+
+ len = cs8900_mem_get_reg(cs, CS8900_PP_RxLength);
+
+ for (i = 0; i < ((len + 1) / 2); i++) {
+ ((short *)data)[i] = cs8900_io_get_reg(cs,
+ CS8900_IO_RX_TX_DATA_PORT0);
+ }
+ return len;
+}
+
+void cs8900_tx_load (cs8900_device *cs, struct mbuf *m)
+{
+ int len;
+ unsigned short *data;
+ int i;
+
+ len = 0;
+
+ do {
+ memcpy(&g_enetbuf[len], mtod(m, const void *), m->m_len);
+ len += m->m_len;
+ m = m->m_next;
+ } while (m != 0);
+
+ data = (unsigned short *) &g_enetbuf[0];
+ for (i = 0; i < ((len + 1) / 2); i++) {
+ cs8900_io_set_reg(cs,
+ CS8900_IO_RX_TX_DATA_PORT0,
+ data[i]);
+ }
+}
diff --git a/bsps/arm/gumstix/net/rtl8019.c b/bsps/arm/gumstix/net/rtl8019.c
new file mode 100644
index 0000000..00fd2fd
--- /dev/null
+++ b/bsps/arm/gumstix/net/rtl8019.c
@@ -0,0 +1,1197 @@
+/*
+ *By Yang Xi <hiyangxi@gmail.com>.
+ *RTL8019 ethernet driver for Gumstix on SKYEYE simulator
+ *Based on NE2000 driver for pc386 bsp
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <bsp/irq.h>
+#include "wd80x3.h"
+
+#include <stdio.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <rtems/bspIo.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+#include <net/if_arp.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+
+/* Define this to force byte-wide data transfers with the NIC. This
+ is needed for boards like the TS-1325 386EX PC, which support only
+ an 8-bit PC/104 bus. Undefine this on a normal PC.*/
+
+#define NE2000_BYTE_TRANSFERS
+
+/* Define this to print debugging messages with printk. */
+
+/*#define DEBUG_NE2000
+ #define DEBUG_NE*/
+
+/* We expect to be able to read a complete packet into an mbuf. */
+
+#if (MCLBYTES < 1520)
+# error "Driver must have MCLBYTES >= 1520"
+#endif
+
+/* The 8390 macro definitions in wd80x3.h expect RO to be defined. */
+#define RO 0
+
+/* Minimum size of Ethernet packet. */
+#define ET_MINLEN 60
+
+/* The number of NE2000 devices supported by this driver. */
+
+#define NNEDRIVER 1
+
+/* RTEMS event number used by the interrupt handler to signal the
+ driver task. This must not be any of the events used by the
+ network task synchronization. */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/* RTEMS event number used to start the transmit daemon. This must
+ not be the same as INTERRUPT_EVENT. */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/* Interrupts we want to handle from the device. */
+
+#define NE_INTERRUPTS \
+ (MSK_PRX | MSK_PTX | MSK_RXE | MSK_TXE | MSK_OVW | MSK_CNT)
+
+/* The size of a page in device memory. */
+
+#define NE_PAGE_SIZE (256)
+
+/* The first page address in device memory. */
+
+#define NE_START_PAGE (0x40)
+
+/* The last page address, plus 1. */
+
+#define NE_STOP_PAGE (0x80)
+
+/* The number of pages used for a single transmit buffer. This is
+ 1536 bytes, enough for a full size packet. */
+
+#define NE_TX_PAGES (6)
+
+/* The number of transmit buffers. We use two, so we can load one
+ packet while the other is being sent. */
+
+#define NE_TX_BUFS (2)
+
+/* We use the first pages in memory as transmit buffers, and the
+ remaining ones as receive buffers. */
+
+#define NE_FIRST_TX_PAGE (NE_START_PAGE)
+
+#define NE_FIRST_RX_PAGE (NE_FIRST_TX_PAGE + NE_TX_PAGES * NE_TX_BUFS)
+
+/* Data we store for each NE2000 device. */
+
+struct ne_softc {
+ /* The bsdnet information structure. */
+ struct arpcom arpcom;
+
+ /* The interrupt request number. */
+ unsigned int irno;
+ /* The base IO port number. */
+ unsigned int port;
+
+ /* Whether we accept broadcasts. */
+ int accept_broadcasts;
+
+ /* The thread ID of the transmit task. */
+ rtems_id tx_daemon_tid;
+ /* The thread ID of the receive task. */
+ rtems_id rx_daemon_tid;
+
+ /* Whether we use byte-transfers with the device. */
+ bool byte_transfers;
+
+ /* The number of memory buffers which the transmit daemon has loaded
+ with data to be sent, but which have not yet been completely
+ sent. */
+ int inuse;
+ /* The index of the next available transmit memory buffer. */
+ int nextavail;
+ /* The index of the next transmit buffer to send. */
+ int nextsend;
+ /* Nonzero if the device is currently transmitting a packet. */
+ int transmitting;
+ /* The length of the data stored in each transmit buffer. */
+ int sendlen[NE_TX_BUFS];
+
+ /* Set if we have a packet overrun while receiving. */
+ int overrun;
+ /* Set if we should resend after an overrun. */
+ int resend;
+
+ /* Statistics. */
+ struct {
+ /* Number of packets received. */
+ unsigned long rx_packets;
+ /* Number of packets sent. */
+ unsigned long tx_packets;
+ /* Number of interrupts. */
+ unsigned long interrupts;
+ /* Number of receive acknowledgements. */
+ unsigned long rx_acks;
+ /* Number of transmit acknowledgements. */
+ unsigned long tx_acks;
+ /* Number of packet overruns. */
+ unsigned long overruns;
+ /* Number of frame errors. */
+ unsigned long rx_frame_errors;
+ /* Number of CRC errors. */
+ unsigned long rx_crc_errors;
+ /* Number of missed packets. */
+ unsigned long rx_missed_errors;
+ } stats;
+};
+
+/* The list of NE2000 devices on this system. */
+
+static struct ne_softc ne_softc[NNEDRIVER];
+
+/*
+ * receive ring descriptor
+ *
+ * The National Semiconductor DS8390 Network interface controller uses
+ * the following receive ring headers. The way this works is that the
+ * memory on the interface card is chopped up into 256 bytes blocks.
+ * A contiguous portion of those blocks are marked for receive packets
+ * by setting start and end block #'s in the NIC. For each packet that
+ * is put into the receive ring, one of these headers (4 bytes each) is
+ * tacked onto the front. The first byte is a copy of the receiver status
+ * register at the time the packet was received.
+ */
+struct ne_ring
+{
+ unsigned char rsr; /* receiver status */
+ unsigned char next; /* pointer to next packet */
+ unsigned short count; /* bytes in packet (length + 4) */
+};
+
+/* Forward declarations to avoid warnings */
+
+static void ne_init_irq_handler (struct ne_softc *sc);
+static void ne_stop (struct ne_softc *sc);
+static void ne_stop_hardware (struct ne_softc *sc);
+static void ne_init (void *arg);
+static void ne_init_hardware (struct ne_softc *sc);
+
+static void ne_reset(struct ne_softc *sc);
+#ifdef DEBUG_NE
+static void ne_dump(struct ne_softc *sc);
+#endif
+
+/* Read data from an NE2000 device. Read LEN bytes at ADDR, storing
+ them into P. */
+
+static void
+ne_read_data (struct ne_softc *sc, int addr, int len, unsigned char *p)
+{
+ unsigned int port = sc->port;
+ unsigned int dport = port + DATAPORT;
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STA);
+ outport_byte (port + RBCR0, len);
+ outport_byte (port + RBCR1, len >> 8);
+ outport_byte (port + RSAR0, addr);
+ outport_byte (port + RSAR1, addr >> 8);
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RRE | MSK_STA);
+
+ if (sc->byte_transfers)
+ {
+ unsigned char d;
+ while (len > 0)
+ {
+ inport_byte(dport, d);
+ *p++ = d;
+ len--;
+ }
+ }
+ else /* word transfers */
+ {
+ unsigned short d;
+ while (len > 1)
+ {
+ inport_word(dport, d);
+ *p++ = d;
+ *p++ = d >> 8;
+ len -= 2;
+ }
+ if (len)
+ {
+ inport_word(dport, d);
+ *p++ = d;
+ }
+ }
+
+ outport_byte (port + ISR, MSK_RDC);
+}
+
+/* Handle the current NE2000 status. This is called when the device
+ signals an interrupt. It is also called at other times while
+ NE2000 interrupts have been disabled. */
+
+static void
+ne_check_status (struct ne_softc *sc, int from_irq_handler)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+ unsigned char status;
+
+ /* It seems that we need to use a loop here, because if the NE2000
+ signals an interrupt because packet transmission is complete, and
+ then receives a packet while interrupts are disabled, it seems to
+ sometimes fail to signal the interrupt for the received packet
+ when interrupts are reenabled. (Based on the behaviour of the
+ Realtek 8019AS chip). */
+
+ /* int count = 0; */
+ while (1)
+ {
+ inport_byte (port + ISR, status);
+#ifdef DEBUG_NE2000
+ printk ("NE2000 status 0x%x\n", status);
+#endif
+ if (status == 0)
+ break;
+
+ /* ack */
+ outport_byte (port + ISR, status);
+
+ /* Check for incoming packet overwrite. */
+ if (status & MSK_OVW)
+ {
+ ifp->if_timer = 0;
+#ifdef DEBUG_NE
+ printk("^\n");
+#endif
+ ++sc->stats.overruns;
+ ne_reset(sc);
+ /* Reenable device interrupts. */
+ if (from_irq_handler)
+ outport_byte(port + IMR, NE_INTERRUPTS);
+ return;
+ }
+
+ /* Check for transmitted packet. The transmit daemon may now be
+ able to send another packet to the device. */
+ if ((status & (MSK_PTX | MSK_TXE)) != 0)
+ {
+ ifp->if_timer = 0;
+ ++sc->stats.tx_acks;
+ --sc->inuse;
+ sc->transmitting = 0;
+ if (sc->inuse > 0 || (sc->arpcom.ac_if.if_flags & IFF_OACTIVE) != 0)
+ rtems_bsdnet_event_send (sc->tx_daemon_tid, START_TRANSMIT_EVENT);
+ }
+
+ /* Check for received packet. */
+ if ((status & (MSK_PRX | MSK_RXE)) != 0)
+ {
+ ++sc->stats.rx_acks;
+ rtems_bsdnet_event_send (sc->rx_daemon_tid, INTERRUPT_EVENT);
+ }
+
+ /* Check for counter change. */
+ if ((status & MSK_CNT) != 0)
+ {
+ unsigned char add;
+ inport_byte (port + CNTR0, add);
+ sc->stats.rx_frame_errors += add;
+ inport_byte (port + CNTR1, add);
+ sc->stats.rx_crc_errors += add;
+ inport_byte (port + CNTR2, add);
+ sc->stats.rx_missed_errors += add;
+ }
+
+ break;
+ }
+
+ outport_byte (port + CMDR, MSK_PG0 | MSK_STA | MSK_RD2);
+
+}
+
+/* Handle an NE2000 interrupt. */
+
+static void
+ne_interrupt_handler (void *arg)
+{
+ struct ne_softc *sc = arg;
+
+ if (sc == NULL)
+ return;
+
+ ++sc->stats.interrupts;
+
+#ifdef DEBUG_NE
+ printk("!");
+#endif
+ ne_check_status(sc, 1);
+}
+
+/* Turn NE2000 interrupts on. */
+
+static void
+ne_interrupt_on (struct ne_softc *sc)
+{
+#ifdef DEBUG_NE
+ printk ("ne_interrupt_on()\n");
+#endif
+ if (sc != NULL)
+ outport_byte (sc->port + IMR, NE_INTERRUPTS);
+}
+
+/* Initialize the NE2000 hardware. */
+
+static void
+ne_init_hardware (struct ne_softc *sc)
+{
+ unsigned int port = sc->port;
+ int i;
+
+#ifdef DEBUG_NE2000
+ printk ("ne_init_hardware()\n");
+#endif
+
+ /* Initialize registers. */
+
+ /* Set interface for page 0, Remote DMA complete, Stopped */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ /* Set FIFO threshold to 8, No auto-init Remote DMA, byte order=80x86 */
+ /* byte-wide DMA xfers */
+ if (sc->byte_transfers)
+ outport_byte (port + DCR, MSK_FT10 | MSK_BMS);
+ /* word-wide DMA xfers */
+ else
+ outport_byte (port + DCR, MSK_FT10 | MSK_BMS | MSK_WTS);
+
+ /* Clear Remote Byte Count Registers */
+ outport_byte (port + RBCR0, 0);
+ outport_byte (port + RBCR1, 0);
+
+ /* For the moment, don't store incoming packets in memory. */
+ outport_byte (port + RCR, MSK_MON);
+
+ /* Place NIC in internal loopback mode */
+ outport_byte (port + TCR, MSK_LOOP);
+
+ /* Initialize transmit/receive (ring-buffer) Page Start */
+ outport_byte (port + TPSR, NE_FIRST_TX_PAGE);
+ outport_byte (port + PSTART, NE_FIRST_RX_PAGE);
+
+ /* Initialize Receiver (ring-buffer) Page Stop and Boundary */
+ outport_byte (port + PSTOP, NE_STOP_PAGE);
+ outport_byte (port + BNRY, NE_STOP_PAGE - 1);
+
+ /* Clear all interrupts */
+ outport_byte (port + ISR, 0xff);
+ /* Disable all interrupts */
+ outport_byte (port + IMR, 0);
+
+ /* Program Command Register for page 1 */
+ outport_byte (port + CMDR, MSK_PG1 | MSK_RD2 | MSK_STP);
+
+ /* Set the Ethernet hardware address. */
+ for (i = 0; i < ETHER_ADDR_LEN; ++i)
+ outport_byte (port + PAR + i, sc->arpcom.ac_enaddr[i]);
+
+ /* Set Current Page pointer to next_packet */
+ outport_byte (port + CURR, NE_FIRST_RX_PAGE);
+
+ /* Clear the multicast address. */
+ for (i = 0; i < MARsize; ++i)
+ outport_byte (port + MAR + i, 0);
+
+ /* Set page 0 registers */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ /* accept broadcast */
+ outport_byte (port + RCR, (sc->accept_broadcasts ? MSK_AB : 0));
+
+ /* Start interface */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STA);
+
+ /* Take interface out of loopback */
+ outport_byte (port + TCR, 0);
+}
+
+/* Set up interrupts.
+*/
+static void
+ne_init_irq_handler(struct ne_softc *sc)
+{
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+
+#ifdef DEBUG_NE
+ printk("ne_init_irq_handler(%d)\n", sc->irno);
+#endif
+
+ status = rtems_interrupt_handler_install(
+ sc->irno,
+ "RTL8019",
+ RTEMS_INTERRUPT_UNIQUE,
+ ne_interrupt_handler,
+ sc
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+ ne_interrupt_on(sc);
+}
+
+/* The NE2000 packet receive daemon. This task is started when the
+ NE2000 driver is initialized. */
+
+#ifdef DEBUG_NE
+static int ccc = 0; /* experinent! */
+#endif
+
+static void
+ne_rx_daemon (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+
+ while (1)
+ {
+ rtems_event_set events;
+
+ /* Wait for the interrupt handler to tell us that there is a
+ packet ready to receive. */
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Don't let the device interrupt us now. */
+ outport_byte (port + IMR, 0);
+
+ while (1)
+ {
+ unsigned char startpage, currpage;
+ unsigned short len;
+ unsigned char next, cnt1, cnt2;
+ struct mbuf *m = NULL;
+ unsigned char *p;
+ int startaddr;
+ int toend;
+ struct ether_header *eh;
+ struct ne_ring hdr; /* ring buffer header */
+ int reset;
+
+ inport_byte (port + BNRY, startpage);
+
+ outport_byte (port + CMDR, MSK_PG1 | MSK_RD2);
+ inport_byte (port + CURR, currpage);
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2);
+
+ ++startpage;
+ if (startpage >= NE_STOP_PAGE)
+ startpage = NE_FIRST_RX_PAGE;
+
+ if (startpage == currpage)
+ break;
+
+#ifdef DEBUG_NE2000
+ printk ("ne_rx_daemon: start page %x; current page %x\n",
+ startpage, currpage);
+#endif
+
+ reset = 0;
+
+ /* Read the buffer header */
+ startaddr = startpage * NE_PAGE_SIZE;
+ ne_read_data(sc, startaddr, sizeof(hdr), (unsigned char *)&hdr);
+ next = hdr.next;
+
+ if (next >= NE_STOP_PAGE)
+ next = NE_FIRST_RX_PAGE;
+
+ /* check packet length */
+ len = hdr.count;
+ if (currpage < startpage)
+ cnt1 = currpage + (NE_STOP_PAGE - NE_FIRST_RX_PAGE) - startpage;
+ else
+ cnt1 = currpage - startpage;
+ cnt2 = len / NE_PAGE_SIZE;
+ if (len % NE_PAGE_SIZE)
+ cnt2++;
+ if (cnt1 < cnt2)
+ {
+#ifdef DEBUG_NE
+ printk("(%x<%x:%x)\n", cnt1, cnt2, len);
+/*
+ printk("start page 0x%x; current page 0x%x\n",
+ startpage, currpage);
+ printk("cnt1 < cnt2 (0x%x, 0x%x); len 0x%x\n",
+ cnt1, cnt2, len);
+*/
+#endif
+ reset = 1;
+ }
+ if (len > (ETHER_MAX_LEN - ETHER_CRC_LEN + sizeof(struct ne_ring)) ||
+ len < (ETHER_MIN_LEN - ETHER_CRC_LEN + sizeof(struct ne_ring)) ||
+ len > MCLBYTES)
+ {
+#ifdef DEBUG_NE
+ printk("(%x)", len);
+
+ printk("start page 0x%x; current page 0x%x\n",
+ startpage, currpage);
+ printk("len out of range: 0x%x\n", len);
+ printk("stat: 0x%x, next: 0x%x\n", hdr.rsr, hdr.next);
+#endif
+ reset = 1;
+ }
+#ifdef DEBUG_NE
+ if (++ccc == 100)
+ { ccc = 0; reset = 1;
+ printk("T");
+ }
+#endif
+
+ /* reset interface */
+ if (reset)
+ {
+ printk("Reset in RX\n");
+ ne_reset(sc);
+ goto Next;
+ }
+
+ /* The first four bytes of the length are the buffer header
+ * Just decrease them by 2 since in ARM, we have to make sure
+ * 4bytes memory access align on 4bytes
+ */
+ len -= 2;
+ startaddr += 2;
+
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+
+ if (m == NULL)
+ panic ("ne_rx_daemon");
+
+ m->m_pkthdr.rcvif = ifp;
+ m->m_nextpkt = 0;
+
+ p = mtod (m, unsigned char *);
+ m->m_len = m->m_pkthdr.len = len - (sizeof(struct ether_header) + 2);
+
+ toend = NE_STOP_PAGE * NE_PAGE_SIZE - startaddr;
+ if (toend < len)
+ {
+ ne_read_data (sc, startaddr, toend, p);
+ p += toend;
+ len -= toend;
+ startaddr = NE_FIRST_RX_PAGE * NE_PAGE_SIZE;
+ }
+
+ if (len > 0)
+ ne_read_data (sc, startaddr, len, p);
+
+ m->m_data +=2;
+ eh = mtod(m, struct ether_header *);
+ m->m_data += sizeof (struct ether_header);
+
+#ifdef DEBUG_NE
+ /*printk("[r%d]", hdr.count - sizeof(hdr));*/
+ printk("<\n");
+#endif
+ ether_input (ifp, eh, m);
+ ++sc->stats.rx_packets;
+ outport_byte (port + BNRY, next - 1);
+ }
+
+ if (sc->overrun) {
+ outport_byte (port + ISR, MSK_OVW);
+ outport_byte (port + TCR, 0);
+ if (sc->resend)
+ outport_byte (port + CMDR, MSK_PG0 | MSK_TXP | MSK_RD2 | MSK_STA);
+ sc->resend = 0;
+ sc->overrun = 0;
+ }
+
+ Next:
+ /* Reenable device interrupts. */
+ outport_byte (port + IMR, NE_INTERRUPTS);
+ }
+}
+
+/* Load an NE2000 packet onto the device. */
+
+static void
+ne_loadpacket (struct ne_softc *sc, struct mbuf *m)
+{
+ unsigned int port = sc->port;
+ unsigned int dport = port + DATAPORT;
+ struct mbuf *mhold = m;
+ int leftover;
+ unsigned char leftover_data;
+ int timeout;
+ int send_cnt = 0;
+
+#ifdef DEBUG_NE2000
+ printk ("Uploading NE2000 packet\n");
+#endif
+
+ /* Reset remote DMA complete flag. */
+ outport_byte (port + ISR, MSK_RDC);
+
+ /* Write out the count. */
+ outport_byte (port + RBCR0, m->m_pkthdr.len);
+ outport_byte (port + RBCR1, m->m_pkthdr.len >> 8);
+
+ sc->sendlen[sc->nextavail] = m->m_pkthdr.len;
+
+ /* Tell the device which address we want to write to. */
+ outport_byte (port + RSAR0, 0);
+ outport_byte (port + RSAR1,
+ NE_FIRST_TX_PAGE + (sc->nextavail * NE_TX_PAGES));
+
+ /* Set up the write. */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RWR | MSK_STA);
+
+ /* Transfer the mbuf chain to device memory. NE2000 devices require
+ that the data be transferred as words, so we need to handle odd
+ length mbufs. Never occurs if we force byte transfers. */
+
+ leftover = 0;
+ leftover_data = '\0';
+
+ for (; m != NULL; m = m->m_next) {
+ int len;
+ unsigned char *data;
+
+ len = m->m_len;
+ if (len == 0)
+ continue;
+
+ data = mtod (m, unsigned char *);
+
+ if (leftover) {
+ unsigned char next;
+
+ /* Data left over from previous mbuf in chain. */
+ next = *data++;
+ --len;
+ outport_word (dport, leftover_data | (next << 8));
+ send_cnt += 2;
+ leftover = 0;
+ }
+
+ /* If using byte transfers, len always ends up as zero so
+ there are no leftovers. */
+
+ if (sc->byte_transfers)
+ while (len > 0) {
+ outport_byte (dport, *data++);
+ len--;
+ }
+ else
+ while (len > 1) {
+ outport_word (dport, data[0] | (data[1] << 8));
+ data += 2;
+ len -= 2;
+ send_cnt += 2;
+ }
+
+ if (len > 0)
+ {
+ leftover = 1;
+ leftover_data = *data++;
+ }
+ }
+
+ if (leftover)
+ {
+ outport_word (dport, leftover_data);
+ send_cnt += 2;
+ }
+
+#ifdef DEBUG_NE
+ /* printk("{l%d|%d}", send_cnt, sc->nextavail); */
+ printk("v");
+#endif
+ m_freem (mhold);
+
+ /* Wait for the device to complete accepting the data, with a
+ limiting counter so that we don't wait too long. */
+ for (timeout = 0; timeout < 1000; ++timeout)
+ {
+ unsigned char status;
+
+ inport_byte (port + ISR, status);
+
+#ifdef DEBUG_NE2000
+ if ((status &~ MSK_RDC) != 0)
+ printk ("Status 0x%x while waiting for acknowledgement of uploaded packet\n",
+ status);
+#endif
+
+ if ((status & MSK_RDC) != 0) {
+ outport_byte (port + ISR, MSK_RDC);
+ break;
+ }
+ }
+
+ if (timeout >= 1000)
+ printk ("Timed out waiting for acknowledgement of uploaded NE2000 packet\n");
+
+ ++sc->nextavail;
+ if (sc->nextavail == NE_TX_BUFS)
+ sc->nextavail = 0;
+}
+
+/* Tell the NE2000 to transmit a buffer whose contents we have already
+ loaded onto the device. */
+
+static void
+ne_transmit (struct ne_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+ int len;
+
+#ifdef DEBUG_NE2000
+ printk ("Transmitting NE2000 packet\n");
+#endif
+
+ len = sc->sendlen[sc->nextsend];
+ if (len < ET_MINLEN)
+ len = ET_MINLEN;
+ outport_byte (port + TBCR0, len);
+ outport_byte (port + TBCR1, len >> 8);
+
+ outport_byte (port + TPSR, NE_FIRST_TX_PAGE + (sc->nextsend * NE_TX_PAGES));
+
+ outport_byte (port + CMDR, MSK_PG0 | MSK_TXP | MSK_RD2 | MSK_STA);
+
+#ifdef DEBUG_NE
+ /* printk("{s%d|%d}", len, sc->nextsend); */
+ printk(">");
+#endif
+ ++sc->nextsend;
+ if (sc->nextsend == NE_TX_BUFS)
+ sc->nextsend = 0;
+
+ ++sc->stats.tx_packets;
+
+ /* set watchdog timer */
+ ifp->if_timer = 2;
+}
+
+/* The NE2000 packet transmit daemon. This task is started when the
+ NE2000 driver is initialized. */
+
+static void
+ne_tx_daemon (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ unsigned int port = sc->port;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ while (1) {
+ rtems_event_set events;
+
+ /* Wait for a packet to be ready for sending, or for there to be
+ room for another packet in the device memory. */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+#ifdef DEBUG_NE2000
+ printk ("ne_tx_daemon\n");
+#endif
+
+ /* This daemon handles both uploading data onto the device and
+ telling the device to transmit data which has been uploaded.
+ These are separate tasks, because while the device is
+ transmitting one buffer we will upload another. */
+
+ /* Don't let the device interrupt us now. */
+ outport_byte (port + IMR, 0);
+
+ while (1) {
+ struct mbuf *m;
+
+ /* If the device is not transmitting a packet, and we have
+ uploaded a packet, tell the device to transmit it. */
+ if (! sc->transmitting && sc->inuse > 0) {
+ sc->transmitting = 1;
+ ne_transmit (sc);
+ }
+
+ /* If we don't have any more buffers to send, quit now. */
+ if (ifp->if_snd.ifq_head == NULL) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ break;
+ }
+
+ /* Allocate a buffer to load data into. If there are none
+ available, quit until a buffer has been transmitted. */
+ if (sc->inuse >= NE_TX_BUFS)
+ break;
+
+ ++sc->inuse;
+
+ IF_DEQUEUE (&ifp->if_snd, m);
+ if (m == NULL)
+ panic ("ne_tx_daemon");
+
+ ne_loadpacket (sc, m);
+
+ /* Check the device status. It may have finished transmitting
+ the last packet. */
+ ne_check_status(sc, 0);
+ }
+
+ /* Reenable device interrupts. */
+ outport_byte (port + IMR, NE_INTERRUPTS);
+ }
+}
+
+/* Start sending an NE2000 packet. */
+
+static void
+ne_start (struct ifnet *ifp)
+{
+ struct ne_softc *sc = ifp->if_softc;
+
+#ifdef DEBUG_NE
+ printk("S");
+#endif
+ /* Tell the transmit daemon to wake up and send a packet. */
+ rtems_bsdnet_event_send (sc->tx_daemon_tid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/* Initialize and start and NE2000. */
+
+static void
+ne_init (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+#ifdef DEBUG_NE
+ printk("ne_init()\n");
+ ne_dump(sc);
+#endif
+
+ /* only once... */
+ if (sc->tx_daemon_tid == 0)
+ {
+ sc->inuse = 0;
+ sc->nextavail = 0;
+ sc->nextsend = 0;
+ sc->transmitting = 0;
+
+ ne_init_hardware (sc);
+
+ sc->tx_daemon_tid = rtems_bsdnet_newproc ("SCtx", 4096, ne_tx_daemon, sc);
+ sc->rx_daemon_tid = rtems_bsdnet_newproc ("SCrx", 4096, ne_rx_daemon, sc);
+
+ /* install rtems irq handler */
+ ne_init_irq_handler(sc);
+ }
+
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+/* Stop an NE2000. */
+
+static void
+ne_stop (struct ne_softc *sc)
+{
+ sc->arpcom.ac_if.if_flags &= ~IFF_RUNNING;
+
+ ne_stop_hardware(sc);
+
+ sc->inuse = 0;
+ sc->nextavail = 0;
+ sc->nextsend = 0;
+ sc->transmitting = 0;
+ sc->overrun = 0;
+ sc->resend = 0;
+}
+
+static void
+ne_stop_hardware (struct ne_softc *sc)
+{
+ unsigned int port = sc->port;
+ int i;
+
+ /* Stop everything. */
+ outport_byte (port + CMDR, MSK_STP | MSK_RD2);
+
+ /* Wait for the interface to stop, using I as a time limit. */
+ for (i = 0; i < 5000; ++i)
+ {
+ unsigned char status;
+
+ inport_byte (port + ISR, status);
+ if ((status & MSK_RST) != 0)
+ break;
+ }
+}
+
+/* reinitializing interface
+*/
+static void
+ne_reset(struct ne_softc *sc)
+{
+ ne_stop(sc);
+ ne_init_hardware(sc);
+ sc->arpcom.ac_if.if_flags |= IFF_RUNNING;
+ sc->arpcom.ac_if.if_flags &= ~IFF_OACTIVE;
+#ifdef DEBUG_NE
+ printk("*");
+#endif
+}
+
+#ifdef DEBUG_NE
+/* show anything about ne
+*/
+static void
+ne_dump(struct ne_softc *sc)
+{
+ int i;
+ printk("\nne configuration:\n");
+ printk("ethernet addr:");
+ for (i=0; i<ETHER_ADDR_LEN; i++)
+ printk(" %x", sc->arpcom.ac_enaddr[i]);
+ printk("\n");
+ printk("irq = %d\n", sc->irno);
+ printk("port = 0x%x\n", sc->port);
+ printk("accept_broadcasts = %d\n", sc->accept_broadcasts);
+ printk("byte_transfers = %d\n", sc->byte_transfers);
+}
+#endif
+
+/* Show NE2000 interface statistics. */
+
+static void
+ne_stats (struct ne_softc *sc)
+{
+ printf (" Received packets: %-8lu", sc->stats.rx_packets);
+ printf (" Transmitted packets: %-8lu\n", sc->stats.tx_packets);
+ printf (" Receive acks: %-8lu", sc->stats.rx_acks);
+ printf (" Transmit acks: %-8lu\n", sc->stats.tx_acks);
+ printf (" Packet overruns: %-8lu", sc->stats.overruns);
+ printf (" Frame errors: %-8lu\n", sc->stats.rx_frame_errors);
+ printf (" CRC errors: %-8lu", sc->stats.rx_crc_errors);
+ printf (" Missed packets: %-8lu\n", sc->stats.rx_missed_errors);
+ printf (" Interrupts: %-8lu\n", sc->stats.interrupts);
+}
+
+/* NE2000 driver ioctl handler. */
+
+static int
+ne_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct ne_softc *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ error = ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ ne_stop (sc);
+ break;
+
+ case IFF_UP:
+ printk("IFF_UP\n");
+ ne_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ ne_stop (sc);
+ ne_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ ne_stats (sc);
+ break;
+
+ /* FIXME: Multicast commands must be added here. */
+
+ default:
+ error = EINVAL;
+ break;
+ }
+
+ return error;
+}
+
+/*
+ * Device timeout/watchdog routine. Entered if the device neglects to
+ * generate an interrupt after a transmit has been started on it.
+ */
+static void
+ne_watchdog(struct ifnet *ifp)
+{
+ struct ne_softc *sc = ifp->if_softc;
+
+ printk("ne2000: device timeout\n");
+ ifp->if_oerrors++;
+
+ ne_reset(sc);
+}
+
+static void
+print_byte(unsigned char b)
+{
+ printk("%x%x", b >> 4, b & 0x0f);
+}
+
+/* Attach an NE2000 driver to the system. */
+
+int
+rtems_ne_driver_attach (struct rtems_bsdnet_ifconfig *config, int attach)
+{
+ int i;
+ struct ne_softc *sc;
+ struct ifnet *ifp;
+ int mtu;
+
+ /* dettach ... */
+ if (!attach)
+ return 0;
+
+ /* Find a free driver. */
+ sc = NULL;
+ for (i = 0; i < NNEDRIVER; ++i) {
+ sc = &ne_softc[i];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc == NULL)
+ break;
+ }
+
+ if (sc == NULL) {
+ printf ("Too many NE2000 drivers.\n");
+ return 0;
+ }
+
+ memset (sc, 0, sizeof *sc);
+
+ /* Check whether we do byte-wide or word-wide transfers. */
+
+#ifdef NE2000_BYTE_TRANSFERS
+ sc->byte_transfers = true;
+#else
+ sc->byte_transfers = false;
+#endif
+
+ /* Handle the options passed in by the caller. */
+
+ if (config->mtu != 0)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ /* We use 16 as the default IRQ. */
+ sc->irno = XSCALE_IRQ_NETWORK;
+
+
+
+ /*IO prts are mapped to 0X40000600 */
+ sc->port = 0x40000600;
+
+ sc->accept_broadcasts = ! config->ignore_broadcast;
+
+ if (config->hardware_address != NULL)
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address,
+ ETHER_ADDR_LEN);
+ else
+ {
+ unsigned char prom[16];
+ int ia;
+
+ /* Read the PROM to get the Ethernet hardware address. */
+
+ outport_byte (sc->port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ if (sc->byte_transfers) {
+ outport_byte (sc->port + DCR, MSK_FT10 | MSK_BMS);
+ }
+ else {
+ outport_byte (sc->port + DCR, MSK_FT10 | MSK_BMS | MSK_WTS);
+ }
+
+ outport_byte (sc->port + RBCR0, 0);
+ outport_byte (sc->port + RBCR1, 0);
+ outport_byte (sc->port + RCR, MSK_MON);
+ outport_byte (sc->port + TCR, MSK_LOOP);
+ outport_byte (sc->port + IMR, 0);
+ outport_byte (sc->port + ISR, 0xff);
+
+ ne_read_data (sc, 0, sizeof prom, prom);
+
+ outport_byte (sc->port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ for (ia = 0; ia < ETHER_ADDR_LEN; ++ia)
+ sc->arpcom.ac_enaddr[ia] = prom[ia * 2];
+ }
+
+ /* Set up the network interface. */
+
+ ifp->if_softc = sc;
+ ifp->if_unit = i + 1;
+ ifp->if_name = "ne";
+ ifp->if_mtu = mtu;
+ ifp->if_init = ne_init;
+ ifp->if_ioctl = ne_ioctl;
+ ifp->if_watchdog = ne_watchdog;
+ ifp->if_start = ne_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /* Attach the interface. */
+
+ if_attach (ifp);
+ ether_ifattach (ifp);
+
+ printk("network device '%s' <", config->name);
+ print_byte(sc->arpcom.ac_enaddr[0]);
+ for (i=1; i<ETHER_ADDR_LEN; i++)
+ { printk(":");
+ print_byte(sc->arpcom.ac_enaddr[i]);
+ }
+ printk("> initialized on port 0x%x, irq %d\n", sc->port, sc->irno);
+
+ return 1;
+}
diff --git a/bsps/arm/gumstix/net/wd80x3.h b/bsps/arm/gumstix/net/wd80x3.h
new file mode 100644
index 0000000..0a9f343
--- /dev/null
+++ b/bsps/arm/gumstix/net/wd80x3.h
@@ -0,0 +1,303 @@
+/**
+ * @file
+ * @ingroup gumstix_dp8390
+ * @brief DP8390 Ethernet Controller Support
+ */
+
+/*
+ * Information about the DP8390 Ethernet controller.
+ */
+
+#ifndef __BSP_WD80x3_h
+#define __BSP_WD80x3_h
+
+/* Register descriptions */
+
+/**
+ * @defgroup gumstix_dp8390 DP8390 Support
+ * @ingroup RTEMSBSPsARMGumstix
+ * @brief DP8390 Ethernet Controller Support
+ * @{
+ */
+
+/**
+ * @name Controller DP8390.
+ * @{
+ */
+
+/** @brief Port Window. */
+#define DATAPORT 0x10
+/** @brief Issue a read for reset */
+#define RESET 0x1f
+/** @brief I/O port definition */
+#define W83CREG 0x00
+#define ADDROM 0x08
+
+/** @} */
+
+/**
+ * @name page 0 read or read/write registers
+ * @{
+ */
+
+#define CMDR 0x00+RO
+/** @brief current local dma addr 0 for read */
+#define CLDA0 0x01+RO
+/** @brief current local dma addr 1 for read */
+#define CLDA1 0x02+RO
+/** @brief boundary reg for rd and wr */
+#define BNRY 0x03+RO
+/** @brief tx status reg for rd */
+#define TSR 0x04+RO
+/** @brief number of collision reg for rd */
+#define NCR 0x05+RO
+/** @breif FIFO for rd */
+#define FIFO 0x06+RO
+/** @brief interrupt status reg for rd and wr */
+#define ISR 0x07+RO
+/** @brief current remote dma address 0 for rd */
+#define CRDA0 0x08+RO
+/** @brief current remote dma address 1 for rd */
+#define CRDA1 0x09+RO
+/** @brief rx status reg for rd */
+#define RSR 0x0C+RO
+/** @brief tally cnt 0 for frm alg err for rd */
+#define CNTR0 0x0D+RO
+/** @brief tally cnt 1 for crc err for rd */
+#define CNTR1 RO+0x0E
+/** @brief tally cnt 2 for missed pkt for rd */
+#define CNTR2 0x0F+RO
+
+/** @} */
+
+/**
+ * @name page 0 write registers
+ * @{
+ */
+
+/** @brief page start register */
+#define PSTART 0x01+RO
+/** @brief page stop register */
+#define PSTOP 0x02+RO
+/** @breif tx start page start reg */
+#define TPSR 0x04+RO
+/** @brief tx byte count 0 reg */
+#define TBCR0 0x05+RO
+/** @brief tx byte count 1 reg */
+#define TBCR1 0x06+RO
+/** @brief remote start address reg 0 */
+#define RSAR0 0x08+RO
+/** @brief remote start address reg 1 */
+#define RSAR1 0x09+RO
+/** @brief remote byte count reg 0 */
+#define RBCR0 0x0A+RO
+/** @brief remote byte count reg 1 */
+#define RBCR1 0x0B+RO
+/** @brief rx configuration reg */
+#define RCR 0x0C+RO
+/** @brief tx configuration reg */
+#define TCR 0x0D+RO
+/** @brief data configuration reg */
+#define DCR RO+0x0E
+/** @brief interrupt mask reg */
+#define IMR 0x0F+RO
+
+/** @} */
+
+/**
+ * @name page 1 registers
+ * @{
+ */
+
+/** @brief physical addr reg base for rd and wr */
+#define PAR 0x01+RO
+/** @brief current page reg for rd and wr */
+#define CURR 0x07+RO
+/** @brief multicast addr reg base fro rd and WR */
+#define MAR 0x08+RO
+/** @brief size of multicast addr space */
+#define MARsize 8
+
+/** @} */
+
+/**
+ * @name W83CREG command bits
+ * @{
+ */
+
+/** @brief W83CREG masks */
+#define MSK_RESET 0x80
+#define MSK_ENASH 0x40
+/** @brief memory decode bits, corresponding */
+#define MSK_DECOD 0x3F
+
+/** @} */
+
+/**
+ * @name CMDR command bits
+ * @{
+ */
+
+/** @brief stop the chip */
+#define MSK_STP 0x01
+/** @brief start the chip */
+#define MSK_STA 0x02
+/** @brief initial txing of a frm */
+#define MSK_TXP 0x04
+/** @brief remote read */
+#define MSK_RRE 0x08
+/** @brief remote write */
+#define MSK_RWR 0x10
+/** @brief no DMA used */
+#define MSK_RD2 0x20
+/** @brief select register page 0 */
+#define MSK_PG0 0x00
+/** @brief select register page 1 */
+#define MSK_PG1 0x40
+/** @brief select register page 2 */
+#define MSK_PG2 0x80
+
+/** @} */
+
+/**
+ * @name ISR and TSR status bits
+ * @{
+ */
+
+/* @brief rx with no error */
+#define MSK_PRX 0x01
+/* @brief tx with no error */
+#define MSK_PTX 0x02
+/* @brief rx with error */
+#define MSK_RXE 0x04
+/* @brief tx with error */
+#define MSK_TXE 0x08
+/* @brief overwrite warning */
+#define MSK_OVW 0x10
+/* @brief MSB of one of the tally counters is set */
+#define MSK_CNT 0x20
+/* @brief remote dma completed */
+#define MSK_RDC 0x40
+/* @brief reset state indicator */
+#define MSK_RST 0x80
+
+/** @} */
+
+/**
+ * @name DCR command bits
+ * @{
+ */
+
+/** @brief word transfer mode selection */
+#define MSK_WTS 0x01
+/** @brief byte order selection */
+#define MSK_BOS 0x02
+/** @brief long addr selection */
+#define MSK_LAS 0x04
+/** @brief burst mode selection */
+#define MSK_BMS 0x08
+/** @brief autoinitialize remote */
+#define MSK_ARM 0x10
+/** @brief burst lrngth selection */
+#define MSK_FT00 0x00
+/** @brief burst lrngth selection */
+#define MSK_FT01 0x20
+/** @brief burst lrngth selection */
+#define MSK_FT10 0x40
+/** @brief burst lrngth selection */
+#define MSK_FT11 0x60
+
+/** @} */
+
+/**
+ * @name RCR command bits
+ * @{
+ */
+
+/** @brief save error pkts */
+#define MSK_SEP 0x01
+/** @brief accept runt pkt */
+#define MSK_AR 0x02
+/** @brief 8390 RCR */
+#define MSK_AB 0x04
+/** @brief accept multicast */
+#define MSK_AM 0x08
+/** @brief accept all pkt with physical adr */
+#define MSK_PRO 0x10
+/** @brief monitor mode */
+#define MSK_MON 0x20
+
+/** @} */
+
+/**
+ * @name TCR command bits
+ * @{
+ */
+
+/** @brief inhibit CRC, do not append crc */
+#define MSK_CRC 0x01
+/** @brief set loopback mode */
+#define MSK_LOOP 0x02
+/** @brief Accept broadcasts */
+#define MSK_BCST 0x04
+/** @brief encoded loopback control */
+#define MSK_LB01 0x06
+/** @brief auto tx disable */
+#define MSK_ATD 0x08
+/** @brief collision offset enable */
+#define MSK_OFST 0x10
+
+/** @} */
+
+/**
+ * @name receive status bits
+ * @{
+ */
+
+/** @brief rx without error */
+#define SMK_PRX 0x01
+/** @brief CRC error */
+#define SMK_CRC 0x02
+/** @brief frame alignment error */
+#define SMK_FAE 0x04
+/** @brief FIFO overrun */
+#define SMK_FO 0x08
+/** @brief missed pkt */
+#define SMK_MPA 0x10
+/** @brief physical/multicase address */
+#define SMK_PHY 0x20
+/** @brief receiver disable. set in monitor mode */
+#define SMK_DIS 0x40
+/** @brief deferring */
+#define SMK_DEF 0x80
+
+/** @} */
+
+/**
+ * @name transmit status bits
+ * @{
+ */
+
+/** @brief tx without error */
+#define SMK_PTX 0x01
+/** @brief non deferred tx */
+#define SMK_DFR 0x02
+/** @brief tx collided */
+#define SMK_COL 0x04
+/** @brief tx abort because of excessive collisions */
+#define SMK_ABT 0x08
+/** @brief carrier sense lost */
+#define SMK_CRS 0x10
+/** @brief FIFO underrun */
+#define SMK_FU 0x20
+/** @brief collision detect heartbeat */
+#define SMK_CDH 0x40
+/** @brief out of window collision */
+#define SMK_OWC 0x80
+
+/** @} */
+
+/** @} */
+
+#endif
+/* end of include */
diff --git a/bsps/arm/rtl22xx/net/network.c b/bsps/arm/rtl22xx/net/network.c
new file mode 100644
index 0000000..5581b8f
--- /dev/null
+++ b/bsps/arm/rtl22xx/net/network.c
@@ -0,0 +1,126 @@
+/*Note: this file is copy from 7312 BSP, and untested yet*/
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <bsp/irq.h>
+#include <libchip/cs8900.h>
+#include <assert.h>
+
+#define CS8900_BASE 0x20000300
+unsigned int bsp_cs8900_io_base = 0;
+unsigned int bsp_cs8900_memory_base = 0;
+static void cs8900_isr(void *);
+
+char g_enetbuf[1520];
+
+static void cs8900_isr(void *arg)
+{
+ cs8900_interrupt(LPC22xx_INTERRUPT_EINT2, arg);
+}
+
+/* cs8900_io_set_reg - set one of the I/O addressed registers */
+void cs8900_io_set_reg (cs8900_device *cs, unsigned short reg, unsigned short data)
+{
+ /* works the same for all values of dev */
+/*
+ printf("cs8900_io_set_reg: reg: %#6x, val %#6x\n",
+ CS8900_BASE + reg,
+ data);
+*/
+ *(unsigned short *)(CS8900_BASE + reg) = data;
+}
+
+/* cs8900_io_get_reg - reads one of the I/O addressed registers */
+unsigned short cs8900_io_get_reg (cs8900_device *cs, unsigned short reg)
+{
+ unsigned short val;
+ /* works the same for all values of dev */
+ val = *(unsigned short *)(CS8900_BASE + reg);
+/*
+ printf("cs8900_io_get_reg: reg: %#6x, val %#6x\n", reg, val);
+*/
+ return val;
+}
+
+/* cs8900_mem_set_reg - sets one of the registers mapped through
+ * PacketPage
+ */
+void cs8900_mem_set_reg (cs8900_device *cs, unsigned long reg, unsigned short data)
+{
+ /* works the same for all values of dev */
+ cs8900_io_set_reg(cs, CS8900_IO_PACKET_PAGE_PTR, reg);
+ cs8900_io_set_reg(cs, CS8900_IO_PP_DATA_PORT0, data);
+}
+
+/* cs8900_mem_get_reg - reads one of the registers mapped through
+ * PacketPage
+ */
+unsigned short cs8900_mem_get_reg (cs8900_device *cs, unsigned long reg)
+{
+ /* works the same for all values of dev */
+ cs8900_io_set_reg(cs, CS8900_IO_PACKET_PAGE_PTR, reg);
+ return cs8900_io_get_reg(cs, CS8900_IO_PP_DATA_PORT0);
+}
+
+void cs8900_attach_interrupt (cs8900_device *cs)
+{
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+ status = rtems_interrupt_handler_install(
+ LPC22xx_INTERRUPT_EINT2,
+ "Network",
+ RTEMS_INTERRUPT_UNIQUE,
+ cs8900_isr,
+ cs
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+void cs8900_detach_interrupt (cs8900_device *cs)
+{
+ rtems_status_code status = RTEMS_SUCCESSFUL;
+ status = rtems_interrupt_handler_remove(
+ LPC22xx_INTERRUPT_EINT2,
+ cs8900_isr,
+ cs
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+unsigned short cs8900_get_data_block (cs8900_device *cs, unsigned char *data)
+{
+ int len;
+ int i;
+
+ len = cs8900_mem_get_reg(cs, CS8900_PP_RxLength);
+
+ for (i = 0; i < ((len + 1) / 2); i++) {
+ ((short *)data)[i] = cs8900_io_get_reg(cs,
+ CS8900_IO_RX_TX_DATA_PORT0);
+ }
+ return len;
+}
+
+void cs8900_tx_load (cs8900_device *cs, struct mbuf *m)
+{
+ int len;
+ unsigned short *data;
+ int i;
+
+ len = 0;
+
+ do {
+ memcpy(&g_enetbuf[len], mtod(m, const void *), m->m_len);
+ len += m->m_len;
+ m = m->m_next;
+ } while (m != 0);
+
+ data = (unsigned short *) &g_enetbuf[0];
+ for (i = 0; i < ((len + 1) / 2); i++) {
+ cs8900_io_set_reg(cs,
+ CS8900_IO_RX_TX_DATA_PORT0,
+ data[i]);
+ }
+}
diff --git a/bsps/bfin/bf537Stamp/net/ethernet.c b/bsps/bfin/bf537Stamp/net/ethernet.c
new file mode 100644
index 0000000..1594219
--- /dev/null
+++ b/bsps/bfin/bf537Stamp/net/ethernet.c
@@ -0,0 +1,880 @@
+/*
+ * RTEMS network driver for Blackfin ethernet controller
+ *
+ * COPYRIGHT (c) 2008 Kallisti Labs, Los Gatos, CA, USA
+ * written by Allan Hessenflow <allanh@kallisti.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems/cache.h>
+
+#include <stdio.h>
+#include <inttypes.h>
+#include <string.h>
+
+#include <errno.h>
+#include <rtems/error.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <libcpu/dmaRegs.h>
+#include <libcpu/ethernetRegs.h>
+#include <libcpu/ethernet.h>
+
+#if (BFIN_ETHERNET_DEBUG & BFIN_ETHERNET_DEBUG_DUMP_MBUFS)
+#include <rtems/dumpbuf.h>
+#endif
+
+/*
+ * Number of devices supported by this driver
+ */
+#ifndef N_BFIN_ETHERNET
+# define N_BFIN_ETHERNET 1
+#endif
+
+
+/* #define BFIN_IPCHECKSUMS */
+
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+
+/* largest Ethernet frame MAC will handle */
+#define BFIN_ETHERNET_MAX_FRAME_LENGTH 1556
+
+#if MCLBYTES < (BFIN_ETHERNET_MAX_FRAME_LENGTH + 2)
+#error MCLBYTES too small
+#endif
+
+#define BFIN_REG16(base, offset) \
+ (*((uint16_t volatile *) ((char *)(base) + (offset))))
+#define BFIN_REG32(base, offset) \
+ (*((uint32_t volatile *) ((char *)(base) + (offset))))
+
+
+#define DMA_MODE_RX (DMA_CONFIG_FLOW_DESC_LARGE | \
+ (5 << DMA_CONFIG_NDSIZE_SHIFT) | \
+ DMA_CONFIG_WDSIZE_32 | \
+ DMA_CONFIG_WNR | \
+ DMA_CONFIG_DMAEN)
+
+#define DMA_MODE_TX (DMA_CONFIG_FLOW_DESC_LARGE | \
+ (5 << DMA_CONFIG_NDSIZE_SHIFT) | \
+ DMA_CONFIG_WDSIZE_32 | \
+ DMA_CONFIG_DMAEN)
+
+#define DMA_MODE_STATUS (DMA_CONFIG_FLOW_DESC_LARGE | \
+ (5 << DMA_CONFIG_NDSIZE_SHIFT) | \
+ DMA_CONFIG_DI_EN | \
+ DMA_CONFIG_WDSIZE_32 | \
+ DMA_CONFIG_WNR | \
+ DMA_CONFIG_DMAEN)
+
+#define DMA_MODE_STATUS_NO_INT (DMA_CONFIG_FLOW_DESC_LARGE | \
+ (5 << DMA_CONFIG_NDSIZE_SHIFT) | \
+ DMA_CONFIG_WDSIZE_32 | \
+ DMA_CONFIG_WNR | \
+ DMA_CONFIG_DMAEN)
+
+#define DMA_MODE_STATUS_LAST (DMA_CONFIG_FLOW_STOP | \
+ (0 << DMA_CONFIG_NDSIZE_SHIFT) | \
+ DMA_CONFIG_DI_EN | \
+ DMA_CONFIG_WDSIZE_32 | \
+ DMA_CONFIG_WNR | \
+ DMA_CONFIG_DMAEN)
+
+/* five 16 bit words */
+typedef struct dmaDescS {
+ struct dmaDescS *next;
+ void *addr;
+ uint16_t dmaConfig;
+} dmaDescT;
+
+typedef struct {
+ uint32_t status;
+} txStatusT;
+
+#ifdef BFIN_IPCHECKSUMS
+typedef struct {
+ uint16_t ipHeaderChecksum;
+ uint16_t ipPayloadChecksum;
+ uint32_t status;
+} rxStatusT;
+#else
+typedef struct {
+ uint32_t status;
+} rxStatusT;
+#endif
+
+typedef struct {
+ dmaDescT data;
+ dmaDescT status;
+ struct mbuf *m;
+} rxPacketDescT;
+
+typedef struct {
+ dmaDescT data;
+ dmaDescT status;
+ bool inUse;
+ union {
+ uint32_t dummy; /* try to force 32 bit alignment */
+ struct {
+ uint16_t length;
+ char data[BFIN_ETHERNET_MAX_FRAME_LENGTH];
+ } packet;
+ } buffer;
+} txPacketDescT;
+
+
+/* hardware-specific storage */
+struct bfin_ethernetSoftc {
+ struct arpcom arpcom; /* this entry must be first */
+
+ uint32_t sclk;
+
+ void *ethBase;
+ void *rxdmaBase;
+ void *txdmaBase;
+
+ int acceptBroadcast;
+
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ void *status;
+ int rxDescCount;
+ rxPacketDescT *rx;
+ int txDescCount;
+ txPacketDescT *tx;
+
+ bool rmii;
+ int phyAddr;
+
+ /* statistics */
+#ifdef BISON
+ unsigned long Interrupts;
+ unsigned long rxInterrupts;
+ unsigned long rxMissed;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxBadCRC;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txSingleCollision;
+ unsigned long txMultipleCollision;
+ unsigned long txCollision;
+ unsigned long txDeferred;
+ unsigned long txUnderrun;
+ unsigned long txLateCollision;
+ unsigned long txExcessiveCollision;
+ unsigned long txExcessiveDeferral;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+#endif
+};
+
+static struct bfin_ethernetSoftc ethernetSoftc[N_BFIN_ETHERNET];
+
+
+/* Shut down the interface. */
+static void ethernetStop(struct bfin_ethernetSoftc *sc) {
+ struct ifnet *ifp;
+ void *ethBase;
+
+ ifp = &sc->arpcom.ac_if;
+ ethBase = sc->ethBase;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /* stop the transmitter and receiver. */
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) &= ~(EMAC_OPMODE_TE |
+ EMAC_OPMODE_RE);
+}
+
+/* Show interface statistics */
+static void bfin_ethernetStats(struct bfin_ethernetSoftc *sc) {
+#ifdef BISON
+ printf(" Total Interrupts:%-8lu", sc->Interrupts);
+ printf(" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf(" Giant:%-8lu", sc->rxGiant);
+ printf(" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf(" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf(" Collision:%-8lu", sc->rxCollision);
+ printf(" Missed:%-8lu\n", sc->rxMissed);
+
+ printf( " Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf( " Deferred:%-8lu", sc->txDeferred);
+ printf(" Lost Carrier:%-8lu\n", sc->txLostCarrier);
+ printf( "Single Collisions:%-8lu", sc->txSingleCollision);
+ printf( "Multiple Collisions:%-8lu", sc->txMultipleCollision);
+ printf("Excessive Collisions:%-8lu\n", sc->txExcessiveCollision);
+ printf( " Total Collisions:%-8lu", sc->txCollision);
+ printf( " Late Collision:%-8lu", sc->txLateCollision);
+ printf(" Underrun:%-8lu\n", sc->txUnderrun);
+ printf( " Raw output wait:%-8lu\n", sc->txRawWait);
+#endif /*BISON*/
+}
+
+void bfin_ethernet_rxdma_isr(int vector) {
+ struct bfin_ethernetSoftc *sc;
+ void *rxdmaBase;
+ uint16_t status;
+ int i;
+
+ for (i = 0; i < N_BFIN_ETHERNET; i++) {
+ sc = &ethernetSoftc[i];
+ rxdmaBase = sc->rxdmaBase;
+ status = BFIN_REG16(rxdmaBase, DMA_IRQ_STATUS_OFFSET);
+ if (status & DMA_IRQ_STATUS_DMA_DONE)
+ rtems_bsdnet_event_send (sc->rxDaemonTid, INTERRUPT_EVENT);
+ BFIN_REG16(rxdmaBase, DMA_IRQ_STATUS_OFFSET) = status;
+ }
+}
+
+void bfin_ethernet_txdma_isr(int vector) {
+ struct bfin_ethernetSoftc *sc;
+ void *txdmaBase;
+ uint16_t status;
+ int i;
+
+ for (i = 0; i < N_BFIN_ETHERNET; i++) {
+ sc = &ethernetSoftc[i];
+ txdmaBase = sc->txdmaBase;
+ status = BFIN_REG16(txdmaBase, DMA_IRQ_STATUS_OFFSET);
+ if (status & DMA_IRQ_STATUS_DMA_DONE)
+ rtems_bsdnet_event_send (sc->txDaemonTid, INTERRUPT_EVENT);
+ BFIN_REG16(txdmaBase, DMA_IRQ_STATUS_OFFSET) = status;
+ }
+}
+
+void bfin_ethernet_mac_isr(int vector) {
+ struct bfin_ethernetSoftc *sc;
+ void *ethBase;
+ int i;
+
+ for (i = 0; i < N_BFIN_ETHERNET; i++) {
+ sc = &ethernetSoftc[i];
+ ethBase = sc->ethBase;
+ BFIN_REG32(ethBase, EMAC_SYSTAT_OFFSET) = ~(uint32_t) 0;
+ }
+}
+
+static bool txFree(struct bfin_ethernetSoftc *sc, int index) {
+ bool freed;
+ txStatusT *status;
+
+ freed = false;
+ if (sc->tx[index].inUse) {
+ status = (txStatusT *) sc->tx[index].status.addr;
+ rtems_cache_invalidate_multiple_data_lines(status, sizeof(*status));
+ if (status->status != 0) {
+ /* update statistics */
+
+ sc->tx[index].inUse = false;
+ freed = true;
+ }
+ }
+
+ return freed;
+}
+
+static void txDaemon(void *arg) {
+ struct bfin_ethernetSoftc *sc;
+ struct ifnet *ifp;
+ struct mbuf *m, *first;
+ rtems_event_set events;
+ void *ethBase;
+ void *txdmaBase;
+ txStatusT *status;
+ int head;
+ int prevHead;
+ int tail;
+ int length;
+ char *ptr;
+
+ sc = (struct bfin_ethernetSoftc *) arg;
+ ifp = &sc->arpcom.ac_if;
+
+ ethBase = sc->ethBase;
+ txdmaBase = sc->txdmaBase;
+ head = 0;
+ prevHead = sc->txDescCount - 1;
+ tail = 0;
+
+ while (1) {
+ /* wait for packet or isr */
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT | INTERRUPT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ /* if no descriptors are available, try to free one. To reduce
+ transmit latency only do one here. */
+ if (sc->tx[head].inUse && txFree(sc, tail)) {
+ if (++tail == sc->txDescCount)
+ tail = 0;
+ }
+ /* send packets until the queue is empty or we run out of tx
+ descriptors */
+ while (!sc->tx[head].inUse && (ifp->if_flags & IFF_OACTIVE)) {
+ /* get the next mbuf chain to transmit */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (m != NULL) {
+ /* copy packet into our buffer */
+ ptr = sc->tx[head].buffer.packet.data;
+ length = 0;
+ first = m;
+ while (m && length <= BFIN_ETHERNET_MAX_FRAME_LENGTH) {
+ length += m->m_len;
+ if (length <= BFIN_ETHERNET_MAX_FRAME_LENGTH)
+ memcpy(ptr, m->m_data, m->m_len);
+ ptr += m->m_len;
+ m = m->m_next;
+ }
+ m_freem(first); /* all done with mbuf */
+ if (length <= BFIN_ETHERNET_MAX_FRAME_LENGTH) {
+ sc->tx[head].buffer.packet.length = length;
+
+ /* setup tx dma */
+ status = (txStatusT *) sc->tx[head].status.addr;
+ status->status = 0;
+ sc->tx[head].inUse = true;
+ rtems_cache_flush_multiple_data_lines(status, sizeof(*status));
+
+ /* configure dma to stop after sending this packet */
+ sc->tx[head].status.dmaConfig = DMA_MODE_STATUS_LAST;
+ rtems_cache_flush_multiple_data_lines(
+ &sc->tx[head].status.dmaConfig,
+ sizeof(sc->tx[head].status.dmaConfig));
+ rtems_cache_flush_multiple_data_lines(
+ &sc->tx[head].buffer.packet,
+ length + sizeof(uint16_t));
+
+ /* modify previous descriptor to let it continue
+ automatically */
+ sc->tx[prevHead].status.dmaConfig = DMA_MODE_STATUS;
+ rtems_cache_flush_multiple_data_lines(
+ &sc->tx[prevHead].status.dmaConfig,
+ sizeof(sc->tx[prevHead].status.dmaConfig));
+
+ /* restart dma if it stopped before the packet we just
+ added. this is purely to reduce transmit latency,
+ as it would be restarted anyway after this loop (and
+ needs to be, as there's a very small chance that the
+ dma controller had started the last status transfer
+ before the new dmaConfig word was written above and
+ is still doing that status transfer when we check the
+ status below. this will be caught by the check
+ outside the loop as that is guaranteed to run at least
+ once after the last dma complete interrupt. */
+ if ((BFIN_REG16(txdmaBase, DMA_IRQ_STATUS_OFFSET) &
+ DMA_IRQ_STATUS_DMA_RUN) == 0 &&
+ BFIN_REG32(txdmaBase, DMA_NEXT_DESC_PTR_OFFSET) !=
+ (uint32_t) sc->tx[head].data.next) {
+ BFIN_REG16(txdmaBase, DMA_CONFIG_OFFSET) = DMA_MODE_TX;
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) |= EMAC_OPMODE_TE;
+ }
+
+ if (++head == sc->txDescCount)
+ head = 0;
+ if (++prevHead == sc->txDescCount)
+ prevHead = 0;
+
+ /* if no descriptors are available, try to free one */
+ if (sc->tx[head].inUse && txFree(sc, tail)) {
+ if (++tail == sc->txDescCount)
+ tail = 0;
+ }
+ } else {
+ /* dropping packet: too large */
+
+ }
+ } else {
+ /* no packets queued */
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+ }
+
+ /* if dma stopped and there's more to do, restart it */
+ if ((BFIN_REG16(txdmaBase, DMA_IRQ_STATUS_OFFSET) &
+ DMA_IRQ_STATUS_DMA_RUN) == 0 &&
+ BFIN_REG32(txdmaBase, DMA_NEXT_DESC_PTR_OFFSET) !=
+ (uint32_t) &sc->tx[head].data) {
+ BFIN_REG16(txdmaBase, DMA_CONFIG_OFFSET) = DMA_MODE_TX;
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) |= EMAC_OPMODE_TE;
+ }
+
+ /* free up any additional tx descriptors */
+ while (txFree(sc, tail)) {
+ if (++tail == sc->txDescCount)
+ tail = 0;
+ }
+ }
+}
+
+
+static void rxDaemon(void *arg) {
+ struct bfin_ethernetSoftc *sc;
+ struct ifnet *ifp;
+ struct mbuf *m;
+ struct mbuf *rxPacket;
+ void *dataPtr;
+ rtems_event_set events;
+ struct ether_header *eh;
+ rxStatusT *status;
+ uint32_t rxStatus;
+ int head;
+ int prevHead;
+ int length;
+ void *ethBase;
+ void *rxdmaBase;
+
+ sc = (struct bfin_ethernetSoftc *) arg;
+ rxdmaBase = sc->rxdmaBase;
+ ethBase = sc->ethBase;
+ ifp = &sc->arpcom.ac_if;
+ prevHead = sc->rxDescCount - 1;
+ head = 0;
+
+ BFIN_REG16(rxdmaBase, DMA_CONFIG_OFFSET) = DMA_MODE_RX;
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) |= EMAC_OPMODE_RE;
+
+ while (1) {
+ status = sc->rx[head].status.addr;
+ rtems_cache_invalidate_multiple_data_lines(status, sizeof(*status));
+ while (status->status != 0) {
+ if (status->status & EMAC_RX_STAT_RX_OK) {
+ /* get new cluster to replace this one */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ } else
+ m = NULL;
+
+ rxStatus = status->status;
+ /* update statistics */
+
+
+ if (m) {
+ /* save received packet to send up a little later */
+ rxPacket = sc->rx[head].m;
+ dataPtr = sc->rx[head].data.addr;
+
+ /* setup dma for new cluster */
+ sc->rx[head].m = m;
+ sc->rx[head].data.addr = (void *) (((intptr_t) m->m_data + 3) & ~3);
+ /* invalidate cache for new data buffer, in case any lines
+ are dirty from previous owner */
+ rtems_cache_invalidate_multiple_data_lines(
+ sc->rx[head].data.addr,
+ BFIN_ETHERNET_MAX_FRAME_LENGTH + 2);
+ } else
+ rxPacket = NULL;
+
+ sc->rx[head].status.dmaConfig = DMA_MODE_STATUS_LAST;
+ rtems_cache_flush_multiple_data_lines(&sc->rx[head],
+ sizeof(sc->rx[head]));
+
+ /* mark descriptor as empty */
+ status->status = 0;
+ rtems_cache_flush_multiple_data_lines(&status->status,
+ sizeof(status->status));
+
+ /* allow dma to continue from previous descriptor into this
+ one */
+ sc->rx[prevHead].status.dmaConfig = DMA_MODE_STATUS;
+ rtems_cache_flush_multiple_data_lines(
+ &sc->rx[prevHead].status.dmaConfig,
+ sizeof(sc->rx[prevHead].status.dmaConfig));
+
+ if (rxPacket) {
+ /* send it up */
+ eh = (struct ether_header *) ((intptr_t) dataPtr + 2);
+ rxPacket->m_data = (caddr_t) ((intptr_t) dataPtr + 2 + 14);
+ length = (rxStatus & EMAC_RX_STAT_RX_FRLEN_MASK) >>
+ EMAC_RX_STAT_RX_FRLEN_SHIFT;
+ rxPacket->m_len = length - 14;
+ rxPacket->m_pkthdr.len = rxPacket->m_len;
+ /* invalidate packet buffer cache again (even though it
+ was invalidated prior to giving it to dma engine),
+ because speculative reads might cause cache lines to
+ be filled at any time */
+ rtems_cache_invalidate_multiple_data_lines(eh, length);
+ ether_input(ifp, eh, rxPacket);
+ }
+
+ if (++prevHead == sc->rxDescCount)
+ prevHead = 0;
+ if (++head == sc->rxDescCount)
+ head = 0;
+ status = sc->rx[head].status.addr;
+ rtems_cache_invalidate_multiple_data_lines(status, sizeof(*status));
+ }
+
+ /* if dma stopped before the next descriptor, restart it */
+ if ((BFIN_REG16(rxdmaBase, DMA_IRQ_STATUS_OFFSET) &
+ DMA_IRQ_STATUS_DMA_RUN) == 0 &&
+ BFIN_REG32(rxdmaBase, DMA_NEXT_DESC_PTR_OFFSET) !=
+ (uint32_t) &sc->rx[head].data) {
+ BFIN_REG16(rxdmaBase, DMA_CONFIG_OFFSET) = DMA_MODE_RX;
+ }
+
+ rtems_bsdnet_event_receive(INTERRUPT_EVENT, RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT, &events);
+ }
+
+}
+
+/*
+ ******************************************************************
+ * *
+ * Initialization Routines *
+ * *
+ ******************************************************************
+ */
+
+static void resetHardware(struct bfin_ethernetSoftc *sc) {
+ void *ethBase;
+ void *rxdmaBase;
+ void *txdmaBase;
+
+ ethBase = sc->ethBase;
+ rxdmaBase = sc->rxdmaBase;
+ txdmaBase = sc->txdmaBase;
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) = 0;
+ BFIN_REG16(rxdmaBase, DMA_CONFIG_OFFSET) = 0;
+ BFIN_REG16(txdmaBase, DMA_CONFIG_OFFSET) = 0;
+}
+
+static void initializeHardware(struct bfin_ethernetSoftc *sc) {
+ struct ifnet *ifp;
+ struct mbuf *m;
+ unsigned char *hwaddr;
+ int cacheAlignment;
+ int rxStatusSize;
+ int txStatusSize;
+ char *ptr;
+ int i;
+ void *ethBase;
+ void *rxdmaBase;
+ void *txdmaBase;
+ uint32_t divisor;
+
+ ifp = &sc->arpcom.ac_if;
+ ethBase = sc->ethBase;
+ rxdmaBase = sc->rxdmaBase;
+ txdmaBase = sc->txdmaBase;
+
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) = 0;
+ BFIN_REG32(ethBase, EMAC_FLC_OFFSET) = 0;
+ divisor = (sc->sclk / 25000000) / 2 - 1;
+ BFIN_REG32(ethBase, EMAC_SYSCTL_OFFSET) = (divisor <<
+ EMAC_SYSCTL_MDCDIV_SHIFT) |
+ EMAC_SYSCTL_RXDWA;
+#ifdef BFIN_IPCHECKSUMS
+ BFIN_REG32(ethBase, EMAC_SYSCTL_OFFSET) |= EMAC_SYSCTL_RXCKS;
+#endif
+ BFIN_REG32(ethBase, EMAC_SYSTAT_OFFSET) = ~(uint32_t) 0;
+ BFIN_REG32(ethBase, EMAC_RX_IRQE_OFFSET) = 0;
+ BFIN_REG32(ethBase, EMAC_RX_STKY_OFFSET) = ~(uint32_t) 0;
+ BFIN_REG32(ethBase, EMAC_TX_IRQE_OFFSET) = 0;
+ BFIN_REG32(ethBase, EMAC_TX_STKY_OFFSET) = ~(uint32_t) 0;
+ BFIN_REG32(ethBase, EMAC_MMC_RIRQE_OFFSET) = 0;
+ BFIN_REG32(ethBase, EMAC_MMC_RIRQS_OFFSET) = ~(uint32_t) 0;
+ BFIN_REG32(ethBase, EMAC_MMC_TIRQE_OFFSET) = 0;
+ BFIN_REG32(ethBase, EMAC_MMC_TIRQS_OFFSET) = ~(uint32_t) 0;
+ BFIN_REG32(ethBase, EMAC_MMC_CTL_OFFSET) = EMAC_MMC_CTL_MMCE |
+ EMAC_MMC_CTL_CCOR |
+ EMAC_MMC_CTL_RSTC;
+ BFIN_REG32(ethBase, EMAC_MMC_CTL_OFFSET) = EMAC_MMC_CTL_MMCE |
+ EMAC_MMC_CTL_CCOR;
+
+ BFIN_REG16(rxdmaBase, DMA_CONFIG_OFFSET) = 0;
+ BFIN_REG16(txdmaBase, DMA_CONFIG_OFFSET) = 0;
+ BFIN_REG16(rxdmaBase, DMA_X_COUNT_OFFSET) = 0;
+ BFIN_REG16(txdmaBase, DMA_X_COUNT_OFFSET) = 0;
+ BFIN_REG16(rxdmaBase, DMA_X_MODIFY_OFFSET) = 4;
+ BFIN_REG16(txdmaBase, DMA_X_MODIFY_OFFSET) = 4;
+ BFIN_REG16(rxdmaBase, DMA_Y_COUNT_OFFSET) = 0;
+ BFIN_REG16(txdmaBase, DMA_Y_COUNT_OFFSET) = 0;
+ BFIN_REG16(rxdmaBase, DMA_Y_MODIFY_OFFSET) = 0;
+ BFIN_REG16(txdmaBase, DMA_Y_MODIFY_OFFSET) = 0;
+ BFIN_REG16(rxdmaBase, DMA_IRQ_STATUS_OFFSET) = DMA_IRQ_STATUS_DMA_ERR |
+ DMA_IRQ_STATUS_DMA_DONE;
+
+ /* The status structures cannot share cache lines with anything else,
+ including other status structures, so we can safely manage both the
+ processor and DMA writing to them. So this rounds up the structure
+ sizes to a multiple of the cache line size. */
+ cacheAlignment = (int) rtems_cache_get_data_line_size();
+ if (cacheAlignment == 0)
+ cacheAlignment = 1;
+ rxStatusSize = cacheAlignment * ((sizeof(rxStatusT) + cacheAlignment - 1) /
+ cacheAlignment);
+ txStatusSize = cacheAlignment * ((sizeof(txStatusT) + cacheAlignment - 1) /
+ cacheAlignment);
+ /* Allocate enough extra to allow structures to start at cache aligned
+ boundary. */
+ sc->status = malloc(sc->rxDescCount * rxStatusSize +
+ sc->txDescCount * txStatusSize +
+ cacheAlignment - 1, M_DEVBUF, M_NOWAIT);
+ sc->rx = malloc(sc->rxDescCount * sizeof(*sc->rx), M_DEVBUF, M_NOWAIT);
+ sc->tx = malloc(sc->txDescCount * sizeof(*sc->tx), M_DEVBUF, M_NOWAIT);
+ if (sc->status == NULL || sc->rx == NULL || sc->tx == NULL)
+ rtems_panic("No memory!\n");
+
+ /* Start status structures at cache aligned boundary. */
+ ptr = (char *) (((intptr_t) sc->status + cacheAlignment - 1) &
+ ~(cacheAlignment - 1));
+ memset(ptr, 0, sc->rxDescCount * rxStatusSize +
+ sc->txDescCount * txStatusSize);
+ memset(sc->rx, 0, sc->rxDescCount * sizeof(*sc->rx));
+ memset(sc->tx, 0, sc->txDescCount * sizeof(*sc->tx));
+ rtems_cache_flush_multiple_data_lines(ptr, sc->rxDescCount * rxStatusSize +
+ sc->txDescCount * txStatusSize);
+ for (i = 0; i < sc->rxDescCount; i++) {
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rx[i].m = m;
+ /* start dma at 32 bit boundary */
+ sc->rx[i].data.addr = (void *) (((intptr_t) m->m_data + 3) & ~3);
+ rtems_cache_invalidate_multiple_data_lines(
+ sc->rx[i].data.addr,
+ BFIN_ETHERNET_MAX_FRAME_LENGTH + 2);
+ sc->rx[i].data.dmaConfig = DMA_MODE_RX;
+ sc->rx[i].data.next = &(sc->rx[i].status);
+ sc->rx[i].status.addr = ptr;
+ if (i < sc->rxDescCount - 1) {
+ sc->rx[i].status.dmaConfig = DMA_MODE_STATUS;
+ sc->rx[i].status.next = &(sc->rx[i + 1].data);
+ } else {
+ sc->rx[i].status.dmaConfig = DMA_MODE_STATUS_LAST;
+ sc->rx[i].status.next = &(sc->rx[0].data);
+ }
+ ptr += rxStatusSize;
+ }
+ rtems_cache_flush_multiple_data_lines(sc->rx, sc->rxDescCount *
+ sizeof(*sc->rx));
+ for (i = 0; i < sc->txDescCount; i++) {
+ sc->tx[i].data.addr = &sc->tx[i].buffer.packet;
+ sc->tx[i].data.dmaConfig = DMA_MODE_TX;
+ sc->tx[i].data.next = &(sc->tx[i].status);
+ sc->tx[i].status.addr = ptr;
+ sc->tx[i].status.dmaConfig = DMA_MODE_STATUS_LAST;
+ if (i < sc->txDescCount - 1)
+ sc->tx[i].status.next = &(sc->tx[i + 1].data);
+ else
+ sc->tx[i].status.next = &(sc->tx[0].data);
+ sc->tx[i].inUse = false;
+ ptr += txStatusSize;
+ }
+ rtems_cache_flush_multiple_data_lines(sc->tx, sc->txDescCount *
+ sizeof(*sc->tx));
+
+ BFIN_REG32(rxdmaBase, DMA_NEXT_DESC_PTR_OFFSET) = (uint32_t) &sc->rx[0].data;
+ BFIN_REG32(txdmaBase, DMA_NEXT_DESC_PTR_OFFSET) = (uint32_t) &sc->tx[0].data;
+
+ hwaddr = sc->arpcom.ac_enaddr;
+ BFIN_REG16(ethBase, EMAC_ADDRHI_OFFSET) = ((uint16_t) hwaddr[5] << 8) |
+ hwaddr[4];
+ BFIN_REG32(ethBase, EMAC_ADDRLO_OFFSET) = ((uint32_t) hwaddr[3] << 24) |
+ ((uint32_t) hwaddr[2] << 16) |
+ ((uint32_t) hwaddr[1] << 8) |
+ hwaddr[0];
+
+ if (sc->acceptBroadcast)
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) &= ~EMAC_OPMODE_DBF;
+ else
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) |= EMAC_OPMODE_DBF;
+
+}
+
+/* send packet (caller provides header) */
+static void ethernetStart(struct ifnet *ifp) {
+ struct bfin_ethernetSoftc *sc;
+
+ sc = ifp->if_softc;
+
+ ifp->if_flags |= IFF_OACTIVE;
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+}
+
+/* initialize and start the device */
+static void ethernetInit(void *arg) {
+ struct bfin_ethernetSoftc *sc;
+ struct ifnet *ifp;
+ void *ethBase;
+
+ sc = arg;
+ ifp = &sc->arpcom.ac_if;
+ ethBase = sc->ethBase;
+
+ if (sc->txDaemonTid == 0) {
+ initializeHardware(sc);
+
+ /* start driver tasks */
+ sc->rxDaemonTid = rtems_bsdnet_newproc("BFrx", 4096, rxDaemon, sc);
+ sc->txDaemonTid = rtems_bsdnet_newproc("BFtx", 4096, txDaemon, sc);
+
+ }
+
+ if (ifp->if_flags & IFF_PROMISC)
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) |= EMAC_OPMODE_PR;
+ else
+ BFIN_REG32(ethBase, EMAC_OPMODE_OFFSET) &= ~EMAC_OPMODE_PR;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+}
+
+/* driver ioctl handler */
+static int ethernetIoctl(struct ifnet *ifp, ioctl_command_t command,
+ caddr_t data) {
+ int result;
+ struct bfin_ethernetSoftc *sc = ifp->if_softc;
+
+ result = 0;
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ ethernetStop(sc);
+ break;
+ case IFF_UP:
+ ethernetInit(sc);
+ break;
+ case IFF_UP | IFF_RUNNING:
+ ethernetStop(sc);
+ ethernetInit(sc);
+ break;
+ default:
+ break;
+ }
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ bfin_ethernetStats(sc);
+ break;
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ default:
+ result = EINVAL;
+ break;
+ }
+
+ return result;
+}
+
+/* attach a BFIN ETHERNET driver to the system */
+int bfin_ethernet_driver_attach(struct rtems_bsdnet_ifconfig *config,
+ int attaching,
+ bfin_ethernet_configuration_t *chip) {
+ struct bfin_ethernetSoftc *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+
+ if ((unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0)
+ return 0;
+
+ if ((unitNumber <= 0) || (unitNumber > N_BFIN_ETHERNET)) {
+ printf("Bad bfin ethernet unit number %d.\n", unitNumber);
+ return 0;
+ }
+ sc = &ethernetSoftc[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf("Driver already in use.\n");
+ return 0;
+ }
+
+ memset(sc, 0, sizeof(*sc));
+
+ /* process options */
+ if (config->hardware_address)
+ memcpy(sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ else
+ memset(sc->arpcom.ac_enaddr, 0x08, ETHER_ADDR_LEN);
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxDescCount = config->rbuf_count;
+ else
+ sc->rxDescCount = chip->rxDescCount;
+ if (config->xbuf_count)
+ sc->txDescCount = config->xbuf_count;
+ else
+ sc->txDescCount = chip->txDescCount;
+ /* minimum two of each type descriptor */
+ if (sc->rxDescCount <= 1)
+ sc->rxDescCount = 2;
+ if (sc->txDescCount <= 1)
+ sc->txDescCount = 2;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ sc->sclk = chip->sclk;
+ sc->ethBase = chip->ethBaseAddress;
+ sc->rxdmaBase = chip->rxdmaBaseAddress;
+ sc->txdmaBase = chip->txdmaBaseAddress;
+
+ /* make sure we should not have any interrupts asserted */
+ resetHardware(sc);
+
+ sc->rmii = (chip->phyType == rmii);
+ sc->phyAddr = chip->phyAddr;
+
+ /* set up network interface values */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = ethernetInit;
+ ifp->if_ioctl = ethernetIoctl;
+ ifp->if_start = ethernetStart;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ return 1;
+}
+
diff --git a/bsps/bfin/bf537Stamp/net/networkconfig.c b/bsps/bfin/bf537Stamp/net/networkconfig.c
new file mode 100644
index 0000000..85655b3
--- /dev/null
+++ b/bsps/bfin/bf537Stamp/net/networkconfig.c
@@ -0,0 +1,69 @@
+/* networkconfig.c
+ *
+ * This file contains the network driver attach function and configuration
+ * for the bf537Stamp.
+ *
+ * Copyright (c) 2008 Kallisti Labs, Los Gatos, CA, USA
+ * written by Allan Hessenflow <allanh@kallisti.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <rtems/rtems_bsdnet.h>
+#include <libcpu/interrupt.h>
+#include <libcpu/ethernet.h>
+
+
+static bfin_ethernet_configuration_t ethConfig = {
+ SCLK,
+ (void *) EMAC_BASE_ADDRESS,
+ (void *) DMA1_BASE_ADDRESS, /* ethernet receive */
+ (void *) DMA2_BASE_ADDRESS, /* ethernet transmit */
+ 16, /* receive descriptors */
+ 16, /* transmit descriptors */
+ mii, /* phy type */
+ 1 /* phy address */
+};
+
+static bfin_isr_t ethISRs[] = {
+ /* careful - shared with a bunch of things */
+/*
+ {SIC_MAC_ERROR_VECTOR,
+ bfin_ethernet_mac_isr,
+ 0,
+ 0,
+ NULL},
+*/
+ /* careful - shared with porth irqa */
+ {SIC_DMA1_MAC_RX_VECTOR,
+ bfin_ethernet_rxdma_isr,
+ 0,
+ 0,
+ NULL},
+ /* careful - shared with porth irqb */
+ {SIC_DMA2_MAC_TX_VECTOR,
+ bfin_ethernet_txdma_isr,
+ 0,
+ 0,
+ NULL}
+};
+
+int bf537Stamp_network_driver_attach(struct rtems_bsdnet_ifconfig *config,
+ int attaching) {
+ int result;
+ int i;
+
+ result = bfin_ethernet_driver_attach(config, attaching, &ethConfig);
+ for (i = 0; i < sizeof(ethISRs) / sizeof(ethISRs[0]); i++) {
+ bfin_interrupt_register(&ethISRs[i]);
+ bfin_interrupt_enable(&ethISRs[i], TRUE);
+ }
+
+ return result;
+}
+
diff --git a/bsps/i386/pc386/net/3c509.c b/bsps/i386/pc386/net/3c509.c
new file mode 100644
index 0000000..b30ad03
--- /dev/null
+++ b/bsps/i386/pc386/net/3c509.c
@@ -0,0 +1,1538 @@
+/*
+ * Ported by Rosimildo da Silva.
+ * ConnectTel,Inc.
+ * e-mail: rdasilva@connecttel.com
+ *
+ * MODULE DESCRIPTION:
+ * RTEMS driver for 3COM 3C509 Ethernet Card.
+ * The driver has been tested on PC with a single network card.
+ *
+ *
+ * This driver was based on the FreeBSD implementation( if_ep.c ) of the 3c5x9
+ * family and on the network framework of the RTEMS network driver.
+ * ( WD80x3 by Eric Norum ).
+ * See notes below:
+ *
+ ******************************************************************************
+ * Copyright (c) 1994 Herb Peyerl <hpeyerl@novatel.ca>
+ * 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed by Herb Peyerl.
+ * 4. The name of Herb Peyerl may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR 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.
+ *
+ *******************************************************************************
+ *
+ * RTEMS driver for M68360 WD1 Ethernet
+ *
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+
+#include <stdio.h>
+#include <stdarg.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <assert.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/libkern.h>
+
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <bsp/irq.h>
+
+/* Local includes */
+#include "3c509.h"
+#include "elink.h"
+
+/* #define ET_MINLEN 60 */ /* minimum message length */
+
+/*
+ * Number of WDs supported by this driver
+ */
+#define NWDDRIVER 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+/*
+#define RX_BUF_COUNT 15
+#define TX_BUF_COUNT 4
+#define TX_BD_PER_BUF 4
+*/
+
+/*
+ * RTEMS event used by interrupt handler to signal driver tasks.
+ * This must not be any of the events used by the network task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet including CRC
+ */
+
+/*
+#define RBUF_SIZE 1520
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+*/
+
+/* network driver name */
+#define NET_DRIVER_NAME "ep"
+
+/*
+ * Per device structure.
+ *
+ * XXX Note: id_conflicts should either become an array of things we're
+ * specifically allowed to conflict with or be subsumed into some
+ * more powerful mechanism for detecting and dealing with multiple types
+ * of non-fatal conflict. -jkh XXX
+ */
+struct isa_device
+{
+ int id_id; /* device id */
+ int id_unit; /* unit number */
+ int id_iobase; /* base i/o address */
+ u_int id_irq; /* interrupt request */
+};
+
+struct ep_board
+{
+ int epb_addr; /* address of this board */
+ char epb_used; /* was this entry already used for configuring ? */
+ /* data from EEPROM for later use */
+ u_short eth_addr[3]; /* Ethernet address */
+ u_short prod_id; /* product ID */
+ u_short res_cfg; /* resource configuration */
+};
+
+/*
+ * Ethernet software status per interface.
+ */
+struct ep_softc
+{
+ struct arpcom arpcom; /* Ethernet common part */
+ int ep_io_addr; /* i/o bus address */
+ struct mbuf *top, *mcur;
+ short cur_len;
+ u_short ep_connectors; /* Connectors on this card. */
+ u_char ep_connector; /* Configured connector. */
+ int stat; /* some flags */
+ struct ep_board *epb;
+ int unit;
+
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+ rtems_vector_number name;
+
+ int acceptBroadcast;
+
+ short tx_underrun;
+ short rx_no_first;
+ short rx_no_mbuf;
+ short rx_bpf_disc;
+ short rx_overrunf;
+ short rx_overrunl;
+};
+
+/* static unsigned long loopc; */
+static volatile unsigned long overrun;
+static volatile unsigned long resend;
+static struct ep_softc ep_softc[ NWDDRIVER ];
+static struct isa_device isa_dev[ NWDDRIVER ] =
+{
+ { 0, /* device id */
+ 0, /* unit number */
+ -1, /* base i/o address ??? */
+ 0 /* interrupt request ??? */
+ }
+};
+
+static u_long ep_unit;
+static int ep_boards;
+struct ep_board ep_board[ EP_MAX_BOARDS + 1];
+static int ep_current_tag = EP_LAST_TAG + 1;
+static char *ep_conn_type[] = {"UTP", "AUI", "???", "BNC"};
+
+#define ep_ftst(f) (sc->stat&(f))
+#define ep_fset(f) (sc->stat|=(f))
+#define ep_frst(f) (sc->stat&=~(f))
+
+/* forward declarations for functions */
+static int ep_attach( struct ep_softc *sc );
+static int ep_isa_probe( struct isa_device *is );
+static void epinit( struct ep_softc *sc );
+static void epread( register struct ep_softc *sc );
+static void epstart( struct ifnet *ifp );
+static void epread( register struct ep_softc *sc );
+static int ep_isa_attach( struct isa_device *is );
+static int get_eeprom_data( int id_port, int offset );
+static void ep_intr( struct ep_softc *sc );
+
+/* external functions */
+extern void Wait_X_ms( unsigned int timeToWait ); /* timer.c ??? */
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Writes a buffer of data to the I/O port. The data is sent to the
+ * port as 32 bits units( 4 bytes ).
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static __inline void outsl( unsigned short io_addr, uint8_t *out_data, int len )
+{
+ u_long *pl = ( u_long *)out_data;
+ while( len-- )
+ {
+ outport_long( io_addr, *pl );
+ pl++;
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Writes a buffer of data to the I/O port. The data is sent to the
+ * port as 16 bits units( 2 bytes ).
+ *
+ * RETURNS:
+ *
+ **********************************************************************************/
+static __inline void outsw( unsigned short io_addr, uint8_t *out_data, int len )
+{
+ u_short *ps = ( u_short *)out_data;
+ while( len-- )
+ {
+ outport_word( io_addr, *ps );
+ ps++;
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Writes a buffer of data to the I/O port. The data is sent to the
+ * port as 8 bits units( 1 byte ).
+ *
+ * RETURNS: nothing
+ *
+ **********************************************************************************/
+static __inline void outsb( unsigned short io_addr, uint8_t *out_data, int len )
+{
+ while( len-- )
+ {
+ outport_byte( io_addr, *out_data );
+ out_data++;
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Read a buffer of data from an I/O port. The data is read as 16 bits
+ * units or 2 bytes.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static __inline void insw( unsigned short io_addr, uint8_t *in_data, int len )
+{
+ u_short *ps = ( u_short *)in_data;
+ while( len-- )
+ {
+ inport_word( io_addr, *ps );
+ ps++;
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Read a buffer of data from an I/O port. The data is read as 32 bits
+ * units or 4 bytes.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static __inline void insl( unsigned short io_addr, uint8_t *in_data, int len )
+{
+ u_long *pl = ( u_long *)in_data;
+ while( len-- )
+ {
+ inport_long( io_addr, *pl );
+ pl++;
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Read a buffer of data from an I/O port. The data is read as 8 bits
+ * units or 1 bytes.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static __inline void insb( unsigned short io_addr, uint8_t *in_data, int len )
+{
+ while( len-- )
+ {
+ inport_byte( io_addr, *in_data++ );
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Writes a word to the I/O port.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+/*
+ * Routine to output a word as defined in FreeBSD.
+ */
+static __inline void outw( unsigned short io_addr, unsigned short out_data )
+{
+ outport_word( io_addr, out_data );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Routine to read a word as defined in FreeBSD.
+ *
+ * RETURNS: nothing
+ *
+ **********************************************************************************/
+static __inline unsigned short inw( unsigned short io_addr )
+{
+ unsigned short in_data;
+ inport_word( io_addr, in_data );
+ return in_data;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Routine to output a word as defined in FreeBSD.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static __inline void outb( unsigned short io_addr, uint8_t out_data )
+{
+ outport_byte( io_addr, out_data );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Routine to read a word as defined in FreeBSD.
+ *
+ * RETURNS: byte read.
+ *
+ **********************************************************************************/
+static __inline uint8_t inb( unsigned short io_addr )
+{
+ uint8_t in_data;
+ inport_byte( io_addr, in_data );
+ return in_data;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * We get eeprom data from the id_port given an offset into the eeprom.
+ * Basically; after the ID_sequence is sent to all of the cards; they enter
+ * the ID_CMD state where they will accept command requests. 0x80-0xbf loads
+ * the eeprom data. We then read the port 16 times and with every read; the
+ * cards check for contention (ie: if one card writes a 0 bit and another
+ * writes a 1 bit then the host sees a 0. At the end of the cycle; each card
+ * compares the data on the bus; if there is a difference then that card goes
+ * into ID_WAIT state again). In the meantime; one bit of data is returned in
+ * the AX register which is conveniently returned to us by inb(). Hence; we
+ * read 16 times getting one bit of data with each read.
+ *
+ * RETURNS: 16 bit word from the EEPROM
+ *
+ **********************************************************************************/
+static int get_eeprom_data( int id_port, int offset )
+{
+ int i, data = 0;
+ outb(id_port, 0x80 + offset);
+ Wait_X_ms( 1 );
+ for (i = 0; i < 16; i++)
+ data = (data << 1) | (inw(id_port) & 1);
+ return( data );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * Driver interrupt handler. This routine is called by the RTEMS kernel when this
+ * interrupt is raised.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static rtems_isr ap_interrupt_handler(void *arg)
+{
+ struct ep_softc *sc = (struct ep_softc *)arg;
+
+ /* de-activate any pending interrrupt, and sent and event to interrupt task
+ * to process all events required by this interrupt.
+ */
+ outw( BASE + EP_COMMAND, SET_INTR_MASK ); /* disable all Ints */
+ rtems_bsdnet_event_send( sc->rxDaemonTid, INTERRUPT_EVENT );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * Initializes the ethernet hardware.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void _3c509_initialize_hardware (struct ep_softc *sc)
+{
+ rtems_status_code status;
+
+ epinit( sc );
+
+ /*
+ * Set up interrupts
+ */
+ printf ("3c509: IRQ with Kernel: %d\n", (int)sc->name );
+ status = rtems_interrupt_handler_install(
+ sc->name,
+ "3c509",
+ RTEMS_INTERRUPT_UNIQUE,
+ ap_interrupt_handler,
+ sc
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Driver interrupt daemon.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void _3c509_rxDaemon (void *arg)
+{
+ struct ep_softc *dp = (struct ep_softc *)&ep_softc[ 0 ];
+ rtems_event_set events;
+
+ printf ("3C509: RX Daemon is starting.\n");
+ for( ;; )
+ {
+ /* printk( "R-" ); */
+ rtems_bsdnet_event_receive( INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events );
+ /* printk( "R+" ); */
+ ep_intr( dp );
+ epstart( &dp->arpcom.ac_if );
+ }
+ printf ("3C509: RX Daemon is finishing.\n");
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Driver transmit daemon
+ *
+ * RETURNS:
+ *
+ **********************************************************************************/
+static void _3c509_txDaemon (void *arg)
+{
+ struct ep_softc *sc = (struct ep_softc *)&ep_softc[0];
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ rtems_event_set events;
+
+ printf ("3C509: TX Daemon is starting.\n");
+ for( ;; )
+ {
+ /*
+ * Wait for packet
+ */
+ /* printk( "T-\n" ); */
+ rtems_bsdnet_event_receive( START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events );
+ /* printk( "T+\n" ); */
+ epstart( ifp );
+ while( ifp->if_flags & IFF_OACTIVE )
+ epstart( ifp );
+ }
+ printf ("3C509: TX Daemon is finishing.\n");
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Activates the trabsmitter task...
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void _3c509_start (struct ifnet *ifp)
+{
+ struct ep_softc *sc = ifp->if_softc;
+ /* printk ("S"); */
+ ifp->if_flags |= IFF_OACTIVE;
+ rtems_bsdnet_event_send( sc->txDaemonTid, START_TRANSMIT_EVENT );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Initialize and start the device
+ *
+ * RETURNS:
+ *
+ **********************************************************************************/
+static void _3c509_init (void *arg)
+{
+ struct ep_softc *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ printf ("3C509: Initialization called.\n");
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up WD hardware
+ */
+ _3c509_initialize_hardware (sc);
+ printf ("3C509: starting network driver tasks..\n");
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("APtx", 4096, _3c509_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("APrx", 4096, _3c509_rxDaemon, sc);
+ }
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Stop the device
+ *
+ * RETURNS:
+ *
+ **********************************************************************************/
+static void _3c509_stop (struct ep_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ printf ("3C509: stop() called.\n");
+ /*
+ * Stop the transmitter
+ */
+ outw(BASE + EP_COMMAND, RX_DISABLE);
+ outw(BASE + EP_COMMAND, RX_DISCARD_TOP_PACK);
+ while (inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS);
+ outw(BASE + EP_COMMAND, TX_DISABLE);
+ outw(BASE + EP_COMMAND, STOP_TRANSCEIVER);
+ outw(BASE + EP_COMMAND, RX_RESET);
+ outw(BASE + EP_COMMAND, TX_RESET);
+ while (inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS);
+ outw(BASE + EP_COMMAND, C_INTR_LATCH);
+ outw(BASE + EP_COMMAND, SET_RD_0_MASK);
+ outw(BASE + EP_COMMAND, SET_INTR_MASK);
+ outw(BASE + EP_COMMAND, SET_RX_FILTER);
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Show interface statistics
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void _3c509_stats (struct ep_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ printf ("3C509: stats() called.\n");
+ printf("\tStat: %x\n", sc->stat);
+ printf("\tIpackets=%ld, Opackets=%ld\n", ifp->if_ipackets, ifp->if_opackets);
+ printf("\tNOF=%d, NOMB=%d, BPFD=%d, RXOF=%d, RXOL=%d, TXU=%d\n",
+ sc->rx_no_first, sc->rx_no_mbuf, sc->rx_bpf_disc, sc->rx_overrunf,
+ sc->rx_overrunl, sc->tx_underrun );
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Driver ioctl handler
+ *
+ * RETURNS:
+ *
+ **********************************************************************************/
+static int _3c509_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct ep_softc *sc = ifp->if_softc;
+ int error = 0;
+
+ printf ("3C509: ioctl() called.\n");
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ _3c509_stop (sc);
+ break;
+
+ case IFF_UP:
+ _3c509_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ _3c509_stop (sc);
+ _3c509_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ _3c509_stats( sc );
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * Attaches this network driver to the system. This function is called by the network
+ * interface during the initialization of the system.
+ *
+ * RETURNS: - 1 - success; 0 - fail to initialize
+ *
+ **********************************************************************************/
+int rtems_3c509_driver_attach (struct rtems_bsdnet_ifconfig *config )
+{
+ struct ep_softc *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int i;
+
+ printf ("3C509: attach() called.\n");
+
+ /*
+ * init some variables
+ */
+ overrun = 0;
+ resend = 0;
+ ep_unit = 0;
+ ep_boards = 0;
+
+ /*
+ * Find a free driver
+ */
+ for (i = 0 ; i < NWDDRIVER ; i++) {
+ sc = &ep_softc[i];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc == NULL)
+ break;
+ }
+ if (i >= NWDDRIVER)
+ {
+ printf ("Too many 3C509 drivers.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if( config->hardware_address )
+ {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+ else
+ {
+ /* set it to something ... */
+ memset (sc->arpcom.ac_enaddr, 0x08,ETHER_ADDR_LEN);
+ }
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ if (config->irno)
+ sc->name = config->irno;
+ else
+ sc->name = 10;
+
+ if (config->port)
+ sc->ep_io_addr = config->port;
+ else
+ sc->ep_io_addr = 0x300;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ printf ("3C509: isa_probe() looking for a card...\n");
+ if( !ep_isa_probe( &isa_dev[ 0 ] ) )
+ {
+ printf ("3C509: isa_probe() fail to find a board.\n");
+ return 0;
+ }
+
+ /* A board has been found, so proceed with the installation of the driver */
+ ep_isa_attach( &isa_dev[ 0 ] );
+ /*
+ * Set up network interface values
+ */
+
+ ifp->if_softc = sc;
+ ifp->if_unit = i;
+ ifp->if_name = NET_DRIVER_NAME;
+ ifp->if_mtu = mtu;
+ ifp->if_init = _3c509_init;
+ ifp->if_ioctl = _3c509_ioctl;
+ ifp->if_start = _3c509_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+ if( ifp->if_snd.ifq_maxlen == 0 )
+ {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ printf ("3C509: attach() is complete.\n");
+ return 1;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * This function looks for a 3COM card 3c5x9 in an isa bus. If a board is found, it
+ * returns a structure describing the caracteristics of the card. It returns zero when
+ * card can not be found.
+ *
+ * RETURNS: 0 - fail - could not find a card...
+ * <> description of the card.
+ *
+ **********************************************************************************/
+static struct ep_board *ep_look_for_board_at( struct isa_device *is )
+{
+ int data, i, j, id_port = ELINK_ID_PORT;
+ int count = 0;
+
+ if(ep_current_tag == (EP_LAST_TAG + 1) )
+ {
+ /* Come here just one time */
+ ep_current_tag--;
+
+ /* Look for the ISA boards. Init and leave them actived */
+ outb(id_port, 0);
+ outb(id_port, 0);
+
+ elink_idseq(0xCF);
+ elink_reset();
+ Wait_X_ms( 10 ); /* RPS: assuming delay in miliseconds */
+ for (i = 0; i < EP_MAX_BOARDS; i++)
+ {
+ outb(id_port, 0);
+ outb(id_port, 0);
+ elink_idseq(0xCF);
+
+ data = get_eeprom_data(id_port, EEPROM_MFG_ID);
+ if (data != MFG_ID)
+ break;
+
+ /* resolve contention using the Ethernet address */
+ for (j = 0; j < 3; j++)
+ get_eeprom_data(id_port, j);
+
+ /* and save this address for later use */
+
+ for (j = 0; j < 3; j++)
+ ep_board[ep_boards].eth_addr[j] = get_eeprom_data(id_port, j);
+
+ ep_board[ep_boards].res_cfg = get_eeprom_data(id_port, EEPROM_RESOURCE_CFG);
+ ep_board[ep_boards].prod_id = get_eeprom_data(id_port, EEPROM_PROD_ID);
+ ep_board[ep_boards].epb_used = 0;
+#ifdef PC98
+ ep_board[ep_boards].epb_addr =
+ (get_eeprom_data(id_port, EEPROM_ADDR_CFG) & 0x1f) * 0x100 + 0x40d0;
+#else
+ ep_board[ep_boards].epb_addr =
+ (get_eeprom_data(id_port, EEPROM_ADDR_CFG) & 0x1f) * 0x10 + 0x200;
+ if (ep_board[ep_boards].epb_addr > 0x3E0)
+ /* Board in EISA configuration mode */
+ continue;
+#endif /* PC98 */
+
+ outb(id_port, ep_current_tag); /* tags board */
+ outb(id_port, ACTIVATE_ADAPTER_TO_CONFIG);
+ ep_boards++;
+ count++;
+ ep_current_tag--;
+ }
+ ep_board[ep_boards].epb_addr = 0;
+ if( count )
+ {
+ printf("%d 3C5x9 board(s) on ISA found at", count);
+ for (j = 0; ep_board[j].epb_addr; j++)
+ if( ep_board[j].epb_addr <= 0x3E0 )
+ printf(" 0x%x", ep_board[j].epb_addr );
+ printf("\n");
+ }
+ }
+
+ /* we have two cases:
+ *
+ * 1. Device was configured with 'port ?'
+ * In this case we search for the first unused card in list
+ *
+ * 2. Device was configured with 'port xxx'
+ * In this case we search for the unused card with that address
+ *
+ */
+
+ if (IS_BASE == -1)
+ { /* port? */
+ for (i = 0; ep_board[i].epb_addr && ep_board[i].epb_used; i++) ;
+ if (ep_board[i].epb_addr == 0)
+ return 0;
+
+ IS_BASE = ep_board[i].epb_addr;
+ ep_board[i].epb_used = 1;
+ return &ep_board[ i ];
+ }
+ else
+ {
+ for (i = 0; ep_board[i].epb_addr && ep_board[i].epb_addr != IS_BASE; i++ ) ;
+ if (ep_board[i].epb_used || ep_board[i].epb_addr != IS_BASE)
+ return 0;
+ if (inw(IS_BASE + EP_W0_EEPROM_COMMAND) & EEPROM_TST_MODE)
+ {
+ printf("ep%d: 3c5x9 at 0x%x in PnP mode. Disable PnP mode!\n",
+ is->id_unit, IS_BASE );
+ }
+ ep_board[i].epb_used = 1;
+ return &ep_board[i];
+ }
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * This routine checks if there card installed on the machine.
+ *
+ * RETURNS: 0 - no card founded.
+ * 16 - size of the IO range for the card.
+ *
+ **********************************************************************************/
+static int ep_isa_probe( struct isa_device *is )
+{
+ struct ep_softc *sc;
+ struct ep_board *epb;
+ u_short k;
+
+ /* try to find a 3COM 3c5x9 .... */
+ if( (epb = ep_look_for_board_at(is)) == 0 )
+ return (0);
+
+ sc = &ep_softc[ 0 ];
+ sc->ep_io_addr = epb->epb_addr;
+ sc->epb = epb;
+
+ /*
+ * The iobase was found and MFG_ID was 0x6d50. PROD_ID should be
+ * 0x9[0-f]50 (IBM-PC)
+ * 0x9[0-f]5[0-f] (PC-98)
+ */
+ GO_WINDOW(0);
+ k = sc->epb->prod_id;
+#ifdef PC98
+ if ((k & 0xf0f0) != (PROD_ID & 0xf0f0))
+ {
+#else
+ if ((k & 0xf0ff) != (PROD_ID & 0xf0ff))
+ {
+#endif
+ printf("ep_isa_probe: ignoring model %04x\n", k );
+/* ep_unit--; */
+ return (0);
+ }
+ k = sc->epb->res_cfg;
+ k >>= 12;
+
+ /* Now we have two cases again:
+ *
+ * 1. Device was configured with 'irq?'
+ * In this case we use irq read from the board
+ *
+ * 2. Device was configured with 'irq xxx'
+ * In this case we set up the board to use specified interrupt
+ *
+ */
+
+ if (is->id_irq == 0)
+ { /* irq? */
+ is->id_irq = ( k == 2 ) ? 9 : k;
+ }
+
+ sc->stat = 0; /* 16 bit access */
+
+ /* By now, the adapter is already activated */
+
+ return (EP_IOSIZE); /* 16 bytes of I/O space used. */
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * This routine attaches this network driver and the network interface routines.
+ *
+ * RETURNS: 0 - failed to attach
+ * 1 - success
+ *
+ **********************************************************************************/
+static int ep_isa_attach( struct isa_device *is )
+{
+ struct ep_softc *sc = &ep_softc[ 0 ];
+ u_short config;
+ int irq;
+
+ sc->ep_connectors = 0;
+ config = inw( IS_BASE + EP_W0_CONFIG_CTRL );
+ if (config & IS_AUI)
+ {
+ sc->ep_connectors |= AUI;
+ }
+ if (config & IS_BNC)
+ {
+ sc->ep_connectors |= BNC;
+ }
+ if (config & IS_UTP)
+ {
+ sc->ep_connectors |= UTP;
+ }
+ if( !(sc->ep_connectors & 7) )
+ printf( "no connectors!" );
+ sc->ep_connector = inw(BASE + EP_W0_ADDRESS_CFG) >> ACF_CONNECTOR_BITS;
+
+ /*
+ * Write IRQ value to board
+ */
+
+ irq = is->id_irq;
+ /* update the interrupt line number to registered with kernel */
+ sc->name = irq;
+
+ GO_WINDOW( 0 );
+ SET_IRQ( BASE, irq );
+
+ printf( "3C509: I/O=0x%x, IRQ=%d, CONNECTOR=%s, ",
+ sc->ep_io_addr, (int)sc->name,ep_conn_type[ sc->ep_connector ] );
+
+ ep_attach( sc );
+ return 1;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Completes the initialization/attachement of the driver.
+ *
+ * RETURNS: 0 - ok.
+ *
+ **********************************************************************************/
+static int ep_attach( struct ep_softc *sc )
+{
+ u_short *p;
+ int i;
+
+ /*
+ * Setup the station address
+ */
+ p = (u_short *) &sc->arpcom.ac_enaddr;
+ GO_WINDOW(2);
+ printf("ADDRESS=" );
+ for (i = 0; i < 3; i++)
+ {
+ p[i] = htons( sc->epb->eth_addr[i] );
+ outw( BASE + EP_W2_ADDR_0 + (i * 2), ntohs( p[i] ) );
+ printf("%04x ", (u_short)ntohs( p[i] ) );
+ }
+ printf("\n" );
+
+ sc->rx_no_first = sc->rx_no_mbuf =
+ sc->rx_bpf_disc = sc->rx_overrunf = sc->rx_overrunl =
+ sc->tx_underrun = 0;
+
+ ep_fset( F_RX_FIRST );
+ sc->top = sc->mcur = 0;
+ return 0;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * Initializes the card.
+ * The order in here seems important. Otherwise we may not receive interrupts. ?!
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void epinit( struct ep_softc *sc )
+{
+ register struct ifnet *ifp = &sc->arpcom.ac_if;
+ int i, j;
+
+ while( inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS ) ;
+ GO_WINDOW(0);
+ outw(BASE + EP_COMMAND, STOP_TRANSCEIVER);
+ GO_WINDOW(4);
+ outw(BASE + EP_W4_MEDIA_TYPE, DISABLE_UTP);
+ GO_WINDOW(0);
+
+ /* Disable the card */
+ outw(BASE + EP_W0_CONFIG_CTRL, 0);
+
+ /* Enable the card */
+ outw(BASE + EP_W0_CONFIG_CTRL, ENABLE_DRQ_IRQ);
+
+ GO_WINDOW(2);
+
+ /* Reload the ether_addr. */
+ for (i = 0; i < 6; i++)
+ outb(BASE + EP_W2_ADDR_0 + i, sc->arpcom.ac_enaddr[i]);
+
+ outw(BASE + EP_COMMAND, RX_RESET);
+ outw(BASE + EP_COMMAND, TX_RESET);
+ while (inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS);
+
+ /* Window 1 is operating window */
+ GO_WINDOW(1);
+ for (i = 0; i < 31; i++)
+ inb(BASE + EP_W1_TX_STATUS);
+
+ /* get rid of stray intr's */
+ outw(BASE + EP_COMMAND, ACK_INTR | 0xff);
+
+ outw(BASE + EP_COMMAND, SET_RD_0_MASK | S_5_INTS);
+
+ outw(BASE + EP_COMMAND, SET_INTR_MASK | S_5_INTS);
+
+ if (ifp->if_flags & IFF_PROMISC)
+ outw(BASE + EP_COMMAND, SET_RX_FILTER | FIL_INDIVIDUAL |
+ FIL_GROUP | FIL_BRDCST | FIL_ALL);
+ else
+ outw(BASE + EP_COMMAND, SET_RX_FILTER | FIL_INDIVIDUAL | FIL_GROUP | FIL_BRDCST);
+
+ /*
+ * S.B.
+ *
+ * Now behavior was slightly changed:
+ *
+ * if any of flags link[0-2] is used and its connector is
+ * physically present the following connectors are used:
+ *
+ * link0 - AUI * highest precedence
+ * link1 - BNC
+ * link2 - UTP * lowest precedence
+ *
+ * If none of them is specified then
+ * connector specified in the EEPROM is used
+ * (if present on card or AUI if not).
+ *
+ */
+
+ /* Set the xcvr. */
+ if (ifp->if_flags & IFF_LINK0 && sc->ep_connectors & AUI)
+ {
+ i = ACF_CONNECTOR_AUI;
+ }
+ else if (ifp->if_flags & IFF_LINK1 && sc->ep_connectors & BNC)
+ {
+ i = ACF_CONNECTOR_BNC;
+ }
+ else if (ifp->if_flags & IFF_LINK2 && sc->ep_connectors & UTP)
+ {
+ i = ACF_CONNECTOR_UTP;
+ }
+ else
+ {
+ i = sc->ep_connector;
+ }
+ GO_WINDOW(0);
+ j = inw(BASE + EP_W0_ADDRESS_CFG) & 0x3fff;
+ outw(BASE + EP_W0_ADDRESS_CFG, j | (i << ACF_CONNECTOR_BITS));
+
+ switch(i)
+ {
+ case ACF_CONNECTOR_UTP:
+ if (sc->ep_connectors & UTP)
+ {
+ GO_WINDOW(4);
+ outw(BASE + EP_W4_MEDIA_TYPE, ENABLE_UTP);
+ }
+ break;
+
+ case ACF_CONNECTOR_BNC:
+ if (sc->ep_connectors & BNC)
+ {
+ outw(BASE + EP_COMMAND, START_TRANSCEIVER);
+ Wait_X_ms( 1 );
+ }
+ break;
+
+ case ACF_CONNECTOR_AUI:
+ /* nothing to do */
+ break;
+
+ default:
+ printf("ep%d: strange connector type in EEPROM: assuming AUI\n", sc->unit);
+ break;
+ }
+
+ outw(BASE + EP_COMMAND, RX_ENABLE);
+ outw(BASE + EP_COMMAND, TX_ENABLE);
+
+ ifp->if_flags |= IFF_RUNNING;
+ ifp->if_flags &= ~IFF_OACTIVE; /* just in case */
+
+ sc->rx_no_first = sc->rx_no_mbuf =
+ sc->rx_bpf_disc = sc->rx_overrunf = sc->rx_overrunl =
+ sc->tx_underrun = 0;
+
+ ep_fset(F_RX_FIRST);
+ if( sc->top )
+ {
+ m_freem( sc->top );
+ sc->top = sc->mcur = 0;
+ }
+ outw(BASE + EP_COMMAND, SET_RX_EARLY_THRESH | RX_INIT_EARLY_THRESH);
+ outw(BASE + EP_COMMAND, SET_TX_START_THRESH | 16);
+
+ /*
+ * Store up a bunch of mbuf's for use later. (MAX_MBS). First we free up
+ * any that we had in case we're being called from intr or somewhere
+ * else.
+ */
+
+ GO_WINDOW(1);
+}
+
+static const char padmap[] = {0, 3, 2, 1};
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Routine to transmit frames to the card.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void epstart( struct ifnet *ifp )
+{
+ register struct ep_softc *sc = ifp->if_softc;
+ register u_int len;
+ register struct mbuf *m;
+ struct mbuf *top;
+ int pad;
+
+ while( inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS )
+ ;
+startagain:
+ /* printk( "S-" ); */
+
+ /* Sneak a peek at the next packet */
+ m = ifp->if_snd.ifq_head;
+ if (m == 0)
+ {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ return;
+ }
+
+ for( len = 0, top = m; m; m = m->m_next )
+ len += m->m_len;
+
+ pad = padmap[ len & 3 ];
+
+ /*
+ * The 3c509 automatically pads short packets to minimum ethernet length,
+ * but we drop packets that are too large. Perhaps we should truncate
+ * them instead?
+ */
+ if( len + pad > ETHER_MAX_LEN )
+ {
+ /* packet is obviously too large: toss it */
+ ++ifp->if_oerrors;
+ IF_DEQUEUE( &ifp->if_snd, m );
+ m_freem( m );
+ goto readcheck;
+ }
+ if (inw(BASE + EP_W1_FREE_TX) < len + pad + 4)
+ {
+ /* no room in FIFO */
+ outw(BASE + EP_COMMAND, SET_TX_AVAIL_THRESH | (len + pad + 4));
+ /* make sure */
+ if (inw(BASE + EP_W1_FREE_TX) < len + pad + 4)
+ {
+ ifp->if_flags |= IFF_OACTIVE;
+ return;
+ }
+ }
+ IF_DEQUEUE( &ifp->if_snd, m );
+ outw(BASE + EP_W1_TX_PIO_WR_1, len);
+ outw(BASE + EP_W1_TX_PIO_WR_1, 0x0); /* Second dword meaningless */
+
+ for (top = m; m != 0; m = m->m_next)
+ {
+ if( ep_ftst(F_ACCESS_32_BITS ) )
+ {
+ outsl( BASE + EP_W1_TX_PIO_WR_1, mtod(m, uint8_t *), m->m_len / 4 );
+ if( m->m_len & 3 )
+ outsb(BASE + EP_W1_TX_PIO_WR_1, mtod(m, uint8_t *) + (m->m_len & (~3)), m->m_len & 3 );
+ }
+ else
+ {
+ outsw( BASE + EP_W1_TX_PIO_WR_1, mtod(m, uint8_t *), m->m_len / 2 );
+ if( m->m_len & 1 )
+ outb( BASE + EP_W1_TX_PIO_WR_1, *(mtod(m, uint8_t *) + m->m_len - 1) );
+ }
+ }
+ while( pad-- )
+ {
+ outb(BASE + EP_W1_TX_PIO_WR_1, 0); /* Padding */
+ }
+ ifp->if_timer = 2;
+ ifp->if_opackets++;
+ m_freem(top);
+
+/* goto startagain; */
+ /*
+ * Is another packet coming in? We don't want to overflow the tiny RX
+ * fifo.
+ */
+readcheck:
+ if( inw(BASE + EP_W1_RX_STATUS) & RX_BYTES_MASK )
+ {
+ /*
+ * we check if we have packets left, in that case we prepare to come
+ * back later
+ */
+ if( ifp->if_snd.ifq_head )
+ {
+ outw(BASE + EP_COMMAND, SET_TX_AVAIL_THRESH | 8);
+ }
+ return;
+ }
+ goto startagain;
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION: Routine to read frames from the card.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void epread( register struct ep_softc *sc )
+{
+ struct ether_header *eh;
+ struct mbuf *top, *mcur, *m;
+ struct ifnet *ifp;
+ int lenthisone;
+
+ short rx_fifo2, status;
+ register short rx_fifo;
+
+ ifp = &sc->arpcom.ac_if;
+ status = inw( BASE + EP_W1_RX_STATUS );
+
+read_again:
+
+ if (status & ERR_RX)
+ {
+ ++ifp->if_ierrors;
+ if( status & ERR_RX_OVERRUN )
+ {
+ /*
+ * we can think the rx latency is actually greather than we
+ * expect
+ */
+ if( ep_ftst(F_RX_FIRST) )
+ sc->rx_overrunf++;
+ else
+ sc->rx_overrunl++;
+
+ }
+ goto out;
+ }
+ rx_fifo = rx_fifo2 = status & RX_BYTES_MASK;
+
+ if( ep_ftst( F_RX_FIRST ) )
+ {
+ MGETHDR( m, M_DONTWAIT, MT_DATA );
+ if( !m )
+ goto out;
+ if( rx_fifo >= MINCLSIZE )
+ MCLGET( m, M_DONTWAIT );
+ sc->top = sc->mcur = top = m;
+#define EROUND ((sizeof(struct ether_header) + 3) & ~3)
+#define EOFF (EROUND - sizeof(struct ether_header))
+ top->m_data += EOFF;
+
+ /* Read what should be the header. */
+ insw(BASE + EP_W1_RX_PIO_RD_1, mtod(top, uint8_t *), sizeof(struct ether_header) / 2);
+ top->m_len = sizeof(struct ether_header);
+ rx_fifo -= sizeof(struct ether_header);
+ sc->cur_len = rx_fifo2;
+ }
+ else
+ {
+ /* come here if we didn't have a complete packet last time */
+ top = sc->top;
+ m = sc->mcur;
+ sc->cur_len += rx_fifo2;
+ }
+
+ /* Reads what is left in the RX FIFO */
+ while (rx_fifo > 0)
+ {
+ lenthisone = min( rx_fifo, M_TRAILINGSPACE(m) );
+ if( lenthisone == 0 )
+ { /* no room in this one */
+ mcur = m;
+ MGET(m, M_WAIT, MT_DATA);
+ if (!m)
+ goto out;
+ if (rx_fifo >= MINCLSIZE)
+ MCLGET(m, M_WAIT);
+ m->m_len = 0;
+ mcur->m_next = m;
+ lenthisone = min(rx_fifo, M_TRAILINGSPACE(m));
+ }
+ if( ep_ftst( F_ACCESS_32_BITS ) )
+ { /* default for EISA configured cards*/
+ insl( BASE + EP_W1_RX_PIO_RD_1, mtod(m, uint8_t *) + m->m_len, lenthisone / 4);
+ m->m_len += (lenthisone & ~3);
+ if (lenthisone & 3)
+ insb(BASE + EP_W1_RX_PIO_RD_1, mtod(m, uint8_t *) + m->m_len, lenthisone & 3);
+ m->m_len += (lenthisone & 3);
+ }
+ else
+ {
+ insw(BASE + EP_W1_RX_PIO_RD_1, mtod(m, uint8_t *) + m->m_len, lenthisone / 2);
+ m->m_len += lenthisone;
+ if( lenthisone & 1 )
+ *(mtod(m, uint8_t *) + m->m_len - 1) = inb(BASE + EP_W1_RX_PIO_RD_1);
+ }
+ rx_fifo -= lenthisone;
+ }
+
+ if( status & ERR_RX_INCOMPLETE)
+ { /* we haven't received the complete packet */
+ sc->mcur = m;
+ sc->rx_no_first++; /* to know how often we come here */
+ ep_frst( F_RX_FIRST );
+ if( !((status = inw(BASE + EP_W1_RX_STATUS)) & ERR_RX_INCOMPLETE) )
+ {
+ /* we see if by now, the packet has completly arrived */
+ goto read_again;
+ }
+ outw(BASE + EP_COMMAND, SET_RX_EARLY_THRESH | RX_NEXT_EARLY_THRESH);
+ return;
+ }
+ outw(BASE + EP_COMMAND, RX_DISCARD_TOP_PACK);
+ ++ifp->if_ipackets;
+ ep_fset(F_RX_FIRST);
+ top->m_pkthdr.rcvif = &sc->arpcom.ac_if;
+ top->m_pkthdr.len = sc->cur_len;
+
+ eh = mtod(top, struct ether_header *);
+ m_adj(top, sizeof(struct ether_header));
+ ether_input(ifp, eh, top);
+ sc->top = 0;
+ while (inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS)
+ ;
+ outw(BASE + EP_COMMAND, SET_RX_EARLY_THRESH | RX_INIT_EARLY_THRESH);
+ return;
+
+out:
+ outw(BASE + EP_COMMAND, RX_DISCARD_TOP_PACK);
+ if (sc->top)
+ {
+ m_freem(sc->top);
+ sc->top = 0;
+ sc->rx_no_mbuf++;
+ }
+ ep_fset(F_RX_FIRST);
+ while (inw(BASE + EP_STATUS) & S_COMMAND_IN_PROGRESS) ;
+ outw(BASE + EP_COMMAND, SET_RX_EARLY_THRESH | RX_INIT_EARLY_THRESH);
+}
+
+/**********************************************************************************
+ *
+ * DESCRIPTION:
+ * This routine handles interrupts. It is called from the "RX" task whenever
+ * the ISR post an event to the task.
+ * This is basically the "isr" from the FreeBSD driver.
+ *
+ * RETURNS: nothing.
+ *
+ **********************************************************************************/
+static void ep_intr( struct ep_softc *sc )
+{
+ register int status;
+ struct ifnet *ifp;
+ ifp = &sc->arpcom.ac_if;
+
+rescan:
+
+ /* printk( "I-" ); */
+ while( ( status = inw(BASE + EP_STATUS)) & S_5_INTS )
+ {
+ /* first acknowledge all interrupt sources */
+ outw( BASE + EP_COMMAND, ACK_INTR | ( status & S_MASK ) );
+
+ if( status & ( S_RX_COMPLETE | S_RX_EARLY ) )
+ {
+ epread( sc );
+ continue;
+ }
+ if (status & S_TX_AVAIL)
+ {
+ /* we need ACK */
+ ifp->if_timer = 0;
+ ifp->if_flags &= ~IFF_OACTIVE;
+ GO_WINDOW(1);
+ inw(BASE + EP_W1_FREE_TX);
+ epstart(ifp);
+ }
+ if (status & S_CARD_FAILURE)
+ {
+ ifp->if_timer = 0;
+ printf("\nep%d:\n\tStatus: %x\n", sc->unit, status);
+ GO_WINDOW(4);
+ printf("\tFIFO Diagnostic: %x\n", inw(BASE + EP_W4_FIFO_DIAG));
+ printf("\tStat: %x\n", sc->stat);
+ printf("\tIpackets=%ld, Opackets=%ld\n", ifp->if_ipackets, ifp->if_opackets);
+ printf("\tNOF=%d, NOMB=%d, BPFD=%d, RXOF=%d, RXOL=%d, TXU=%d\n",
+ sc->rx_no_first, sc->rx_no_mbuf, sc->rx_bpf_disc, sc->rx_overrunf,
+ sc->rx_overrunl, sc->tx_underrun);
+
+ printf("ep%d: Status: %x (input buffer overflow)\n", sc->unit, status);
+ ++ifp->if_ierrors;
+ epinit(sc);
+ return;
+ }
+ if (status & S_TX_COMPLETE)
+ {
+ ifp->if_timer = 0;
+ /* we need ACK. we do it at the end */
+ /*
+ * We need to read TX_STATUS until we get a 0 status in order to
+ * turn off the interrupt flag.
+ */
+ while ((status = inb(BASE + EP_W1_TX_STATUS)) & TXS_COMPLETE)
+ {
+ if (status & TXS_SUCCES_INTR_REQ)
+ ;
+ else if( status & (TXS_UNDERRUN | TXS_JABBER | TXS_MAX_COLLISION ) )
+ {
+ outw(BASE + EP_COMMAND, TX_RESET);
+ if (status & TXS_UNDERRUN)
+ {
+ sc->tx_underrun++;
+ }
+ else
+ {
+ if( status & TXS_JABBER )
+ ;
+ else /* TXS_MAX_COLLISION - we shouldn't get here */
+ ++ifp->if_collisions;
+ }
+ ++ifp->if_oerrors;
+ outw(BASE + EP_COMMAND, TX_ENABLE);
+ /*
+ * To have a tx_avail_int but giving the chance to the
+ * Reception
+ */
+ if( ifp->if_snd.ifq_head )
+ {
+ outw(BASE + EP_COMMAND, SET_TX_AVAIL_THRESH | 8);
+ }
+ }
+ outb( BASE + EP_W1_TX_STATUS, 0x0 ); /* pops up the next status */
+ } /* while */
+ ifp->if_flags &= ~IFF_OACTIVE;
+ GO_WINDOW(1);
+ inw(BASE + EP_W1_FREE_TX);
+ epstart( ifp );
+ } /* end TX_COMPLETE */
+ }
+ outw(BASE + EP_COMMAND, C_INTR_LATCH); /* ACK int Latch */
+ if( (status = inw(BASE + EP_STATUS) ) & S_5_INTS )
+ goto rescan;
+
+ /* re-enable Ints */
+ outw( BASE + EP_COMMAND, SET_INTR_MASK | S_5_INTS );
+ /* printk( "I+" ); */
+}
diff --git a/bsps/i386/pc386/net/3c509.h b/bsps/i386/pc386/net/3c509.h
new file mode 100644
index 0000000..300f864
--- /dev/null
+++ b/bsps/i386/pc386/net/3c509.h
@@ -0,0 +1,436 @@
+/**
+ * @file
+ *
+ * @ingroup pc386_3c509
+ *
+ * @brief 3C509 PC card support.
+ */
+
+/*
+ * Copyright (c) 1993 Herb Peyerl (hpeyerl@novatel.ca) 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. The name
+ * of the author may not be used to endorse or promote products derived from
+ * this software without specific prior written permission
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
+ * EVENT SHALL THE AUTHOR 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.
+ *
+ * if_epreg.h,v 1.4 1994/11/13 10:12:37 gibbs Exp Modified by:
+ *
+ October 2, 1994
+
+ Modified by: Andres Vega Garcia
+
+ INRIA - Sophia Antipolis, France
+ e-mail: avega@sophia.inria.fr
+ finger: avega@pax.inria.fr
+
+ */
+/*
+ * Promiscuous mode added and interrupt logic slightly changed
+ * to reduce the number of adapter failures. Transceiver select
+ * logic changed to use value from EEPROM. Autoconfiguration
+ * features added.
+ * Done by:
+ * Serge Babkin
+ * Chelindbank (Chelyabinsk, Russia)
+ * babkin@hq.icb.chel.su
+ */
+
+/*
+ * Pccard support for 3C589 by:
+ * HAMADA Naoki
+ * nao@tom-yam.or.jp
+ */
+
+/**
+ * @defgroup pc386_3c509 3C509 Support
+ *
+ * @ingroup RTEMSBSPsI386
+ *
+ * @brief 3C509 support.
+ */
+
+/*
+typedef unsigned short u_short;
+typedef unsigned long u_long;
+typedef unsigned char u_char;
+*/
+
+/*
+ * Some global constants
+ */
+#define F_RX_FIRST 0x1
+#define F_PROMISC 0x8
+#define F_ACCESS_32_BITS 0x100
+
+#define TX_INIT_RATE 16
+#define TX_INIT_MAX_RATE 64
+#define RX_INIT_LATENCY 64
+#define RX_INIT_EARLY_THRESH 208 /* not less than MINCLSIZE */
+#define RX_NEXT_EARLY_THRESH 500
+
+#define EEPROMSIZE 0x40
+#define MAX_EEPROMBUSY 1000
+#define EP_LAST_TAG 0xd7
+#define EP_MAX_BOARDS 16
+/*
+ * This `ID' port is a mere hack. There's currently no chance to register
+ * it with config's idea of the ports that are in use.
+ *
+ * "After the automatic configuration is completed, the IDS is in its initial
+ * state (ID-WAIT), and it monitors all write access to I/O port 01x0h, where
+ * 'x' is any hex digit. If a zero is written to any one of these ports, then
+ * that address is remembered and becomes the ID port. A second zero written
+ * to that port resets the ID sequence to its initial state. The IDS watches
+ * for the ID sequence to be written to the ID port."
+ *
+ * We prefer 0x110 over 0x100 so to not conflict with the Plaque&Pray
+ * ports.
+ */
+#define EP_ID_PORT 0x110
+#define EP_IOSIZE 16 /* 16 bytes of I/O space used. */
+
+/*
+ * some macros to acces long named fields
+ */
+#define IS_BASE (is->id_iobase)
+#define BASE (sc->ep_io_addr)
+
+/*
+ * Commands to read/write EEPROM trough EEPROM command register (Window 0,
+ * Offset 0xa)
+ */
+#define EEPROM_CMD_RD 0x0080 /* Read: Address required (5 bits) */
+#define EEPROM_CMD_WR 0x0040 /* Write: Address required (5 bits) */
+#define EEPROM_CMD_ERASE 0x00c0 /* Erase: Address required (5 bits) */
+#define EEPROM_CMD_EWEN 0x0030 /* Erase/Write Enable: No data required */
+
+#define EEPROM_BUSY (1<<15)
+#define EEPROM_TST_MODE (1<<14)
+
+/*
+ * Some short functions, worth to let them be a macro
+ */
+#define is_eeprom_busy(b) (inw((b)+EP_W0_EEPROM_COMMAND)&EEPROM_BUSY)
+#define GO_WINDOW(x) outw(BASE+EP_COMMAND, WINDOW_SELECT|(x))
+
+/**************************************************************************
+ * *
+ * These define the EEPROM data structure. They are used in the probe
+ * function to verify the existence of the adapter after having sent
+ * the ID_Sequence.
+ *
+ * There are others but only the ones we use are defined here.
+ *
+ **************************************************************************/
+
+#define EEPROM_NODE_ADDR_0 0x0 /* Word */
+#define EEPROM_NODE_ADDR_1 0x1 /* Word */
+#define EEPROM_NODE_ADDR_2 0x2 /* Word */
+#define EEPROM_PROD_ID 0x3 /* 0x9[0-f]50 */
+#define EEPROM_MFG_ID 0x7 /* 0x6d50 */
+#define EEPROM_ADDR_CFG 0x8 /* Base addr */
+#define EEPROM_RESOURCE_CFG 0x9 /* IRQ. Bits 12-15 */
+
+/**************************************************************************
+ * *
+ * These are the registers for the 3Com 3c509 and their bit patterns when *
+ * applicable. They have been taken out the the "EtherLink III Parallel *
+ * Tasking EISA and ISA Technical Reference" "Beta Draft 10/30/92" manual *
+ * from 3com. *
+ * *
+ **************************************************************************/
+
+#define EP_COMMAND 0x0e /* Write. BASE+0x0e is always a
+ * command reg. */
+#define EP_STATUS 0x0e /* Read. BASE+0x0e is always status
+ * reg. */
+#define EP_WINDOW 0x0f /* Read. BASE+0x0f is always window
+ * reg. */
+/*
+ * Window 0 registers. Setup.
+ */
+/* Write */
+#define EP_W0_EEPROM_DATA 0x0c
+#define EP_W0_EEPROM_COMMAND 0x0a
+#define EP_W0_RESOURCE_CFG 0x08
+#define EP_W0_ADDRESS_CFG 0x06
+#define EP_W0_CONFIG_CTRL 0x04
+/* Read */
+#define EP_W0_PRODUCT_ID 0x02
+#define EP_W0_MFG_ID 0x00
+
+/*
+ * Window 1 registers. Operating Set.
+ */
+/* Write */
+#define EP_W1_TX_PIO_WR_2 0x02
+#define EP_W1_TX_PIO_WR_1 0x00
+/* Read */
+#define EP_W1_FREE_TX 0x0c
+#define EP_W1_TX_STATUS 0x0b /* byte */
+#define EP_W1_TIMER 0x0a /* byte */
+#define EP_W1_RX_STATUS 0x08
+#define EP_W1_RX_PIO_RD_2 0x02
+#define EP_W1_RX_PIO_RD_1 0x00
+
+/*
+ * Window 2 registers. Station Address Setup/Read
+ */
+/* Read/Write */
+#define EP_W2_ADDR_5 0x05
+#define EP_W2_ADDR_4 0x04
+#define EP_W2_ADDR_3 0x03
+#define EP_W2_ADDR_2 0x02
+#define EP_W2_ADDR_1 0x01
+#define EP_W2_ADDR_0 0x00
+
+/*
+ * Window 3 registers. FIFO Management.
+ */
+/* Read */
+#define EP_W3_FREE_TX 0x0c
+#define EP_W3_FREE_RX 0x0a
+
+/*
+ * Window 4 registers. Diagnostics.
+ */
+/* Read/Write */
+#define EP_W4_MEDIA_TYPE 0x0a
+#define EP_W4_CTRLR_STATUS 0x08
+#define EP_W4_NET_DIAG 0x06
+#define EP_W4_FIFO_DIAG 0x04
+#define EP_W4_HOST_DIAG 0x02
+#define EP_W4_TX_DIAG 0x00
+
+/*
+ * Window 5 Registers. Results and Internal status.
+ */
+/* Read */
+#define EP_W5_READ_0_MASK 0x0c
+#define EP_W5_INTR_MASK 0x0a
+#define EP_W5_RX_FILTER 0x08
+#define EP_W5_RX_EARLY_THRESH 0x06
+#define EP_W5_TX_AVAIL_THRESH 0x02
+#define EP_W5_TX_START_THRESH 0x00
+
+/*
+ * Window 6 registers. Statistics.
+ */
+/* Read/Write */
+#define TX_TOTAL_OK 0x0c
+#define RX_TOTAL_OK 0x0a
+#define TX_DEFERRALS 0x08
+#define RX_FRAMES_OK 0x07
+#define TX_FRAMES_OK 0x06
+#define RX_OVERRUNS 0x05
+#define TX_COLLISIONS 0x04
+#define TX_AFTER_1_COLLISION 0x03
+#define TX_AFTER_X_COLLISIONS 0x02
+#define TX_NO_SQE 0x01
+#define TX_CD_LOST 0x00
+
+/****************************************
+ *
+ * Register definitions.
+ *
+ ****************************************/
+
+/*
+ * Command register. All windows.
+ *
+ * 16 bit register.
+ * 15-11: 5-bit code for command to be executed.
+ * 10-0: 11-bit arg if any. For commands with no args;
+ * this can be set to anything.
+ */
+#define GLOBAL_RESET (u_short) 0x0000 /* Wait at least 1ms
+ * after issuing */
+#define WINDOW_SELECT (u_short) (0x1<<11)
+#define START_TRANSCEIVER (u_short) (0x2<<11) /* Read ADDR_CFG reg to
+ * determine whether
+ * this is needed. If
+ * so; wait 800 uSec
+ * before using trans-
+ * ceiver. */
+#define RX_DISABLE (u_short) (0x3<<11) /* state disabled on
+ * power-up */
+#define RX_ENABLE (u_short) (0x4<<11)
+#define RX_RESET (u_short) (0x5<<11)
+#define RX_DISCARD_TOP_PACK (u_short) (0x8<<11)
+#define TX_ENABLE (u_short) (0x9<<11)
+#define TX_DISABLE (u_short) (0xa<<11)
+#define TX_RESET (u_short) (0xb<<11)
+#define REQ_INTR (u_short) (0xc<<11)
+#define SET_INTR_MASK (u_short) (0xe<<11)
+#define SET_RD_0_MASK (u_short) (0xf<<11)
+#define SET_RX_FILTER (u_short) (0x10<<11)
+#define FIL_INDIVIDUAL (u_short) (0x1)
+#define FIL_GROUP (u_short) (0x2)
+#define FIL_BRDCST (u_short) (0x4)
+#define FIL_ALL (u_short) (0x8)
+#define SET_RX_EARLY_THRESH (u_short) (0x11<<11)
+#define SET_TX_AVAIL_THRESH (u_short) (0x12<<11)
+#define SET_TX_START_THRESH (u_short) (0x13<<11)
+#define STATS_ENABLE (u_short) (0x15<<11)
+#define STATS_DISABLE (u_short) (0x16<<11)
+#define STOP_TRANSCEIVER (u_short) (0x17<<11)
+/*
+ * The following C_* acknowledge the various interrupts. Some of them don't
+ * do anything. See the manual.
+ */
+#define ACK_INTR (u_short) (0x6800)
+#define C_INTR_LATCH (u_short) (ACK_INTR|0x1)
+#define C_CARD_FAILURE (u_short) (ACK_INTR|0x2)
+#define C_TX_COMPLETE (u_short) (ACK_INTR|0x4)
+#define C_TX_AVAIL (u_short) (ACK_INTR|0x8)
+#define C_RX_COMPLETE (u_short) (ACK_INTR|0x10)
+#define C_RX_EARLY (u_short) (ACK_INTR|0x20)
+#define C_INT_RQD (u_short) (ACK_INTR|0x40)
+#define C_UPD_STATS (u_short) (ACK_INTR|0x80)
+#define C_MASK (u_short) 0xFF /* mask of C_* */
+
+/*
+ * Status register. All windows.
+ *
+ * 15-13: Window number(0-7).
+ * 12: Command_in_progress.
+ * 11: reserved.
+ * 10: reserved.
+ * 9: reserved.
+ * 8: reserved.
+ * 7: Update Statistics.
+ * 6: Interrupt Requested.
+ * 5: RX Early.
+ * 4: RX Complete.
+ * 3: TX Available.
+ * 2: TX Complete.
+ * 1: Adapter Failure.
+ * 0: Interrupt Latch.
+ */
+#define S_INTR_LATCH (u_short) (0x1)
+#define S_CARD_FAILURE (u_short) (0x2)
+#define S_TX_COMPLETE (u_short) (0x4)
+#define S_TX_AVAIL (u_short) (0x8)
+#define S_RX_COMPLETE (u_short) (0x10)
+#define S_RX_EARLY (u_short) (0x20)
+#define S_INT_RQD (u_short) (0x40)
+#define S_UPD_STATS (u_short) (0x80)
+#define S_MASK (u_short) 0xFF /* mask of S_* */
+#define S_5_INTS (S_CARD_FAILURE|S_TX_COMPLETE|\
+ S_TX_AVAIL|S_RX_COMPLETE|S_RX_EARLY)
+#define S_COMMAND_IN_PROGRESS (u_short) (0x1000)
+
+/* Address Config. Register.
+ * Window 0/Port 06
+ */
+
+#define ACF_CONNECTOR_BITS 14
+#define ACF_CONNECTOR_UTP 0
+#define ACF_CONNECTOR_AUI 1
+#define ACF_CONNECTOR_BNC 3
+
+/* Resource configuration register.
+ * Window 0/Port 08
+ *
+ */
+
+#define SET_IRQ(base,irq) outw((base) + EP_W0_RESOURCE_CFG, \
+ ((inw((base) + EP_W0_RESOURCE_CFG) & 0x0fff) | \
+ ((u_short)(irq)<<12)) ) /* set IRQ i */
+
+/*
+ * FIFO Registers.
+ * RX Status. Window 1/Port 08
+ *
+ * 15: Incomplete or FIFO empty.
+ * 14: 1: Error in RX Packet 0: Incomplete or no error.
+ * 13-11: Type of error.
+ * 1000 = Overrun.
+ * 1011 = Run Packet Error.
+ * 1100 = Alignment Error.
+ * 1101 = CRC Error.
+ * 1001 = Oversize Packet Error (>1514 bytes)
+ * 0010 = Dribble Bits.
+ * (all other error codes, no errors.)
+ *
+ * 10-0: RX Bytes (0-1514)
+ */
+#define ERR_RX_INCOMPLETE (u_short) (0x1<<15)
+#define ERR_RX (u_short) (0x1<<14)
+#define ERR_RX_OVERRUN (u_short) (0x8<<11)
+#define ERR_RX_RUN_PKT (u_short) (0xb<<11)
+#define ERR_RX_ALIGN (u_short) (0xc<<11)
+#define ERR_RX_CRC (u_short) (0xd<<11)
+#define ERR_RX_OVERSIZE (u_short) (0x9<<11)
+#define ERR_RX_DRIBBLE (u_short) (0x2<<11)
+
+/*
+ * FIFO Registers.
+ * TX Status. Window 1/Port 0B
+ *
+ * Reports the transmit status of a completed transmission. Writing this
+ * register pops the transmit completion stack.
+ *
+ * Window 1/Port 0x0b.
+ *
+ * 7: Complete
+ * 6: Interrupt on successful transmission requested.
+ * 5: Jabber Error (TP Only, TX Reset required. )
+ * 4: Underrun (TX Reset required. )
+ * 3: Maximum Collisions.
+ * 2: TX Status Overflow.
+ * 1-0: Undefined.
+ *
+ */
+#define TXS_COMPLETE 0x80
+#define TXS_SUCCES_INTR_REQ 0x40
+#define TXS_JABBER 0x20
+#define TXS_UNDERRUN 0x10
+#define TXS_MAX_COLLISION 0x8
+#define TXS_STATUS_OVERFLOW 0x4
+
+/*
+ * Configuration control register.
+ * Window 0/Port 04
+ */
+/* Read */
+#define IS_AUI (1<<13)
+#define IS_BNC (1<<12)
+#define IS_UTP (1<<9)
+/* Write */
+#define ENABLE_DRQ_IRQ 0x0001
+#define W0_P4_CMD_RESET_ADAPTER 0x4
+#define W0_P4_CMD_ENABLE_ADAPTER 0x1
+/*
+ * Media type and status.
+ * Window 4/Port 0A
+ */
+#define ENABLE_UTP 0xc0
+#define DISABLE_UTP 0x0
+
+/*
+ * Misc defines for various things.
+ */
+#define ACTIVATE_ADAPTER_TO_CONFIG 0xff /* to the id_port */
+#define MFG_ID 0x6d50 /* in EEPROM and W0 ADDR_CONFIG */
+#define PROD_ID 0x9150
+
+#define AUI 0x1
+#define BNC 0x2
+#define UTP 0x4
+
+#define RX_BYTES_MASK (u_short) (0x07ff)
diff --git a/bsps/i386/pc386/net/elink.c b/bsps/i386/pc386/net/elink.c
new file mode 100644
index 0000000..65cfdfd
--- /dev/null
+++ b/bsps/i386/pc386/net/elink.c
@@ -0,0 +1,82 @@
+/*
+ * Copyright (c) 1994 Charles Hannum. 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed by Charles Hannum.
+ * 4. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR 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.
+ */
+
+/*
+ * Common code for dealing with 3COM ethernet cards.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <sys/types.h>
+
+#include "elink.h"
+
+#include <bsp.h>
+
+static void outb( unsigned short io_addr, unsigned char out_data )
+{
+ outport_byte( io_addr, out_data );
+}
+
+/*
+ * Issue a `global reset' to all cards. We have to be careful to do this only
+ * once during autoconfig, to prevent resetting boards that have already been
+ * configured.
+ */
+void
+elink_reset()
+{
+ static int x = 0;
+
+ if (x == 0) {
+ x = 1;
+ outb(ELINK_ID_PORT, ELINK_RESET);
+ }
+}
+
+/*
+ * The `ID sequence' is really just snapshots of an 8-bit CRC register as 0
+ * bits are shifted in. Different board types use different polynomials.
+ */
+void
+elink_idseq(u_char p)
+{
+ register int i;
+ register u_char c;
+
+ c = 0xff;
+ for (i = 255; i; i--) {
+ outb(ELINK_ID_PORT, c);
+ if (c & 0x80) {
+ c <<= 1;
+ c ^= p;
+ } else
+ c <<= 1;
+ }
+}
diff --git a/bsps/i386/pc386/net/elink.h b/bsps/i386/pc386/net/elink.h
new file mode 100644
index 0000000..bcb13a4
--- /dev/null
+++ b/bsps/i386/pc386/net/elink.h
@@ -0,0 +1,49 @@
+/**
+ * @file
+ *
+ * @ingroup pc386_3c509
+ *
+ * @brief EtherLink definitions.
+ */
+
+/*
+ * Copyright (c) 1994 Charles Hannum. 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed by Charles Hannum.
+ * 4. The name of the author may not be used to endorse or promote products
+ * derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR 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.
+ */
+
+#ifdef PC98
+#define ELINK_ID_PORT 0x71d0
+#else
+#define ELINK_ID_PORT 0x110
+#endif
+#define ELINK_RESET 0xc0
+
+#define ELINK_507_POLY 0xe7
+#define ELINK_509_POLY 0xcf
+
+extern void elink_reset ( void );
+extern void elink_idseq ( u_char p );
diff --git a/bsps/i386/pc386/net/ne2000.c b/bsps/i386/pc386/net/ne2000.c
new file mode 100644
index 0000000..08d8057
--- /dev/null
+++ b/bsps/i386/pc386/net/ne2000.c
@@ -0,0 +1,1310 @@
+/* ne2k.c -- RTEMS NE2000 Ethernet driver.
+ * Written by Ian Lance Taylor, Zembu Labs.
+ * October, 1998.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * Both the ne2000 and the wd80x3 are based on the National Semiconductor
+ * 8390 chip, so there is a fair amount of overlap between the two
+ * drivers. It would be possible in principle to combine some code into
+ * a separate set of subroutines called by both. In fact, the drivers in
+ * both OpenBSD and Linux work this way. I didn't bother, because for
+ * the relatively simple drivers used by RTEMS, the overlap is not
+ * especially large, and any reasonable use of subroutines would lead to
+ * slightly less efficient code.
+
+ * This ne2000 driver uses two transmit buffers. While one packet is
+ * being transmitted over the Ethernet, RTEMS will upload another. Since
+ * uploading a packet to the ne2000 is rather slow, I don't think there
+ * is any point to having more than two transmit buffers. However, the
+ * code does make it possible, by changing NE_TX_BUFS, although that
+ * would of course reduce the number of receive buffers.
+ *
+ * I suspect that the wd80x3 driver would benefit slightly from copying
+ * the multiple transmit buffer code. However, I have no way to test
+ * that.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/wd80x3.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <bsp/irq.h>
+
+/* Define this to force byte-wide data transfers with the NIC. This
+ is needed for boards like the TS-1325 386EX PC, which support only
+ an 8-bit PC/104 bus. Undefine this on a normal PC.*/
+
+/* #define NE2000_BYTE_TRANSFERS */
+
+/* Define this to print debugging messages with printk. */
+
+/* #define DEBUG_NE2000 */
+/* #define DEBUG_NE */
+
+/* We expect to be able to read a complete packet into an mbuf. */
+
+#if (MCLBYTES < 1520)
+# error "Driver must have MCLBYTES >= 1520"
+#endif
+
+/* The 8390 macro definitions in wd80x3.h expect RO to be defined. */
+#define RO 0
+
+/* Minimum size of Ethernet packet. */
+#define ET_MINLEN 60
+
+/* The number of NE2000 devices supported by this driver. */
+
+#define NNEDRIVER 1
+
+/* RTEMS event number used by the interrupt handler to signal the
+ driver task. This must not be any of the events used by the
+ network task synchronization. */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/* RTEMS event number used to start the transmit daemon. This must
+ not be the same as INTERRUPT_EVENT. */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/* Interrupts we want to handle from the device. */
+
+#define NE_INTERRUPTS \
+ (MSK_PRX | MSK_PTX | MSK_RXE | MSK_TXE | MSK_OVW | MSK_CNT)
+
+/* The size of a page in device memory. */
+
+#define NE_PAGE_SIZE (256)
+
+/* The first page address in device memory. */
+
+#define NE_START_PAGE (0x40)
+
+/* The last page address, plus 1. */
+
+#define NE_STOP_PAGE (0x80)
+
+/* The number of pages used for a single transmit buffer. This is
+ 1536 bytes, enough for a full size packet. */
+
+#define NE_TX_PAGES (6)
+
+/* The number of transmit buffers. We use two, so we can load one
+ packet while the other is being sent. */
+
+#define NE_TX_BUFS (2)
+
+/* We use the first pages in memory as transmit buffers, and the
+ remaining ones as receive buffers. */
+
+#define NE_FIRST_TX_PAGE (NE_START_PAGE)
+
+#define NE_FIRST_RX_PAGE (NE_FIRST_TX_PAGE + NE_TX_PAGES * NE_TX_BUFS)
+
+/* Data we store for each NE2000 device. */
+
+struct ne_softc {
+ /* The bsdnet information structure. */
+ struct arpcom arpcom;
+
+ /* The interrupt request number. */
+ unsigned int irno;
+ /* The base IO port number. */
+ unsigned int port;
+
+ /* Whether we accept broadcasts. */
+ int accept_broadcasts;
+
+ /* The thread ID of the transmit task. */
+ rtems_id tx_daemon_tid;
+ /* The thread ID of the receive task. */
+ rtems_id rx_daemon_tid;
+
+ /* Whether we use byte-transfers with the device. */
+ bool byte_transfers;
+
+ /* The number of memory buffers which the transmit daemon has loaded
+ with data to be sent, but which have not yet been completely
+ sent. */
+ int inuse;
+ /* The index of the next available transmit memory buffer. */
+ int nextavail;
+ /* The index of the next transmit buffer to send. */
+ int nextsend;
+ /* Nonzero if the device is currently transmitting a packet. */
+ int transmitting;
+ /* The length of the data stored in each transmit buffer. */
+ int sendlen[NE_TX_BUFS];
+
+ /* Set if we have a packet overrun while receiving. */
+ int overrun;
+ /* Set if we should resend after an overrun. */
+ int resend;
+
+ /* Statistics. */
+ struct {
+ /* Number of packets received. */
+ unsigned long rx_packets;
+ /* Number of packets sent. */
+ unsigned long tx_packets;
+ /* Number of interrupts. */
+ unsigned long interrupts;
+ /* Number of receive acknowledgements. */
+ unsigned long rx_acks;
+ /* Number of transmit acknowledgements. */
+ unsigned long tx_acks;
+ /* Number of packet overruns. */
+ unsigned long overruns;
+ /* Number of frame errors. */
+ unsigned long rx_frame_errors;
+ /* Number of CRC errors. */
+ unsigned long rx_crc_errors;
+ /* Number of missed packets. */
+ unsigned long rx_missed_errors;
+ } stats;
+};
+
+/* The list of NE2000 devices on this system. */
+
+static struct ne_softc ne_softc[NNEDRIVER];
+
+/*
+ * receive ring descriptor
+ *
+ * The National Semiconductor DS8390 Network interface controller uses
+ * the following receive ring headers. The way this works is that the
+ * memory on the interface card is chopped up into 256 bytes blocks.
+ * A contiguous portion of those blocks are marked for receive packets
+ * by setting start and end block #'s in the NIC. For each packet that
+ * is put into the receive ring, one of these headers (4 bytes each) is
+ * tacked onto the front. The first byte is a copy of the receiver status
+ * register at the time the packet was received.
+ */
+struct ne_ring
+{
+ unsigned char rsr; /* receiver status */
+ unsigned char next; /* pointer to next packet */
+ unsigned char cnt_lo; /* bytes in packet (length + 4) */
+ unsigned char cnt_hi; /* 16-bit, little-endian value */
+};
+
+/* Forward declarations to avoid warnings */
+
+static void ne_init_irq_handler (int irno);
+static void ne_stop (struct ne_softc *sc);
+static void ne_stop_hardware (struct ne_softc *sc);
+static void ne_init (void *arg);
+static void ne_init_hardware (struct ne_softc *sc);
+
+static void ne_reset(struct ne_softc *sc);
+#ifdef DEBUG_NE
+static void ne_dump(struct ne_softc *sc);
+#endif
+
+/* Find the NE2000 device which is attached at a particular interrupt
+ vector. */
+
+static struct ne_softc *
+ne_device_for_irno (int irno)
+{
+ int i;
+
+ for (i = 0; i < NNEDRIVER; ++i)
+ {
+ if (ne_softc[i].irno == irno
+ && ne_softc[i].arpcom.ac_if.if_softc != NULL)
+ return &ne_softc[i];
+ }
+
+ return NULL;
+}
+
+/* Read data from an NE2000 device. Read LEN bytes at ADDR, storing
+ them into P. */
+
+static void
+ne_read_data (struct ne_softc *sc, int addr, int len, unsigned char *p)
+{
+ unsigned int port = sc->port;
+ unsigned int dport = port + DATAPORT;
+
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STA);
+ outport_byte (port + RBCR0, len);
+ outport_byte (port + RBCR1, len >> 8);
+ outport_byte (port + RSAR0, addr);
+ outport_byte (port + RSAR1, addr >> 8);
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RRE | MSK_STA);
+
+ if (sc->byte_transfers)
+ {
+ unsigned char d;
+ while (len > 0)
+ {
+ inport_byte(dport, d);
+ *p++ = d;
+ len--;
+ }
+ }
+ else /* word transfers */
+ {
+ unsigned short d;
+ while (len > 1)
+ {
+ inport_word(dport, d);
+ *p++ = d;
+ *p++ = d >> 8;
+ len -= 2;
+ }
+ if (len)
+ {
+ inport_word(dport, d);
+ *p++ = d;
+ }
+ }
+
+ outport_byte (port + ISR, MSK_RDC);
+}
+
+/* Handle the current NE2000 status. This is called when the device
+ signals an interrupt. It is also called at other times while
+ NE2000 interrupts have been disabled. */
+
+static void
+ne_check_status (struct ne_softc *sc, int from_irq_handler)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+ unsigned char status;
+
+ /* It seems that we need to use a loop here, because if the NE2000
+ signals an interrupt because packet transmission is complete, and
+ then receives a packet while interrupts are disabled, it seems to
+ sometimes fail to signal the interrupt for the received packet
+ when interrupts are reenabled. (Based on the behaviour of the
+ Realtek 8019AS chip). */
+
+ /* int count = 0; */
+ while (1)
+ {
+ inport_byte (port + ISR, status);
+ if (status == 0)
+ break;
+
+ /* ack */
+ outport_byte (port + ISR, status);
+
+#ifdef DEBUG_NE2000
+ printk ("NE2000 status 0x%x (8259 enabled: %s; mask: %x)\n", status,
+ i8259s_cache & (1 << sc->irno) ? "no" : "yes",
+ i8259s_cache);
+#endif
+
+ /* Check for incoming packet overwrite. */
+ if (status & MSK_OVW)
+ {
+ ifp->if_timer = 0;
+#ifdef DEBUG_NE
+ printk("^");
+#endif
+ ++sc->stats.overruns;
+ ne_reset(sc);
+ /* Reenable device interrupts. */
+ if (from_irq_handler)
+ outport_byte(port + IMR, NE_INTERRUPTS);
+ return;
+ }
+
+ /* Check for transmitted packet. The transmit daemon may now be
+ able to send another packet to the device. */
+ if ((status & (MSK_PTX | MSK_TXE)) != 0)
+ {
+ ifp->if_timer = 0;
+ ++sc->stats.tx_acks;
+ --sc->inuse;
+ sc->transmitting = 0;
+ if (sc->inuse > 0 || (sc->arpcom.ac_if.if_flags & IFF_OACTIVE) != 0)
+ rtems_bsdnet_event_send (sc->tx_daemon_tid, START_TRANSMIT_EVENT);
+ }
+
+ /* Check for received packet. */
+ if ((status & (MSK_PRX | MSK_RXE)) != 0)
+ {
+ ++sc->stats.rx_acks;
+ rtems_bsdnet_event_send (sc->rx_daemon_tid, INTERRUPT_EVENT);
+ }
+
+ /* Check for counter change. */
+ if ((status & MSK_CNT) != 0)
+ {
+ unsigned char add;
+ inport_byte (port + CNTR0, add);
+ sc->stats.rx_frame_errors += add;
+ inport_byte (port + CNTR1, add);
+ sc->stats.rx_crc_errors += add;
+ inport_byte (port + CNTR2, add);
+ sc->stats.rx_missed_errors += add;
+ }
+
+ break;
+ /* if (++count >= 1000)
+ {
+ printk("status: %x\n", status);
+ ne_reset(sc);
+ if (from_irq_handler)
+ outport_byte(port + IMR, NE_INTERRUPTS);
+ return;
+ } */
+ }
+
+ outport_byte (port + CMDR, MSK_PG0 | MSK_STA | MSK_RD2);
+}
+
+/* Handle an NE2000 interrupt. */
+
+static void
+ne_interrupt_handler (rtems_irq_hdl_param cdata)
+{
+ rtems_vector_number v = (rtems_vector_number) cdata;
+ struct ne_softc *sc;
+
+ sc = ne_device_for_irno (v);
+ if (sc == NULL)
+ return;
+
+ ++sc->stats.interrupts;
+
+#ifdef DEBUG_NE
+ printk("!");
+#endif
+ ne_check_status(sc, 1);
+}
+
+/* Turn NE2000 interrupts on. */
+
+static void
+ne_interrupt_on (const rtems_irq_connect_data *irq)
+{
+ struct ne_softc *sc;
+
+#ifdef DEBUG_NE
+ printk ("ne_interrupt_on()\n");
+#endif
+ sc = ne_device_for_irno (irq->name);
+ if (sc != NULL)
+ outport_byte (sc->port + IMR, NE_INTERRUPTS);
+}
+
+/* Turn NE2000 interrupts off. See ne_interrupt_on. */
+
+static void
+ne_interrupt_off (const rtems_irq_connect_data *irq)
+{
+ struct ne_softc *sc;
+
+#ifdef DEBUG_NE
+ printk ("ne_interrupt_off()\n");
+#endif
+ sc = ne_device_for_irno (irq->name);
+ if (sc != NULL)
+ outport_byte (sc->port + IMR, 0);
+}
+
+/* Initialize the NE2000 hardware. */
+
+static void
+ne_init_hardware (struct ne_softc *sc)
+{
+ unsigned int port = sc->port;
+ int i;
+
+#ifdef DEBUG_NE2000
+ printk ("ne_init_hardware()\n");
+#endif
+
+ /* Initialize registers. */
+
+ /* Set interface for page 0, Remote DMA complete, Stopped */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ /* Set FIFO threshold to 8, No auto-init Remote DMA, byte order=80x86 */
+ /* byte-wide DMA xfers */
+ if (sc->byte_transfers)
+ outport_byte (port + DCR, MSK_FT10 | MSK_BMS);
+ /* word-wide DMA xfers */
+ else
+ outport_byte (port + DCR, MSK_FT10 | MSK_BMS | MSK_WTS);
+
+ /* Clear Remote Byte Count Registers */
+ outport_byte (port + RBCR0, 0);
+ outport_byte (port + RBCR1, 0);
+
+ /* For the moment, don't store incoming packets in memory. */
+ outport_byte (port + RCR, MSK_MON);
+
+ /* Place NIC in internal loopback mode */
+ outport_byte (port + TCR, MSK_LOOP);
+
+ /* Initialize transmit/receive (ring-buffer) Page Start */
+ outport_byte (port + TPSR, NE_FIRST_TX_PAGE);
+ outport_byte (port + PSTART, NE_FIRST_RX_PAGE);
+
+ /* Initialize Receiver (ring-buffer) Page Stop and Boundary */
+ outport_byte (port + PSTOP, NE_STOP_PAGE);
+ outport_byte (port + BNRY, NE_STOP_PAGE - 1);
+
+ /* Clear all interrupts */
+ outport_byte (port + ISR, 0xff);
+ /* Disable all interrupts */
+ outport_byte (port + IMR, 0);
+
+ /* Program Command Register for page 1 */
+ outport_byte (port + CMDR, MSK_PG1 | MSK_RD2 | MSK_STP);
+
+ /* Set the Ethernet hardware address. */
+ for (i = 0; i < ETHER_ADDR_LEN; ++i)
+ outport_byte (port + PAR + i, sc->arpcom.ac_enaddr[i]);
+
+ /* Set Current Page pointer to next_packet */
+ outport_byte (port + CURR, NE_FIRST_RX_PAGE);
+
+ /* Clear the multicast address. */
+ for (i = 0; i < MARsize; ++i)
+ outport_byte (port + MAR + i, 0);
+
+ /* Set page 0 registers */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ /* accept broadcast + multicast */
+ outport_byte (port + RCR, (sc->accept_broadcasts ? MSK_AB : 0) | MSK_AM);
+
+ /* Start interface */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STA);
+
+ /* Take interface out of loopback */
+ outport_byte (port + TCR, 0);
+}
+
+/* Set up interrupts.
+*/
+static void
+ne_init_irq_handler(int irno)
+{
+ rtems_irq_connect_data irq;
+
+#ifdef DEBUG_NE
+ printk("ne_init_irq_handler(%d)\n", irno);
+#endif
+ irq.name = irno;
+ irq.hdl = ne_interrupt_handler;
+ irq.handle = (rtems_irq_hdl) irno;
+ irq.on = ne_interrupt_on;
+ irq.off = ne_interrupt_off;
+ irq.isOn = NULL;
+
+ if (!BSP_install_rtems_irq_handler (&irq))
+ rtems_panic ("Can't attach NE interrupt handler for irq %d\n", irno);
+}
+
+/* The NE2000 packet receive daemon. This task is started when the
+ NE2000 driver is initialized. */
+
+#ifdef DEBUG_NE
+static int ccc = 0; /* experinent! */
+#endif
+
+static void
+ne_rx_daemon (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+
+ while (1)
+ {
+ rtems_event_set events;
+
+ /* Wait for the interrupt handler to tell us that there is a
+ packet ready to receive. */
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Don't let the device interrupt us now. */
+ outport_byte (port + IMR, 0);
+
+ while (1)
+ {
+ unsigned char startpage, currpage;
+ unsigned short len;
+ unsigned char next, cnt1, cnt2;
+ struct mbuf *m;
+ unsigned char *p;
+ int startaddr;
+ int toend;
+ struct ether_header *eh;
+ struct ne_ring hdr; /* ring buffer header */
+ int reset;
+
+ inport_byte (port + BNRY, startpage);
+
+ outport_byte (port + CMDR, MSK_PG1 | MSK_RD2);
+ inport_byte (port + CURR, currpage);
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RD2);
+
+ ++startpage;
+ if (startpage >= NE_STOP_PAGE)
+ startpage = NE_FIRST_RX_PAGE;
+
+ if (startpage == currpage)
+ break;
+
+#ifdef DEBUG_NE2000
+ printk ("ne_rx_daemon: start page %x; current page %x\n",
+ startpage, currpage);
+#endif
+
+ reset = 0;
+
+ /* Read the buffer header */
+ startaddr = startpage * NE_PAGE_SIZE;
+ ne_read_data(sc, startaddr, sizeof(hdr), (unsigned char *)&hdr);
+ next = hdr.next;
+ if (next >= NE_STOP_PAGE)
+ next = NE_FIRST_RX_PAGE;
+
+ /* check packet length */
+ len = ( hdr.cnt_hi << 8 ) | hdr.cnt_lo;
+ if (currpage < startpage)
+ cnt1 = currpage + (NE_STOP_PAGE - NE_FIRST_RX_PAGE) - startpage;
+ else
+ cnt1 = currpage - startpage;
+ cnt2 = len / NE_PAGE_SIZE;
+ if (len % NE_PAGE_SIZE)
+ cnt2++;
+ if (cnt1 < cnt2)
+ {
+#ifdef DEBUG_NE
+ printk("(%x<%x:%x)", cnt1, cnt2, len);
+/*
+ printk("start page 0x%x; current page 0x%x\n",
+ startpage, currpage);
+ printk("cnt1 < cnt2 (0x%x, 0x%x); len 0x%x\n",
+ cnt1, cnt2, len);
+*/
+#endif
+ reset = 1;
+ }
+ if (len > (ETHER_MAX_LEN - ETHER_CRC_LEN + sizeof(struct ne_ring)) ||
+ len < (ETHER_MIN_LEN - ETHER_CRC_LEN + sizeof(struct ne_ring)) ||
+ len > MCLBYTES)
+ {
+#ifdef DEBUG_NE
+ printk("(%x)", len);
+/*
+ printk("start page 0x%x; current page 0x%x\n",
+ startpage, currpage);
+ printk("len out of range: 0x%x\n", len);
+ printk("stat: 0x%x, next: 0x%x\n", hdr.rsr, hdr.next);
+*/
+#endif
+ reset = 1;
+ }
+#ifdef DEBUG_NE
+ if (++ccc == 100)
+ { ccc = 0; reset = 1;
+ printk("T");
+ }
+#endif
+
+ /* reset interface */
+ if (reset)
+ {
+ ne_reset(sc);
+ goto Next;
+ }
+
+ /* The first four bytes of the length are the buffer header. */
+ len -= sizeof(struct ne_ring);
+ startaddr += sizeof(struct ne_ring);
+
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+
+ p = mtod (m, unsigned char *);
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+
+ toend = NE_STOP_PAGE * NE_PAGE_SIZE - startaddr;
+ if (toend < len)
+ {
+ ne_read_data (sc, startaddr, toend, p);
+ p += toend;
+ len -= toend;
+ startaddr = NE_FIRST_RX_PAGE * NE_PAGE_SIZE;
+ }
+
+ if (len > 0)
+ ne_read_data (sc, startaddr, len, p);
+
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof (struct ether_header);
+
+#ifdef DEBUG_NE
+ /* printk("[r%d]", ((hdr.cnt_hi<<8) + hdr.cnt_lo - sizeof(hdr))); */
+ printk("<");
+#endif
+ ether_input (ifp, eh, m);
+ ++sc->stats.rx_packets;
+
+ outport_byte (port + BNRY, next - 1);
+ }
+
+ if (sc->overrun) {
+ outport_byte (port + ISR, MSK_OVW);
+ outport_byte (port + TCR, 0);
+ if (sc->resend)
+ outport_byte (port + CMDR, MSK_PG0 | MSK_TXP | MSK_RD2 | MSK_STA);
+ sc->resend = 0;
+ sc->overrun = 0;
+ }
+
+ Next:
+ /* Reenable device interrupts. */
+ outport_byte (port + IMR, NE_INTERRUPTS);
+ }
+}
+
+/* Load an NE2000 packet onto the device. */
+
+static void
+ne_loadpacket (struct ne_softc *sc, struct mbuf *m)
+{
+ unsigned int port = sc->port;
+ unsigned int dport = port + DATAPORT;
+ struct mbuf *mhold = m;
+ int leftover;
+ unsigned char leftover_data;
+ int timeout;
+ int send_cnt = 0;
+
+#ifdef DEBUG_NE2000
+ printk ("Uploading NE2000 packet\n");
+#endif
+
+ /* Reset remote DMA complete flag. */
+ outport_byte (port + ISR, MSK_RDC);
+
+ /* Write out the count. */
+ outport_byte (port + RBCR0, m->m_pkthdr.len);
+ outport_byte (port + RBCR1, m->m_pkthdr.len >> 8);
+
+ sc->sendlen[sc->nextavail] = m->m_pkthdr.len;
+
+ /* Tell the device which address we want to write to. */
+ outport_byte (port + RSAR0, 0);
+ outport_byte (port + RSAR1,
+ NE_FIRST_TX_PAGE + (sc->nextavail * NE_TX_PAGES));
+
+ /* Set up the write. */
+ outport_byte (port + CMDR, MSK_PG0 | MSK_RWR | MSK_STA);
+
+ /* Transfer the mbuf chain to device memory. NE2000 devices require
+ that the data be transferred as words, so we need to handle odd
+ length mbufs. Never occurs if we force byte transfers. */
+
+ leftover = 0;
+ leftover_data = '\0';
+
+ for (; m != NULL; m = m->m_next) {
+ int len;
+ unsigned char *data;
+
+ len = m->m_len;
+ if (len == 0)
+ continue;
+
+ data = mtod (m, unsigned char *);
+
+ if (leftover) {
+ unsigned char next;
+
+ /* Data left over from previous mbuf in chain. */
+ next = *data++;
+ --len;
+ outport_word (dport, leftover_data | (next << 8));
+ send_cnt += 2;
+ leftover = 0;
+ }
+
+ /* If using byte transfers, len always ends up as zero so
+ there are no leftovers. */
+
+ if (sc->byte_transfers)
+ while (len > 0) {
+ outport_byte (dport, *data++);
+ len--;
+ }
+ else
+ while (len > 1) {
+ outport_word (dport, data[0] | (data[1] << 8));
+ data += 2;
+ len -= 2;
+ send_cnt += 2;
+ }
+
+ if (len > 0)
+ {
+ leftover = 1;
+ leftover_data = *data++;
+ }
+ }
+
+ if (leftover)
+ {
+ outport_word (dport, leftover_data);
+ send_cnt += 2;
+ }
+
+#ifdef DEBUG_NE
+ /* printk("{l%d|%d}", send_cnt, sc->nextavail); */
+ printk("v");
+#endif
+ m_freem (mhold);
+
+ /* Wait for the device to complete accepting the data, with a
+ limiting counter so that we don't wait too long. */
+ for (timeout = 0; timeout < 100; ++timeout)
+ {
+ unsigned char status;
+
+ inport_byte (port + ISR, status);
+
+#ifdef DEBUG_NE2000
+ if ((status &~ MSK_RDC) != 0)
+ printk ("Status 0x%x while waiting for acknowledgement of uploaded packet\n",
+ status);
+#endif
+
+ if ((status & MSK_RDC) != 0) {
+ outport_byte (port + ISR, MSK_RDC);
+ break;
+ }
+ }
+
+ if (timeout >= 100)
+ printk ("Timed out waiting for acknowledgement of uploaded NE2000 packet\n");
+
+ ++sc->nextavail;
+ if (sc->nextavail == NE_TX_BUFS)
+ sc->nextavail = 0;
+}
+
+/* Tell the NE2000 to transmit a buffer whose contents we have already
+ loaded onto the device. */
+
+static void
+ne_transmit (struct ne_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int port = sc->port;
+ int len;
+
+#ifdef DEBUG_NE2000
+ printk ("Transmitting NE2000 packet\n");
+#endif
+
+ len = sc->sendlen[sc->nextsend];
+ if (len < ET_MINLEN)
+ len = ET_MINLEN;
+ outport_byte (port + TBCR0, len);
+ outport_byte (port + TBCR1, len >> 8);
+
+ outport_byte (port + TPSR, NE_FIRST_TX_PAGE + (sc->nextsend * NE_TX_PAGES));
+
+ outport_byte (port + CMDR, MSK_PG0 | MSK_TXP | MSK_RD2 | MSK_STA);
+
+#ifdef DEBUG_NE
+ /* printk("{s%d|%d}", len, sc->nextsend); */
+ printk(">");
+#endif
+ ++sc->nextsend;
+ if (sc->nextsend == NE_TX_BUFS)
+ sc->nextsend = 0;
+
+ ++sc->stats.tx_packets;
+
+ /* set watchdog timer */
+ ifp->if_timer = 2;
+}
+
+/* The NE2000 packet transmit daemon. This task is started when the
+ NE2000 driver is initialized. */
+
+static void
+ne_tx_daemon (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ unsigned int port = sc->port;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ while (1) {
+ rtems_event_set events;
+
+ /* Wait for a packet to be ready for sending, or for there to be
+ room for another packet in the device memory. */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+#ifdef DEBUG_NE2000
+ printk ("ne_tx_daemon\n");
+#endif
+
+ /* This daemon handles both uploading data onto the device and
+ telling the device to transmit data which has been uploaded.
+ These are separate tasks, because while the device is
+ transmitting one buffer we will upload another. */
+
+ /* Don't let the device interrupt us now. */
+ outport_byte (port + IMR, 0);
+
+ while (1) {
+ struct mbuf *m;
+
+ /* If the device is not transmitting a packet, and we have
+ uploaded a packet, tell the device to transmit it. */
+ if (! sc->transmitting && sc->inuse > 0) {
+ sc->transmitting = 1;
+ ne_transmit (sc);
+ }
+
+ /* If we don't have any more buffers to send, quit now. */
+ if (ifp->if_snd.ifq_head == NULL) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ break;
+ }
+
+ /* Allocate a buffer to load data into. If there are none
+ available, quit until a buffer has been transmitted. */
+ if (sc->inuse >= NE_TX_BUFS)
+ break;
+
+ ++sc->inuse;
+
+ IF_DEQUEUE (&ifp->if_snd, m);
+ if (m == NULL)
+ panic ("ne_tx_daemon");
+
+ ne_loadpacket (sc, m);
+
+ /* Check the device status. It may have finished transmitting
+ the last packet. */
+ ne_check_status(sc, 0);
+ }
+
+ /* Reenable device interrupts. */
+ outport_byte (port + IMR, NE_INTERRUPTS);
+ }
+}
+
+/* Start sending an NE2000 packet. */
+
+static void
+ne_start (struct ifnet *ifp)
+{
+ struct ne_softc *sc = ifp->if_softc;
+
+#ifdef DEBUG_NE
+ printk("S");
+#endif
+ /* Tell the transmit daemon to wake up and send a packet. */
+ rtems_bsdnet_event_send (sc->tx_daemon_tid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/* Initialize and start and NE2000. */
+
+static void
+ne_init (void *arg)
+{
+ struct ne_softc *sc = (struct ne_softc *) arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+#ifdef DEBUG_NE
+ printk("ne_init()\n");
+ ne_dump(sc);
+#endif
+
+ /* only once... */
+ if (sc->tx_daemon_tid == 0)
+ {
+ sc->inuse = 0;
+ sc->nextavail = 0;
+ sc->nextsend = 0;
+ sc->transmitting = 0;
+
+ ne_init_hardware (sc);
+
+ sc->tx_daemon_tid = rtems_bsdnet_newproc ("SCtx", 4096, ne_tx_daemon, sc);
+ sc->rx_daemon_tid = rtems_bsdnet_newproc ("SCrx", 4096, ne_rx_daemon, sc);
+
+ /* install rtems irq handler */
+ ne_init_irq_handler(sc->irno);
+ }
+
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+/* Stop an NE2000. */
+
+static void
+ne_stop (struct ne_softc *sc)
+{
+ sc->arpcom.ac_if.if_flags &= ~IFF_RUNNING;
+
+ ne_stop_hardware(sc);
+
+ sc->inuse = 0;
+ sc->nextavail = 0;
+ sc->nextsend = 0;
+ sc->transmitting = 0;
+ sc->overrun = 0;
+ sc->resend = 0;
+}
+
+static void
+ne_stop_hardware (struct ne_softc *sc)
+{
+ unsigned int port = sc->port;
+ int i;
+
+ /* Stop everything. */
+ outport_byte (port + CMDR, MSK_STP | MSK_RD2);
+
+ /* Wait for the interface to stop, using I as a time limit. */
+ for (i = 0; i < 5000; ++i)
+ {
+ unsigned char status;
+
+ inport_byte (port + ISR, status);
+ if ((status & MSK_RST) != 0)
+ break;
+ }
+}
+
+/* reinitializing interface
+*/
+static void
+ne_reset(struct ne_softc *sc)
+{
+ ne_stop(sc);
+ ne_init_hardware(sc);
+ sc->arpcom.ac_if.if_flags |= IFF_RUNNING;
+ sc->arpcom.ac_if.if_flags &= ~IFF_OACTIVE;
+#ifdef DEBUG_NE
+ printk("*");
+#endif
+}
+
+#ifdef DEBUG_NE
+/* show anything about ne
+*/
+static void
+ne_dump(struct ne_softc *sc)
+{
+ int i;
+ printk("\nne configuration:\n");
+ printk("ethernet addr:");
+ for (i=0; i<ETHER_ADDR_LEN; i++)
+ printk(" %x", sc->arpcom.ac_enaddr[i]);
+ printk("\n");
+ printk("irq = %d\n", sc->irno);
+ printk("port = 0x%x\n", sc->port);
+ printk("accept_broadcasts = %d\n", sc->accept_broadcasts);
+ printk("byte_transfers = %d\n", sc->byte_transfers);
+}
+#endif
+
+/* Show NE2000 interface statistics. */
+
+static void
+ne_stats (struct ne_softc *sc)
+{
+ printf (" Received packets: %-8lu", sc->stats.rx_packets);
+ printf (" Transmitted packets: %-8lu\n", sc->stats.tx_packets);
+ printf (" Receive acks: %-8lu", sc->stats.rx_acks);
+ printf (" Transmit acks: %-8lu\n", sc->stats.tx_acks);
+ printf (" Packet overruns: %-8lu", sc->stats.overruns);
+ printf (" Frame errors: %-8lu\n", sc->stats.rx_frame_errors);
+ printf (" CRC errors: %-8lu", sc->stats.rx_crc_errors);
+ printf (" Missed packets: %-8lu\n", sc->stats.rx_missed_errors);
+ printf (" Interrupts: %-8lu\n", sc->stats.interrupts);
+}
+
+static int ne_set_multicast_filter(struct ne_softc* sc)
+{
+ int i=0;
+ unsigned int port = sc->port;
+ unsigned char cmd = 0;
+
+ /* Save CMDR settings */
+ inport_byte(port + CMDR, cmd);
+ /* Change to page 1 */
+ outport_byte(port + CMDR, cmd | MSK_PG1);
+
+ /* Set MAR to accept _all_ multicast packets */
+ for (i = 0; i < MARsize; ++i) {
+ outport_byte (port + MAR + i, 0xFF);
+ }
+
+ /* Revert to original CMDR settings */
+ outport_byte(port + CMDR, cmd);
+
+ return 0;
+}
+
+/* NE2000 driver ioctl handler. */
+
+static int
+ne_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct ne_softc *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ error = ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ ne_stop (sc);
+ break;
+
+ case IFF_UP:
+ ne_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ ne_stop (sc);
+ ne_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ {
+ struct ifreq* ifr = (struct ifreq*) data;
+ error = (command == SIOCADDMULTI ?
+ ether_addmulti(ifr, &(sc->arpcom)) :
+ ether_delmulti(ifr, &(sc->arpcom)) );
+ /* ENETRESET indicates that driver should update its multicast filters */
+ if(error == ENETRESET) {
+ error = ne_set_multicast_filter(sc);
+ }
+ break;
+ }
+
+ case SIO_RTEMS_SHOW_STATS:
+ ne_stats (sc);
+ break;
+
+ default:
+ error = EINVAL;
+ break;
+ }
+
+ return error;
+}
+
+/*
+ * Device timeout/watchdog routine. Entered if the device neglects to
+ * generate an interrupt after a transmit has been started on it.
+ */
+static void
+ne_watchdog(struct ifnet *ifp)
+{
+ struct ne_softc *sc = ifp->if_softc;
+
+ printk("ne2000: device timeout\n");
+ ifp->if_oerrors++;
+
+ ne_reset(sc);
+}
+
+static void
+print_byte(unsigned char b)
+{
+ printk("%x%x", b >> 4, b & 0x0f);
+}
+
+/* Attach an NE2000 driver to the system. */
+
+int
+rtems_ne_driver_attach (struct rtems_bsdnet_ifconfig *config, int attach)
+{
+ int i;
+ struct ne_softc *sc;
+ struct ifnet *ifp;
+ int mtu;
+
+ /* dettach ... */
+ if (!attach)
+ return 0;
+
+ /* Find a free driver. */
+ sc = NULL;
+ for (i = 0; i < NNEDRIVER; ++i) {
+ sc = &ne_softc[i];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc == NULL)
+ break;
+ }
+
+ if (sc == NULL) {
+ printf ("Too many NE2000 drivers.\n");
+ return 0;
+ }
+
+ memset (sc, 0, sizeof *sc);
+
+ /* Check whether we do byte-wide or word-wide transfers. */
+
+#ifdef NE2000_BYTE_TRANSFERS
+ sc->byte_transfers = true;
+#else
+ sc->byte_transfers = false;
+#endif
+
+ /* Handle the options passed in by the caller. */
+
+ if (config->mtu != 0)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ if (config->irno != 0)
+ sc->irno = config->irno;
+ else {
+ const char* opt;
+ opt = bsp_cmdline_arg ("--ne2k-irq=");
+ if (opt) {
+ opt += sizeof ("--ne2k-irq=") - 1;
+ sc->irno = strtoul (opt, 0, 0);
+ }
+ if (sc->irno == 0) {
+ /* We use 5 as the default IRQ. */
+ sc->irno = 5;
+ }
+ }
+
+ if (config->port != 0)
+ sc->port = config->port;
+ else {
+ const char* opt;
+ opt = bsp_cmdline_arg ("--ne2k-port=");
+ if (opt) {
+ opt += sizeof ("--ne2k-port=") - 1;
+ sc->port = strtoul (opt, 0, 0);
+ }
+ if (config->port == 0) {
+ /* We use 0x300 as the default IO port number. */
+ sc->port = 0x300;
+ }
+ }
+
+ sc->accept_broadcasts = ! config->ignore_broadcast;
+
+ if (config->hardware_address != NULL)
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address,
+ ETHER_ADDR_LEN);
+ else
+ {
+ unsigned char prom[16];
+ int ia;
+
+ /* Read the PROM to get the Ethernet hardware address. */
+
+ outport_byte (sc->port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ if (sc->byte_transfers) {
+ outport_byte (sc->port + DCR, MSK_FT10 | MSK_BMS);
+ }
+ else {
+ outport_byte (sc->port + DCR, MSK_FT10 | MSK_BMS | MSK_WTS);
+ }
+
+ outport_byte (sc->port + RBCR0, 0);
+ outport_byte (sc->port + RBCR1, 0);
+ outport_byte (sc->port + RCR, MSK_MON);
+ outport_byte (sc->port + TCR, MSK_LOOP);
+ outport_byte (sc->port + IMR, 0);
+ outport_byte (sc->port + ISR, 0xff);
+
+ ne_read_data (sc, 0, sizeof prom, prom);
+
+ outport_byte (sc->port + CMDR, MSK_PG0 | MSK_RD2 | MSK_STP);
+
+ for (ia = 0; ia < ETHER_ADDR_LEN; ++ia)
+ sc->arpcom.ac_enaddr[ia] = prom[ia * 2];
+ }
+
+ /* Set up the network interface. */
+
+ ifp->if_softc = sc;
+ ifp->if_unit = i + 1;
+ ifp->if_name = "ne";
+ ifp->if_mtu = mtu;
+ ifp->if_init = ne_init;
+ ifp->if_ioctl = ne_ioctl;
+ ifp->if_watchdog = ne_watchdog;
+ ifp->if_start = ne_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /* Attach the interface. */
+
+ if_attach (ifp);
+ ether_ifattach (ifp);
+
+ printk("network device '%s' <", config->name);
+ print_byte(sc->arpcom.ac_enaddr[0]);
+ for (i=1; i<ETHER_ADDR_LEN; i++)
+ { printk(":");
+ print_byte(sc->arpcom.ac_enaddr[i]);
+ }
+ printk("> initialized on port 0x%x, irq %d\n", sc->port, sc->irno);
+
+ return 1;
+}
diff --git a/bsps/i386/pc386/net/wd8003.c b/bsps/i386/pc386/net/wd8003.c
new file mode 100644
index 0000000..f455bcc
--- /dev/null
+++ b/bsps/i386/pc386/net/wd8003.c
@@ -0,0 +1,647 @@
+/*
+ * RTEMS driver for WD800x
+ *
+ * Based on the 68360 Network Driver by:
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/wd80x3.h>
+
+#include <stdio.h>
+#include <stdarg.h>
+#include <string.h> /* memcpy, memset */
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <assert.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <bsp/irq.h>
+
+#define ET_MINLEN 60 /* minimum message length */
+
+/*
+ * Number of WDs supported by this driver
+ */
+#define NWDDRIVER 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 15
+#define TX_BUF_COUNT 4
+#define TX_BD_PER_BUF 4
+
+/*
+ * RTEMS event used by interrupt handler to signal driver tasks.
+ * This must not be any of the events used by the network task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet including CRC
+ */
+#define RBUF_SIZE 1520
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+/*
+ * Per-device data
+ */
+struct wd_softc {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+ rtems_vector_number name;
+
+ unsigned int port;
+ unsigned char *base;
+ unsigned long bpar;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxRunt;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txHeartbeat;
+ unsigned long txLateCollision;
+ unsigned long txRetryLimit;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+};
+
+#define RO 0x10
+
+#define SHATOT (8*1024) /* size of shared memory */
+#define SHAPAGE 256 /* shared memory information */
+#define MAXSIZ 1536 /*(MAXBUF - MESSH_SZ)*/
+#define OUTPAGE ((SHATOT-(MAXSIZ+SHAPAGE-1))/SHAPAGE)
+
+static volatile unsigned long overrun;
+static volatile unsigned long resend;
+static struct wd_softc wd_softc[NWDDRIVER];
+
+/*
+ * WD interrupt handler
+ */
+static void
+wd8003Enet_interrupt_handler (void * unused)
+{
+ unsigned int tport;
+ unsigned char status, status2;
+
+ tport = wd_softc[0].port ;
+
+ /*
+ * Read status
+ */
+ inport_byte(tport+ISR, status);
+ outport_byte(tport+IMR, 0x00);
+
+ /*
+ * Ring overwrite
+ */
+
+ if (status & MSK_OVW){
+ outport_byte(tport+CMDR, MSK_STP + MSK_RD2); /* stop 8390 */
+ Wait_X_ms(2);
+ outport_byte(tport+RBCR0, 0); /* clear byte count */
+ outport_byte(tport+RBCR1, 0);
+ inport_byte(tport+ISR, status2);
+ status |= (status2 & (MSK_PTX+MSK_TXE)) ; /* TX status */
+ outport_byte(tport+TCR, MSK_LOOP); /* loopback mode */
+ outport_byte(tport+CMDR, MSK_STA + MSK_RD2); /* start */
+ overrun = 1 ;
+ if ((status & (MSK_PTX+MSK_TXE)) == 0)
+ resend = 1;
+ }
+
+ /*
+ * Frame received?
+ */
+ if (status & (MSK_PRX+MSK_RXE)) {
+ outport_byte(tport+ISR, status & (MSK_PRX+MSK_RXE));
+ wd_softc[0].rxInterrupts++;
+ rtems_bsdnet_event_send (wd_softc[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+
+}
+
+/*
+ * Initialize the ethernet hardware
+ */
+static void
+wd8003Enet_initialize_hardware (struct wd_softc *sc)
+{
+ int i1, ultra;
+ char cc1, cc2;
+ unsigned char temp;
+ rtems_status_code status;
+ unsigned int tport;
+ unsigned char *hwaddr;
+
+ tport = sc->port;
+
+ /* address from board ROM */
+ inport_byte(tport+0x04, temp);
+ outport_byte(tport+0x04, temp & 0x7f);
+
+ hwaddr = sc->arpcom.ac_enaddr;
+ for (i1=cc2=0; i1<8; i1++) {
+ inport_byte(tport + ADDROM + i1, cc1);
+ cc2 += cc1;
+ if (i1 < 6)
+ hwaddr[i1] = cc1;
+ }
+
+ inport_byte(tport+0x04, temp);
+ outport_byte(tport+0x04, temp | 0x80); /* alternate registers */
+ outport_byte(tport+W83CREG, MSK_RESET); /* reset board, set buffer */
+ outport_byte(tport+W83CREG, 0);
+ outport_byte(tport+W83CREG, MSK_ENASH + (int)((sc->bpar>>13)&0x3f));
+
+ outport_byte(tport+CMDR, MSK_PG0 + MSK_RD2);
+ cc1 = MSK_BMS + MSK_FT10; /* configure 8 or 16 bits */
+
+ inport_byte(tport+0x07, temp) ;
+
+ ultra = ((temp & 0xf0) == 0x20 || (temp & 0xf0) == 0x40);
+ if (ultra)
+ cc1 = MSK_WTS + MSK_BMS + MSK_FT10;
+ outport_byte(tport+DCR, cc1);
+ outport_byte(tport+RBCR0, 0);
+ outport_byte(tport+RBCR1, 0);
+ outport_byte(tport+RCR, MSK_MON); /* disable the rxer */
+ outport_byte(tport+TCR, 0); /* normal operation */
+ outport_byte(tport+PSTOP, OUTPAGE); /* init PSTOP */
+ outport_byte(tport+PSTART, 0); /* init PSTART */
+ outport_byte(tport+BNRY, -1); /* init BNRY */
+ outport_byte(tport+ISR, -1); /* clear IR's */
+ outport_byte(tport+IMR, 0x15); /* enable interrupt */
+
+ outport_byte(tport+CMDR, MSK_PG1 + MSK_RD2);
+
+ for (i1=0; i1<6; i1++) /* initial physical addr */
+ outport_byte(tport+PAR+i1, hwaddr[i1]);
+
+ for (i1=0; i1<MARsize; i1++) /* clear multicast */
+ outport_byte(tport+MAR+i1, 0);
+ outport_byte(tport+CURR, 0); /* init current packet */
+
+ outport_byte(tport+CMDR, MSK_PG0 + MSK_RD2);
+ outport_byte(tport+CMDR, MSK_STA + MSK_RD2); /* put 8390 on line */
+ outport_byte(tport+RCR, MSK_AB); /* MSK_AB accept broadcast */
+
+ if (ultra) {
+ inport_byte(tport+0x0c, temp);
+ outport_byte(tport+0x0c, temp | 0x80);
+ outport_byte(tport+0x05, 0x80);
+ outport_byte(tport+0x06, 0x01);
+ }
+
+ /*
+ * Set up interrupts
+ */
+
+ status = rtems_interrupt_handler_install(
+ sc->name,
+ "wd8003",
+ RTEMS_INTERRUPT_UNIQUE,
+ wd8003Enet_interrupt_handler,
+ NULL
+ );
+ assert(status == RTEMS_SUCCESSFUL);
+}
+
+static void
+wd_rxDaemon (void *arg)
+{
+ unsigned int tport;
+ struct ether_header *eh;
+ struct wd_softc *dp = (struct wd_softc *)&wd_softc[0];
+ struct ifnet *ifp = &dp->arpcom.ac_if;
+ struct mbuf *m;
+ unsigned int i2;
+ unsigned int len;
+ volatile unsigned char start, next, current;
+ unsigned char *shp, *temp;
+ unsigned short *real_short_ptr;
+ rtems_event_set events;
+
+ tport = wd_softc[0].port ;
+
+ for (;;){
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ for (;;){
+ inport_byte(tport+BNRY, start);
+
+ outport_byte(tport+CMDR, MSK_PG1 + MSK_RD2);
+ inport_byte(tport+CURR, current);
+ outport_byte(tport+CMDR, MSK_PG0 + MSK_RD2);
+
+ start += 1;
+ if (start >= OUTPAGE){
+ start = 0;
+ }
+
+ if (current == start)
+ break;
+
+ /* real_short_ptr avoids cast on lvalue which gcc no longer allows */
+ shp = dp->base + 1 + (SHAPAGE * start);
+ next = *shp++;
+ real_short_ptr = (unsigned short *)shp;
+ len = *(real_short_ptr)++ - 4;
+
+ if (next >= OUTPAGE){
+ next = 0;
+ }
+
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+
+ temp = (unsigned char *) m->m_data;
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+
+ if ((i2 = (OUTPAGE - start) * SHAPAGE - 4) < len){
+ memcpy(temp, shp, i2);
+ len -= i2;
+ temp += i2;
+ shp = dp->base;
+ }
+ memcpy(temp, shp, len);
+
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ outport_byte(tport+BNRY, next-1);
+ }
+
+ /*
+ * Ring overwrite
+ */
+ if (overrun){
+ outport_byte(tport+ISR, MSK_OVW); /* reset IR */
+ outport_byte(tport+TCR, 0); /* out of loopback */
+ if (resend == 1)
+ outport_byte(tport+CMDR, MSK_TXP + MSK_RD2); /* resend */
+ resend = 0;
+ overrun = 0;
+ }
+
+ outport_byte(tport+IMR, 0x15); /* re-enable IT rx */
+ }
+}
+
+static void
+sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct wd_softc *dp = ifp->if_softc;
+ struct mbuf *n;
+ unsigned int len, tport;
+ uint8_t *shp, txReady;
+
+ tport = dp->port;
+
+ /*
+ * Waiting for Transmitter ready
+ */
+ inport_byte(tport+CMDR, txReady);
+ while(txReady & MSK_TXP)
+ inport_byte(tport+CMDR, txReady);
+
+ len = 0;
+ shp = dp->base + (SHAPAGE * OUTPAGE);
+
+ n = m;
+
+ for (;;){
+ len += m->m_len;
+ memcpy(shp, (char *)m->m_data, m->m_len);
+ shp += m->m_len ;
+ if ((m = m->m_next) == NULL)
+ break;
+ }
+
+ m_freem(n);
+
+ if (len < ET_MINLEN) len = ET_MINLEN;
+ outport_byte(tport+TBCR0, len);
+ outport_byte(tport+TBCR1, (len >> 8) );
+ outport_byte(tport+TPSR, OUTPAGE);
+ outport_byte(tport+CMDR, MSK_TXP + MSK_RD2);
+}
+
+/*
+ * Driver transmit daemon
+ */
+static void
+wd_txDaemon (void *arg)
+{
+ struct wd_softc *sc = (struct wd_softc *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT, RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+wd_start (struct ifnet *ifp)
+{
+ struct wd_softc *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/*
+ * Initialize and start the device
+ */
+static void
+wd_init (void *arg)
+{
+ struct wd_softc *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up WD hardware
+ */
+ wd8003Enet_initialize_hardware (sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("SCtx", 4096, wd_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("SCrx", 4096, wd_rxDaemon, sc);
+ }
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+}
+
+/*
+ * Stop the device
+ */
+static void
+wd_stop (struct wd_softc *sc)
+{
+ unsigned int tport;
+ unsigned char temp;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Stop the transmitter
+ */
+ tport=wd_softc[0].port ;
+ inport_byte(tport+0x04,temp);
+ outport_byte(tport+0x04, temp & 0x7f);
+ outport_byte(tport + CMDR, MSK_STP + MSK_RD2);
+
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+wd_stats (struct wd_softc *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Not First:%-8lu", sc->rxNotFirst);
+ printf (" Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Runt:%-8lu", sc->rxRunt);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" Collision:%-8lu\n", sc->rxCollision);
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" Deferred:%-8lu", sc->txDeferred);
+ printf (" Missed Hearbeat:%-8lu\n", sc->txHeartbeat);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf ("Retransmit Limit:%-8lu", sc->txRetryLimit);
+ printf (" Late Collision:%-8lu\n", sc->txLateCollision);
+ printf (" Underrun:%-8lu", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+/*
+ * Driver ioctl handler
+ */
+static int
+wd_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct wd_softc *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ wd_stop (sc);
+ break;
+
+ case IFF_UP:
+ wd_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ wd_stop (sc);
+ wd_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ wd_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/*
+ * Attach an WD driver to the system
+ */
+int
+rtems_wd_driver_attach (struct rtems_bsdnet_ifconfig *config, int attach)
+{
+ struct wd_softc *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int i;
+
+ /*
+ * Find a free driver
+ */
+ for (i = 0 ; i < NWDDRIVER ; i++) {
+ sc = &wd_softc[i];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc == NULL)
+ break;
+ }
+ if (i >= NWDDRIVER) {
+ printf ("Too many WD drivers.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address) {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address,
+ ETHER_ADDR_LEN);
+ }
+ else {
+ memset (sc->arpcom.ac_enaddr, 0x08,ETHER_ADDR_LEN);
+ }
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ if (config->irno)
+ sc->name = config->irno;
+ else
+ sc->name = 5;
+
+ if (config->port)
+ sc->port = config->port;
+ else
+ sc->port = 0x240;
+
+ if (config->bpar) {
+ sc->bpar = config->bpar;
+ sc->base = (unsigned char*) config->bpar;
+ }
+ else {
+ sc->bpar = 0xD0000;
+ sc->base = (unsigned char*) 0xD0000;
+ }
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = i + 1;
+ ifp->if_name = "wd";
+ ifp->if_mtu = mtu;
+ ifp->if_init = wd_init;
+ ifp->if_ioctl = wd_ioctl;
+ ifp->if_start = wd_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * init some variables
+ */
+ overrun = 0;
+ resend = 0;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+};
diff --git a/bsps/include/libchip/cs8900.h b/bsps/include/libchip/cs8900.h
new file mode 100644
index 0000000..79c9438
--- /dev/null
+++ b/bsps/include/libchip/cs8900.h
@@ -0,0 +1,761 @@
+/*
+ ------------------------------------------------------------------------
+
+ Copyright Cybertec Pty Ltd, 2000
+ All rights reserved Cybertec Pty Ltd, 2000
+
+ Port to the DIMM PC copyright (c) 2004 Angelo Fraietta
+ This project has been assisted by the Commonwealth Government
+ through the Australia Council, its arts funding and advisory body.
+
+ COPYRIGHT (c) 1989-1998.
+ On-Line Applications Research Corporation (OAR).
+
+ The license and distribution terms for this file may be
+ found in the file LICENSE in this distribution or at
+ http://www.rtems.org/license/LICENSE.
+
+ ------------------------------------------------------------------------
+
+ CS8900 RTEMS driver.
+
+ This is a generic driver that requires a BSP backend. The BSP backend
+ provides the glue to the specific bus for the target hardware. It has
+ been tested with Coldfire processors, and the PC. These targets have
+ completely different bus, byte order and interrupt structures.
+
+ An example BSP backend is provided in the pci386 BSP.
+
+ The BSP provides the following functions:
+
+ cs8900_io_set_reg
+ cs8900_io_get_reg
+ cs8900_mem_set_reg
+ cs8900_mem_get_reg
+ cs8900_put_data_block
+ cs8900_get_data_block
+ cs8900_tx_load
+ cs8900_attach_interrupt
+ cs8900_detach_interrupt
+
+ The header file provides documentation for these functions. There
+ are four types of functions.
+
+ The I/O set/get functions access the CS8900 I/O registers via the
+ I/O Mode. For example on a PC with an ISA bus you would use the
+ IA32 in/out port instructions. The cs8900_device structure passed
+ to these functions provide these functions with the I/O base
+ address. The BSP must provide these functions.
+
+ The Memory set/get functions access the CS8900 internal registers
+ and frame buffers directly from a 4K byte block of host memory.
+ Memory mode provides a faster access to the CS8900. The cs8900_device
+ structure passed to these functions provides the memory base
+ address. The BSP needs to provide these functions but they do not
+ need to be implemented if the mem_base field is set to 0. The
+ driver will use I/O mode only.
+
+ The Block transfer functions are used to read or write a block
+ of memory from the CS8900. This saves the driver making a number
+ of small calls. The BSP driver must know if I/O or Memory mode
+ can be used.
+
+ The final group of functions is to handle interrupts. The BSP
+ must take care of save and restoring any interrupt state
+ information.
+
+ The BSP declares a 'cs8900_device' structure for each device being
+ attached to the networking stack. It also creates a
+ 'struct rtems_bsdnet_ifconfig' which is used to attach the interface
+ to the networking stack. The following code declares the BSD config:
+
+ static cs8900_device cs8900;
+
+ static struct rtems_bsdnet_ifconfig cs8900_ifconfig =
+ {
+ "cs0",
+ cs8900_driver_attach,
+ NULL,
+ NULL,
+ NULL,
+ NULL,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0
+ };
+
+ The device linked to the BSD config structure with:
+
+ cs8900_ifconfig.drv_ctrl = &cs8900;
+
+ If you have a specific hardware address you should point the BSD
+ config structure to that address. If you do not the driver will read
+ the MAC address from the CS8900. This assumes the CS8900 has read
+ the address from an external EEPROM or has been setup by a BIOS or
+ boot monitor. For EEPROM less you need to supply the MAC address.
+
+ Set the I/O and Memory base addresses. If the Memory base address
+ is 0 the driver will use I/O mode only. A typical initialisation
+ looks like:
+
+ printf ("RTEMS BSD Network initialisation.\n");
+ rtems_bsdnet_initialize_network ();
+
+ #define ETHERNET_IO_BASE 0x300
+ #define ETHERNET_MEM_BASE 0
+ #define ETHERNET_IRQ_LEVEL 0
+
+ cs8900_device *cs = &cs8900;
+
+ memset (cs, 0, sizeof (cs8900_device));
+
+ cs->dev = 0;
+ cs->io_base = ETHERNET_IO_BASE;
+ cs->mem_base = ETHERNET_MEM_BASE;
+ cs->irq_level = ETHERNET_IRQ_LEVEL;
+ cs->rx_queue_size = 30;
+
+ cs8900_ifconfig.drv_ctrl = &cs8900;
+
+ printf ("CS8900 initialisation\n");
+
+ rtems_bsdnet_attach (&cs8900_ifconfig);
+
+ flags = IFF_UP;
+ if (rtems_bsdnet_ifconfig (cs8900_ifconfig.name,
+ SIOCSIFFLAGS,
+ &flags) < 0)
+ {
+ printf ("error: can't bring up %s: %s\n",
+ cs8900_ifconfig.name, strerror (errno));
+ return;
+ }
+
+ rtems_bsdnet_do_bootp_and_rootfs ();
+
+ The IRQ level is the one documented in the CS8900 datasheet and below
+ in the CS8900 device structure. You need to map your target IRQ to the
+ CS8900 in the BSP driver.
+
+ */
+
+#if !defined(_CS8900_H_)
+#define _CS8900_H_
+
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+/* #include <target.h> what does this provide? joel to chris */
+
+#define ET_MINLEN 60
+
+/*
+ * CS8900 device register definitions
+ */
+
+/*
+ * Crystal ESIA product id.
+ */
+
+#define CS8900_ESIA_ID (0x630e)
+
+/*
+ * IO Registers.
+ */
+
+#define CS8900_IO_RX_TX_DATA_PORT0 (0x0000)
+#define CS8900_IO_TX_TX_DATA_PORT1 (0x0002)
+#define CS8900_IO_TxCMD (0x0004)
+#define CS8900_IO_TxLength (0x0006)
+#define CS8900_IO_ISQ (0x0008)
+#define CS8900_IO_PACKET_PAGE_PTR (0x000a)
+#define CS8900_IO_PP_DATA_PORT0 (0x000c)
+#define CS8900_IO_PP_DATA_PORT1 (0x000e)
+
+/*
+ * Packet Page Registers.
+ */
+
+/*
+ * Bus Interface Registers.
+ */
+
+#define CS8900_PP_PROD_ID (0x0000)
+#define CS8900_PP_IO_BASE (0x0020)
+#define CS8900_PP_INT (0x0022)
+#define CS8900_PP_DMA_CHANNEL (0x0024)
+#define CS8900_PP_DMA_SOF (0x0026)
+#define CS8900_PP_DMA_FRM_CNT (0x0028)
+#define CS8900_PP_DMA_RX_BCNT (0x002a)
+#define CS8900_PP_MEM_BASE (0x002c)
+#define CS8900_PP_BPROM_BASE (0x0030)
+#define CS8900_PP_BPROM_AMASK (0x0034)
+#define CS8900_PP_EEPROM_CMD (0x0040)
+#define CS8900_PP_EEPROM_DATA (0x0042)
+#define CS8900_PP_RX_FRAME_BCNT (0x0050)
+
+/*
+ * Configuration and Control Registers.
+ */
+
+#define CS8900_PP_RxCFG (0x0102)
+#define CS8900_PP_RxCTL (0x0104)
+#define CS8900_PP_TxCFG (0x0106)
+#define CS8900_PP_TxCMD_READ (0x0108)
+#define CS8900_PP_BufCFG (0x010a)
+#define CS8900_PP_LineCFG (0x0112)
+#define CS8900_PP_SelfCTL (0x0114)
+#define CS8900_PP_BusCTL (0x0116)
+#define CS8900_PP_TestCTL (0x0118)
+
+/*
+ * Status and Event Registers.
+ */
+
+#define CS8900_PP_ISQ (0x0120)
+#define CS8900_PP_RxEvent (0x0124)
+#define CS8900_PP_TxEvent (0x0128)
+#define CS8900_PP_BufEvent (0x012c)
+#define CS8900_PP_RxMISS (0x0130)
+#define CS8900_PP_TxCol (0x0132)
+#define CS8900_PP_LineST (0x0134)
+#define CS8900_PP_SelfST (0x0136)
+#define CS8900_PP_BusST (0x0138)
+#define CS8900_PP_TDR (0x013c)
+
+/*
+ * Initiate Transmit Registers.
+ */
+
+#define CS8900_PP_TxCMD (0x0144)
+#define CS8900_PP_TxLength (0x0146)
+
+/*
+ * Address Filter Registers.
+ */
+
+#define CS8900_PP_LAF (0x0150)
+#define CS8900_PP_IA (0x0158)
+
+/*
+ * Frame Location.
+ */
+
+#define CS8900_PP_RxStatus (0x0400)
+#define CS8900_PP_RxLength (0x0402)
+#define CS8900_PP_RxFrameLoc (0x0404)
+#define CS8900_PP_TxFrameLoc (0x0a00)
+
+/*
+ * Bit Definitions of Registers.
+ */
+
+/*
+ * IO Packet Page Pointer.
+ */
+
+#define CS8900_PPP_AUTO_INCREMENT (0x8000)
+
+/*
+ * Reg 3. Receiver Configuration.
+ */
+
+#define CS8900_RX_CONFIG_SKIP_1 (1 << 6)
+#define CS8900_RX_CONFIG_STREAM_ENABLE (1 << 7)
+#define CS8900_RX_CONFIG_RX_OK (1 << 8)
+#define CS8900_RX_CONFIG_RX_DMA (1 << 9)
+#define CS8900_RX_CONFIG_RX_AUTO_DMA (1 << 10)
+#define CS8900_RX_CONFIG_BUFFER_CRC (1 << 11)
+#define CS8900_RX_CONFIG_CRC_ERROR (1 << 12)
+#define CS8900_RX_CONFIG_RUNT (1 << 13)
+#define CS8900_RX_CONFIG_EXTRA_DATA (1 << 14)
+
+/*
+ * Reg 4. Receiver Event.
+ */
+
+#define CS8900_RX_EVENT_HASH_IA_MATCH (1 << 6)
+#define CS8900_RX_EVENT_DRIBBLE_BITS (1 << 7)
+#define CS8900_RX_EVENT_RX_OK (1 << 8)
+#define CS8900_RX_EVENT_HASHED (1 << 9)
+#define CS8900_RX_EVENT_IA (1 << 10)
+#define CS8900_RX_EVENT_BROADCAST (1 << 11)
+#define CS8900_RX_EVENT_CRC_ERROR (1 << 12)
+#define CS8900_RX_EVENT_RUNT (1 << 13)
+#define CS8900_RX_EVENT_EXTRA_DATA (1 << 14)
+
+/*
+ * Reg 5. Receiver Control.
+ */
+
+#define CS8900_RX_CTRL_HASH_IA_MATCH (1 << 6)
+#define CS8900_RX_CTRL_PROMISCUOUS (1 << 7)
+#define CS8900_RX_CTRL_RX_OK (1 << 8)
+#define CS8900_RX_CTRL_MULTICAST (1 << 9)
+#define CS8900_RX_CTRL_INDIVIDUAL (1 << 10)
+#define CS8900_RX_CTRL_BROADCAST (1 << 11)
+#define CS8900_RX_CTRL_CRC_ERROR (1 << 12)
+#define CS8900_RX_CTRL_RUNT (1 << 13)
+#define CS8900_RX_CTRL_EXTRA_DATA (1 << 14)
+
+/*
+ * Reg 7. Transmit Configuration.
+ */
+
+#define CS8900_TX_CONFIG_LOSS_OF_CARRIER (1 << 6)
+#define CS8900_TX_CONFIG_SQ_ERROR (1 << 7)
+#define CS8900_TX_CONFIG_TX_OK (1 << 8)
+#define CS8900_TX_CONFIG_OUT_OF_WINDOW (1 << 9)
+#define CS8900_TX_CONFIG_JABBER (1 << 10)
+#define CS8900_TX_CONFIG_ANY_COLLISION (1 << 11)
+#define CS8900_TX_CONFIG_16_COLLISION (1 << 15)
+
+/*
+ * Reg 8. Transmit Event.
+ */
+
+#define CS8900_TX_EVENT_LOSS_OF_CARRIER (1 << 6)
+#define CS8900_TX_EVENT_SQ_ERROR (1 << 7)
+#define CS8900_TX_EVENT_TX_OK (1 << 8)
+#define CS8900_TX_EVENT_OUT_OF_WINDOW (1 << 9)
+#define CS8900_TX_EVENT_JABBER (1 << 10)
+#define CS8900_TX_EVENT_16_COLLISIONS (1 << 15)
+
+/*
+ * Reg 9. Transmit Command Status.
+ */
+
+#define CS8900_TX_CMD_STATUS_TX_START_5 (0 << 6)
+#define CS8900_TX_CMD_STATUS_TX_START_381 (1 << 6)
+#define CS8900_TX_CMD_STATUS_TX_START_1021 (2 << 6)
+#define CS8900_TX_CMD_STATUS_TX_START_ENTIRE (3 << 6)
+#define CS8900_TX_CMD_STATUS_FORCE (1 << 8)
+#define CS8900_TX_CMD_STATUS_ONE_COLLISION (1 << 9)
+#define CS8900_TX_CMD_STATUS_INHIBIT_CRC (1 << 12)
+#define CS8900_TX_CMD_STATUS_TX_PAD_DISABLED (1 << 13)
+
+/*
+ * Reg B. Buffer Configuration.
+ */
+
+#define CS8900_BUFFER_CONFIG_SW_INT (1 << 6)
+#define CS8900_BUFFER_CONFIG_RX_DMA_DONE (1 << 7)
+#define CS8900_BUFFER_CONFIG_RDY_FOR_TX (1 << 8)
+#define CS8900_BUFFER_CONFIG_TX_UNDERRUN (1 << 9)
+#define CS8900_BUFFER_CONFIG_RX_MISSED (1 << 10)
+#define CS8900_BUFFER_CONFIG_RX_128_BYTES (1 << 11)
+#define CS8900_BUFFER_CONFIG_TX_COL_OVF (1 << 12)
+#define CS8900_BUFFER_CONFIG_RX_MISSED_OVF (1 << 13)
+#define CS8900_BUFFER_CONFIG_RX_DEST_MATCH (1 << 15)
+
+/*
+ * Reg C. Buffer Event.
+ */
+
+#define CS8900_BUFFER_EVENT_SW_INT (1 << 6)
+#define CS8900_BUFFER_EVENT_RX_DMA_DONE (1 << 7)
+#define CS8900_BUFFER_EVENT_RDY_FOR_TX (1 << 8)
+#define CS8900_BUFFER_EVENT_TX_UNDERRUN (1 << 9)
+#define CS8900_BUFFER_EVENT_RX_MISSED (1 << 10)
+#define CS8900_BUFFER_EVENT_RX_128_BYTES (1 << 11)
+#define CS8900_BUFFER_EVENT_RX_DEST_MATCH (1 << 15)
+
+/*
+ * Reg 13. Line Control.
+ */
+
+#define CS8900_LINE_CTRL_RX_ON (1 << 6)
+#define CS8900_LINE_CTRL_TX_ON (1 << 7)
+#define CS8900_LINE_CTRL_AUI (1 << 8)
+#define CS8900_LINE_CTRL_10BASET (0 << 9)
+#define CS8900_LINE_CTRL_AUTO_AUI_10BASET (1 << 9)
+#define CS8900_LINE_CTRL_MOD_BACKOFF (1 << 11)
+#define CS8900_LINE_CTRL_POLARITY_DISABLED (1 << 12)
+#define CS8900_LINE_CTRL_2_PART_DEF_DISABLED (1 << 13)
+#define CS8900_LINE_CTRL_LO_RX_SQUELCH (1 << 14)
+
+/*
+ * Reg 14. Line Status.
+ */
+
+#define CS8900_LINE_STATUS_LINK_OK (1 << 7)
+#define CS8900_LINE_STATUS_AUI (1 << 8)
+#define CS8900_LINE_STATUS_10_BASE_T (1 << 9)
+#define CS8900_LINE_STATUS_POLARITY_OK (1 << 12)
+#define CS8900_LINE_STATUS_CRS (1 << 14)
+
+/*
+ * Reg 15. Self Control.
+ */
+
+#define CS8900_SELF_CTRL_RESET (1 << 6)
+#define CS8900_SELF_CTRL_SW_SUSPEND (1 << 8)
+#define CS8900_SELF_CTRL_HW_SLEEP (1 << 9)
+#define CS8900_SELF_CTRL_HW_STANDBY (1 << 10)
+#define CS8900_SELF_CTRL_HC0E (1 << 12)
+#define CS8900_SELF_CTRL_HC1E (1 << 13)
+#define CS8900_SELF_CTRL_HCB0 (1 << 14)
+#define CS8900_SELF_CTRL_HCB1 (1 << 15)
+
+/*
+ * Reg 16. Self Status.
+ */
+
+#define CS8900_SELF_STATUS_3_3_V (1 << 6)
+#define CS8900_SELF_STATUS_INITD (1 << 7)
+#define CS8900_SELF_STATUS_SIBUST (1 << 8)
+#define CS8900_SELF_STATUS_EEPROM_PRESENT (1 << 9)
+#define CS8900_SELF_STATUS_EEPROM_OK (1 << 10)
+#define CS8900_SELF_STATUS_EL_PRESENT (1 << 11)
+#define CS8900_SELF_STATUS_EE_SIZE (1 << 12)
+
+/*
+ * Reg 17. Bus Control.
+ */
+
+#define CS8900_BUS_CTRL_RESET_RX_DMA (1 << 6)
+#define CS8900_BUS_CTRL_USE_SA (1 << 9)
+#define CS8900_BUS_CTRL_MEMORY_ENABLE (1 << 10)
+#define CS8900_BUS_CTRL_DMA_BURST (1 << 11)
+#define CS8900_BUS_CTRL_IOCHRDYE (1 << 12)
+#define CS8900_BUS_CTRL_RX_DMA_SIZE (1 << 13)
+#define CS8900_BUS_CTRL_ENABLE_INT (1 << 15)
+
+/*
+ * Reg 18. Bus Status.
+ */
+
+#define CS8900_BUS_STATUS_TX_BID_ERROR (1 << 7)
+#define CS8900_BUS_STATUS_RDY_FOR_TX_NOW (1 << 8)
+
+/*
+ * Trace for debugging the isq processing. Define to 1 to enable.
+ */
+#define CS8900_TRACE 0
+#define CS8900_TRACE_SIZE (400)
+
+/*
+ * The default receive queue size. If the BSP sets this field to
+ * 0 this default is used.
+ */
+#define CS8900_RX_QUEUE_SIZE (30)
+
+/*
+ * Stats, more for debugging than anything else.
+ */
+
+typedef struct
+{
+ unsigned long rx_packets; /* total packets received */
+ unsigned long tx_packets; /* total packets transmitted */
+ unsigned long rx_bytes; /* total bytes received */
+ unsigned long tx_bytes; /* total bytes transmitted */
+ unsigned long rx_interrupts; /* total number of rx interrupts */
+ unsigned long tx_interrupts; /* total number of tx interrupts */
+
+ /* detailed rx errors: */
+ unsigned long rx_dropped; /* no mbufs in queue */
+ unsigned long rx_no_mbufs; /* no mbufs */
+ unsigned long rx_no_clusters; /* no clusters */
+ unsigned long rx_oversize_errors;
+ unsigned long rx_crc_errors; /* recved pkt with crc error */
+ unsigned long rx_runt_errors;
+ unsigned long rx_missed_errors; /* receiver missed packet */
+
+ /* detailed tx errors */
+ unsigned long tx_ok;
+ unsigned long tx_collisions;
+ unsigned long tx_bid_errors;
+ unsigned long tx_wait_for_rdy4tx;
+ unsigned long tx_rdy4tx;
+ unsigned long tx_underrun_errors;
+ unsigned long tx_dropped;
+ unsigned long tx_resends;
+
+ /* interrupt watch dog */
+ unsigned long int_swint_req;
+ unsigned long int_swint_res;
+ unsigned long int_lockup;
+
+ unsigned long interrupts;
+
+} eth_statistics;
+
+/*
+ * CS8900 device structure
+ */
+
+typedef struct
+{
+ /*
+ * Device number.
+ */
+
+ int dev;
+
+ /*
+ * Memory base addresses. Making mem_base 0 forces the
+ * driver to perform only I/O space accesses.
+ */
+
+ unsigned long io_base;
+ unsigned long mem_base;
+
+ /*
+ * The IRQ level as defined in the datasheet for the CS8900.
+ *
+ * ISA BUS Pin Value
+ * IRQ10 INTRQ0 0
+ * IRQ11 INTRQ1 1
+ * IRQ12 INTRQ2 2
+ * IRQ5 INTRQ3 3
+ */
+
+ int irq_level;
+
+ /*
+ * The MAC address.
+ */
+
+ unsigned char mac_address[6];
+
+ /*
+ * The bsdnet information structure.
+ */
+
+ struct arpcom arpcom;
+
+ /*
+ * Driver state and resources.
+ */
+
+ int accept_bcast;
+ int tx_active;
+
+ rtems_id rx_task;
+ rtems_id tx_task;
+
+ /*
+ * The queues. FIXME : these should be changed to be mbuf lists.
+ */
+
+ struct mbuf *rx_ready_head;
+ struct mbuf *rx_ready_tail;
+ int rx_ready_len;
+
+ struct mbuf *rx_loaded_head;
+ struct mbuf *rx_loaded_tail;
+ int rx_loaded_len;
+
+ /*
+ * Number of mbufs queued for the interrupt handler to
+ * loop reading.
+ */
+
+ int rx_queue_size;
+
+#if CS8900_TRACE
+ unsigned short trace_key[CS8900_TRACE_SIZE];
+ unsigned long trace_var[CS8900_TRACE_SIZE];
+ unsigned long trace_time[CS8900_TRACE_SIZE];
+ int trace_in;
+#endif
+
+ /**
+ * Standard(!) ethernet statistics
+ */
+
+ eth_statistics eth_stats;
+
+} cs8900_device;
+
+/*
+ * Link active returns the state of the PHY.
+ *
+ * @param cs Pointer to the device structure.
+ */
+
+int cs8900_link_active (cs8900_device *cs);
+
+/**
+ * The RTEMS network stack driver attach function that is loaded into the
+ * the rtems_bsdnet_ifconfig struct. The network stack will call this
+ * function when attaching the driver. The BSP must load the 'drv_ctrl'
+ * field of the structure before calling the 'rtems_bsdnet_attach'
+ * function.
+ *
+ * @param config The RTEMS BSD config structure.
+ *
+ * @param attaching True is the stack is attaching the interface.
+ *
+ * @retval int Set to 1 if the device has attached.
+ */
+
+int cs8900_driver_attach (struct rtems_bsdnet_ifconfig *config,
+ int attaching);
+
+/**
+ * The BSP specific interrupt wrapper calls this function when a device
+ * interrupt occurs.
+ *
+ * @param v The RTEMS vector number that generated the interrupt.
+ *
+ * @param cs Pointer to the device structure passed to the interrupt
+ * catch function provided by the BSP.
+ *
+ * @retval rtems_isr The standard ISR return type.
+ */
+
+rtems_isr cs8900_interrupt (rtems_vector_number v, void *cs);
+
+/**
+ * Get the MAC address for the interface.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param mac_address Pointer to the memory to load the MAC address. This
+ * is a 6 byte buffer so do not exceeed the bounds.
+ */
+
+void cs8900_get_mac_addr (cs8900_device *cs, unsigned char *mac_address);
+
+/**
+ * Catch the device interrupt. When the interrupt is called call the
+ * function 'cs8900_interrupt'.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ */
+
+void cs8900_attach_interrupt (cs8900_device *cs);
+
+/**
+ * Detach the device interrupt.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ */
+
+void cs8900_detach_interrupt (cs8900_device *cs);
+
+/**
+ * Write to an IO space register.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param reg Register offset from the IO base.
+ *
+ * @param data The data to be written to the register.
+ */
+
+void cs8900_io_set_reg (cs8900_device *cs,
+ unsigned short reg, unsigned short data);
+
+/**
+ * Read an IO space register.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param reg Register offset from the IO base.
+ *
+ * @retval unsigned short The register data.
+ */
+
+unsigned short cs8900_io_get_reg (cs8900_device *cs, unsigned short reg);
+
+/**
+ * Write to a memory space register. Will only be called is the mem_base
+ * field of the 'cs' struct is not 0.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param reg Register offset from the memory base.
+ *
+ * @param data The data to be written to the register.
+ */
+
+void cs8900_mem_set_reg (cs8900_device *cs,
+ unsigned long reg, unsigned short data);
+
+/**
+ * Read a memory space register. Will only be called is the mem_base
+ * field of the 'cs' struct is not 0.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param reg Register offset from the IO base.
+ *
+ * @retval unsigned short The register data.
+ */
+
+unsigned short cs8900_mem_get_reg (cs8900_device *cs, unsigned long reg);
+
+/**
+ * Write a block of data to the interface. The BSP codes if this is an IO or
+ * memory space write.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param len The length of data to write.
+ *
+ * @param data Pointer to the data to be written.
+ */
+
+void cs8900_put_data_block (cs8900_device *cs, int len, unsigned char *data);
+
+/**
+ * Read a block of data from the interface. The BSP codes if this is an IO or
+ * memory space write. The read must not be longer than the MTU size.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param data Pointer to the buffer where the data is to be written.
+ *
+ * @retval unsigned short The number of bytes read from the device.
+ */
+
+unsigned short cs8900_get_data_block (cs8900_device *cs, unsigned char *data);
+
+/**
+ * Load a mbuf chain to the device ready for tranmission.
+ *
+ * BSP to provide this function.
+ *
+ * @param cs Pointer to the device structure.
+ *
+ * @param m Pointer to the head of an mbuf chain.
+ */
+
+void cs8900_tx_load (cs8900_device *cs, struct mbuf *m);
+
+#endif
diff --git a/bsps/include/libchip/greth.h b/bsps/include/libchip/greth.h
new file mode 100644
index 0000000..c6e000d
--- /dev/null
+++ b/bsps/include/libchip/greth.h
@@ -0,0 +1,152 @@
+/*
+ * Gaisler Research ethernet MAC driver
+ * adapted from Opencores driver by Marko Isomaki
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+
+#ifndef _GR_ETH_
+#define _GR_ETH_
+
+
+/* Configuration Information */
+
+typedef struct {
+ void *base_address;
+ rtems_vector_number vector;
+ uint32_t txd_count;
+ uint32_t rxd_count;
+} greth_configuration_t;
+
+/* Ethernet configuration registers */
+
+typedef struct _greth_regs {
+ volatile uint32_t ctrl; /* Ctrl Register */
+ volatile uint32_t status; /* Status Register */
+ volatile uint32_t mac_addr_msb; /* Bit 47-32 of MAC address */
+ volatile uint32_t mac_addr_lsb; /* Bit 31-0 of MAC address */
+ volatile uint32_t mdio_ctrl; /* MDIO control and status */
+ volatile uint32_t txdesc; /* Transmit descriptor pointer */
+ volatile uint32_t rxdesc; /* Receive descriptor pointer */
+} greth_regs;
+
+#define GRETH_TOTAL_BD 128
+#define GRETH_MAXBUF_LEN 1520
+
+/* Tx BD */
+#define GRETH_TXD_ENABLE 0x0800 /* Tx BD Enable */
+#define GRETH_TXD_WRAP 0x1000 /* Tx BD Wrap (last BD) */
+#define GRETH_TXD_IRQ 0x2000 /* Tx BD IRQ Enable */
+#define GRETH_TXD_MORE 0x20000 /* Tx BD More (more descs for packet) */
+#define GRETH_TXD_IPCS 0x40000 /* Tx BD insert ip chksum */
+#define GRETH_TXD_TCPCS 0x80000 /* Tx BD insert tcp chksum */
+#define GRETH_TXD_UDPCS 0x100000 /* Tx BD insert udp chksum */
+
+#define GRETH_TXD_UNDERRUN 0x4000 /* Tx BD Underrun Status */
+#define GRETH_TXD_RETLIM 0x8000 /* Tx BD Retransmission Limit Status */
+#define GRETH_TXD_LATECOL 0x10000 /* Tx BD Late Collision */
+
+#define GRETH_TXD_STATS (GRETH_TXD_UNDERRUN | \
+ GRETH_TXD_RETLIM | \
+ GRETH_TXD_LATECOL)
+
+#define GRETH_TXD_CS (GRETH_TXD_IPCS | \
+ GRETH_TXD_TCPCS | \
+ GRETH_TXD_UDPCS)
+
+/* Rx BD */
+#define GRETH_RXD_ENABLE 0x0800 /* Rx BD Enable */
+#define GRETH_RXD_WRAP 0x1000 /* Rx BD Wrap (last BD) */
+#define GRETH_RXD_IRQ 0x2000 /* Rx BD IRQ Enable */
+
+#define GRETH_RXD_DRIBBLE 0x4000 /* Rx BD Dribble Nibble Status */
+#define GRETH_RXD_TOOLONG 0x8000 /* Rx BD Too Long Status */
+#define GRETH_RXD_CRCERR 0x10000 /* Rx BD CRC Error Status */
+#define GRETH_RXD_OVERRUN 0x20000 /* Rx BD Overrun Status */
+#define GRETH_RXD_LENERR 0x40000 /* Rx BD Length Error */
+#define GRETH_RXD_ID 0x40000 /* Rx BD IP Detected */
+#define GRETH_RXD_IR 0x40000 /* Rx BD IP Chksum Error */
+#define GRETH_RXD_UD 0x40000 /* Rx BD UDP Detected*/
+#define GRETH_RXD_UR 0x40000 /* Rx BD UDP Chksum Error */
+#define GRETH_RXD_TD 0x40000 /* Rx BD TCP Detected */
+#define GRETH_RXD_TR 0x40000 /* Rx BD TCP Chksum Error */
+
+
+#define GRETH_RXD_STATS (GRETH_RXD_OVERRUN | \
+ GRETH_RXD_DRIBBLE | \
+ GRETH_RXD_TOOLONG | \
+ GRETH_RXD_CRCERR)
+
+/* CTRL Register */
+#define GRETH_CTRL_TXEN 0x00000001 /* Transmit Enable */
+#define GRETH_CTRL_RXEN 0x00000002 /* Receive Enable */
+#define GRETH_CTRL_TXIRQ 0x00000004 /* Transmit Enable */
+#define GRETH_CTRL_RXIRQ 0x00000008 /* Receive Enable */
+#define GRETH_CTRL_FULLD 0x00000010 /* Full Duplex */
+#define GRETH_CTRL_PRO 0x00000020 /* Promiscuous (receive all) */
+#define GRETH_CTRL_RST 0x00000040 /* Reset MAC */
+
+/* Status Register */
+#define GRETH_STATUS_RXERR 0x00000001 /* Receive Error */
+#define GRETH_STATUS_TXERR 0x00000002 /* Transmit Error IRQ */
+#define GRETH_STATUS_RXIRQ 0x00000004 /* Receive Frame IRQ */
+#define GRETH_STATUS_TXIRQ 0x00000008 /* Transmit Error IRQ */
+#define GRETH_STATUS_RXAHBERR 0x00000010 /* Receiver AHB Error */
+#define GRETH_STATUS_TXAHBERR 0x00000020 /* Transmitter AHB Error */
+
+/* MDIO Control */
+#define GRETH_MDIO_WRITE 0x00000001 /* MDIO Write */
+#define GRETH_MDIO_READ 0x00000002 /* MDIO Read */
+#define GRETH_MDIO_LINKFAIL 0x00000004 /* MDIO Link failed */
+#define GRETH_MDIO_BUSY 0x00000008 /* MDIO Link Busy */
+#define GRETH_MDIO_REGADR 0x000007C0 /* Register Address */
+#define GRETH_MDIO_PHYADR 0x0000F800 /* PHY address */
+#define GRETH_MDIO_DATA 0xFFFF0000 /* MDIO DATA */
+
+
+/* MII registers */
+#define GRETH_MII_EXTADV_1000FD 0x00000200
+#define GRETH_MII_EXTADV_1000HD 0x00000100
+#define GRETH_MII_EXTPRT_1000FD 0x00000800
+#define GRETH_MII_EXTPRT_1000HD 0x00000400
+
+#define GRETH_MII_100T4 0x00000200
+#define GRETH_MII_100TXFD 0x00000100
+#define GRETH_MII_100TXHD 0x00000080
+#define GRETH_MII_10FD 0x00000040
+#define GRETH_MII_10HD 0x00000020
+
+
+
+/* Attach routine */
+
+int rtems_greth_driver_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ greth_configuration_t *chip
+);
+
+/* PHY data */
+struct phy_device_info
+{
+ int vendor;
+ int device;
+ int rev;
+
+ int adv;
+ int part;
+
+ int extadv;
+ int extpart;
+};
+
+/*
+#ifdef CPU_U32_FIX
+void ipalign(struct mbuf *m);
+#endif
+
+*/
+#endif
+
diff --git a/bsps/include/libchip/open_eth.h b/bsps/include/libchip/open_eth.h
new file mode 100644
index 0000000..66a5204
--- /dev/null
+++ b/bsps/include/libchip/open_eth.h
@@ -0,0 +1,173 @@
+/* Opencores ethernet MAC driver */
+/* adapted from linux driver by Jiri Gaisler */
+
+#ifndef _OPEN_ETH_
+#define _OPEN_ETH_
+
+
+/* Configuration Information */
+
+typedef struct {
+ void *base_address;
+ uint32_t vector;
+ uint32_t txd_count;
+ uint32_t rxd_count;
+ uint32_t en100MHz;
+} open_eth_configuration_t;
+
+
+/* Ethernet buffer descriptor */
+
+typedef struct _oeth_rxtxdesc {
+ volatile uint32_t len_status; /* Length and status */
+ volatile uint32_t *addr; /* Buffer pointer */
+} oeth_rxtxdesc;
+
+/* Ethernet configuration registers */
+
+typedef struct _oeth_regs {
+ volatile uint32_t moder; /* Mode Register */
+ volatile uint32_t int_src; /* Interrupt Source Register */
+ volatile uint32_t int_mask; /* Interrupt Mask Register */
+ volatile uint32_t ipgt; /* Back to Bak Inter Packet Gap Register */
+ volatile uint32_t ipgr1; /* Non Back to Back Inter Packet Gap Register 1 */
+ volatile uint32_t ipgr2; /* Non Back to Back Inter Packet Gap Register 2 */
+ volatile uint32_t packet_len; /* Packet Length Register (min. and max.) */
+ volatile uint32_t collconf; /* Collision and Retry Configuration Register */
+ volatile uint32_t tx_bd_num; /* Transmit Buffer Descriptor Number Register */
+ volatile uint32_t ctrlmoder; /* Control Module Mode Register */
+ volatile uint32_t miimoder; /* MII Mode Register */
+ volatile uint32_t miicommand; /* MII Command Register */
+ volatile uint32_t miiaddress; /* MII Address Register */
+ volatile uint32_t miitx_data; /* MII Transmit Data Register */
+ volatile uint32_t miirx_data; /* MII Receive Data Register */
+ volatile uint32_t miistatus; /* MII Status Register */
+ volatile uint32_t mac_addr0; /* MAC Individual Address Register 0 */
+ volatile uint32_t mac_addr1; /* MAC Individual Address Register 1 */
+ volatile uint32_t hash_addr0; /* Hash Register 0 */
+ volatile uint32_t hash_addr1; /* Hash Register 1 */
+ volatile uint32_t txctrl; /* Transmitter control register */
+ uint32_t empty[235]; /* Unused space */
+ oeth_rxtxdesc xd[128]; /* TX & RX descriptors */
+} oeth_regs;
+
+#define OETH_TOTAL_BD 128
+#define OETH_MAXBUF_LEN 0x610
+
+/* Tx BD */
+#define OETH_TX_BD_READY 0x8000 /* Tx BD Ready */
+#define OETH_TX_BD_IRQ 0x4000 /* Tx BD IRQ Enable */
+#define OETH_TX_BD_WRAP 0x2000 /* Tx BD Wrap (last BD) */
+#define OETH_TX_BD_PAD 0x1000 /* Tx BD Pad Enable */
+#define OETH_TX_BD_CRC 0x0800 /* Tx BD CRC Enable */
+
+#define OETH_TX_BD_UNDERRUN 0x0100 /* Tx BD Underrun Status */
+#define OETH_TX_BD_RETRY 0x00F0 /* Tx BD Retry Status */
+#define OETH_TX_BD_RETLIM 0x0008 /* Tx BD Retransmission Limit Status */
+#define OETH_TX_BD_LATECOL 0x0004 /* Tx BD Late Collision Status */
+#define OETH_TX_BD_DEFER 0x0002 /* Tx BD Defer Status */
+#define OETH_TX_BD_CARRIER 0x0001 /* Tx BD Carrier Sense Lost Status */
+#define OETH_TX_BD_STATS (OETH_TX_BD_UNDERRUN | \
+ OETH_TX_BD_RETRY | \
+ OETH_TX_BD_RETLIM | \
+ OETH_TX_BD_LATECOL | \
+ OETH_TX_BD_DEFER | \
+ OETH_TX_BD_CARRIER)
+
+/* Rx BD */
+#define OETH_RX_BD_EMPTY 0x8000 /* Rx BD Empty */
+#define OETH_RX_BD_IRQ 0x4000 /* Rx BD IRQ Enable */
+#define OETH_RX_BD_WRAP 0x2000 /* Rx BD Wrap (last BD) */
+
+#define OETH_RX_BD_MISS 0x0080 /* Rx BD Miss Status */
+#define OETH_RX_BD_OVERRUN 0x0040 /* Rx BD Overrun Status */
+#define OETH_RX_BD_INVSIMB 0x0020 /* Rx BD Invalid Symbol Status */
+#define OETH_RX_BD_DRIBBLE 0x0010 /* Rx BD Dribble Nibble Status */
+#define OETH_RX_BD_TOOLONG 0x0008 /* Rx BD Too Long Status */
+#define OETH_RX_BD_SHORT 0x0004 /* Rx BD Too Short Frame Status */
+#define OETH_RX_BD_CRCERR 0x0002 /* Rx BD CRC Error Status */
+#define OETH_RX_BD_LATECOL 0x0001 /* Rx BD Late Collision Status */
+#define OETH_RX_BD_STATS (OETH_RX_BD_MISS | \
+ OETH_RX_BD_OVERRUN | \
+ OETH_RX_BD_INVSIMB | \
+ OETH_RX_BD_DRIBBLE | \
+ OETH_RX_BD_TOOLONG | \
+ OETH_RX_BD_SHORT | \
+ OETH_RX_BD_CRCERR | \
+ OETH_RX_BD_LATECOL)
+
+/* MODER Register */
+#define OETH_MODER_RXEN 0x00000001 /* Receive Enable */
+#define OETH_MODER_TXEN 0x00000002 /* Transmit Enable */
+#define OETH_MODER_NOPRE 0x00000004 /* No Preamble */
+#define OETH_MODER_BRO 0x00000008 /* Reject Broadcast */
+#define OETH_MODER_IAM 0x00000010 /* Use Individual Hash */
+#define OETH_MODER_PRO 0x00000020 /* Promiscuous (receive all) */
+#define OETH_MODER_IFG 0x00000040 /* Min. IFG not required */
+#define OETH_MODER_LOOPBCK 0x00000080 /* Loop Back */
+#define OETH_MODER_NOBCKOF 0x00000100 /* No Backoff */
+#define OETH_MODER_EXDFREN 0x00000200 /* Excess Defer */
+#define OETH_MODER_FULLD 0x00000400 /* Full Duplex */
+#define OETH_MODER_RST 0x00000800 /* Reset MAC */
+#define OETH_MODER_DLYCRCEN 0x00001000 /* Delayed CRC Enable */
+#define OETH_MODER_CRCEN 0x00002000 /* CRC Enable */
+#define OETH_MODER_HUGEN 0x00004000 /* Huge Enable */
+#define OETH_MODER_PAD 0x00008000 /* Pad Enable */
+#define OETH_MODER_RECSMALL 0x00010000 /* Receive Small */
+
+/* Interrupt Source Register */
+#define OETH_INT_TXB 0x00000001 /* Transmit Buffer IRQ */
+#define OETH_INT_TXE 0x00000002 /* Transmit Error IRQ */
+#define OETH_INT_RXF 0x00000004 /* Receive Frame IRQ */
+#define OETH_INT_RXE 0x00000008 /* Receive Error IRQ */
+#define OETH_INT_BUSY 0x00000010 /* Busy IRQ */
+#define OETH_INT_TXC 0x00000020 /* Transmit Control Frame IRQ */
+#define OETH_INT_RXC 0x00000040 /* Received Control Frame IRQ */
+
+/* Interrupt Mask Register */
+#define OETH_INT_MASK_TXB 0x00000001 /* Transmit Buffer IRQ Mask */
+#define OETH_INT_MASK_TXE 0x00000002 /* Transmit Error IRQ Mask */
+#define OETH_INT_MASK_RXF 0x00000004 /* Receive Frame IRQ Mask */
+#define OETH_INT_MASK_RXE 0x00000008 /* Receive Error IRQ Mask */
+#define OETH_INT_MASK_BUSY 0x00000010 /* Busy IRQ Mask */
+#define OETH_INT_MASK_TXC 0x00000020 /* Transmit Control Frame IRQ Mask */
+#define OETH_INT_MASK_RXC 0x00000040 /* Received Control Frame IRQ Mask */
+
+/* Control Module Mode Register */
+#define OETH_CTRLMODER_PASSALL 0x00000001 /* Pass Control Frames */
+#define OETH_CTRLMODER_RXFLOW 0x00000002 /* Receive Control Flow Enable */
+#define OETH_CTRLMODER_TXFLOW 0x00000004 /* Transmit Control Flow Enable */
+
+/* MII Mode Register */
+#define OETH_MIIMODER_CLKDIV 0x000000FF /* Clock Divider */
+#define OETH_MIIMODER_NOPRE 0x00000100 /* No Preamble */
+#define OETH_MIIMODER_RST 0x00000200 /* MIIM Reset */
+
+/* MII Command Register */
+#define OETH_MIICOMMAND_SCANSTAT 0x00000001 /* Scan Status */
+#define OETH_MIICOMMAND_RSTAT 0x00000002 /* Read Status */
+#define OETH_MIICOMMAND_WCTRLDATA 0x00000004 /* Write Control Data */
+
+/* MII Address Register */
+#define OETH_MIIADDRESS_FIAD 0x0000001F /* PHY Address */
+#define OETH_MIIADDRESS_RGAD 0x00001F00 /* RGAD Address */
+
+/* MII Status Register */
+#define OETH_MIISTATUS_LINKFAIL 0x00000001 /* Link Fail */
+#define OETH_MIISTATUS_BUSY 0x00000002 /* MII Busy */
+#define OETH_MIISTATUS_NVALID 0x00000004 /* Data in MII Status Register is invalid */
+
+/* Attatch routine */
+
+int rtems_open_eth_driver_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ open_eth_configuration_t *chip
+);
+
+/*
+#ifdef CPU_U32_FIX
+void ipalign(struct mbuf *m);
+#endif
+
+*/
+#endif /* _OPEN_ETH_ */
diff --git a/bsps/include/libchip/smc91111exp.h b/bsps/include/libchip/smc91111exp.h
new file mode 100644
index 0000000..08e086d
--- /dev/null
+++ b/bsps/include/libchip/smc91111exp.h
@@ -0,0 +1,26 @@
+#ifndef _SMC91111_EXP_H_
+#define _SMC91111_EXP_H_
+
+#include <bsp.h>
+
+typedef struct scmv91111_configuration {
+ void *baseaddr;
+ rtems_vector_number vector;
+ unsigned int pio;
+ unsigned int ctl_rspeed;
+ unsigned int ctl_rfduplx;
+ unsigned int ctl_autoneg;
+#ifdef BSP_FEATURE_IRQ_EXTENSION
+ const char * info;
+ rtems_option options;
+ rtems_interrupt_handler interrupt_wrapper;
+ void * arg;
+#endif
+} scmv91111_configuration_t;
+
+int _rtems_smc91111_driver_attach (struct rtems_bsdnet_ifconfig *config,
+ scmv91111_configuration_t * scm_config);
+
+#endif /* _SMC_91111_EXP_H_ */
+
+
diff --git a/bsps/include/libchip/sonic.h b/bsps/include/libchip/sonic.h
new file mode 100644
index 0000000..fe119ff
--- /dev/null
+++ b/bsps/include/libchip/sonic.h
@@ -0,0 +1,458 @@
+/*
+ * RTEMS NETWORK DRIVER FOR NATIONAL DP83932 `SONIC'
+ * SYSTEMS-ORIENTED NETWORK INTERFACE CONTROLLER
+ *
+ * REUSABLE CHIP DRIVER CONFIGURATION
+ *
+ * References:
+ *
+ * 1) DP83932C-20/25/33 MHz SONIC(TM) Systems-Oriented Network Interface
+ * Controller data sheet. TL/F/10492, RRD-B30M105, National Semiconductor,
+ * 1995.
+ *
+ * 2) Software Driver Programmer's Guide for the DP83932 SONIC(TM),
+ * Application Note 746, Wesley Lee and Mike Lui, TL/F/11140,
+ * RRD-B30M75, National Semiconductor, March, 1991.
+ *
+ * COPYRIGHT (c) 1989-1997.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#ifndef _SONIC_DP83932_
+#define _SONIC_DP83932_
+
+
+ /*
+ * Debug levels
+ *
+ */
+
+#define SONIC_DEBUG_NONE 0x0000
+#define SONIC_DEBUG_ALL 0xFFFF
+#define SONIC_DEBUG_PRINT_REGISTERS 0x0001
+#define SONIC_DEBUG_MEMORY 0x0002
+#define SONIC_DEBUG_MEMORY_ALLOCATE 0x0004
+#define SONIC_DEBUG_MEMORY_DESCRIPTORS 0x0008
+#define SONIC_DEBUG_FRAGMENTS 0x0008
+#define SONIC_DEBUG_CAM 0x0010
+#define SONIC_DEBUG_DESCRIPTORS 0x0020
+#define SONIC_DEBUG_ERRORS 0x0040
+#define SONIC_DEBUG_DUMP_TX_MBUFS 0x0080
+#define SONIC_DEBUG_DUMP_RX_MBUFS 0x0100
+
+#define SONIC_DEBUG_DUMP_MBUFS \
+ (SONIC_DEBUG_DUMP_TX_MBUFS|SONIC_DEBUG_DUMP_RX_MBUFS)
+
+#define SONIC_DEBUG (SONIC_DEBUG_NONE)
+/*
+#define SONIC_DEBUG (SONIC_DEBUG_ERRORS | SONIC_DEBUG_PRINT_REGISTERS |\
+ SONIC_DEBUG_DESCRIPTORS)
+*/
+
+/*
+ ((SONIC_DEBUG_ALL) & ~(SONIC_DEBUG_PRINT_REGISTERS|SONIC_DEBUG_DUMP_MBUFS))
+ ((SONIC_DEBUG_ALL) & ~(SONIC_DEBUG_DUMP_MBUFS))
+*/
+
+#if (SONIC_DEBUG & SONIC_DEBUG_PRINT_REGISTERS)
+extern char SONIC_Reg_name[64][6];
+#endif
+
+
+/*
+ * Configuration Information
+ */
+
+typedef void (*sonic_write_register_t)(
+ void *base,
+ uint32_t regno,
+ uint32_t value
+);
+
+typedef uint32_t (*sonic_read_register_t)(
+ void *base,
+ uint32_t regno
+);
+
+typedef struct {
+ void *base_address;
+ uint32_t vector;
+ uint32_t dcr_value;
+ uint32_t dc2_value;
+ uint32_t tda_count;
+ uint32_t rda_count;
+ sonic_write_register_t write_register;
+ sonic_read_register_t read_register;
+} sonic_configuration_t;
+
+/*
+ ******************************************************************
+ * *
+ * Device Registers *
+ * *
+ ******************************************************************
+ */
+#define SONIC_REG_CR 0x00 /* Command */
+#define SONIC_REG_DCR 0x01 /* Data configuration */
+#define SONIC_REG_RCR 0x02 /* Receive control */
+#define SONIC_REG_TCR 0x03 /* Transmit control */
+#define SONIC_REG_IMR 0x04 /* Interrupt mask */
+#define SONIC_REG_ISR 0x05 /* Interrupt status */
+#define SONIC_REG_UTDA 0x06 /* Upper transmit descriptor address */
+#define SONIC_REG_CTDA 0x07 /* Current transmit descriptor address */
+#define SONIC_REG_URDA 0x0D /* Upper receive descriptor address */
+#define SONIC_REG_CRDA 0x0E /* Current receive descriptor address */
+#define SONIC_REG_EOBC 0x13 /* End of buffer word count */
+#define SONIC_REG_URRA 0x14 /* Upper receive resource */
+#define SONIC_REG_RSA 0x15 /* Resource start address */
+#define SONIC_REG_REA 0x16 /* Resource end address */
+#define SONIC_REG_RRP 0x17 /* Resouce read pointer */
+#define SONIC_REG_RWP 0x18 /* Resouce write pointer */
+#define SONIC_REG_CEP 0x21 /* CAM entry pointer */
+#define SONIC_REG_CAP2 0x22 /* CAM address port 2 */
+#define SONIC_REG_CAP1 0x23 /* CAM address port 1 */
+#define SONIC_REG_CAP0 0x24 /* CAM address port 0 */
+#define SONIC_REG_CE 0x25 /* CAM enable */
+#define SONIC_REG_CDP 0x26 /* CAM descriptor pointer */
+#define SONIC_REG_CDC 0x27 /* CAM descriptor count */
+#define SONIC_REG_SR 0x28 /* Silicon revision */
+#define SONIC_REG_WT0 0x29 /* Watchdog timer 0 */
+#define SONIC_REG_WT1 0x2A /* Watchdog timer 1 */
+#define SONIC_REG_RSC 0x2B /* Receive sequence counter */
+#define SONIC_REG_CRCT 0x2C /* CRC error tally */
+#define SONIC_REG_FAET 0x2D /* FAE tally */
+#define SONIC_REG_MPT 0x2E /* Missed packet tally */
+#define SONIC_REG_MDT 0x2F /* TX Maximum Deferral */
+#define SONIC_REG_DCR2 0x3F /* Data configuration 2 */
+
+/*
+ * Command register
+ */
+#define CR_LCAM 0x0200
+#define CR_RRRA 0x0100
+#define CR_RST 0x0080
+#define CR_ST 0x0020
+#define CR_STP 0x0010
+#define CR_RXEN 0x0008
+#define CR_RXDIS 0x0004
+#define CR_TXP 0x0002
+#define CR_HTX 0x0001
+
+/*
+ * Data configuration register
+ */
+#define DCR_EXBUS 0x8000
+#define DCR_LBR 0x2000
+#define DCR_PO1 0x1000
+#define DCR_PO0 0x0800
+#define DCR_SBUS 0x0400
+#define DCR_USR1 0x0200
+#define DCR_USR0 0x0100
+#define DCR_WC1 0x0080
+#define DCR_WC0 0x0040
+#define DCR_DW 0x0020
+#define DCR_BMS 0x0010
+#define DCR_RFT1 0x0008
+#define DCR_RFT0 0x0004
+#define DCR_TFT1 0x0002
+#define DCR_TFT0 0x0001
+
+/* data configuration register aliases */
+#define DCR_SYNC DCR_SBUS /* synchronous (memory cycle 2 clocks) */
+#define DCR_ASYNC 0 /* asynchronous (memory cycle 3 clocks) */
+
+#define DCR_WAIT0 0 /* 0 wait states added */
+#define DCR_WAIT1 DCR_WC0 /* 1 wait state added */
+#define DCR_WAIT2 DCR_WC1 /* 2 wait states added */
+#define DCR_WAIT3 (DCR_WC1|DCR_WC0) /* 3 wait states added */
+
+#define DCR_DW16 0 /* use 16-bit DMA accesses */
+#define DCR_DW32 DCR_DW /* use 32-bit DMA accesses */
+
+#define DCR_DMAEF 0 /* DMA until TX/RX FIFO has emptied/filled */
+#define DCR_DMABLOCK DCR_BMS /* DMA until RX/TX threshold crossed */
+
+#define DCR_RFT4 0 /* receive threshold 4 bytes */
+#define DCR_RFT8 DCR_RFT0 /* receive threshold 8 bytes */
+#define DCR_RFT16 DCR_RFT1 /* receive threshold 16 bytes */
+#define DCR_RFT24 (DCR_RFT1|DCR_RFT0) /* receive threshold 24 bytes */
+
+#define DCR_TFT8 0 /* transmit threshold 8 bytes */
+#define DCR_TFT16 DCR_TFT0 /* transmit threshold 16 bytes */
+#define DCR_TFT24 DCR_TFT1 /* transmit threshold 24 bytes */
+#define DCR_TFT28 (DCR_TFT1|DCR_TFT0) /* transmit threshold 28 bytes */
+
+/*
+ * Receive control register
+ */
+#define RCR_ERR 0x8000
+#define RCR_RNT 0x4000
+#define RCR_BRD 0x2000
+#define RCR_PRO 0x1000
+#define RCR_AMC 0x0800
+#define RCR_LB1 0x0400
+#define RCR_LB0 0x0200
+#define RCR_MC 0x0100
+#define RCR_BC 0x0080
+#define RCR_LPKT 0x0040
+#define RCR_CRS 0x0020
+#define RCR_COL 0x0010
+#define RCR_CRCR 0x0008
+#define RCR_FAER 0x0004
+#define RCR_LBK 0x0002
+#define RCR_PRX 0x0001
+
+/*
+ * Transmit control register
+ */
+#define TCR_PINT 0x8000
+#define TCR_POWC 0x4000
+#define TCR_CRCI 0x2000
+#define TCR_EXDIS 0x1000
+#define TCR_EXD 0x0400
+#define TCR_DEF 0x0200
+#define TCR_NCRS 0x0100
+#define TCR_CRSL 0x0080
+#define TCR_EXC 0x0040
+#define TCR_OWC 0x0020
+#define TCR_PMB 0x0008
+#define TCR_FU 0x0004
+#define TCR_BCM 0x0002
+#define TCR_PTX 0x0001
+
+/*
+ * Interrupt mask register
+ */
+#define IMR_BREN 0x4000
+#define IMR_HBLEN 0x2000
+#define IMR_LCDEN 0x1000
+#define IMR_PINTEN 0x0800
+#define IMR_PRXEN 0x0400
+#define IMR_PTXEN 0x0200
+#define IMR_TXEREN 0x0100
+#define IMR_TCEN 0x0080
+#define IMR_RDEEN 0x0040
+#define IMR_RBEEN 0x0020
+#define IMR_RBAEEN 0x0010
+#define IMR_CRCEN 0x0008
+#define IMR_FAEEN 0x0004
+#define IMR_MPEN 0x0002
+#define IMR_RFOEN 0x0001
+
+/*
+ * Interrupt status register
+ */
+#define ISR_BR 0x4000
+#define ISR_HBL 0x2000
+#define ISR_LCD 0x1000
+#define ISR_PINT 0x0800
+#define ISR_PKTRX 0x0400
+#define ISR_TXDN 0x0200
+#define ISR_TXER 0x0100
+#define ISR_TC 0x0080
+#define ISR_RDE 0x0040
+#define ISR_RBE 0x0020
+#define ISR_RBAE 0x0010
+#define ISR_CRC 0x0008
+#define ISR_FAE 0x0004
+#define ISR_MP 0x0002
+#define ISR_RFO 0x0001
+
+/*
+ * Data configuration register 2
+ */
+#define DCR2_EXPO3 0x8000
+#define DCR2_EXPO2 0x4000
+#define DCR2_EXPO1 0x2000
+#define DCR2_EXPO0 0x1000
+#define DCR2_HBDIS 0x0800
+#define DCR2_PH 0x0010
+#define DCR2_PCM 0x0004
+#define DCR2_PCNM 0x0002
+#define DCR2_RJCM 0x0001
+
+/*
+ * Known values for the Silicon Revision Register.
+ * Note that DP83934 has revision 5 and seems to work.
+ */
+
+#define SONIC_REVISION_B 4
+#define SONIC_REVISION_DP83934 5
+#define SONIC_REVISION_C 6
+
+/*
+ ******************************************************************
+ * *
+ * Transmit Buffer Management *
+ * *
+ ******************************************************************
+ */
+
+/*
+ * Transmit descriptor area entry.
+ * There is one transmit descriptor for each packet to be transmitted.
+ * Statically reserve space for up to MAXIMUM_FRAGS_PER_PACKET fragments
+ * per descriptor.
+ */
+#define MAXIMUM_FRAGS_PER_DESCRIPTOR 6
+struct TransmitDescriptor {
+ uint32_t status;
+ uint32_t pkt_config;
+ uint32_t pkt_size;
+ uint32_t frag_count;
+
+ /*
+ * Packet fragment pointers
+ */
+ struct TransmitDescriptorFragLink {
+ uint32_t frag_lsw; /* LSW of fragment address */
+#define frag_link frag_lsw
+ uint32_t frag_msw; /* MSW of fragment address */
+ uint32_t frag_size;
+ } frag[MAXIMUM_FRAGS_PER_DESCRIPTOR];
+
+ /*
+ * Space for link if all fragment pointers are used.
+ */
+ uint32_t link_pad;
+
+ /*
+ * Extra RTEMS stuff
+ */
+ struct TransmitDescriptor *next; /* Circularly-linked list */
+ struct mbuf *mbufp; /* First mbuf in packet */
+ volatile uint32_t *linkp; /* Pointer to un[xxx].link */
+};
+typedef struct TransmitDescriptor TransmitDescriptor_t;
+typedef volatile TransmitDescriptor_t *TransmitDescriptorPointer_t;
+
+/*
+ * Transmit Configuration.
+ * For standard Ethernet transmission, all bits in the transmit
+ * configuration field are set to 0.
+ */
+#define TDA_CONFIG_PINT 0x8000
+#define TDA_CONFIG_POWC 0x4000
+#define TDA_CONFIG_CRCI 0x2000
+#define TDA_CONFIG_EXDIS 0x1000
+
+/*
+ * Transmit status
+ */
+#define TDA_STATUS_COLLISION_MASK 0xF800
+#define TDA_STATUS_COLLISION_SHIFT 11
+#define TDA_STATUS_EXD 0x0400
+#define TDA_STATUS_DEF 0x0200
+#define TDA_STATUS_NCRS 0x0100
+#define TDA_STATUS_CRSL 0x0080
+#define TDA_STATUS_EXC 0x0040
+#define TDA_STATUS_OWC 0x0020
+#define TDA_STATUS_PMB 0x0008
+#define TDA_STATUS_FU 0x0004
+#define TDA_STATUS_BCM 0x0002
+#define TDA_STATUS_PTX 0x0001
+
+#define TDA_LINK_EOL 0x0001
+#define TDA_LINK_EOL_MASK 0xFFFE
+
+
+
+/*
+ ******************************************************************
+ * *
+ * Receive Buffer Management *
+ * *
+ ******************************************************************
+ */
+
+/*
+ * Receive resource area entry.
+ * There is one receive resource entry for each receive buffer area (RBA).
+ * This driver allows only one packet per receive buffer area, so one
+ * receive resource entry corresponds to one correctly-received packet.
+ */
+struct ReceiveResource {
+ uint32_t buff_ptr_lsw; /* LSW of RBA address */
+ uint32_t buff_ptr_msw; /* MSW of RBA address */
+ uint32_t buff_wc_lsw; /* LSW of RBA size (16-bit words) */
+ uint32_t buff_wc_msw; /* MSW of RBA size (16-bit words) */
+};
+typedef struct ReceiveResource ReceiveResource_t;
+typedef volatile ReceiveResource_t *ReceiveResourcePointer_t;
+
+/*
+ * Receive descriptor area entry.
+ * There is one receive descriptor for each packet received.
+ */
+struct ReceiveDescriptor {
+ uint32_t status;
+ uint32_t byte_count;
+ uint32_t pkt_lsw; /* LSW of packet address */
+ uint32_t pkt_msw; /* MSW of packet address */
+ uint32_t seq_no;
+ uint32_t link;
+ uint32_t in_use;
+
+ /*
+ * Extra RTEMS stuff
+ */
+ volatile struct ReceiveDescriptor *next; /* Circularly-linked list */
+ struct mbuf *mbufp; /* First mbuf in packet */
+};
+typedef struct ReceiveDescriptor ReceiveDescriptor_t;
+typedef volatile ReceiveDescriptor_t *ReceiveDescriptorPointer_t;
+
+typedef struct {
+ uint32_t cep; /* CAM Entry Pointer */
+ uint32_t cap0; /* CAM Address Port 0 xx-xx-xx-xx-YY-YY */
+ uint32_t cap1; /* CAM Address Port 1 xx-xx-YY-YY-xxxx */
+ uint32_t cap2; /* CAM Address Port 2 YY-YY-xx-xx-xx-xx */
+ uint32_t ce;
+} CamDescriptor_t;
+
+typedef volatile CamDescriptor_t *CamDescriptorPointer_t;
+
+/*
+ * Receive status
+ */
+#define RDA_STATUS_ERR 0x8800
+#define RDA_STATUS_RNT 0x4000
+#define RDA_STATUS_BRD 0x2000
+#define RDA_STATUS_PRO 0x1000
+#define RDA_STATUS_AMC 0x0800
+#define RDA_STATUS_LB1 0x0400
+#define RDA_STATUS_LB0 0x0200
+#define RDA_STATUS_MC 0x0100
+#define RDA_STATUS_BC 0x0080
+#define RDA_STATUS_LPKT 0x0040
+#define RDA_STATUS_CRS 0x0020
+#define RDA_STATUS_COL 0x0010
+#define RDA_STATUS_CRCR 0x0008
+#define RDA_STATUS_FAER 0x0004
+#define RDA_STATUS_LBK 0x0002
+#define RDA_STATUS_PRX 0x0001
+
+#define RDA_LINK_EOL 0x0001
+#define RDA_LINK_EOL_MASK 0xFFFE
+#define RDA_IN_USE 0x0000 /* SONIC has finished with the packet */
+ /* and the driver can process it */
+#define RDA_FREE 0xFFFF /* SONIC can use it */
+
+/*
+ * Attach routine
+ */
+
+int rtems_sonic_driver_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ sonic_configuration_t *chip
+);
+
+#ifdef CPU_U32_FIX
+void ipalign(struct mbuf *m);
+#endif
+
+#endif /* _SONIC_DP83932_ */
diff --git a/bsps/lm32/shared/net/dp83848phy.h b/bsps/lm32/shared/net/dp83848phy.h
new file mode 100644
index 0000000..edc40cb
--- /dev/null
+++ b/bsps/lm32/shared/net/dp83848phy.h
@@ -0,0 +1,186 @@
+/**
+ * @file
+ * @ingroup lm32_tsmac
+ * @brief LatticeMico32 TSMAC (Tri-Speed MAC) definitions
+ */
+
+/*
+ * This file contains definitions for LatticeMico32 TSMAC (Tri-Speed MAC)
+ *
+ * COPYRIGHT (c) 1989-1999.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * Jukka Pietarinen <jukka.pietarinen@mrf.fi>, 2008,
+ * Micro-Research Finland Oy
+ */
+
+#ifndef _DP83848PHY_H
+#define _DP83848PHY_H
+
+#define DEFAULT_PHY_ADDRESS (0x01)
+
+#define PHY_BMCR (0x00)
+#define PHY_BMCR_RESET (1<<15)
+#define PHY_BMCR_LOOPBACK (1<<14)
+#define PHY_BMCR_SPEEDSEL (1<<13)
+#define PHY_BMCR_AN_ENA (1<<12)
+#define PHY_BMCR_PWRDWN (1<<11)
+#define PHY_BMCR_ISOLATE (1<<10)
+#define PHY_BMCR_RESTART_AN (1<<9)
+#define PHY_BMCR_DUPLEX_MODE (1<<8)
+#define PHY_BMCR_COLL_TEST (1<<7)
+#define PHY_BMSR (0x01)
+#define PHY_BMSR_100_T4 (1<<15)
+#define PHY_BMSR_100_TX_FD (1<<14)
+#define PHY_BMSR_100_TX_HD (1<<13)
+#define PHY_BMSR_10_T_FD (1<<12)
+#define PHY_BMSR_10_T_HD (1<<11)
+#define PHY_BMSR_PRESUP (1<<6)
+#define PHY_BMSR_AN_CMPL (1<<5)
+#define PHY_BMSR_REM_FLT (1<<4)
+#define PHY_BMSR_AN_AB (1<<3)
+#define PHY_BMSR_LINK_STAT (1<<2)
+#define PHY_BMSR_JABBDET (1<<1)
+#define PHY_BMSR_EXT_CAP (1<<0)
+#define PHY_PHYIDR1 (0x02)
+#define DEFAULT_PHYIDR1 (0x2000)
+#define PHY_PHYIDR2 (0x03)
+#define DEFAULT_PHYIDR2 (0x5C90)
+#define PHY_ANAR (0x04)
+#define PHY_ANAR_NP (1<<15)
+#define PHY_ANAR_RF (1<<13)
+#define PHY_ANAR_ASM_DIR (1<<11)
+#define PHY_ANAR_PAUSE (1<<10)
+#define PHY_ANAR_T4 (1<<9)
+#define PHY_ANAR_TX_FD (1<<8)
+#define PHY_ANAR_TX (1<<7)
+#define PHY_ANAR_10_FD (1<<6)
+#define PHY_ANAR_10 (1<<5)
+#define PHY_ANAR_SEL_MASK (0x0f)
+#define PHY_ANAR_SEL_SHIFT (0)
+#define PHY_ANAR_SEL_DEF (1)
+#define PHY_ANLPAR (0x05)
+#define PHY_ANLPAR_NP (1<<15)
+#define PHY_ANLPAR_ACK (1<<14)
+#define PHY_ANLPAR_RF (1<<13)
+#define PHY_ANLPAR_ASM_DIR (1<<11)
+#define PHY_ANLPAR_PAUSE (1<<10)
+#define PHY_ANLPAR_T4 (1<<9)
+#define PHY_ANLPAR_TX_FD (1<<8)
+#define PHY_ANLPAR_TX (1<<7)
+#define PHY_ANLPAR_10_FD (1<<6)
+#define PHY_ANLPAR_10 (1<<5)
+#define PHY_ANLPAR_SEL_MASK (0x0f)
+#define PHY_ANLPAR_SEL_SHIFT (0)
+#define PHY_ANLPARNP (0x05)
+#define PHY_ANLPARNP_NP (1<<15)
+#define PHY_ANLPARNP_ACK (1<<14)
+#define PHY_ANLPARNP_MP (1<<13)
+#define PHY_ANLPARNP_ACK2 (1<<12)
+#define PHY_ANLPARNP_TOGGLE (1<<11)
+#define PHY_ANLPARNP_CDE_MASK (0x03ff)
+#define PHY_ANER (0x06)
+#define PHY_ANER_PDF (1<<4)
+#define PHY_ANER_LP_NP_ABLE (1<<3)
+#define PHY_ANER_NP_ABLE (1<<2)
+#define PHY_ANER_PAGE_RX (1<<1)
+#define PHY_ANER_LP_AN_ABLE (1<<0)
+#define PHY_ANNPTR (0x07)
+#define PHY_ANNPTR_NP (1<<15)
+#define PHY_ANNPTR_MP (1<<13)
+#define PHY_ANNPTR_ACK2 (1<<12)
+#define PHY_ANNPTR_TOG_TX (1<<11)
+#define PHY_ANNPTR_CDE_MASK (0x03ff)
+#define PHY_PHYSTS (0x10)
+#define PHY_PHYSTS_MDIX_MDE (1<<14)
+#define PHY_PHYSTS_RCV_ERRL (1<<13)
+#define PHY_PHYSTS_POLSTAT (1<<12)
+#define PHY_PHYSTS_FCSL (1<<11)
+#define PHY_PHYSTS_SD (1<<10)
+#define PHY_PHYSTS_DESCL (1<<9)
+#define PHY_PHYSTS_PGREC (1<<8)
+#define PHY_PHYSTS_MIIIRQ (1<<7)
+#define PHY_PHYSTS_REM_FLT (1<<6)
+#define PHY_PHYSTS_JABBDET (1<<5)
+#define PHY_PHYSTS_AN_CMP (1<<4)
+#define PHY_PHYSTS_LOOPBACK (1<<3)
+#define PHY_PHYSTS_DUPLEX (1<<2)
+#define PHY_PHYSTS_SPEED (1<<1)
+#define PHY_PHYSTS_LINK (1<<0)
+#define PHY_MICR (0x11)
+#define PHY_MICR_TINT (1<<2)
+#define PHY_MICR_INTEN (1<<1)
+#define PHY_MICR_INT_OE (1<<0)
+#define PHY_MISR (0x12)
+#define PHY_MISR_ED_INT (1<<14)
+#define PHY_MISR_LINK_INT (1<<13)
+#define PHY_MISR_SPD_INT (1<<12)
+#define PHY_MISR_DUP_INT (1<<11)
+#define PHY_MISR_ANC_INT (1<<10)
+#define PHY_MISR_FHF_INT (1<<9)
+#define PHY_MISR_RHF_INT (1<<8)
+#define PHY_MISR_ED_INT_EN (1<<6)
+#define PHY_MISR_LINK_INT_EN (1<<5)
+#define PHY_MISR_SPD_INT_EN (1<<4)
+#define PHY_MISR_DUP_INT_EN (1<<3)
+#define PHY_MISR_ANC_INT_EN (1<<2)
+#define PHY_MISR_FHF_INT_EN (1<<1)
+#define PHY_MISR_RHF_INT_EN (1<<0)
+#define PHY_FCSCR (0x14)
+#define PHY_RECR (0x15)
+#define PHY_PCSR (0x16)
+#define PHY_PCSR_TQ_EN (1<<10)
+#define PHY_PCSR_SDFPMA (1<<9)
+#define PHY_PCSR_SD_OPT (1<<8)
+#define PHY_PCSR_DESC_TIME (1<<7)
+#define PHY_PCSR_F_100_OK (1<<5)
+#define PHY_PCSR_NRZI_BYPASS (1<<2)
+#define PHY_RBR (0x17)
+#define PHY_RBR_RMII_MODE (1<<5)
+#define PHY_RBR_RMII_REV1_0 (1<<4)
+#define PHY_RBR_RX_OVF_STS (1<<3)
+#define PHY_RBR_RX_UNF_STS (1<<2)
+#define PHY_RBR_ELAST_BUF1 (1<<1)
+#define PHY_RBR_ELAST_BUF0 (1<<0)
+#define PHY_LEDCR (0x18)
+#define PHY_LEDCR_DRV_SPDLED (1<<5)
+#define PHY_LEDCR_DRV_LNKLED (1<<4)
+#define PHY_LEDCR_DRV_ACTLED (1<<3)
+#define PHY_LEDCR_SPDLED (1<<2)
+#define PHY_LEDCR_LNKLED (1<<1)
+#define PHY_LEDCR_ACTLED (1<<0)
+#define PHY_PHYCR (0x19)
+#define PHY_PHYCR_MDIX_EN (1<<15)
+#define PHY_PHYCR_FORCE_MDIX (1<<14)
+#define PHY_PHYCR_PAUSE_RX (1<<13)
+#define PHY_PHYCR_PAUSE_TX (1<<12)
+#define PHY_PHYCR_BIST_FE (1<<11)
+#define PHY_PHYCR_PSR_15 (1<<10)
+#define PHY_PHYCR_BIST_STATUS (1<<9)
+#define PHY_PHYCR_BIST_START (1<<8)
+#define PHY_PHYCR_BP_STRETCH (1<<7)
+#define PHY_PHYCR_LED_CNFG1 (1<<6)
+#define PHY_PHYCR_LED_CNFG0 (1<<5)
+#define PHY_PHYCR_ADDR4 (1<<4)
+#define PHY_PHYCR_ADDR3 (1<<3)
+#define PHY_PHYCR_ADDR2 (1<<2)
+#define PHY_PHYCR_ADDR1 (1<<1)
+#define PHY_PHYCR_ADDR0 (1<<0)
+#define PHY_10BTSCR (0x1A)
+#define PHY_10BTSCR_SERIAL (1<<15)
+#define PHY_10BTSCR_SQ_MASK (0x07)
+#define PHY_10BTSCR_SQ_SHIFT (9)
+#define PHY_10BTSCR_LP_10_DIS (1<<8)
+#define PHY_10BTSCR_LP_DIS (1<<7)
+#define PHY_10BTSCR_FLINK_10 (1<<1)
+#define PHY_10BTSCR_POL (1<<4)
+#define PHY_10BTSCR_HB_DIS (1<<1)
+#define PHY_10BTSCR_JAB_DIS (1<<0)
+#define PHY_CDCTRL1 (0x1B)
+#define PHY_EDCR (0x1D)
+
+#endif /* _DP83848PHY_H */
diff --git a/bsps/lm32/shared/net/network.c b/bsps/lm32/shared/net/network.c
new file mode 100644
index 0000000..b53f25d
--- /dev/null
+++ b/bsps/lm32/shared/net/network.c
@@ -0,0 +1,319 @@
+/*
+ * RTEMS driver for Minimac2 ethernet IP-core of Milkymist SoC
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * COPYRIGHT (c) Yann Sionneau <yann.sionneau@telecom-sudparis.eu> (GSoC 2010)
+ * Telecom SudParis, France
+ * Copyright (C) 2011 Sebastien Bourdeauducq
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+#define RTEMS_STATUS_CHECKS_USE_PRINTK
+
+#include <bsp.h>
+#include <bsp/irq-generic.h>
+#include <stdio.h>
+#include <string.h>
+#include <rtems/bspIo.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/status-checks.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <net/ethernet.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <rtems.h>
+#include "bspopts.h"
+#include "../include/system_conf.h"
+#include "network.h"
+
+#define CTS_EVENT RTEMS_EVENT_1
+#define RX_EVENT RTEMS_EVENT_1
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+static struct arpcom arpcom;
+static rtems_id rx_daemon_id;
+static rtems_id tx_daemon_id;
+
+static void minimac_init(void *arg);
+static int minimac_ioctl(struct ifnet *ifp, ioctl_command_t command,
+ caddr_t data);
+static void minimac_start(struct ifnet *ifp);
+
+static void rx_daemon(void *arg);
+static void tx_daemon(void *arg);
+static rtems_isr rx_interrupt_handler(rtems_vector_number vector);
+static rtems_isr tx_interrupt_handler(rtems_vector_number vector);
+
+static bool validate_mac(const char *m)
+{
+ int i;
+
+ for(i=0;i<6;i++)
+ if((m[i] != 0x00) && (m[i] != 0xff))
+ return true;
+ return false;
+}
+
+static const char *get_mac_address(void)
+{
+ const char *flash_mac = (const char *)FLASH_OFFSET_MAC_ADDRESS;
+ static const char fallback_mac[6] = { 0x10, 0xe2, 0xd5, 0x00, 0x00, 0x00 };
+
+ if(validate_mac(flash_mac))
+ return flash_mac;
+ else {
+ printk("Warning: using fallback MAC address\n");
+ return fallback_mac;
+ }
+}
+
+int rtems_minimac_driver_attach(struct rtems_bsdnet_ifconfig *config,
+ int attaching)
+{
+ struct ifnet *ifp;
+ rtems_isr_entry dummy;
+ int i;
+ static int registered;
+ uint8_t *tx_buffer = (uint8_t *)MINIMAC_TX_BASE;
+
+ if(!attaching) {
+ printk("Minimac driver cannot be detached.\n");
+ return 0;
+ }
+
+ ifp = &(arpcom.ac_if);
+
+ if(registered) {
+ printk("Minimac driver already in use.\n");
+ return 0;
+ }
+ registered = 1;
+
+ memcpy(arpcom.ac_enaddr, get_mac_address(), 6);
+ ifp->if_mtu = ETHERMTU;
+ ifp->if_unit = 0;
+ ifp->if_name = "minimac";
+ ifp->if_init = minimac_init;
+ ifp->if_ioctl = minimac_ioctl;
+ ifp->if_start = minimac_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ rx_daemon_id = rtems_bsdnet_newproc("mrxd", 4096, rx_daemon, NULL);
+ tx_daemon_id = rtems_bsdnet_newproc("mtxd", 4096, tx_daemon, NULL);
+ rtems_interrupt_catch(rx_interrupt_handler, MM_IRQ_ETHRX, &dummy);
+ rtems_interrupt_catch(tx_interrupt_handler, MM_IRQ_ETHTX, &dummy);
+
+ MM_WRITE(MM_MINIMAC_STATE0, MINIMAC_STATE_LOADED);
+ MM_WRITE(MM_MINIMAC_STATE1, MINIMAC_STATE_LOADED);
+
+ for(i=0;i<7; i++)
+ tx_buffer[i] = 0x55;
+ tx_buffer[7] = 0xd5;
+ MM_WRITE(MM_MINIMAC_SETUP, 0);
+ rtems_bsdnet_event_send(tx_daemon_id, CTS_EVENT);
+
+ bsp_interrupt_vector_enable(MM_IRQ_ETHRX);
+ bsp_interrupt_vector_enable(MM_IRQ_ETHTX);
+
+ return 1;
+}
+
+static void minimac_start(struct ifnet *ifp)
+{
+ rtems_bsdnet_event_send(tx_daemon_id, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void minimac_init(void *arg)
+{
+ struct ifnet *ifp = &arpcom.ac_if;
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+static void minimac_stop(void)
+{
+ struct ifnet *ifp = &arpcom.ac_if;
+ ifp->if_flags &= ~IFF_RUNNING;
+}
+
+static int minimac_ioctl(struct ifnet *ifp, ioctl_command_t command,
+ caddr_t data)
+{
+ int error;
+
+ error = 0;
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch(ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ minimac_stop();
+ break;
+ case IFF_UP:
+ minimac_init(NULL);
+ break;
+ case IFF_UP | IFF_RUNNING:
+ minimac_stop();
+ minimac_init(NULL);
+ break;
+ default:
+ break;
+ }
+ break;
+
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+
+static rtems_isr rx_interrupt_handler(rtems_vector_number vector)
+{
+ /* Deassert IRQ line.
+ * The RX daemon will then read all the slots we marked as empty.
+ */
+ if(MM_READ(MM_MINIMAC_STATE0) == MINIMAC_STATE_PENDING)
+ MM_WRITE(MM_MINIMAC_STATE0, MINIMAC_STATE_EMPTY);
+ if(MM_READ(MM_MINIMAC_STATE1) == MINIMAC_STATE_PENDING)
+ MM_WRITE(MM_MINIMAC_STATE1, MINIMAC_STATE_EMPTY);
+
+ rtems_bsdnet_event_send(rx_daemon_id, RX_EVENT);
+
+ lm32_interrupt_ack(1 << MM_IRQ_ETHRX);
+}
+
+static void receive_packet(uint8_t *buffer, int length)
+{
+ struct ifnet *ifp = &arpcom.ac_if;
+ struct mbuf *m;
+ struct ether_header *eh;
+ uint32_t computed_crc, net_crc;
+
+ if(length < 64) {
+ printk("Warning: Ethernet packet too short\n");
+ return;
+ }
+
+ length -= 4; /* strip CRC */
+ net_crc = ((uint32_t)buffer[length])
+ | ((uint32_t)buffer[length+1] << 8)
+ | ((uint32_t)buffer[length+2] << 16)
+ | ((uint32_t)buffer[length+3] << 24);
+ length -= 8; /* strip preamble */
+ computed_crc = ether_crc32_le(&buffer[8], length) ^ 0xffffffff;
+ if(computed_crc == net_crc) {
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ length -= sizeof(struct ether_header); /* strip Ethernet header */
+ memcpy(m->m_data, &buffer[8+sizeof(struct ether_header)], length);
+ m->m_len = m->m_pkthdr.len = length;
+ m->m_pkthdr.rcvif = ifp;
+ eh = (struct ether_header *)&buffer[8];
+ ether_input(ifp, eh, m);
+ } else
+ printk("Ethernet CRC error: got %08x expected %08x (len=%d)\n",
+ net_crc, computed_crc, length);
+}
+
+static void rx_daemon(void *arg)
+{
+ rtems_event_set events;
+
+ while(1) {
+ rtems_bsdnet_event_receive(RX_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ if(MM_READ(MM_MINIMAC_STATE0) == MINIMAC_STATE_EMPTY) {
+ receive_packet((uint8_t *)MINIMAC_RX0_BASE, MM_READ(MM_MINIMAC_COUNT0));
+ MM_WRITE(MM_MINIMAC_STATE0, MINIMAC_STATE_LOADED);
+ }
+ if(MM_READ(MM_MINIMAC_STATE1) == MINIMAC_STATE_EMPTY) {
+ receive_packet((uint8_t *)MINIMAC_RX1_BASE, MM_READ(MM_MINIMAC_COUNT1));
+ MM_WRITE(MM_MINIMAC_STATE1, MINIMAC_STATE_LOADED);
+ }
+ }
+}
+
+/* RTEMS apparently doesn't support m_length() ... */
+static int copy_mbuf_chain(struct mbuf *m, uint8_t *target)
+{
+ int len;
+
+ len = 0;
+ while(m != NULL) {
+ if(m->m_len > 0) {
+ m_copydata(m, 0, m->m_len, (caddr_t)(target + len));
+ len += m->m_len;
+ }
+ m = m->m_next;
+ }
+ return len;
+}
+
+static void send_packet(struct ifnet *ifp, struct mbuf *m)
+{
+ unsigned int len;
+ unsigned int crc;
+ uint8_t *tx_buffer = (uint8_t *)(MINIMAC_TX_BASE+8);
+
+ len = copy_mbuf_chain(m, tx_buffer);
+ for(;len<60;len++)
+ tx_buffer[len] = 0x00; // Padding
+
+ crc = ether_crc32_le(tx_buffer, len) ^ 0xffffffff;
+
+ tx_buffer[len] = crc & 0xff;
+ tx_buffer[len+1] = (crc & 0xff00) >> 8;
+ tx_buffer[len+2] = (crc & 0xff0000) >> 16;
+ tx_buffer[len+3] = crc >> 24;
+
+ len += 4; // We add 4 bytes of CRC32
+
+ MM_WRITE(MM_MINIMAC_TXCOUNT, len + 8);
+}
+
+static rtems_isr tx_interrupt_handler(rtems_vector_number vector)
+{
+ lm32_interrupt_ack(1 << MM_IRQ_ETHTX);
+ rtems_bsdnet_event_send(tx_daemon_id, CTS_EVENT);
+}
+
+static void tx_daemon(void *arg)
+{
+ struct ifnet *ifp = &arpcom.ac_if;
+ rtems_event_set events;
+ struct mbuf *m;
+
+ while(1) {
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT, RTEMS_NO_TIMEOUT, &events);
+ while(1) {
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if(m == NULL)
+ break;
+ rtems_bsdnet_event_receive(CTS_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+ send_packet(ifp, m);
+ m_freem(m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
diff --git a/bsps/lm32/shared/net/network.h b/bsps/lm32/shared/net/network.h
new file mode 100644
index 0000000..6d81d30
--- /dev/null
+++ b/bsps/lm32/shared/net/network.h
@@ -0,0 +1,31 @@
+/**
+ * @file
+ * @ingroup lm32_milkymist_network RTEMSBSPsLM32SharedMilkymistOne
+ * @brief Driver for Minimac ethernet
+ */
+
+/* network.h
+ *
+ * RTEMS driver for Minimac ethernet IP-core of Milkymist SoC
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * COPYRIGHT (c) Yann Sionneau <yann.sionneau@telecom-sudparis.eu> (GSoC 2010)
+ * Telecom SudParis, France
+ */
+
+/**
+ * @defgroup lm32_milkymist_network Minimac ethernet driver
+ * @ingroup RTEMSBSPsLM32SharedMilkymistOne
+ * @brief Driver for Minimac ethernet IP-core of Milkymist SoC
+ * @{
+ */
+
+#ifndef __MILKYMIST_NETWORKING_H_
+#define __MILKYMIST_NETWORKING_H_
+
+int rtems_minimac_driver_attach (struct rtems_bsdnet_ifconfig *, int);
+
+#endif
diff --git a/bsps/lm32/shared/net/tsmac.c b/bsps/lm32/shared/net/tsmac.c
new file mode 100644
index 0000000..52abc64
--- /dev/null
+++ b/bsps/lm32/shared/net/tsmac.c
@@ -0,0 +1,821 @@
+/*
+ * This file contains definitions for LatticeMico32 TSMAC (Tri-Speed MAC)
+ *
+ * COPYRIGHT (c) 1989-1999.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * Jukka Pietarinen <jukka.pietarinen@mrf.fi>, 2008,
+ * Micro-Research Finland Oy
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <bsp.h>
+#include <stdio.h>
+#include <string.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/bspIo.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include "../include/system_conf.h"
+#include "tsmac.h"
+#include "dp83848phy.h"
+
+struct tsmac_softc {
+ struct arpcom arpcom;
+ void *ioaddr;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ int rxInterrupts;
+ int rxPktIgnore;
+ int rxLenCheckError;
+ int rxLongFrame;
+ int rxShortFrame;
+ int rxIPGViolation;
+ int rxCRCError;
+ int rxOKPackets;
+ int rxControlFrame;
+ int rxPauseFrame;
+ int rxMulticast;
+ int rxBroadcast;
+ int rxVLANTag;
+ int rxPreShrink;
+ int rxDribNib;
+ int rxUnsupOPCD;
+ int rxByteCnt;
+ int rxFifoFull;
+
+ int txInterrupts;
+ int txUnicast;
+ int txPauseFrame;
+ int txMulticast;
+ int txBroadcast;
+ int txVLANTag;
+ int txBadFCS;
+ int txJumboCnt;
+ int txByteCnt;
+ int txLostCarrier;
+ int txFifoFull;
+};
+
+/*
+ * Macros to access tsmac wrapper registers.
+ */
+
+static inline uint32_t tsmacread(unsigned int reg)
+{
+ return *((uint32_t *)(TS_MAC_CORE_BASE_ADDRESS + reg));
+}
+
+static inline void tsmacwrite(unsigned int reg, uint32_t value)
+{
+ *((uint32_t *)(TS_MAC_CORE_BASE_ADDRESS + reg)) = value;
+}
+
+/*
+ * tsmac is a wishbone to MAC wrapper.
+ * The macros below access to MAC registers.
+ */
+
+static inline uint16_t tsmacregread(unsigned int reg)
+{
+ tsmacwrite(LM32_TSMAC_MAC_REGS_ADDR_RW, reg);
+ return *((uint16_t *)(TS_MAC_CORE_BASE_ADDRESS + LM32_TSMAC_MAC_REGS_DATA + 2));
+}
+
+static inline void tsmacregwrite(unsigned int reg, uint16_t value)
+{
+ *((uint16_t *)(TS_MAC_CORE_BASE_ADDRESS + LM32_TSMAC_MAC_REGS_DATA + 2)) = value;
+ tsmacwrite(LM32_TSMAC_MAC_REGS_ADDR_RW, REGS_ADDR_WRITE | reg);
+}
+
+/*
+#define DEBUG 1
+*/
+
+/* We support one interface */
+
+#define TSMAC_NUM 1
+#define TSMAC_NAME "TSMAC"
+#define TSMAC_MAC0 0x00
+#define TSMAC_MAC1 0x0E
+#define TSMAC_MAC2 0xB2
+#define TSMAC_MAC3 0x00
+#define TSMAC_MAC4 0x00
+#define TSMAC_MAC5 0x01
+
+/*
+ * The interrupt vector number associated with the tsmac device
+ * driver.
+ */
+
+#define TSMAC_VECTOR ( TS_MAC_CORE_IRQ )
+#define TSMAC_IRQMASK ( 1 << TSMAC_VECTOR )
+
+rtems_isr tsmac_interrupt_handler(rtems_vector_number vector);
+
+extern rtems_isr_entry set_vector(rtems_isr_entry handler,
+ rtems_vector_number vector, int type);
+
+/*
+ * Macros to access PHY registers through the (G)MII
+ */
+
+uint16_t tsmacphyread(unsigned int reg)
+{
+ tsmacregwrite(LM32_TSMAC_GMII_MNG_CTL_BYTE0,
+ ((DEFAULT_PHY_ADDRESS & GMII_MNG_CTL_PHY_ADD_MASK) <<
+ GMII_MNG_CTL_PHY_ADD_SHIFT) |
+ ((reg & GMII_MNG_CTL_REG_ADD_MASK) <<
+ GMII_MNG_CTL_REG_ADD_SHIFT) |
+ GMII_MNG_CTL_READ_PHYREG);
+
+ /* Wait for management interface to be ready */
+ while(!(tsmacregread(LM32_TSMAC_GMII_MNG_CTL_BYTE0) & GMII_MNG_CTL_CMD_FIN));
+
+ return tsmacregread(LM32_TSMAC_GMII_MNG_DAT_BYTE0);
+}
+
+void tsmacphywrite(unsigned int reg, uint16_t value)
+{
+ tsmacregwrite(LM32_TSMAC_GMII_MNG_DAT_BYTE0, value);
+ tsmacregwrite(LM32_TSMAC_GMII_MNG_CTL_BYTE0,
+ ((DEFAULT_PHY_ADDRESS & GMII_MNG_CTL_PHY_ADD_MASK) <<
+ GMII_MNG_CTL_PHY_ADD_SHIFT) |
+ ((reg & GMII_MNG_CTL_REG_ADD_MASK) <<
+ GMII_MNG_CTL_REG_ADD_SHIFT) |
+ GMII_MNG_CTL_WRITE_PHYREG);
+
+ /* Wait for management interface to be ready */
+ while(!(tsmacregread(LM32_TSMAC_GMII_MNG_CTL_BYTE0) & GMII_MNG_CTL_CMD_FIN));
+}
+
+/*
+ * Event definitions
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+static struct tsmac_softc tsmac_softc[TSMAC_NUM];
+
+#ifdef CPU_U32_FIX
+
+/*
+ * Routine to align the received packet so that the ip header
+ * is on a 32-bit boundary. Necessary for cpu's that do not
+ * allow unaligned loads and stores and when the 32-bit DMA
+ * mode is used.
+ *
+ * Transfers are done on word basis to avoid possibly slow byte
+ * and half-word writes.
+ *
+ * Copied over from sonic.c driver
+ */
+
+void ipalign(struct mbuf *m)
+{
+ unsigned int *first, *last, data;
+ unsigned int tmp = 0;
+
+ if ((((int) m->m_data) & 2) && (m->m_len)) {
+ last = (unsigned int *) ((((int) m->m_data) + m->m_len + 8) & ~3);
+ first = (unsigned int *) (((int) m->m_data) & ~3);
+ tmp = *first << 16;
+ first++;
+ do {
+ data = *first;
+ *first = tmp | (data >> 16);
+ tmp = data << 16;
+ first++;
+ } while (first <= last);
+
+ m->m_data = (caddr_t)(((int) m->m_data) + 2);
+ }
+}
+#endif
+
+/*
+ * Receive task
+ */
+static void tsmac_rxDaemon(void *arg)
+{
+ struct tsmac_softc *tsmac = (struct tsmac_softc *) arg;
+ struct ifnet *ifp = &tsmac->arpcom.ac_if;
+ rtems_event_set events;
+ int rxq, count, len, data;
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_rxDaemon\n");
+#endif
+
+ for(;;)
+ {
+ rtems_bsdnet_event_receive( RTEMS_ALL_EVENTS,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_rxDaemon wakeup\n");
+#endif
+
+ for (;;)
+ {
+ struct mbuf* m;
+ struct ether_header* eh;
+ uint32_t *buf;
+
+ /* Get number of RX frames in RX FIFO */
+ rxq = tsmacread(LM32_TSMAC_RX_FRAMES_CNT);
+
+ if (rxq == 0)
+ break;
+
+ /* Get length of frame */
+ len = tsmacread(LM32_TSMAC_RX_LEN_FIFO);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": Frames %d, len 0x%04x (%d)\n",
+ rxq, len, len);
+#endif
+
+ /*
+ * Get memory for packet
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+
+ m->m_pkthdr.rcvif = ifp;
+
+ buf = (uint32_t *) mtod(m, uint32_t*);
+ for (count = 0; count < len; count += 4)
+ {
+ data = tsmacread(LM32_TSMAC_RX_DATA_FIFO);
+ *buf++ = data;
+#ifdef DEBUG
+ printk("%08x ", data);
+#endif
+ }
+#ifdef DEBUG
+ printk("\n");
+#endif
+
+ m->m_len = m->m_pkthdr.len =
+ len - sizeof(uint32_t) - sizeof(struct ether_header);
+ eh = mtod(m, struct ether_header*);
+ m->m_data += sizeof(struct ether_header);
+
+#ifdef CPU_U32_FIX
+ ipalign(m); /* Align packet on 32-bit boundary */
+#endif
+
+ /* Notify the ip stack that there is a new packet */
+ ether_input(ifp, eh, m);
+
+ /*
+ * Release RX frame
+ */
+ }
+ }
+}
+
+static unsigned char tsmac_txbuf[2048];
+
+static void tsmac_sendpacket(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mbuf *nm = m;
+ int len = 0, i;
+ uint32_t *buf;
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_sendpacket\n");
+#endif
+
+ do
+ {
+#ifdef DEBUG
+ printk("mbuf: 0x%08x len %03x: ", nm->m_data, nm->m_len);
+ for (i = 0; i < nm->m_len; i++)
+ {
+ printk("%02x", mtod(nm, unsigned char*)[i]);
+ if (i & 1)
+ printk(" ");
+ }
+ printk("\n");
+#endif
+
+ if (nm->m_len > 0)
+ {
+ memcpy(&tsmac_txbuf[len], (char *)nm->m_data, nm->m_len);
+ len += nm->m_len;
+ }
+ }
+ while ((nm = nm->m_next) != 0);
+
+ buf = (uint32_t *) tsmac_txbuf;
+ for (i = 0; i < len; i += 4)
+ {
+#ifdef DEBUG
+ printk("%08x", *buf);
+#endif
+ tsmacwrite(LM32_TSMAC_TX_DATA_FIFO, *buf++);
+ }
+#ifdef DEBUG
+ printk("\n");
+#endif
+
+ /*
+ * Enqueue TX frame
+ */
+ tsmacwrite(LM32_TSMAC_TX_LEN_FIFO, len);
+}
+
+/*
+ * Transmit task
+ */
+static void tsmac_txDaemon(void *arg)
+{
+ struct tsmac_softc *tsmac = (struct tsmac_softc *) arg;
+ struct ifnet *ifp = &tsmac->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+ int txq;
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_txDaemon\n");
+#endif
+
+ for (;;)
+ {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT | INTERRUPT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_txDaemon event\n");
+#endif
+ for (;;)
+ {
+ /*
+ * Here we should read amount of transmit memory available
+ */
+
+ txq = 2048;
+
+ if (txq < ifp->if_mtu)
+ {
+ /*
+ * Here we need to enable transmit done IRQ
+ */
+#ifdef DEBUG
+ printk(TSMAC_NAME ": TXMA %d < MTU + CW%d\n", txq,
+ ifp->if_mtu);
+#endif
+ break;
+ }
+
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": mbuf %08x\n", (int) m);
+#endif
+ if (!m)
+ break;
+ tsmac_sendpacket(ifp, m);
+
+ m_freem(m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Initialize TSMAC hardware
+ */
+void tsmac_init_hardware(struct tsmac_softc *tsmac)
+{
+ unsigned char *mac_addr;
+ int version_id, phyid, stat;
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_init_hardware\n");
+#endif
+
+ version_id = tsmacread(LM32_TSMAC_VERID);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": Version ID %08x\n", version_id);
+#endif
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": MAC MODE %04x\n", tsmacregread(LM32_TSMAC_MODE_BYTE0));
+ printk(TSMAC_NAME ": MAC TX_RX_CTL %04x\n", tsmacregread(LM32_TSMAC_TX_RX_CTL_BYTE0));
+ printk(TSMAC_NAME ": MAC MAX_PKT_SIZE %04x\n", tsmacregread(LM32_TSMAC_MAX_PKT_SIZE_BYTE0));
+ printk(TSMAC_NAME ": MAC IPG_VAL %04x\n", tsmacregread(LM32_TSMAC_IPG_VAL_BYTE0));
+ printk(TSMAC_NAME ": MAC MAC_ADDR0 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_0_BYTE0));
+ printk(TSMAC_NAME ": MAC MAC_ADDR1 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_1_BYTE0));
+ printk(TSMAC_NAME ": MAC MAC_ADDR2 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_2_BYTE0));
+ printk(TSMAC_NAME ": MAC TX_RX_STS %04x\n",
+ tsmacregread(LM32_TSMAC_TX_RX_STS_BYTE0));
+#endif
+
+ /*
+ * Set our physical address
+ */
+ mac_addr = tsmac->arpcom.ac_enaddr;
+ tsmacregwrite(LM32_TSMAC_MAC_ADDR_0_BYTE0, (mac_addr[0] << 8) | mac_addr[1]);
+ tsmacregwrite(LM32_TSMAC_MAC_ADDR_1_BYTE0, (mac_addr[2] << 8) | mac_addr[3]);
+ tsmacregwrite(LM32_TSMAC_MAC_ADDR_2_BYTE0, (mac_addr[4] << 8) | mac_addr[5]);
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": After setting MAC address.\n");
+ printk(TSMAC_NAME ": MAC MAC_ADDR0 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_0_BYTE0));
+ printk(TSMAC_NAME ": MAC MAC_ADDR1 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_1_BYTE0));
+ printk(TSMAC_NAME ": MAC MAC_ADDR2 %04x\n",
+ tsmacregread(LM32_TSMAC_MAC_ADDR_2_BYTE0));
+#endif
+
+ /*
+ * Configure PHY
+ */
+
+ phyid = tsmacphyread(PHY_PHYIDR1);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHYIDR1 %08x\n", phyid);
+#endif
+ phyid = tsmacphyread(PHY_PHYIDR2);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHYIDR2 %08x\n", phyid);
+#endif
+
+#ifdef TSMAC_FORCE_10BASET
+ /* Force 10baseT mode, no AN, full duplex */
+ tsmacphywrite(PHY_BMCR, PHY_BMCR_DUPLEX_MODE);
+ stat = tsmacphyread(PHY_BMCR);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHY BMCR %04x, wrote %04x\n", stat,
+ PHY_BMCR_DUPLEX_MODE);
+#endif
+ stat = tsmacphyread(PHY_BMSR);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHY BMSR %04x\n", stat);
+#endif
+ /* Support for 10baseT modes only */
+ tsmacphywrite(PHY_ANAR, PHY_ANAR_10_FD | PHY_ANAR_10 | PHY_ANAR_SEL_DEF);
+ stat = tsmacphyread(PHY_ANAR);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHY ANAR %04x, wrote %04x\n", stat,
+ PHY_ANAR_10_FD | PHY_ANAR_10 | PHY_ANAR_SEL_DEF);
+#endif
+#endif /* TSMAC_FORCE_10BASET */
+ stat = tsmacphyread(PHY_PHYSTS);
+#ifdef DEBUG
+ printk(TSMAC_NAME ": PHY PHYSTS %04x\n", stat);
+#endif
+
+ /* Enable receive and transmit interrupts */
+ tsmacwrite(LM32_TSMAC_INTR_ENB, INTR_ENB |
+ INTR_RX_SMRY | INTR_TX_SMRY |
+ INTR_RX_PKT_RDY | INTR_TX_PKT_SENT);
+}
+
+/*
+ * Initialize and start the device
+ */
+void tsmac_init(void *arg)
+{
+ struct tsmac_softc *tsmac = &tsmac_softc[0];
+ struct ifnet *ifp = &tsmac->arpcom.ac_if;
+
+#ifdef DEBUG
+ printk(TSMAC_NAME ": tsmac_init, tsmac->txDaemonTid = 0x%x\n",
+ tsmac->txDaemonTid);
+#endif
+
+ if (tsmac->txDaemonTid == 0)
+ {
+ /*
+ * Initialize hardware
+ */
+ tsmac_init_hardware(tsmac);
+
+ /*
+ * Start driver tasks
+ */
+ tsmac->txDaemonTid = rtems_bsdnet_newproc ("TSMACtx", 4096,
+ tsmac_txDaemon, tsmac);
+ tsmac->rxDaemonTid = rtems_bsdnet_newproc ("TSMACrx", 4096,
+ tsmac_rxDaemon, tsmac);
+ /*
+ * Setup interrupt handler
+ */
+ set_vector( tsmac_interrupt_handler, TSMAC_VECTOR, 1 );
+
+ /* Interrupt line for TSMAC */
+ lm32_interrupt_unmask(TSMAC_IRQMASK);
+ }
+
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Receive broadcast
+ */
+
+ tsmacregwrite(LM32_TSMAC_TX_RX_CTL_BYTE0, TX_RX_CTL_RECEIVE_BRDCST |
+ TX_RX_CTL_RECEIVE_PAUSE);
+
+ /*
+ * Enable transmitter
+ * Flow control enable
+ * Enable receiver
+ */
+
+ tsmacregwrite(LM32_TSMAC_MODE_BYTE0, MODE_TX_EN | MODE_RX_EN | MODE_FC_EN);
+
+ /*
+ * Wake up receive task to receive packets in queue
+ */
+ rtems_bsdnet_event_send(tsmac->rxDaemonTid, INTERRUPT_EVENT);
+}
+
+void tsmac_stop(struct ifnet *ifp)
+{
+ /*
+ * Mask tsmac interrupts
+ */
+ lm32_interrupt_mask(TSMAC_IRQMASK);
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Disable transmitter and receiver
+ */
+ tsmacregwrite(LM32_TSMAC_MODE_BYTE0, 0);
+}
+
+/*
+ * Send packet
+ */
+void tsmac_start(struct ifnet *ifp)
+{
+ struct tsmac_softc *tsmac = ifp->if_softc;
+
+ rtems_bsdnet_event_send (tsmac->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+void tsmac_stats(struct tsmac_softc *tsmac)
+{
+ /*
+ * Update counters from TSMAC MIB counters
+ */
+
+ tsmac->rxPktIgnore = tsmacread(LM32_TSMAC_RX_PKT_IGNR_CNT);
+ tsmac->rxLenCheckError = tsmacread(LM32_TSMAC_RX_LEN_CHK_ERR_CNT);
+ tsmac->rxLongFrame = tsmacread(LM32_TSMAC_RX_LNG_FRM_CNT);
+ tsmac->rxShortFrame = tsmacread(LM32_TSMAC_RX_SHRT_FRM_CNT);
+ tsmac->rxIPGViolation = tsmacread(LM32_TSMAC_RX_IPG_VIOL_CNT);
+ tsmac->rxCRCError = tsmacread(LM32_TSMAC_RX_CRC_ERR_CNT);
+ tsmac->rxOKPackets = tsmacread(LM32_TSMAC_RX_OK_PKT_CNT);
+ tsmac->rxControlFrame = tsmacread(LM32_TSMAC_RX_CTL_FRM_CNT);
+ tsmac->rxPauseFrame = tsmacread(LM32_TSMAC_RX_PAUSE_FRM_CNT);
+ tsmac->rxMulticast = tsmacread(LM32_TSMAC_RX_MULTICAST_CNT);
+ tsmac->rxBroadcast = tsmacread(LM32_TSMAC_RX_BRDCAST_CNT);
+ tsmac->rxVLANTag = tsmacread(LM32_TSMAC_RX_VLAN_TAG_CNT);
+ tsmac->rxPreShrink = tsmacread(LM32_TSMAC_RX_PRE_SHRINK_CNT);
+ tsmac->rxDribNib = tsmacread(LM32_TSMAC_RX_DRIB_NIB_CNT);
+ tsmac->rxUnsupOPCD = tsmacread(LM32_TSMAC_RX_UNSUP_OPCD_CNT);
+ tsmac->rxByteCnt = tsmacread(LM32_TSMAC_RX_BYTE_CNT);
+
+ tsmac->txUnicast = tsmacread(LM32_TSMAC_TX_UNICAST_CNT);
+ tsmac->txPauseFrame = tsmacread(LM32_TSMAC_TX_PAUSE_FRM_CNT);
+ tsmac->txMulticast = tsmacread(LM32_TSMAC_TX_MULTICAST_CNT);
+ tsmac->txBroadcast = tsmacread(LM32_TSMAC_TX_BRDCAST_CNT);
+ tsmac->txVLANTag = tsmacread(LM32_TSMAC_TX_VLAN_TAG_CNT);
+ tsmac->txBadFCS = tsmacread(LM32_TSMAC_TX_BAD_FCS_CNT);
+ tsmac->txJumboCnt = tsmacread(LM32_TSMAC_TX_JUMBO_CNT);
+ tsmac->txByteCnt = tsmacread(LM32_TSMAC_TX_BYTE_CNT);
+
+ printk("RX Interrupts: %8d", tsmac->rxInterrupts);
+ printk(" RX Len Chk Error: %8d", tsmac->rxLenCheckError);
+ printk(" RX Long Frame: %8d\n", tsmac->rxLongFrame);
+ printk("RX Short Frame: %8d", tsmac->rxShortFrame);
+ printk(" RX IPG Violation: %8d", tsmac->rxIPGViolation);
+ printk(" RX CRC Errors: %8d\n", tsmac->rxCRCError);
+ printk("RX OK Packets: %8d", tsmac->rxOKPackets);
+ printk(" RX Control Frame: %8d", tsmac->rxControlFrame);
+ printk(" RX Pause Frame: %8d\n", tsmac->rxPauseFrame);
+ printk("RX Multicast: %8d", tsmac->rxMulticast);
+ printk(" RX Broadcast: %8d", tsmac->rxBroadcast);
+ printk(" RX VLAN Tag: %8d\n", tsmac->rxVLANTag);
+ printk("RX Pre Shrink: %8d", tsmac->rxPreShrink);
+ printk(" RX Dribb. Nibble: %8d", tsmac->rxDribNib);
+ printk(" RX Unsupp. OPCD: %8d\n", tsmac->rxUnsupOPCD);
+ printk("RX Byte Count: %8d", tsmac->rxByteCnt);
+ printk(" RX FIFO Full: %8d\n", tsmac->rxFifoFull);
+
+ printk("TX Interrupts: %8d", tsmac->txInterrupts);
+ printk(" TX Unicast: %8d", tsmac->txUnicast);
+ printk(" TX Pause Frame: %8d\n", tsmac->txPauseFrame);
+ printk("TX Multicast: %8d", tsmac->txMulticast);
+ printk(" TX Broadcast: %8d", tsmac->txBroadcast);
+ printk(" TX VLAN Tag: %8d\n", tsmac->txVLANTag);
+ printk("TX Bad FSC: %8d", tsmac->txBadFCS);
+ printk(" TX Jumbo Frame: %8d", tsmac->txJumboCnt);
+ printk(" TX Byte Count: %8d\n", tsmac->txByteCnt);
+ printk("TX FIFO Full: %8d\n", tsmac->txFifoFull);
+}
+
+/*
+ * TSMAC ioctl handler
+ */
+
+int tsmac_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct tsmac_softc *tsmac = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ tsmac_stop ((struct ifnet *) tsmac);
+ break;
+
+ case IFF_UP:
+ tsmac_init ((struct ifnet *) tsmac);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ tsmac_stop ((struct ifnet *) tsmac);
+ tsmac_init ((struct ifnet *) tsmac);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ tsmac_stats (tsmac);
+ break;
+
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/*
+ * Attach a TSMAC driver
+ */
+int rtems_tsmac_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ struct tsmac_softc *tsmac;
+ struct ifnet *ifp;
+ int mtu, i;
+ int unit;
+ char *unitName;
+
+ if ((unit = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0)
+ {
+ printk(TSMAC_NAME ": Driver name parsing failed.\n");
+ return 0;
+ }
+
+ if ((unit < 0) || (unit >= TSMAC_NUM))
+ {
+ printk(TSMAC_NAME ": Bad unit number %d.\n", unit);
+ return 0;
+ }
+
+ tsmac = &tsmac_softc[unit];
+
+ ifp = &tsmac->arpcom.ac_if;
+ if (ifp->if_softc != NULL)
+ {
+ printk(TSMAC_NAME ": Driver already in use.\n");
+ return 0;
+ }
+
+ /* Base address for TSMAC */
+ if (config->bpar == 0)
+ {
+ printk(TSMAC_NAME ": Using default base address 0x%08x.\n", TS_MAC_CORE_BASE_ADDRESS);
+ config->bpar = TS_MAC_CORE_BASE_ADDRESS;
+ }
+ tsmac->ioaddr = config->bpar;
+
+ /* Hardware address for TSMAC */
+ if (config->hardware_address == 0)
+ {
+ printk(TSMAC_NAME ": Using default hardware address.\n");
+ tsmac->arpcom.ac_enaddr[0] = TSMAC_MAC0;
+ tsmac->arpcom.ac_enaddr[1] = TSMAC_MAC1;
+ tsmac->arpcom.ac_enaddr[2] = TSMAC_MAC2;
+ tsmac->arpcom.ac_enaddr[3] = TSMAC_MAC3;
+ tsmac->arpcom.ac_enaddr[4] = TSMAC_MAC4;
+ tsmac->arpcom.ac_enaddr[5] = TSMAC_MAC5;
+ }
+ else
+ memcpy(tsmac->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ printk(TSMAC_NAME ": MAC address ");
+ for (i = 0; i < ETHER_ADDR_LEN; i++)
+ {
+ printk("%02x", tsmac->arpcom.ac_enaddr[i]);
+ if (i != ETHER_ADDR_LEN-1)
+ printk(":");
+ else
+ printk("\n");
+ }
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = tsmac;
+ ifp->if_unit = unit;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = tsmac_init;
+ ifp->if_ioctl = tsmac_ioctl;
+ ifp->if_start = tsmac_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ return 1;
+}
+
+rtems_isr tsmac_interrupt_handler(rtems_vector_number vector)
+{
+ struct tsmac_softc *tsmac = &tsmac_softc[0];
+ uint32_t irq_stat, rx_stat, tx_stat;
+
+ irq_stat = tsmacread(LM32_TSMAC_INTR_SRC);
+ if (irq_stat & INTR_RX_PKT_RDY)
+ {
+ tsmac->rxInterrupts++;
+ rtems_bsdnet_event_send(tsmac->rxDaemonTid, INTERRUPT_EVENT);
+ }
+
+ if (irq_stat & INTR_TX_PKT_SENT)
+ {
+ tsmac->txInterrupts++;
+ rtems_bsdnet_event_send(tsmac->txDaemonTid, INTERRUPT_EVENT);
+ }
+
+ rx_stat = tsmacread(LM32_TSMAC_RX_STATUS);
+ if (rx_stat & STAT_RX_FIFO_FULL)
+ tsmac->rxFifoFull++;
+
+ tx_stat = tsmacread(LM32_TSMAC_TX_STATUS);
+ if (tx_stat & STAT_TX_FIFO_FULL)
+ tsmac->txFifoFull++;
+
+ lm32_interrupt_ack(TSMAC_IRQMASK);
+}
+
diff --git a/bsps/lm32/shared/net/tsmac.h b/bsps/lm32/shared/net/tsmac.h
new file mode 100644
index 0000000..ee7a7a1
--- /dev/null
+++ b/bsps/lm32/shared/net/tsmac.h
@@ -0,0 +1,172 @@
+/**
+ * @file
+ * @ingroup lm32_tsmac
+ * @brief LatticeMico32 TSMAC (Tri-Speed MAC) definitions.
+ */
+
+/*
+ * This file contains definitions for LatticeMico32 TSMAC (Tri-Speed MAC)
+ *
+ * COPYRIGHT (c) 1989-1999.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ * Jukka Pietarinen <jukka.pietarinen@mrf.fi>, 2008,
+ * Micro-Research Finland Oy
+ */
+
+/**
+ * @defgroup lm32_tsmac LM32 TSMAC
+ * @ingroup RTEMSBSPsLM32Shared
+ * @brief LatticeMico32 TSMAC (Tri-Speed MAC) definitions.
+ * @{
+ */
+
+#ifndef _BSPTSMAC_H
+#define _BSPTSMAC_H
+
+/* FIFO Registers */
+
+#define LM32_TSMAC_RX_LEN_FIFO (0x000)
+#define LM32_TSMAC_RX_DATA_FIFO (0x004)
+#define LM32_TSMAC_TX_LEN_FIFO (0x008)
+#define LM32_TSMAC_TX_DATA_FIFO (0x00C)
+
+/* Control and Status Registers */
+
+#define LM32_TSMAC_VERID (0x100)
+#define LM32_TSMAC_INTR_SRC (0x104)
+#define INTR_RX_SMRY (0x00020000)
+#define INTR_TX_SMRY (0x00010000)
+#define INTR_RX_FIFO_FULL (0x00001000)
+#define INTR_RX_ERROR (0x00000800)
+#define INTR_RX_FIFO_ERROR (0x00000400)
+#define INTR_RX_FIFO_ALMOST_FULL (0x00000200)
+#define INTR_RX_PKT_RDY (0x00000100)
+#define INTR_TX_FIFO_FULL (0x00000010)
+#define INTR_TX_DISCFRM (0x00000008)
+#define INTR_TX_FIFO_ALMOST_EMPTY (0x00000004)
+#define INTR_TX_FIFO_ALMOST_FULL (0x00000002)
+#define INTR_TX_PKT_SENT (0x00000001)
+#define LM32_TSMAC_INTR_ENB (0x108)
+#define INTR_ENB (0x00040000)
+#define LM32_TSMAC_RX_STATUS (0x10C)
+#define STAT_RX_FIFO_FULL (0x00000010)
+#define STAT_RX_ERROR (0x00000008)
+#define STAT_RX_FIFO_ERROR (0x00000004)
+#define STAT_RX_FIFO_ALMOST_FULL (0x00000002)
+#define STAT_RX_PKT_RDY (0x00000001)
+#define LM32_TSMAC_TX_STATUS (0x110)
+#define STAT_TX_FIFO_FULL (0x00000010)
+#define STAT_TX_DISCFRM (0x00000008)
+#define STAT_TX_FIFO_ALMOST_EMPTY (0x00000004)
+#define STAT_TX_FIFO_ALMOST_FULL (0x00000002)
+#define STAT_TX_PKT_SENT (0x00000001)
+#define LM32_TSMAC_RX_FRAMES_CNT (0x114)
+#define LM32_TSMAC_TX_FRAMES_CNT (0x118)
+#define LM32_TSMAC_RX_FIFO_TH (0x11C)
+#define LM32_TSMAC_TX_FIFO_TH (0x120)
+#define LM32_TSMAC_SYS_CTL (0x124)
+#define SYS_CTL_TX_FIFO_FLUSH (0x00000010)
+#define SYS_CTL_RX_FIFO_FLUSH (0x00000008)
+#define SYS_CTL_TX_SNDPAUSREQ (0x00000004)
+#define SYS_CTL_TX_FIFOCTRL (0x00000002)
+#define SYS_CTL_IGNORE_NEXT_PKT (0x00000001)
+#define LM32_TSMAC_PAUSE_TMR (0x128)
+
+/* Tri-Speed MAC Registers */
+
+#define LM32_TSMAC_MAC_REGS_DATA (0x200)
+#define LM32_TSMAC_MAC_REGS_ADDR_RW (0x204)
+#define REGS_ADDR_WRITE (0x80000000)
+#define LM32_TSMAC_MODE_BYTE0 (0x000)
+#define MODE_TX_EN (1<<3)
+#define MODE_RX_EN (1<<2)
+#define MODE_FC_EN (1<<1)
+#define MODE_GBIT_EN (1<<0)
+#define LM32_TSMAC_TX_RX_CTL_BYTE0 (0x002)
+#define TX_RX_CTL_RECEIVE_SHORT (1<<8)
+#define TX_RX_CTL_RECEIVE_BRDCST (1<<7)
+#define TX_RX_CTL_DIS_RTRY (1<<6)
+#define TX_RX_CTL_HDEN (1<<5)
+#define TX_RX_CTL_RECEIVE_MLTCST (1<<4)
+#define TX_RX_CTL_RECEIVE_PAUSE (1<<3)
+#define TX_RX_CTL_TX_DIS_FCS (1<<2)
+#define TX_RX_CTL_DISCARD_FCS (1<<1)
+#define TX_RX_CTL_PRMS (1<<0)
+#define LM32_TSMAC_MAX_PKT_SIZE_BYTE0 (0x004)
+#define LM32_TSMAC_IPG_VAL_BYTE0 (0x008)
+#define LM32_TSMAC_MAC_ADDR_0_BYTE0 (0x00A)
+#define LM32_TSMAC_MAC_ADDR_1_BYTE0 (0x00C)
+#define LM32_TSMAC_MAC_ADDR_2_BYTE0 (0x00E)
+#define LM32_TSMAC_TX_RX_STS_BYTE0 (0x012)
+#define TX_RX_STS_RX_IDLE (1<<10)
+#define TX_RX_STS_TAGGED_FRAME (1<<9)
+#define TX_RX_STS_BRDCST_FRAME (1<<8)
+#define TX_RX_STS_MULTCST_FRAME (1<<7)
+#define TX_RX_STS_IPG_SHRINK (1<<6)
+#define TX_RX_STS_SHORT_FRAME (1<<5)
+#define TX_RX_STS_LONG_FRAME (1<<4)
+#define TX_RX_STS_ERROR_FRAME (1<<3)
+#define TX_RX_STS_CRC (1<<2)
+#define TX_RX_STS_PAUSE_FRAME (1<<1)
+#define TX_RX_STS_TX_IDLE (1<<0)
+#define LM32_TSMAC_GMII_MNG_CTL_BYTE0 (0x014)
+#define GMII_MNG_CTL_CMD_FIN (1<<14)
+#define GMII_MNG_CTL_READ_PHYREG (0)
+#define GMII_MNG_CTL_WRITE_PHYREG (1<<13)
+#define GMII_MNG_CTL_PHY_ADD_MASK (0x001f)
+#define GMII_MNG_CTL_PHY_ADD_SHIFT (8)
+#define GMII_MNG_CTL_REG_ADD_MASK (0x001f)
+#define GMII_MNG_CTL_REG_ADD_SHIFT (0)
+#define LM32_TSMAC_GMII_MNG_DAT_BYTE0 (0x016)
+#define LM32_TSMAC_MLT_TAB_0_BYTE0 (0x022)
+#define LM32_TSMAC_MLT_TAB_1_BYTE0 (0x024)
+#define LM32_TSMAC_MLT_TAB_2_BYTE0 (0x026)
+#define LM32_TSMAC_MLT_TAB_3_BYTE0 (0x028)
+#define LM32_TSMAC_MLT_TAB_4_BYTE0 (0x02A)
+#define LM32_TSMAC_MLT_TAB_5_BYTE0 (0x02C)
+#define LM32_TSMAC_MLT_TAB_6_BYTE0 (0x02E)
+#define LM32_TSMAC_MLT_TAB_7_BYTE0 (0x030)
+#define LM32_TSMAC_VLAN_TAG_BYTE0 (0x032)
+#define LM32_TSMAC_PAUS_OP_BYTE0 (0x034)
+
+/* Receive Statistics Counters */
+
+#define LM32_TSMAC_RX_PKT_IGNR_CNT (0x300)
+#define LM32_TSMAC_RX_LEN_CHK_ERR_CNT (0x304)
+#define LM32_TSMAC_RX_LNG_FRM_CNT (0x308)
+#define LM32_TSMAC_RX_SHRT_FRM_CNT (0x30C)
+#define LM32_TSMAC_RX_IPG_VIOL_CNT (0x310)
+#define LM32_TSMAC_RX_CRC_ERR_CNT (0x314)
+#define LM32_TSMAC_RX_OK_PKT_CNT (0x318)
+#define LM32_TSMAC_RX_CTL_FRM_CNT (0x31C)
+#define LM32_TSMAC_RX_PAUSE_FRM_CNT (0x320)
+#define LM32_TSMAC_RX_MULTICAST_CNT (0x324)
+#define LM32_TSMAC_RX_BRDCAST_CNT (0x328)
+#define LM32_TSMAC_RX_VLAN_TAG_CNT (0x32C)
+#define LM32_TSMAC_RX_PRE_SHRINK_CNT (0x330)
+#define LM32_TSMAC_RX_DRIB_NIB_CNT (0x334)
+#define LM32_TSMAC_RX_UNSUP_OPCD_CNT (0x338)
+#define LM32_TSMAC_RX_BYTE_CNT (0x33C)
+
+/* Transmit Statistics Counters */
+
+#define LM32_TSMAC_TX_UNICAST_CNT (0x400)
+#define LM32_TSMAC_TX_PAUSE_FRM_CNT (0x404)
+#define LM32_TSMAC_TX_MULTICAST_CNT (0x408)
+#define LM32_TSMAC_TX_BRDCAST_CNT (0x40C)
+#define LM32_TSMAC_TX_VLAN_TAG_CNT (0x410)
+#define LM32_TSMAC_TX_BAD_FCS_CNT (0x414)
+#define LM32_TSMAC_TX_JUMBO_CNT (0x418)
+#define LM32_TSMAC_TX_BYTE_CNT (0x41C)
+
+#ifdef CPU_U32_FIX
+void ipalign(struct mbuf *m);
+#endif
+
+#endif /* _BSPTSMAC_H */
+/** @} */
diff --git a/bsps/m68k/av5282/net/network.c b/bsps/m68k/av5282/net/network.c
new file mode 100644
index 0000000..8c37e67
--- /dev/null
+++ b/bsps/m68k/av5282/net/network.c
@@ -0,0 +1,940 @@
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <string.h>
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/ethernet.h>
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+#define FEC_INTC0_TX_VECTOR (64+23)
+#define FEC_INTC0_RX_VECTOR (64+27)
+
+#define FEC_INTC0_TX_VECTOR (64+23)
+#define FEC_INTC0_RX_VECTOR (64+27)
+#define MII_VECTOR (64+7) /* IRQ7* pin connected to external transceiver */
+#define MII_EPPAR MCF5282_EPORT_EPPAR_EPPA7_LEVEL
+#define MII_EPDDR MCF5282_EPORT_EPDDR_EPDD7
+#define MII_EPIER MCF5282_EPORT_EPIER_EPIE7
+#define MII_EPPDR MCF5282_EPORT_EPPDR_EPPD7
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses three or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 20
+#define TX_BD_PER_BUF 3
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define TX_INTERRUPT_EVENT RTEMS_EVENT_1
+#define RX_INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+ #error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+typedef struct mcf5282BufferDescriptor_ {
+ volatile uint16_t status;
+ uint16_t length;
+ volatile void *buffer;
+} mcf5282BufferDescriptor_t;
+
+/*
+ * Per-device data
+ */
+struct mcf5282_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ mcf5282BufferDescriptor_t *rxBdBase;
+ mcf5282BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long txInterrupts;
+ unsigned long miiInterrupts;
+ unsigned long txRawWait;
+ unsigned long txRealign;
+ unsigned long txRealignDrop;
+ uint16_t mii_sr2;
+};
+static struct mcf5282_enet_struct enet_driver[NIFACES];
+
+static int
+getMII(int phyNumber, int regNumber);
+
+
+static rtems_isr
+mcf5282_fec_rx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_RXF;
+ MCF5282_FEC_EIMR &= ~MCF5282_FEC_EIMR_RXF;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].rxDaemonTid, RX_INTERRUPT_EVENT);
+}
+
+static rtems_isr
+mcf5282_fec_tx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_TXF;
+ MCF5282_FEC_EIMR &= ~MCF5282_FEC_EIMR_TXF;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].txDaemonTid, TX_INTERRUPT_EVENT);
+}
+
+static rtems_isr
+mcf5282_mii_interrupt_handler( rtems_vector_number v )
+{
+ uint16_t sr2;
+
+ enet_driver[0].miiInterrupts++;
+ getMII(1, 19); /* Read and clear interrupt status bits */
+ enet_driver[0].mii_sr2 = sr2 = getMII(1, 17);
+ if (((sr2 & 0x200) != 0)
+ && ((MCF5282_FEC_TCR & MCF5282_FEC_TCR_FDEN) == 0))
+ MCF5282_FEC_TCR |= MCF5282_FEC_TCR_FDEN;
+ else if (((sr2 & 0x200) == 0)
+ && ((MCF5282_FEC_TCR & MCF5282_FEC_TCR_FDEN) != 0))
+ MCF5282_FEC_TCR &= ~MCF5282_FEC_TCR_FDEN;
+}
+
+/*
+ * Allocate buffer descriptors from (non-cached) on-chip static RAM
+ * Ensure 128-bit (16-byte) alignment
+ */
+extern char __SRAMBASE[];
+
+static mcf5282BufferDescriptor_t *
+mcf5282_bd_allocate(unsigned int count)
+{
+ static mcf5282BufferDescriptor_t *bdp = (mcf5282BufferDescriptor_t *)__SRAMBASE;
+ mcf5282BufferDescriptor_t *p = bdp;
+
+ bdp += count;
+ if ((int)bdp & 0xF)
+ bdp = (mcf5282BufferDescriptor_t *)((char *)bdp + (16 - ((int)bdp & 0xF)));
+ return p;
+}
+
+
+/*
+ * Read MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static int
+getMII(int phyNumber, int regNumber)
+{
+ MCF5282_FEC_MMFR = (0x1 << 30) |
+ (0x2 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16);
+ while ((MCF5282_FEC_EIR & MCF5282_FEC_EIR_MII) == 0);
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_MII;
+ return MCF5282_FEC_MMFR & 0xFFFF;
+}
+
+
+/*
+ * Write MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static void
+setMII(int phyNumber, int regNumber, int value)
+{
+ MCF5282_FEC_MMFR = (0x1 << 30) |
+ (0x1 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16) |
+ (value & 0xFFFF);
+ while ((MCF5282_FEC_EIR & MCF5282_FEC_EIR_MII) == 0);
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_MII;
+}
+
+static void
+mcf5282_fec_initialize_hardware(struct mcf5282_enet_struct *sc)
+{
+ int i;
+ const unsigned char *hwaddr;
+ rtems_status_code status;
+ rtems_isr_entry old_handler;
+ uint32_t clock_speed = get_CPU_clock_speed();
+
+ /*
+ * Issue reset to FEC
+ */
+ MCF5282_FEC_ECR = MCF5282_FEC_ECR_RESET;
+ rtems_task_wake_after(1);
+ MCF5282_FEC_ECR = 0;
+
+ /*
+ * Configuration of I/O ports is done outside of this function
+ */
+#if 0
+ imm->gpio.pbcnt |= MCF5282_GPIO_PBCNT_SET_FEC; /* Set up port b FEC pins */
+#endif
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+ MCF5282_FEC_PALR = (hwaddr[0] << 24) | (hwaddr[1] << 16) |
+ (hwaddr[2] << 8) | (hwaddr[3] << 0);
+ MCF5282_FEC_PAUR = (hwaddr[4] << 24) | (hwaddr[5] << 16);
+
+
+ /*
+ * Clear the hash table
+ */
+ MCF5282_FEC_GAUR = 0;
+ MCF5282_FEC_GALR = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ MCF5282_FEC_EMRBR = 1520; /* Standard Ethernet */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc(sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc(sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = mcf5282_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = mcf5282_bd_allocate(sc->txBdCount);
+ MCF5282_FEC_ERDSR = (int)sc->rxBdBase;
+ MCF5282_FEC_ETDSR = (int)sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous
+ * MII mode
+ * Full duplex
+ * No loopback
+ */
+ MCF5282_FEC_RCR = MCF5282_FEC_RCR_MAX_FL(MAX_MTU_SIZE) |
+ MCF5282_FEC_RCR_MII_MODE;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full duplex
+ * No heartbeat
+ */
+ MCF5282_FEC_TCR = MCF5282_FEC_TCR_FDEN;
+
+ /*
+ * Initialize statistic counters
+ */
+ MCF5282_FEC_MIBC = MCF5282_FEC_MIBC_MIB_DISABLE;
+ {
+ vuint32 *vuip = &MCF5282_FEC_RMON_T_DROP;
+ while (vuip <= &MCF5282_FEC_IEEE_R_OCTETS_OK)
+ *vuip++ = 0;
+ }
+ MCF5282_FEC_MIBC = 0;
+
+ /*
+ * Set MII speed to <= 2.5 MHz
+ */
+ i = (clock_speed + 5000000 - 1) / 5000000;
+ MCF5282_FEC_MSCR = MCF5282_FEC_MSCR_MII_SPEED(i);
+
+ /*
+ * Set PHYS to 100 Mb/s, full duplex
+ */
+ setMII(1, 0, 0x2100);
+ setMII(1, 4, 0x0181);
+ setMII(1, 0, 0x0000);
+ rtems_task_wake_after(2);
+ sc->mii_sr2 = getMII(1, 17);
+ setMII(1, 18, 0x0072);
+ setMII(1, 0, 0x1000);
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ sc->txBdBase[i].status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Set up interrupts
+ */
+ status = rtems_interrupt_catch( mcf5282_fec_tx_interrupt_handler, FEC_INTC0_TX_VECTOR, &old_handler );
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC TX interrupt handler: %s\n",
+ rtems_status_text(status));
+ status = rtems_interrupt_catch(mcf5282_fec_rx_interrupt_handler, FEC_INTC0_RX_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC RX interrupt handler: %s\n",
+ rtems_status_text(status));
+ MCF5282_INTC0_ICR23 = MCF5282_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5282_INTC_ICR_IP(FEC_IRQ_TX_PRIORITY);
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT23 | MCF5282_INTC_IMRL_MASKALL);
+ MCF5282_INTC0_ICR27 = MCF5282_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5282_INTC_ICR_IP(FEC_IRQ_RX_PRIORITY);
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT27 | MCF5282_INTC_IMRL_MASKALL);
+
+ status = rtems_interrupt_catch(mcf5282_mii_interrupt_handler, MII_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC MII interrupt handler: %s\n",
+ rtems_status_text(status));
+ MCF5282_EPORT_EPPAR &= ~MII_EPPAR;
+ MCF5282_EPORT_EPDDR &= ~MII_EPDDR;
+ MCF5282_EPORT_EPIER |= MII_EPIER;
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT7 | MCF5282_INTC_IMRL_MASKALL);
+}
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ */
+void
+fec_retire_tx_bd(volatile struct mcf5282_enet_struct *sc )
+{
+ struct mbuf *m, *n;
+ uint16_t status;
+
+ while ((sc->txBdActiveCount != 0)
+ && (((status = sc->txBdBase[sc->txBdTail].status) & MCF5282_FEC_TxBD_R) == 0)) {
+ if ((status & MCF5282_FEC_TxBD_TO1) == 0) {
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE(m, n);
+ }
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ sc->txBdActiveCount--;
+ }
+}
+
+static void
+fec_rxDaemon (void *arg)
+{
+ volatile struct mcf5282_enet_struct *sc = (volatile struct mcf5282_enet_struct *)arg;
+ struct ifnet *ifp = (struct ifnet* )&sc->arpcom.ac_if;
+ struct mbuf *m;
+ volatile uint16_t status;
+ volatile mcf5282BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ rxBd->status = MCF5282_FEC_RxBD_E;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= MCF5282_FEC_RxBD_W;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ /* Indicate we have some ready buffers available */
+ MCF5282_FEC_RDAR = 0;
+
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & MCF5282_FEC_RxBD_E) {
+ /*
+ * Clear old events.
+ */
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_RXF;
+
+ /*
+ * Wait for packet to arrive.
+ * Check the buffer descriptor before waiting for the event.
+ * This catches the case when a packet arrives between the
+ * `if' above, and the clearing of the RXF bit in the EIR.
+ */
+ while ((status = rxBd->status) & MCF5282_FEC_RxBD_E) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5282_FEC_EIMR |= MCF5282_FEC_EIMR_RXF;
+ rtems_interrupt_enable(level);
+ rtems_bsdnet_event_receive (RX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & MCF5282_FEC_RxBD_L) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+ int len = rxBd->length - sizeof(uint32_t);
+
+ /*
+ * Invalidate the cache and push the packet up.
+ * The cache is so small that it's more efficient to just
+ * invalidate the whole thing unless the packet is very small.
+ */
+ m = sc->rxMbuf[rxBdIndex];
+ if (len < 128)
+ rtems_cache_invalidate_multiple_data_lines(m->m_data, len);
+ else
+ rtems_cache_invalidate_entire_data();
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+ eh = mtod(m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input(ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & MCF5282_FEC_RxBD_W) | MCF5282_FEC_RxBD_E;
+ MCF5282_FEC_RDAR = 0;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void
+fec_sendpacket(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+ volatile mcf5282BufferDescriptor_t *firstTxBd, *txBd;
+ int nAdded;
+ uint16_t status;
+
+ /*
+ * Free up buffer descriptors
+ */
+ fec_retire_tx_bd(sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ firstTxBd = sc->txBdBase + sc->txBdHead;
+
+ while(m != NULL) {
+ /*
+ * Wait for buffer descriptor to become available
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events.
+ */
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_TXF;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Check for buffer descriptors before waiting for the event.
+ * This catches the case when a buffer became available between
+ * the `if' above, and the clearing of the TXF bit in the EIR.
+ */
+ fec_retire_tx_bd(sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5282_FEC_EIMR |= MCF5282_FEC_EIMR_TXF;
+ rtems_interrupt_enable(level);
+ sc->txRawWait++;
+ rtems_bsdnet_event_receive(TX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ fec_retire_tx_bd(sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag on the first fragment
+ * until the whole packet has been readied.
+ */
+ status = nAdded ? MCF5282_FEC_TxBD_R : 0;
+
+ /*
+ * The IP fragmentation routine in ip_output
+ * can produce fragments with zero length.
+ */
+ if (m->m_len){
+ char *p = mtod(m, char *);
+ int offset = (int) p & 0x3;
+ txBd = sc->txBdBase + sc->txBdHead;
+ if (offset == 0) {
+ txBd->buffer = p;
+ txBd->length = m->m_len;
+ sc->txMbuf[sc->txBdHead] = m;
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Stupid FEC can't handle misaligned data!
+ * Move offending bytes to a local buffer.
+ * Use buffer descriptor TO1 bit to indicate this.
+ */
+ int nmove = 4 - offset;
+ char *d = (char *)&sc->txMbuf[sc->txBdHead];
+ status |= MCF5282_FEC_TxBD_TO1;
+ sc->txRealign++;
+ if (nmove > m->m_len)
+ nmove = m->m_len;
+ m->m_data += nmove;
+ m->m_len -= nmove;
+ txBd->buffer = d;
+ txBd->length = nmove;
+ while (nmove--)
+ *d++ = *p++;
+ if (m->m_len == 0) {
+ struct mbuf *n;
+ sc->txRealignDrop++;
+ MFREE(m, n);
+ m = n;
+ }
+ }
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= MCF5282_FEC_TxBD_W;
+ sc->txBdHead = 0;
+ }
+ txBd->status = status;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE(m, n);
+ m = n;
+ }
+ }
+ if (nAdded) {
+ txBd->status = status | MCF5282_FEC_TxBD_R
+ | MCF5282_FEC_TxBD_L
+ | MCF5282_FEC_TxBD_TC;
+ if (nAdded > 1)
+ firstTxBd->status |= MCF5282_FEC_TxBD_R;
+ MCF5282_FEC_TDAR = 0;
+ sc->txBdActiveCount += nAdded;
+ }
+}
+
+void
+fec_txDaemon(void *arg)
+{
+ struct mcf5282_enet_struct *sc = (struct mcf5282_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ fec_sendpacket(ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+mcf5282_enet_start(struct ifnet *ifp)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void
+fec_init(void *arg)
+{
+ struct mcf5282_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+ /*
+ * Set up hardware
+ */
+ mcf5282_fec_initialize_hardware(sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc("FECtx", 4096, fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc("FECrx", 4096, fec_rxDaemon, sc);
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ MCF5282_FEC_RCR |= MCF5282_FEC_RCR_PROM;
+ else
+ MCF5282_FEC_RCR &= ~MCF5282_FEC_RCR_PROM;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ MCF5282_FEC_ECR = MCF5282_FEC_ECR_ETHER_EN;
+}
+
+
+static void
+fec_stop(struct mcf5282_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ MCF5282_FEC_ECR = 0x0;
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+enet_stats(struct mcf5282_enet_struct *sc)
+{
+ printf(" Rx Interrupts:%-10lu", sc->rxInterrupts);
+ printf("Rx Packet Count:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_PACKETS);
+ printf(" Rx Broadcast:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_BC_PKT);
+ printf(" Rx Multicast:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_MC_PKT);
+ printf("CRC/Align error:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_CRC_ALIGN);
+ printf(" Rx Undersize:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_UNDERSIZE);
+ printf(" Rx Oversize:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_OVERSIZE);
+ printf(" Rx Fragment:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_FRAG);
+ printf(" Rx Jabber:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_JAB);
+ printf(" Rx 64:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P64);
+ printf(" Rx 65-127:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P65T0127);
+ printf(" Rx 128-255:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_P128TO255);
+ printf(" Rx 256-511:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P256TO511);
+ printf(" Rx 511-1023:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P512TO1023);
+ printf(" Rx 1024-2047:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_P1024TO2047);
+ printf(" Rx >=2048:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_GTE2048);
+ printf(" Rx Octets:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_OCTETS);
+ printf(" Rx Dropped:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_DROP);
+ printf(" Rx frame OK:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_FRAME_OK);
+ printf(" Rx CRC error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_CRC);
+ printf(" Rx Align error:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_ALIGN);
+ printf(" FIFO Overflow:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_MACERR);
+ printf("Rx Pause Frames:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_FDXFC);
+ printf(" Rx Octets OK:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_OCTETS_OK);
+ printf(" Tx Interrupts:%-10lu", sc->txInterrupts);
+ printf("Tx Output Waits:%-10lu", sc->txRawWait);
+ printf("Tx mbuf realign:%-10lu\n", sc->txRealign);
+ printf("Tx realign drop:%-10lu", sc->txRealignDrop);
+ printf(" Tx Unaccounted:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_DROP);
+ printf("Tx Packet Count:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_PACKETS);
+ printf(" Tx Broadcast:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_BC_PKT);
+ printf(" Tx Multicast:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_MC_PKT);
+ printf("CRC/Align error:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_CRC_ALIGN);
+ printf(" Tx Undersize:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_UNDERSIZE);
+ printf(" Tx Oversize:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_OVERSIZE);
+ printf(" Tx Fragment:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_FRAG);
+ printf(" Tx Jabber:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_JAB);
+ printf(" Tx Collisions:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_COL);
+ printf(" Tx 64:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P64);
+ printf(" Tx 65-127:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P65TO127);
+ printf(" Tx 128-255:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P128TO255);
+ printf(" Tx 256-511:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P256TO511);
+ printf(" Tx 511-1023:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P512TO1023);
+ printf(" Tx 1024-2047:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P1024TO2047);
+ printf(" Tx >=2048:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P_GTE2048);
+ printf(" Tx Octets:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_OCTETS);
+ printf(" Tx Dropped:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_DROP);
+ printf(" Tx Frame OK:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_FRAME_OK);
+ printf(" Tx 1 Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_1COL);
+ printf("Tx >1 Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_MCOL);
+ printf(" Tx Deferred:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_DEF);
+ printf(" Late Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_LCOL);
+ printf(" Excessive Coll:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_EXCOL);
+ printf(" FIFO Underrun:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_MACERR);
+ printf(" Carrier Error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_CSERR);
+ printf(" Tx SQE Error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_SQE);
+ printf("Tx Pause Frames:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_FDXFC);
+ printf(" Tx Octets OK:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_OCTETS_OK);
+ printf(" MII interrupts:%-10lu\n", sc->miiInterrupts);
+
+ printf(" EIR:%8.8lx ", (uint32_t) MCF5282_FEC_EIR);
+ printf("EIMR:%8.8lx ", (uint32_t) MCF5282_FEC_EIMR);
+ printf("RDAR:%8.8lx ", (uint32_t) MCF5282_FEC_RDAR);
+ printf("TDAR:%8.8lx\n", (uint32_t) MCF5282_FEC_TDAR);
+ printf(" ECR:%8.8lx ", (uint32_t) MCF5282_FEC_ECR);
+ printf(" RCR:%8.8lx ", (uint32_t) MCF5282_FEC_RCR);
+ printf(" TCR:%8.8lx\n", (uint32_t) MCF5282_FEC_TCR);
+ printf("FRBR:%8.8lx ", (uint32_t) MCF5282_FEC_FRBR);
+ printf("FRSR:%8.8lx\n", (uint32_t) MCF5282_FEC_FRSR);
+ if (sc->txBdActiveCount != 0) {
+ int i, n;
+ /*
+ * Yes, there are races here with adding and retiring descriptors,
+ * but this diagnostic is more for when things have backed up.
+ */
+ printf("Transmit Buffer Descriptors (Tail %d, Head %d, Unretired %d):\n",
+ sc->txBdTail,
+ sc->txBdHead,
+ sc->txBdActiveCount);
+ i = sc->txBdTail;
+ for (n = 0 ; n < sc->txBdCount ; n++) {
+ if ((sc->txBdBase[i].status & MCF5282_FEC_TxBD_R) != 0)
+ printf(" %3d: status:%4.4x length:%-4d buffer:%p\n",
+ i,
+ sc->txBdBase[i].status,
+ sc->txBdBase[i].length,
+ sc->txBdBase[i].buffer);
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+ }
+}
+
+static int
+fec_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ fec_stop(sc);
+ break;
+
+ case IFF_UP:
+ fec_init(sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ fec_stop(sc);
+ fec_init(sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats(sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+int
+rtems_fec_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching )
+{
+ struct mcf5282_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ unsigned char *hwaddr;
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES)) {
+ printf("Bad FEC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ printf("%s%d: Ethernet address: ", unitName, unitNumber );
+ if (config->hardware_address) {
+ hwaddr = config->hardware_address;
+ printf("%02x:%02x:%02x:%02x:%02x:%02x\n",
+ hwaddr[0], hwaddr[1], hwaddr[2],
+ hwaddr[3], hwaddr[4], hwaddr[5]);
+ memcpy(sc->arpcom.ac_enaddr, hwaddr, ETHER_ADDR_LEN);
+ } else {
+ printf("UNKNOWN\n");
+ }
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = fec_init;
+ ifp->if_ioctl = fec_ioctl;
+ ifp->if_start = mcf5282_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ return 1;
+};
+
diff --git a/bsps/m68k/csb360/net/network.c b/bsps/m68k/csb360/net/network.c
new file mode 100644
index 0000000..95769bf
--- /dev/null
+++ b/bsps/m68k/csb360/net/network.c
@@ -0,0 +1,984 @@
+/*
+ * RTEMS/TCPIP driver for MCF5272 Ethernet
+ *
+ * Modified for MPC860 by Jay Monkman (jmonkman@lopingdog.com)
+ *
+ * This supports Ethernet on either SCC1 or the FEC of the MPC860T.
+ * Right now, we only do 10 Mbps, even with the FEC. The function
+ * rtems_enet_driver_attach determines which one to use. Currently,
+ * only one may be used at a time.
+ *
+ * Based on the MC68360 network driver by
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ *
+ * This supports ethernet on SCC1. Right now, we only do 10 Mbps.
+ *
+ * Modifications by Darlene Stewart <Darlene.Stewart@iit.nrc.ca>
+ * and Charles-Antoine Gauthier <charles.gauthier@iit.nrc.ca>
+ * Copyright (c) 1999, National Research Council of Canada
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 16
+#define TX_BD_PER_BUF 4
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+typedef struct {
+ uint16_t status;
+ uint16_t length;
+ void *buffer;
+} bd_t;
+#define MCF5272_BD_READY (bit(15))
+#define MCF5272_BD_TO1 (bit(14))
+#define MCF5272_BD_WRAP (bit(13))
+#define MCF5272_BD_TO2 (bit(12))
+#define MCF5272_BD_LAST (bit(11))
+#define MCF5272_BD_TX_CRC (bit(10))
+#define MCF5272_BD_DEFER (bit(9))
+#define MCF5272_BD_HEARTBEAT (bit(8))
+#define MCF5272_BD_LATE_COLLISION (bit(7))
+#define MCF5272_BD_RETRY_LIMIT (bit(6))
+#define MCF5272_BD_UNDERRUN (bit(1))
+#define MCF5272_BD_CARRIER_LOST (bit(0))
+
+#define MCF5272_BD_EMPTY (bit(15))
+#define MCF5272_BD_RO1 (bit(14))
+#define MCF5272_BD_WRAP (bit(13))
+#define MCF5272_BD_RO2 (bit(12))
+#define MCF5272_BD_M (bit(8))
+#define MCF5272_BD_BC (bit(7))
+#define MCF5272_BD_MC (bit(6))
+#define MCF5272_BD_LONG (bit(5))
+#define MCF5272_BD_NONALIGNED (bit(4))
+#define MCF5272_BD_SHORT (bit(3))
+#define MCF5272_BD_CRC_ERROR (bit(2))
+#define MCF5272_BD_OVERRUN (bit(1))
+#define MCF5272_BD_TRUNCATED (bit(0))
+
+
+/*
+ * Per-device data
+ */
+struct mcf5272_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ bd_t *rxBdBase;
+ bd_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxRunt;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxTruncated;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txHeartbeat;
+ unsigned long txLateCollision;
+ unsigned long txRetryLimit;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+};
+static struct mcf5272_enet_struct enet_driver[NIFACES];
+
+
+void dump_enet_regs(void)
+{
+ printf("**************************************************************\n");
+ printf("ecr: 0x%08x eir: 0x%08x eimr: 0x%08x ivsr: 0x%08x\n\r",
+ g_enet_regs->ecr, g_enet_regs->eir,
+ g_enet_regs->eimr, g_enet_regs->ivsr);
+ printf("rdar: 0x%08x tdar: 0x%08x mmfr: 0x%08x mscr: 0x%08x\n\r",
+ g_enet_regs->rdar, g_enet_regs->tdar,
+ g_enet_regs->mmfr, g_enet_regs->mscr);
+ printf("frbr: 0x%08x frsr: 0x%08x tfwr: 0x%08x tfsr: 0x%08x\n\r",
+ g_enet_regs->frbr, g_enet_regs->frsr,
+ g_enet_regs->tfwr, g_enet_regs->tfsr);
+ printf("rcr: 0x%08x mflr: 0x%08x tcr: 0x%08x malr: 0x%08x\n\r",
+ g_enet_regs->rcr, g_enet_regs->mflr,
+ g_enet_regs->tcr, g_enet_regs->malr);
+ printf("maur: 0x%08x htur: 0x%08x htlr: 0x%08x erdsr: 0x%08x\n\r",
+ g_enet_regs->maur, g_enet_regs->htur,
+ g_enet_regs->htlr, g_enet_regs->erdsr);
+ printf("etdsr: 0x%08x emrbr: 0x%08x\n\r",
+ g_enet_regs->etdsr, g_enet_regs->emrbr);
+}
+
+
+
+
+/*#define cp printk("%s:%d\n\r", __FUNCTION__, __LINE__) */
+#define cp
+#define mcf5272_bd_allocate(_n_) malloc((_n_) * sizeof(bd_t), 0, M_NOWAIT)
+
+
+
+rtems_isr enet_rx_isr(rtems_vector_number vector)
+{
+ cp;
+ /*
+ * Frame received?
+ */
+ if (g_enet_regs->eir & MCF5272_ENET_EIR_RXF) {
+ cp;
+ g_enet_regs->eir = MCF5272_ENET_EIR_RXF;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send (enet_driver[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+ cp;
+}
+
+rtems_isr enet_tx_isr(rtems_vector_number vector)
+{
+ cp;
+ /*
+ * Buffer transmitted or transmitter error?
+ */
+ if (g_enet_regs->eir & MCF5272_ENET_EIR_TXF) {
+ cp;
+ g_enet_regs->eir = MCF5272_ENET_EIR_TXF;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send (enet_driver[0].txDaemonTid, INTERRUPT_EVENT);
+ }
+ cp;
+}
+
+
+/*
+ * Initialize the ethernet hardware
+ */
+
+
+static void
+mcf5272_enet_initialize_hardware (struct mcf5272_enet_struct *sc)
+{
+ int i;
+ unsigned char *hwaddr;
+ uint32_t icr;
+ /*
+ * Issue reset to FEC
+ */
+ g_enet_regs->ecr=0x1;
+
+ /*
+ * Set the TX and RX fifo sizes. For now, we'll split it evenly
+ */
+ /* If you uncomment these, the FEC will not work right.
+ g_enet_regs->r_fstart = ((g_enet_regs->r_bound & 0x3ff) >> 2) & 0x3ff;
+ g_enet_regs->x_fstart = 0;
+ */
+
+ /* Copy mac address to device */
+
+ hwaddr = sc->arpcom.ac_enaddr;
+
+ g_enet_regs->malr = (hwaddr[0] << 24 |
+ hwaddr[1] << 16 |
+ hwaddr[2] << 8 |
+ hwaddr[3]);
+ g_enet_regs->maur = (hwaddr[4] << 24 |
+ hwaddr[5] << 16);
+
+ /*
+ * Clear the hash table
+ */
+ g_enet_regs->htlr = 0;
+ g_enet_regs->htur = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ g_enet_regs->emrbr = 0x5f0; /* set to 1520 */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc (sc->rxBdCount * sizeof *sc->rxMbuf,
+ M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc (sc->txBdCount * sizeof *sc->txMbuf,
+ M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf) {
+ rtems_panic ("No memory for mbuf pointers");
+ }
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = mcf5272_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = mcf5272_bd_allocate(sc->txBdCount);
+ g_enet_regs->erdsr = (int)sc->rxBdBase;
+ g_enet_regs->etdsr = (int)sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous mode
+ * MII mode
+ * Full duplex
+ * No loopback
+ */
+ g_enet_regs->rcr = 0x00000004;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full duplex
+ * No heartbeat
+ */
+ g_enet_regs->tcr = 0x00000004;
+
+ /*
+ * Set MII speed to 2.5 MHz for 25 Mhz system clock
+ */
+ g_enet_regs->mscr = 0x0a;
+ g_enet_regs->mmfr = 0x58021000;
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++) {
+ (sc->rxBdBase + i)->status = 0;
+ }
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ (sc->txBdBase + i)->status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Mask all FEC interrupts and clear events
+ */
+ g_enet_regs->eimr = (MCF5272_ENET_EIR_TXF |
+ MCF5272_ENET_EIR_RXF);
+ g_enet_regs->eir = ~0;
+
+ /*
+ * Set up interrupts
+ */
+ set_vector(enet_rx_isr, BSP_INTVEC_ERX, 1);
+ set_vector(enet_tx_isr, BSP_INTVEC_ETX, 1);
+
+ /* Configure ethernet interrupts */
+ icr = g_intctrl_regs->icr3;
+ icr = icr & ~((MCF5272_ICR3_ERX_MASK | MCF5272_ICR3_ERX_PI) |
+ (MCF5272_ICR3_ETX_MASK | MCF5272_ICR3_ETX_PI));
+ icr |= ((MCF5272_ICR3_ERX_IPL(BSP_INTLVL_ERX) | MCF5272_ICR3_ERX_PI)|
+ (MCF5272_ICR3_ETX_IPL(BSP_INTLVL_ETX) | MCF5272_ICR3_ETX_PI));
+ g_intctrl_regs->icr3 = icr;
+
+}
+
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ * Note that a buffer descriptor can't be retired as soon as it becomes
+ * ready. The MPC860 manual (MPC860UM/AD 07/98 Rev.1) and the MPC821
+ * manual state that, "If an Ethernet frame is made up of multiple
+ * buffers, the user should not reuse the first buffer descriptor until
+ * the last buffer descriptor of the frame has had its ready bit cleared
+ * by the CPM".
+ */
+static void
+mcf5272_enet_retire_tx_bd (struct mcf5272_enet_struct *sc)
+{
+ uint16_t status;
+ int i;
+ int nRetired;
+ struct mbuf *m, *n;
+
+ i = sc->txBdTail;
+ nRetired = 0;
+ while ((sc->txBdActiveCount != 0) &&
+ (((status = sc->txBdBase[i].status) & MCF5272_BD_READY) == 0)) {
+ /*
+ * See if anything went wrong
+ */
+ if (status & (MCF5272_BD_DEFER |
+ MCF5272_BD_HEARTBEAT |
+ MCF5272_BD_LATE_COLLISION |
+ MCF5272_BD_RETRY_LIMIT |
+ MCF5272_BD_UNDERRUN |
+ MCF5272_BD_CARRIER_LOST)) {
+ /*
+ * Check for errors which stop the transmitter.
+ */
+ if (status & (MCF5272_BD_LATE_COLLISION |
+ MCF5272_BD_RETRY_LIMIT |
+ MCF5272_BD_UNDERRUN)) {
+ if (status & MCF5272_BD_LATE_COLLISION) {
+ enet_driver[0].txLateCollision++;
+ }
+ if (status & MCF5272_BD_RETRY_LIMIT) {
+ enet_driver[0].txRetryLimit++;
+ }
+ if (status & MCF5272_BD_UNDERRUN) {
+ enet_driver[0].txUnderrun++;
+ }
+ }
+ if (status & MCF5272_BD_DEFER) {
+ enet_driver[0].txDeferred++;
+ }
+ if (status & MCF5272_BD_HEARTBEAT) {
+ enet_driver[0].txHeartbeat++;
+ }
+ if (status & MCF5272_BD_CARRIER_LOST) {
+ enet_driver[0].txLostCarrier++;
+ }
+ }
+ nRetired++;
+ if (status & MCF5272_BD_LAST) {
+ /*
+ * A full frame has been transmitted.
+ * Free all the associated buffer descriptors.
+ */
+ sc->txBdActiveCount -= nRetired;
+ while (nRetired) {
+ nRetired--;
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE (m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ }
+ }
+ if (++i == sc->txBdCount) {
+ i = 0;
+ }
+ }
+}
+
+static void
+mcf5272_enet_rxDaemon (void *arg)
+{
+ struct mcf5272_enet_struct *sc = (struct mcf5272_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ bd_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ rxBd->status = MCF5272_BD_EMPTY;
+ g_enet_regs->rdar = 0x1000000;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= MCF5272_BD_WRAP;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & MCF5272_BD_EMPTY) {
+ /*
+ * Clear old events
+ */
+ g_enet_regs->eir = MCF5272_ENET_EIR_RXF;
+
+ /*
+ * Wait for packet
+ * Note that the buffer descriptor is checked
+ * *before* the event wait -- this catches the
+ * possibility that a packet arrived between the
+ * `if' above, and the clearing of the event register.
+ */
+ while ((status = rxBd->status) & MCF5272_BD_EMPTY) {
+ rtems_event_set events;
+
+ /*
+ * Unmask RXF (Full frame received) event
+ */
+ g_enet_regs->eir |= MCF5272_ENET_EIR_RXF;
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ cp;
+ }
+ }
+ cp;
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & MCF5272_BD_LAST) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+
+ m = sc->rxMbuf[rxBdIndex];
+ m->m_len = m->m_pkthdr.len = (rxBd->length -
+ sizeof(uint32_t) -
+ sizeof(struct ether_header));
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ }
+ else {
+ /*
+ * Something went wrong with the reception
+ */
+ if (!(status & MCF5272_BD_LAST)) {
+ sc->rxNotLast++;
+ }
+ if (status & MCF5272_BD_LONG) {
+ sc->rxGiant++;
+ }
+ if (status & MCF5272_BD_NONALIGNED) {
+ sc->rxNonOctet++;
+ }
+ if (status & MCF5272_BD_SHORT) {
+ sc->rxRunt++;
+ }
+ if (status & MCF5272_BD_CRC_ERROR) {
+ sc->rxBadCRC++;
+ }
+ if (status & MCF5272_BD_OVERRUN) {
+ sc->rxOverrun++;
+ }
+ if (status & MCF5272_BD_TRUNCATED) {
+ sc->rxTruncated++;
+ }
+ }
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & MCF5272_BD_WRAP) | MCF5272_BD_EMPTY;
+ g_enet_regs->rdar = 0x1000000;
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBdIndex = 0;
+ }
+ }
+}
+
+static void
+mcf5272_enet_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct mcf5272_enet_struct *sc = ifp->if_softc;
+ volatile bd_t *firstTxBd, *txBd;
+ /* struct mbuf *l = NULL; */
+ uint16_t status;
+ int nAdded;
+ cp;
+
+ /*
+ * Free up buffer descriptors
+ */
+ mcf5272_enet_retire_tx_bd (sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ txBd = firstTxBd = sc->txBdBase + sc->txBdHead;
+ for (;;) {
+ cp;
+ /*
+ * Wait for buffer descriptor to become available.
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events
+ */
+ g_enet_regs->eir = MCF5272_ENET_EIR_TXF;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Note that the buffer descriptors are checked
+ * *before* * entering the wait loop -- this catches
+ * the possibility that a buffer descriptor became
+ * available between the `if' above, and the clearing
+ * of the event register.
+ * This is to catch the case where the transmitter
+ * stops in the middle of a frame -- and only the
+ * last buffer descriptor in a frame can generate
+ * an interrupt.
+ */
+ mcf5272_enet_retire_tx_bd (sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+
+ cp;
+ /*
+ * Unmask TXB (buffer transmitted) and
+ * TXE (transmitter error) events.
+ */
+ g_enet_regs->eir |= MCF5272_ENET_EIR_TXF;
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ cp;
+ mcf5272_enet_retire_tx_bd (sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag till the
+ * whole packet has been readied.
+ */
+ status = nAdded ? MCF5272_BD_READY : 0;
+ cp;
+
+ /*
+ * FIXME: Why not deal with empty mbufs at at higher level?
+ * The IP fragmentation routine in ip_output
+ * can produce packet fragments with zero length.
+ * I think that ip_output should be changed to get
+ * rid of these zero-length mbufs, but for now,
+ * I'll deal with them here.
+ */
+ if (m->m_len) {
+ cp;
+ /*
+ * Fill in the buffer descriptor
+ */
+ txBd->buffer = mtod (m, void *);
+ txBd->length = m->m_len;
+
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= MCF5272_BD_WRAP;
+ sc->txBdHead = 0;
+ }
+ /* l = m;*/
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ cp;
+ MFREE (m, n);
+ m = n;
+ /*
+ if (l != NULL)
+ l->m_next = m;
+ */
+ }
+
+ /*
+ * Set the transmit buffer status.
+ * Break out of the loop if this mbuf is the last in the frame.
+ */
+ if (m == NULL) {
+ cp;
+ if (nAdded) {
+ cp;
+ status |= MCF5272_BD_LAST | MCF5272_BD_TX_CRC;
+ txBd->status = status;
+ firstTxBd->status |= MCF5272_BD_READY;
+ g_enet_regs->tdar = 0x1000000;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ txBd = sc->txBdBase + sc->txBdHead;
+ }
+ cp;
+/*
+ dump_enet_regs();
+ dump_intctrl;
+*/
+
+}
+
+
+void
+mcf5272_enet_txDaemon (void *arg)
+{
+ struct mcf5272_enet_struct *sc = (struct mcf5272_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ cp;
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ cp;
+ /*
+ * Send packets till queue is empty
+ */
+ cp;
+ for (;;) {
+ cp;
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ mcf5272_enet_sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+mcf5272_enet_start (struct ifnet *ifp)
+{
+ struct mcf5272_enet_struct *sc = ifp->if_softc;
+
+ cp;
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ cp;
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+
+static void
+mcf5272_enet_init (void *arg)
+{
+ struct mcf5272_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up SCC hardware
+ */
+ mcf5272_enet_initialize_hardware (sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc("SCtx",
+ 4096,
+ mcf5272_enet_txDaemon,
+ sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc("SCrx",
+ 4096,
+ mcf5272_enet_rxDaemon,
+ sc);
+
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC) {
+ g_enet_regs->rcr |= 0x8;
+ } else {
+ g_enet_regs->rcr &= ~0x8;
+ }
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ g_enet_regs->ecr = 0x2;
+}
+
+
+static void
+mcf5272_enet_stop (struct mcf5272_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ g_enet_regs->ecr = 0x0;
+}
+
+
+/*
+ * Show interface statistics
+ */
+static void
+enet_stats (struct mcf5272_enet_struct *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Not First:%-8lu", sc->rxNotFirst);
+ printf (" Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Runt:%-8lu", sc->rxRunt);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" Truncated:%-8lu\n", sc->rxTruncated);
+/* printf (" Discarded:%-8lu\n", (unsigned long)mcf5272.scc1p.un.ethernet.disfc); */
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" Deferred:%-8lu", sc->txDeferred);
+ printf (" Missed Hearbeat:%-8lu\n", sc->txHeartbeat);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf ("Retransmit Limit:%-8lu", sc->txRetryLimit);
+ printf (" Late Collision:%-8lu\n", sc->txLateCollision);
+ printf (" Underrun:%-8lu", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+
+/*
+ * Driver ioctl handler
+ */
+static int
+mcf5272_enet_ioctl (struct ifnet *ifp, int command, caddr_t data)
+{
+ struct mcf5272_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ mcf5272_enet_stop (sc);
+ break;
+
+ case IFF_UP:
+ mcf5272_enet_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ mcf5272_enet_stop (sc);
+ mcf5272_enet_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+
+int
+rtems_enet_driver_attach (struct rtems_bsdnet_ifconfig *config)
+{
+ struct mcf5272_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+
+ /*
+ * Parse driver name
+ */
+ unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName);
+ if (unitNumber < 0){
+ return 0;
+ }
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber < 0) || (unitNumber > NIFACES)) {
+ printf ("Bad unit number: %d.\n", unitNumber);
+ return 0;
+ }
+
+ sc = &enet_driver[unitNumber];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+
+ sc->arpcom.ac_enaddr[0] = (g_enet_regs->malr >> 24) & 0xff;
+ sc->arpcom.ac_enaddr[1] = (g_enet_regs->malr >> 16) & 0xff;
+ sc->arpcom.ac_enaddr[2] = (g_enet_regs->malr >> 8) & 0xff;
+ sc->arpcom.ac_enaddr[3] = (g_enet_regs->malr >> 0) & 0xff;
+ sc->arpcom.ac_enaddr[4] = (g_enet_regs->maur >> 24) & 0xff;
+ sc->arpcom.ac_enaddr[5] = (g_enet_regs->maur >> 16) & 0xff;
+
+ if (config->mtu) {
+ mtu = config->mtu;
+ } else {
+ mtu = ETHERMTU;
+ }
+
+ if (config->rbuf_count) {
+ sc->rxBdCount = config->rbuf_count;
+ } else {
+ sc->rxBdCount = RX_BUF_COUNT;
+ }
+ if (config->xbuf_count) {
+ sc->txBdCount = config->xbuf_count;
+ } else {
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+ }
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = mcf5272_enet_init;
+ ifp->if_ioctl = mcf5272_enet_ioctl;
+ ifp->if_start = mcf5272_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0) {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ cp;
+ ether_ifattach (ifp);
+ cp;
+ return 1;
+};
+
+
diff --git a/bsps/m68k/gen68360/net/network.c b/bsps/m68k/gen68360/net/network.c
new file mode 100644
index 0000000..b0110af
--- /dev/null
+++ b/bsps/m68k/gen68360/net/network.c
@@ -0,0 +1,1062 @@
+/*
+ * RTEMS driver for M68360 SCC1 Ethernet
+ *
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <rtems/m68k/m68360.h>
+#include <stdio.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+/*
+ * Number of SCCs supported by this driver
+ */
+#define NSCCDRIVER 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 15
+#define TX_BUF_COUNT 4
+#define TX_BD_PER_BUF 4
+
+/*
+ * RTEMS event used by interrupt handler to signal driver tasks.
+ * This must not be any of the events used by the network task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet including CRC
+ */
+#define RBUF_SIZE 1520
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+/*
+ * Per-device data
+ */
+struct scc_softc {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ m360BufferDescriptor_t *rxBdBase;
+ m360BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxRunt;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txHeartbeat;
+ unsigned long txLateCollision;
+ unsigned long txRetryLimit;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+ unsigned long txCoalesced;
+ unsigned long txCoalesceFailed;
+ unsigned long txRetry;
+};
+static struct scc_softc scc_softc[NSCCDRIVER];
+
+extern void *_RomBase; /* From linkcmds */
+
+/*
+ * SCC1 interrupt handler
+ */
+static rtems_isr
+m360Enet_interrupt_handler (rtems_vector_number v)
+{
+ /*
+ * Frame received?
+ */
+ if ((m360.scc1.sccm & 0x8) && (m360.scc1.scce & 0x8)) {
+ m360.scc1.scce = 0x8;
+ m360.scc1.sccm &= ~0x8;
+ scc_softc[0].rxInterrupts++;
+ rtems_bsdnet_event_send (scc_softc[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+
+ /*
+ * Buffer transmitted or transmitter error?
+ */
+ if ((m360.scc1.sccm & 0x12) && (m360.scc1.scce & 0x12)) {
+ m360.scc1.scce = 0x12;
+ m360.scc1.sccm &= ~0x12;
+ scc_softc[0].txInterrupts++;
+ rtems_bsdnet_event_send (scc_softc[0].txDaemonTid, INTERRUPT_EVENT);
+ }
+ m360.cisr = 1UL << 30; /* Clear SCC1 interrupt-in-service bit */
+}
+
+/*
+ * Initialize the ethernet hardware
+ */
+static void
+m360Enet_initialize_hardware (struct scc_softc *sc)
+{
+ int i;
+ unsigned char *hwaddr;
+ rtems_status_code status;
+ rtems_isr_entry old_handler;
+
+ /*
+ * Configure port A CLK1, CLK2, TXD1 and RXD1 pins
+ */
+ m360.papar |= 0x303;
+ m360.padir &= ~0x303;
+ m360.paodr &= ~0x303;
+
+ /*
+ * Configure port C CTS1* and CD1* pins
+ */
+ m360.pcpar &= ~0x30;
+ m360.pcdir &= ~0x30;
+ m360.pcso |= 0x30;
+
+ /*
+ * Connect CLK1 and CLK2 to SCC1
+ */
+ m360.sicr &= ~0xFF;
+ m360.sicr |= (5 << 3) | 4;
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc (sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc (sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = M360AllocateBufferDescriptors(sc->rxBdCount);
+ sc->txBdBase = M360AllocateBufferDescriptors(sc->txBdCount);
+ m360.scc1p.rbase = (char *)sc->rxBdBase - (char *)&m360;
+ m360.scc1p.tbase = (char *)sc->txBdBase - (char *)&m360;
+
+ /*
+ * Send "Init parameters" command
+ */
+ M360ExecuteRISC (M360_CR_OP_INIT_RX_TX | M360_CR_CHAN_SCC1);
+
+ /*
+ * Set receive and transmit function codes
+ */
+ m360.scc1p.rfcr = M360_RFCR_MOT | M360_RFCR_DMA_SPACE;
+ m360.scc1p.tfcr = M360_TFCR_MOT | M360_TFCR_DMA_SPACE;
+
+ /*
+ * Set maximum receive buffer length
+ */
+ m360.scc1p.mrblr = RBUF_SIZE;
+
+ /*
+ * Set CRC parameters
+ */
+ m360.scc1p.un.ethernet.c_pres = 0xFFFFFFFF;
+ m360.scc1p.un.ethernet.c_mask = 0xDEBB20E3;
+
+ /*
+ * Clear diagnostic counters
+ */
+ m360.scc1p.un.ethernet.crcec = 0;
+ m360.scc1p.un.ethernet.alec = 0;
+ m360.scc1p.un.ethernet.disfc = 0;
+
+ /*
+ * Set pad value
+ */
+ m360.scc1p.un.ethernet.pads = 0x8888;
+
+ /*
+ * Set retry limit
+ */
+ m360.scc1p.un.ethernet.ret_lim = 15;
+
+ /*
+ * Set maximum and minimum frame length
+ */
+ m360.scc1p.un.ethernet.mflr = 1518;
+ m360.scc1p.un.ethernet.minflr = 64;
+ m360.scc1p.un.ethernet.maxd1 = RBUF_SIZE;
+ m360.scc1p.un.ethernet.maxd2 = RBUF_SIZE;
+
+ /*
+ * Clear group address hash table
+ */
+ m360.scc1p.un.ethernet.gaddr1 = 0;
+ m360.scc1p.un.ethernet.gaddr2 = 0;
+ m360.scc1p.un.ethernet.gaddr3 = 0;
+ m360.scc1p.un.ethernet.gaddr4 = 0;
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+ m360.scc1p.un.ethernet.paddr_h = (hwaddr[5] << 8) | hwaddr[4];
+ m360.scc1p.un.ethernet.paddr_m = (hwaddr[3] << 8) | hwaddr[2];
+ m360.scc1p.un.ethernet.paddr_l = (hwaddr[1] << 8) | hwaddr[0];
+
+ /*
+ * Aggressive retry
+ */
+ m360.scc1p.un.ethernet.p_per = 0;
+
+ /*
+ * Clear individual address hash table
+ */
+ m360.scc1p.un.ethernet.iaddr1 = 0;
+ m360.scc1p.un.ethernet.iaddr2 = 0;
+ m360.scc1p.un.ethernet.iaddr3 = 0;
+ m360.scc1p.un.ethernet.iaddr4 = 0;
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ (sc->txBdBase + i)->status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Clear any outstanding events
+ */
+ m360.scc1.scce = 0xFFFF;
+
+ /*
+ * Set up interrupts
+ */
+ status = rtems_interrupt_catch (m360Enet_interrupt_handler,
+ (m360.cicr & 0xE0) | 0x1E,
+ &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach M360 SCC1 interrupt handler: %s\n",
+ rtems_status_text (status));
+ m360.scc1.sccm = 0; /* No interrupts unmasked till necessary */
+ m360.cimr |= (1UL << 30); /* Enable SCC1 interrupt */
+
+ /*
+ * Set up General SCC Mode Register
+ * Ethernet configuration
+ */
+ m360.scc1.gsmr_h = 0x0;
+ m360.scc1.gsmr_l = 0x1088000c;
+
+ /*
+ * Set up data synchronization register
+ * Ethernet synchronization pattern
+ */
+ m360.scc1.dsr = 0xd555;
+
+ /*
+ * Set up protocol-specific mode register
+ * Heartbeat check
+ * No force collision
+ * Discard short frames
+ * Individual address mode
+ * Ethernet CRC
+ * Not promisuous
+ * Ignore/accept broadcast packets as specified
+ * Normal backoff timer
+ * No loopback
+ * No input sample at end of frame
+ * 64-byte limit for late collision
+ * Wait 22 bits before looking for start of frame delimiter
+ * Disable full-duplex operation
+ */
+ m360.scc1.psmr = 0x880A | (sc->acceptBroadcast ? 0 : 0x100);
+
+ /*
+ * Enable the TENA (RTS1*) pin
+ */
+#if (defined (M68360_ATLAS_HSB))
+ m360.pbpar |= 0x1000;
+ m360.pbdir |= 0x1000;
+#else
+ m360.pcpar |= 0x1;
+ m360.pcdir &= ~0x1;
+#endif
+}
+
+/*
+ * Soak up buffer descriptors that have been sent
+ * Note that a buffer descriptor can't be retired as soon as it becomes
+ * ready. The MC68360 Errata (May 96) says that, "If an Ethernet frame is
+ * made up of multiple buffers, the user should not reuse the first buffer
+ * descriptor until the last buffer descriptor of the frame has had its
+ * ready bit cleared by the CPM".
+ */
+static void
+m360Enet_retire_tx_bd (struct scc_softc *sc)
+{
+ uint16_t status;
+ int i;
+ int nRetired;
+ struct mbuf *m, *n;
+ int retries = 0;
+ int saveStatus = 0;
+
+ i = sc->txBdTail;
+ nRetired = 0;
+ while ((sc->txBdActiveCount != 0)
+ && (((status = (sc->txBdBase + i)->status) & M360_BD_READY) == 0)) {
+ /*
+ * Check for errors which stop the transmitter.
+ */
+ if (status & (M360_BD_LATE_COLLISION |
+ M360_BD_RETRY_LIMIT |
+ M360_BD_UNDERRUN)) {
+ int j;
+
+ if (status & M360_BD_LATE_COLLISION)
+ sc->txLateCollision++;
+ if (status & M360_BD_RETRY_LIMIT)
+ sc->txRetryLimit++;
+ if (status & M360_BD_UNDERRUN)
+ sc->txUnderrun++;
+
+ /*
+ * Reenable buffer descriptors
+ */
+ j = sc->txBdTail;
+ for (;;) {
+ status = (sc->txBdBase + j)->status;
+ if (status & M360_BD_READY)
+ break;
+ (sc->txBdBase + j)->status = M360_BD_READY |
+ (status & (M360_BD_PAD |
+ M360_BD_WRAP |
+ M360_BD_INTERRUPT |
+ M360_BD_LAST |
+ M360_BD_TX_CRC));
+ if (status & M360_BD_LAST)
+ break;
+ if (++j == sc->txBdCount)
+ j = 0;
+ }
+
+ /*
+ * Move transmitter back to the first
+ * buffer descriptor in the frame.
+ */
+ m360.scc1p._tbptr = m360.scc1p.tbase +
+ sc->txBdTail * sizeof (m360BufferDescriptor_t);
+
+ /*
+ * Restart the transmitter
+ */
+ M360ExecuteRISC (M360_CR_OP_RESTART_TX | M360_CR_CHAN_SCC1);
+ continue;
+ }
+ saveStatus |= status;
+ retries += (status >> 2) & 0xF;
+ nRetired++;
+ if (status & M360_BD_LAST) {
+ /*
+ * A full frame has been transmitted.
+ * Free all the associated buffer descriptors.
+ */
+ if (saveStatus & M360_BD_DEFER)
+ sc->txDeferred++;
+ if (saveStatus & M360_BD_HEARTBEAT)
+ sc->txHeartbeat++;
+ if (saveStatus & M360_BD_CARRIER_LOST)
+ sc->txLostCarrier++;
+ saveStatus = 0;
+ sc->txRetry += retries;
+ retries = 0;
+ sc->txBdActiveCount -= nRetired;
+ while (nRetired) {
+ nRetired--;
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE (m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ }
+ }
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+}
+
+/*
+ * SCC reader task
+ */
+static void
+scc_rxDaemon (void *arg)
+{
+ struct scc_softc *sc = (struct scc_softc *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ volatile m360BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status = M360_BD_EMPTY | M360_BD_INTERRUPT | M360_BD_WRAP;
+ break;
+ }
+ rxBd->status = M360_BD_EMPTY | M360_BD_INTERRUPT;
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & M360_BD_EMPTY) {
+ /*
+ * Clear old events
+ */
+ m360.scc1.scce = 0x8;
+
+ /*
+ * Wait for packet
+ * Note that the buffer descriptor is checked
+ * *before* the event wait -- this catches the
+ * possibility that a packet arrived between the
+ * `if' above, and the clearing of the event register.
+ */
+ while ((status = rxBd->status) & M360_BD_EMPTY) {
+ rtems_interrupt_level level;
+ rtems_event_set events;
+
+ /*
+ * Unmask RXF (Full frame received) event
+ */
+ rtems_interrupt_disable (level);
+ m360.scc1.sccm |= 0x8;
+ rtems_interrupt_enable (level);
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if ((status & (M360_BD_LAST |
+ M360_BD_FIRST_IN_FRAME |
+ M360_BD_LONG |
+ M360_BD_NONALIGNED |
+ M360_BD_SHORT |
+ M360_BD_CRC_ERROR |
+ M360_BD_OVERRUN |
+ M360_BD_COLLISION)) ==
+ (M360_BD_LAST |
+ M360_BD_FIRST_IN_FRAME)) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+
+ m = sc->rxMbuf[rxBdIndex];
+ m->m_len = m->m_pkthdr.len = rxBd->length -
+ sizeof(uint32_t) -
+ sizeof(struct ether_header);
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ }
+ else {
+ /*
+ * Something went wrong with the reception
+ */
+ if (!(status & M360_BD_LAST))
+ sc->rxNotLast++;
+ if (!(status & M360_BD_FIRST_IN_FRAME))
+ sc->rxNotFirst++;
+ if (status & M360_BD_LONG)
+ sc->rxGiant++;
+ if (status & M360_BD_NONALIGNED)
+ sc->rxNonOctet++;
+ if (status & M360_BD_SHORT)
+ sc->rxRunt++;
+ if (status & M360_BD_CRC_ERROR)
+ sc->rxBadCRC++;
+ if (status & M360_BD_OVERRUN)
+ sc->rxOverrun++;
+ if (status & M360_BD_COLLISION)
+ sc->rxCollision++;
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & (M360_BD_WRAP | M360_BD_INTERRUPT)) | M360_BD_EMPTY;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void
+sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct scc_softc *sc = ifp->if_softc;
+ volatile m360BufferDescriptor_t *firstTxBd, *txBd;
+ struct mbuf *l = NULL;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ m360Enet_retire_tx_bd (sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ status = 0;
+ nAdded = 0;
+ txBd = firstTxBd = sc->txBdBase + sc->txBdHead;
+ while (m) {
+ /*
+ * There are more mbufs in the packet than there
+ * are transmit buffer descriptors.
+ * Coalesce into a single buffer.
+ */
+ if (nAdded == sc->txBdCount) {
+ struct mbuf *nm;
+ int j;
+ char *dest;
+
+ /*
+ * Get the pointer to the first mbuf of the packet
+ */
+ if (sc->txBdTail != sc->txBdHead)
+ rtems_panic ("sendpacket coalesce");
+ m = sc->txMbuf[sc->txBdTail];
+
+ /*
+ * Rescind the buffer descriptor READY bits
+ */
+ for (j = 0 ; j < sc->txBdCount ; j++)
+ (sc->txBdBase + j)->status = 0;
+
+ /*
+ * Allocate an mbuf cluster
+ * Toss the packet if allocation fails
+ */
+ MGETHDR (nm, M_DONTWAIT, MT_DATA);
+ if (nm == NULL) {
+ sc->txCoalesceFailed++;
+ m_freem (m);
+ return;
+ }
+ MCLGET (nm, M_DONTWAIT);
+ if (nm->m_ext.ext_buf == NULL) {
+ sc->txCoalesceFailed++;
+ m_freem (m);
+ m_free (nm);
+ return;
+ }
+ nm->m_pkthdr = m->m_pkthdr;
+ nm->m_len = nm->m_pkthdr.len;
+
+ /*
+ * Copy data from packet chain to mbuf cluster
+ */
+ sc->txCoalesced++;
+ dest = nm->m_ext.ext_buf;
+ while (m) {
+ struct mbuf *n;
+
+ if (m->m_len) {
+ memcpy (dest, mtod(m, caddr_t), m->m_len);
+ dest += m->m_len;
+ }
+ MFREE (m, n);
+ m = n;
+ }
+
+ /*
+ * Redo the send with the new mbuf cluster
+ */
+ m = nm;
+ nAdded = 0;
+ status = 0;
+ continue;
+ }
+
+ /*
+ * Wait for buffer descriptor to become available.
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events
+ */
+ m360.scc1.scce = 0x12;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Note that the buffer descriptors are checked
+ * *before* entering the wait loop -- this catches
+ * the possibility that a buffer descriptor became
+ * available between the `if' above, and the clearing
+ * of the event register.
+ * This is to catch the case where the transmitter
+ * stops in the middle of a frame -- and only the
+ * last buffer descriptor in a frame can generate
+ * an interrupt.
+ */
+ m360Enet_retire_tx_bd (sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_interrupt_level level;
+ rtems_event_set events;
+
+ /*
+ * Unmask TXB (buffer transmitted) and
+ * TXE (transmitter error) events.
+ */
+ rtems_interrupt_disable (level);
+ m360.scc1.sccm |= 0x12;
+ rtems_interrupt_enable (level);
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ m360Enet_retire_tx_bd (sc);
+ }
+ }
+
+ /*
+ * The IP fragmentation routine in ip_output
+ * can produce packet fragments with zero length.
+ */
+ if (m->m_len) {
+ /*
+ * Fill in the buffer descriptor.
+ * Don't set the READY flag in the first buffer
+ * descriptor till the whole packet has been readied.
+ */
+ txBd = sc->txBdBase + sc->txBdHead;
+ txBd->buffer = mtod (m, void *);
+ txBd->length = m->m_len;
+ sc->txMbuf[sc->txBdHead] = m;
+ status = nAdded ? M360_BD_READY : 0;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= M360_BD_WRAP;
+ sc->txBdHead = 0;
+ }
+ txBd->status = status;
+ l = m;
+ m = m->m_next;
+ nAdded++;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE (m, n);
+ m = n;
+ if (l != NULL)
+ l->m_next = m;
+ }
+ }
+ if (nAdded) {
+ /*
+ * Send the packet
+ */
+ txBd->status = status | M360_BD_PAD | M360_BD_LAST | M360_BD_TX_CRC | M360_BD_INTERRUPT;
+ firstTxBd->status |= M360_BD_READY;
+ sc->txBdActiveCount += nAdded;
+ }
+}
+
+/*
+ * Driver transmit daemon
+ */
+void
+scc_txDaemon (void *arg)
+{
+ struct scc_softc *sc = (struct scc_softc *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT, RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+scc_start (struct ifnet *ifp)
+{
+ struct scc_softc *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/*
+ * Initialize and start the device
+ */
+static void
+scc_init (void *arg)
+{
+ struct scc_softc *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up SCC hardware
+ */
+ m360Enet_initialize_hardware (sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("SCtx", 4096, scc_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("SCrx", 4096, scc_rxDaemon, sc);
+
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ m360.scc1.psmr |= 0x200;
+ else
+ m360.scc1.psmr &= ~0x200;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ m360.scc1.gsmr_l |= 0x30;
+}
+
+/*
+ * Stop the device
+ */
+static void
+scc_stop (struct scc_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ m360.scc1.gsmr_l &= ~0x30;
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+scc_stats (struct scc_softc *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Not First:%-8lu", sc->rxNotFirst);
+ printf (" Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Runt:%-8lu", sc->rxRunt);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" Collision:%-8lu\n", sc->rxCollision);
+ printf (" Discarded:%-8lu\n", (unsigned long)m360.scc1p.un.ethernet.disfc);
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" Deferred:%-8lu", sc->txDeferred);
+ printf (" Missed Hearbeat:%-8lu\n", sc->txHeartbeat);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf ("Retransmit Limit:%-8lu", sc->txRetryLimit);
+ printf (" Late Collision:%-8lu\n", sc->txLateCollision);
+ printf (" Underrun:%-8lu", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu", sc->txRawWait);
+ printf (" Coalesced:%-8lu\n", sc->txCoalesced);
+ printf (" Coalesce failed:%-8lu", sc->txCoalesceFailed);
+ printf (" Retries:%-8lu\n", sc->txRetry);
+}
+
+/*
+ * Driver ioctl handler
+ */
+static int
+scc_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct scc_softc *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ scc_stop (sc);
+ break;
+
+ case IFF_UP:
+ scc_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ scc_stop (sc);
+ scc_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ scc_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/*
+ * Attach an SCC driver to the system
+ */
+int
+rtems_scc1_driver_attach (struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ struct scc_softc *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+
+ /*
+ * Make sure we're really being attached
+ */
+ if (!attaching) {
+ printf ("SCC1 driver can not be detached.\n");
+ return 0;
+ }
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NSCCDRIVER)) {
+ printf ("Bad SCC unit number.\n");
+ return 0;
+ }
+ sc = &scc_softc[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address) {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+ else {
+ /*
+ * The first 4 bytes of the bootstrap prom
+ * contain the value loaded into the stack
+ * pointer as part of the CPU32's hardware
+ * reset exception handler. The following
+ * 4 bytes contain the value loaded into the
+ * program counter. The boards' Ethernet
+ * address is stored in the six bytes
+ * immediately preceding this initial
+ * program counter value.
+ *
+ * See start360/start360.s.
+ */
+ const unsigned long *ExceptionVectors;
+ const unsigned char *entryPoint;
+
+ /*
+ * Sanity check -- assume entry point must be
+ * within 1 MByte of beginning of boot ROM.
+ */
+ ExceptionVectors = (const unsigned long *)&_RomBase;
+ entryPoint = (const unsigned char *)ExceptionVectors[1];
+ if (((unsigned long)entryPoint - (unsigned long)ExceptionVectors)
+ >= (1 * 1024 * 1024)) {
+ printf ("Warning -- Ethernet address can not be found in bootstrap PROM.\n");
+ sc->arpcom.ac_enaddr[0] = 0x08;
+ sc->arpcom.ac_enaddr[1] = 0xF3;
+ sc->arpcom.ac_enaddr[2] = 0x3E;
+ sc->arpcom.ac_enaddr[3] = 0xC2;
+ sc->arpcom.ac_enaddr[4] = 0x7E;
+ sc->arpcom.ac_enaddr[5] = 0x38;
+ }
+ else {
+ memcpy (sc->arpcom.ac_enaddr, entryPoint - ETHER_ADDR_LEN, ETHER_ADDR_LEN);
+ }
+ }
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = scc_init;
+ ifp->if_ioctl = scc_ioctl;
+ ifp->if_start = scc_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+}
diff --git a/bsps/m68k/genmcf548x/net/network.c b/bsps/m68k/genmcf548x/net/network.c
new file mode 100644
index 0000000..646bd44
--- /dev/null
+++ b/bsps/m68k/genmcf548x/net/network.c
@@ -0,0 +1,1696 @@
+/*===============================================================*\
+| Project: RTEMS generic MCF548X BSP |
++-----------------------------------------------------------------+
+| Partially based on the code references which are named below. |
+| Adaptions, modifications, enhancements and any recent parts of |
+| the code are: |
+| Copyright (c) 2009 |
+| Embedded Brains GmbH |
+| Obere Lagerstr. 30 |
+| D-82178 Puchheim |
+| Germany |
+| rtems@embedded-brains.de |
++-----------------------------------------------------------------+
+| The license and distribution terms for this file may be |
+| found in the file LICENSE in this distribution or at |
+| |
+| http://www.rtems.org/license/LICENSE. |
+| |
++-----------------------------------------------------------------+
+| this file contains the networking driver |
+\*===============================================================*/
+/*
+ * RTEMS/TCPIP driver for MCF548X FEC Ethernet
+ *
+ * Modified for Motorola MPC5200 by Thomas Doerfler, <Thomas.Doerfler@imd-systems.de>
+ * COPYRIGHT (c) 2003, IMD
+ *
+ * Modified for Motorola IceCube (mgt5100) by Peter Rasmussen <prasmus@ipr-engineering.de>
+ * COPYRIGHT (c) 2003, IPR Engineering
+ *
+ * Parts of code are also under property of Driver Information Systems and based
+ * on Motorola Proprietary Information.
+ * COPYRIGHT (c) 2002 MOTOROLA INC.
+ *
+ * Modified for Motorola MCF548X by Thomas Doerfler, <Thomas.Doerfler@imd-systems.de>
+ * COPYRIGHT (c) 2009, IMD
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <stdio.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <net/if_var.h>
+
+#include <bsp.h>
+#include <bsp/irq-generic.h>
+#include <mcf548x/mcf548x.h>
+#include <rtems/rtems_mii_ioctl.h>
+#include <errno.h>
+
+/* freescale-api-specifics... */
+#include <mcf548x/MCD_dma.h>
+#include <mcf548x/mcdma_glue.h>
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 2
+
+#define FEC_WATCHDOG_TIMEOUT 5 /* check media every 5 seconds */
+
+#define DMA_BD_RX_NUM 32 /* Number of receive buffer descriptors */
+#define DMA_BD_TX_NUM 32 /* Number of transmit buffer descriptors */
+
+#define FEC_EVENT RTEMS_EVENT_0
+
+/*
+ * internal SRAM
+ * Layout:
+ * - RxBD channel 0
+ * - TxBD channel 0
+ * - RxBD channel 1
+ * - TxBD channel 1
+ * - DMA task memory
+ */
+extern char _SysSramBase[];
+#define SRAM_RXBD_BASE(base,chan) (((MCD_bufDescFec*)(base)) \
+ +((chan) \
+ *(DMA_BD_RX_NUM+DMA_BD_TX_NUM)))
+
+#define SRAM_TXBD_BASE(base,chan) (((MCD_bufDescFec*)(base)) \
+ +((chan) \
+ *(DMA_BD_RX_NUM+DMA_BD_TX_NUM) \
+ +DMA_BD_RX_NUM))
+
+#define SRAM_DMA_BASE(base) ((void *)SRAM_RXBD_BASE(base,NIFACES+1))
+
+
+#undef ETH_DEBUG
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT DMA_BD_RX_NUM
+#define TX_BUF_COUNT DMA_BD_TX_NUM
+#define TX_BD_PER_BUF 1
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+#define MCF548X_FEC0_IRQ_VECTOR (39+64)
+#define MCF548X_FEC1_IRQ_VECTOR (38+64)
+
+#define MCF548X_FEC_IRQ_VECTOR(chan) (MCF548X_FEC0_IRQ_VECTOR \
+ +(chan)*(MCF548X_FEC1_IRQ_VECTOR \
+ -MCF548X_FEC0_IRQ_VECTOR))
+
+#define MCF548X_FEC_VECTOR2CHAN(vector) (((int)(vector)-MCF548X_FEC0_IRQ_VECTOR) \
+ /(MCF548X_FEC1_IRQ_VECTOR \
+ -MCF548X_FEC0_IRQ_VECTOR))
+
+#define MCDMA_FEC_RX_CHAN(chan) (0 + NIFACES*(chan))
+#define MCDMA_FEC_TX_CHAN(chan) (1 + NIFACES*(chan))
+
+#define MCF548X_FEC0_RX_INITIATOR (16)
+#define MCF548X_FEC1_RX_INITIATOR (30)
+#define MCF548X_FEC_RX_INITIATOR(chan) (MCF548X_FEC0_RX_INITIATOR \
+ +(chan)*(MCF548X_FEC1_RX_INITIATOR \
+ -MCF548X_FEC0_RX_INITIATOR))
+#define MCF548X_FEC0_TX_INITIATOR (17)
+#define MCF548X_FEC1_TX_INITIATOR (31)
+#define MCF548X_FEC_TX_INITIATOR(chan) (MCF548X_FEC0_TX_INITIATOR \
+ +(chan)*(MCF548X_FEC1_TX_INITIATOR \
+ -MCF548X_FEC0_TX_INITIATOR))
+
+/* BD and parameters are stored in SRAM(refer to sdma.h) */
+#define MCF548X_FEC_BD_BASE ETH_BD_BASE
+
+/* RBD bits definitions */
+#define MCF548X_FEC_RBD_EMPTY 0x8000 /* Buffer is empty */
+#define MCF548X_FEC_RBD_WRAP 0x2000 /* Last BD in ring */
+#define MCF548X_FEC_RBD_INT 0x1000 /* Interrupt */
+#define MCF548X_FEC_RBD_LAST 0x0800 /* Buffer is last in frame(useless) */
+#define MCF548X_FEC_RBD_MISS 0x0100 /* Miss bit for prom mode */
+#define MCF548X_FEC_RBD_BC 0x0080 /* The received frame is broadcast frame */
+#define MCF548X_FEC_RBD_MC 0x0040 /* The received frame is multicast frame */
+#define MCF548X_FEC_RBD_LG 0x0020 /* Frame length violation */
+#define MCF548X_FEC_RBD_NO 0x0010 /* Nonoctet align frame */
+#define MCF548X_FEC_RBD_SH 0x0008 /* Short frame, FEC does not support SH and this bit is always cleared */
+#define MCF548X_FEC_RBD_CR 0x0004 /* CRC error */
+#define MCF548X_FEC_RBD_OV 0x0002 /* Receive FIFO overrun */
+#define MCF548X_FEC_RBD_TR 0x0001 /* The receive frame is truncated */
+#define MCF548X_FEC_RBD_ERR (MCF548X_FEC_RBD_LG | \
+ MCF548X_FEC_RBD_NO | \
+ MCF548X_FEC_RBD_CR | \
+ MCF548X_FEC_RBD_OV | \
+ MCF548X_FEC_RBD_TR)
+
+/* TBD bits definitions */
+#define MCF548X_FEC_TBD_READY 0x8000 /* Buffer is ready */
+#define MCF548X_FEC_TBD_WRAP 0x2000 /* Last BD in ring */
+#define MCF548X_FEC_TBD_INT 0x1000 /* Interrupt */
+#define MCF548X_FEC_TBD_LAST 0x0800 /* Buffer is last in frame */
+#define MCF548X_FEC_TBD_TC 0x0400 /* Transmit the CRC */
+#define MCF548X_FEC_TBD_ABC 0x0200 /* Append bad CRC */
+
+#define FEC_INTR_MASK_USED \
+(MCF548X_FEC_EIMR_LC | MCF548X_FEC_EIMR_RL | \
+ MCF548X_FEC_EIMR_XFUN | MCF548X_FEC_EIMR_XFERR | MCF548X_FEC_EIMR_RFERR)
+
+typedef enum {
+ FEC_STATE_RESTART_0,
+ FEC_STATE_RESTART_1,
+ FEC_STATE_NORMAL,
+} fec_state;
+
+/*
+ * Device data
+ */
+struct mcf548x_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int chan;
+ fec_state state;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ MCD_bufDescFec *rxBd;
+ MCD_bufDescFec *txBd;
+ int rxDmaChan; /* dma task */
+ int txDmaChan; /* dma task */
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * MDIO/Phy info
+ */
+ struct rtems_mdio_info mdio_info;
+ int phy_default;
+ int phy_chan; /* which fec channel services this phy access? */
+ int media_state; /* (last detected) state of media */
+
+ unsigned long rxInterrupts;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxBadCRC;
+ unsigned long rxFIFOError;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txLateCollision;
+ unsigned long txUnderrun;
+ unsigned long txFIFOError;
+ unsigned long txMisaligned;
+ unsigned long rxNotFirst;
+ unsigned long txRetryLimit;
+ };
+
+static struct mcf548x_enet_struct enet_driver[NIFACES];
+
+static void mcf548x_fec_restart(struct mcf548x_enet_struct *sc, rtems_id otherDaemon);
+
+static void fec_send_event(rtems_id task)
+{
+ rtems_bsdnet_event_send(task, FEC_EVENT);
+}
+
+static void fec_wait_for_event(void)
+{
+ rtems_event_set out;
+ rtems_bsdnet_event_receive(
+ FEC_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &out
+ );
+}
+
+static void mcf548x_fec_request_restart(struct mcf548x_enet_struct *sc)
+{
+ sc->state = FEC_STATE_RESTART_0;
+ fec_send_event(sc->txDaemonTid);
+ fec_send_event(sc->rxDaemonTid);
+}
+
+/*
+ * Function: MCF548X_eth_addr_filter_set
+ *
+ * Description: Set individual address filter for unicast address and
+ * set physical address registers.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mcf548x_eth_addr_filter_set(struct mcf548x_enet_struct *sc) {
+ unsigned char *mac;
+ unsigned char currByte; /* byte for which to compute the CRC */
+ int byte; /* loop - counter */
+ int bit; /* loop - counter */
+ unsigned long crc = 0xffffffff; /* initial value */
+ int chan = sc->chan;
+
+ /*
+ * Get the mac address of ethernet controller
+ */
+ mac = (unsigned char *)(&sc->arpcom.ac_enaddr);
+
+ /*
+ * 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 itsc 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)
+ {
+
+ MCF548X_FEC_IAUR(chan) = (1 << (crc - 32));
+ MCF548X_FEC_IALR(chan) = 0;
+
+ }
+ else
+ {
+
+ MCF548X_FEC_IAUR(chan) = 0;
+ MCF548X_FEC_IALR(chan) = (1 << crc);
+
+ }
+
+ /*
+ * Set physical address
+ */
+ MCF548X_FEC_PALR(chan) = ((mac[0] << 24) +
+ (mac[1] << 16) +
+ (mac[2] << 8) +
+ mac[3]);
+ MCF548X_FEC_PAUR(chan) = ((mac[4] << 24)
+ + (mac[5] << 16)) + 0x8808;
+
+ }
+
+
+/*
+ * Function: mcf548x_eth_mii_read
+ *
+ * Description: Read a media independent interface (MII) register on an
+ * 18-wire ethernet tranceiver (PHY). Please see your PHY
+ * documentation for the register map.
+ *
+ * Returns: 0 if ok
+ *
+ * Notes:
+ *
+ */
+int mcf548x_eth_mii_read(
+ int phyAddr, /* PHY number to access or -1 */
+ void *uarg, /* unit argument */
+ unsigned regAddr, /* register address */
+ uint32_t *retVal) /* ptr to read buffer */
+{
+ struct mcf548x_enet_struct *sc = uarg;
+ int timeout = 0xffff;
+ int chan = sc->phy_chan;
+
+ /*
+ * reading from any PHY's register is done by properly
+ * programming the FEC's MII data register.
+ */
+ MCF548X_FEC_MMFR(chan) = (MCF548X_FEC_MMFR_ST_01 |
+ MCF548X_FEC_MMFR_OP_READ |
+ MCF548X_FEC_MMFR_TA_10 |
+ MCF548X_FEC_MMFR_PA(phyAddr) |
+ MCF548X_FEC_MMFR_RA(regAddr));
+
+ /*
+ * wait for the related interrupt
+ */
+ while ((timeout--) && (!(MCF548X_FEC_EIR(chan) & MCF548X_FEC_EIR_MII)));
+
+ if(timeout == 0) {
+
+#ifdef ETH_DEBUG
+ iprintf ("Read MDIO failed..." "\r\n");
+#endif
+
+ return 1;
+
+ }
+
+ /*
+ * clear mii interrupt bit
+ */
+ MCF548X_FEC_EIR(chan) = MCF548X_FEC_EIR_MII;
+
+ /*
+ * it's now safe to read the PHY's register
+ */
+ *retVal = (unsigned short) MCF548X_FEC_MMFR(chan);
+
+ return 0;
+
+}
+
+/*
+ * Function: mcf548x_eth_mii_write
+ *
+ * Description: Write a media independent interface (MII) register on an
+ * 18-wire ethernet tranceiver (PHY). Please see your PHY
+ * documentation for the register map.
+ *
+ * Returns: Success (boolean)
+ *
+ * Notes:
+ *
+ */
+static int mcf548x_eth_mii_write(
+ int phyAddr, /* PHY number to access or -1 */
+ void *uarg, /* unit argument */
+ unsigned regAddr, /* register address */
+ uint32_t data) /* write data */
+{
+ struct mcf548x_enet_struct *sc = uarg;
+ int chan = sc->phy_chan;
+ int timeout = 0xffff;
+
+ MCF548X_FEC_MMFR(chan) = (MCF548X_FEC_MMFR_ST_01 |
+ MCF548X_FEC_MMFR_OP_WRITE |
+ MCF548X_FEC_MMFR_TA_10 |
+ MCF548X_FEC_MMFR_PA(phyAddr) |
+ MCF548X_FEC_MMFR_RA(regAddr) |
+ MCF548X_FEC_MMFR_DATA(data));
+
+ /*
+ * wait for the MII interrupt
+ */
+ while ((timeout--) && (!(MCF548X_FEC_EIR(chan) & MCF548X_FEC_EIR_MII)));
+
+ if(timeout == 0)
+ {
+
+#ifdef ETH_DEBUG
+ iprintf ("Write MDIO failed..." "\r\n");
+#endif
+
+ return 1;
+
+ }
+
+ /*
+ * clear MII interrupt bit
+ */
+ MCF548X_FEC_EIR(chan) = MCF548X_FEC_EIR_MII;
+
+ return 0;
+
+ }
+
+
+/*
+ * Function: mcf548x_fec_reset
+ *
+ * Description: Reset a running ethernet driver including the hardware
+ * FIFOs and the FEC.
+ *
+ * Returns: Success (boolean)
+ *
+ * Notes:
+ *
+ */
+static void mcf548x_fec_reset(struct mcf548x_enet_struct *sc) {
+ volatile int delay;
+ int chan = sc->chan;
+ /*
+ * Clear FIFO status registers
+ */
+ MCF548X_FEC_FECRFSR(chan) = ~0;
+ MCF548X_FEC_FECTFSR(chan) = ~0;
+
+ /*
+ * reset the FIFOs
+ */
+ MCF548X_FEC_FRST(chan) = 0x03000000;
+
+ for (delay = 0;delay < 16*4;delay++) {};
+
+ MCF548X_FEC_FRST(chan) = 0x01000000;
+
+ /*
+ * Issue a reset command to the FEC chip
+ */
+ MCF548X_FEC_ECR(chan) |= MCF548X_FEC_ECR_RESET;
+
+ /*
+ * wait at least 16 clock cycles
+ */
+ for (delay = 0;delay < 16*4;delay++) {};
+}
+
+
+/*
+ * Function: mcf548x_fec_off
+ *
+ * Description: Stop the FEC and disable the ethernet SmartComm tasks.
+ * This function "turns off" the driver.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+void mcf548x_fec_off(struct mcf548x_enet_struct *sc)
+ {
+ int counter = 0xffff;
+ int chan = sc->chan;
+
+
+#if defined(ETH_DEBUG)
+ uint32_t phyStatus;
+ int i;
+
+ for(i = 0; i < 9; i++)
+ {
+
+ mcf548x_eth_mii_read(sc->phy_default, sc, i, &phyStatus);
+ iprintf ("Mii reg %d: 0x%04lx" "\r\n", i, phyStatus);
+
+ }
+
+ for(i = 16; i < 21; i++)
+ {
+
+ mcf548x_eth_mii_read(sc->phy_default, sc, i, &phyStatus);
+ iprintf ("Mii reg %d: 0x%04lx" "\r\n", i, phyStatus);
+
+ }
+ for(i = 0; i < 32; i++)
+ {
+
+ mcf548x_eth_mii_read(i, sc, 0, &phyStatus);
+ iprintf ("Mii Phy=%d, reg 0: 0x%04lx" "\r\n", i, phyStatus);
+
+ }
+#endif /* ETH_DEBUG */
+
+ /*
+ * block FEC chip interrupts
+ */
+ MCF548X_FEC_EIMR(chan) = 0;
+
+ /*
+ * issue graceful stop command to the FEC transmitter if necessary
+ */
+ MCF548X_FEC_TCR(chan) |= MCF548X_FEC_TCR_GTS;
+
+ /*
+ * wait for graceful stop to register
+ * FIXME: add rtems_task_wake_after here, if it takes to long
+ */
+ while((counter--) && (!( MCF548X_FEC_EIR(chan) & MCF548X_FEC_EIR_GRA)));
+
+ /*
+ * Disable the SmartDMA transmit and receive tasks.
+ */
+ MCD_killDma( sc->rxDmaChan );
+ MCD_killDma( sc->txDmaChan );
+ /*
+ * Disable transmit / receive interrupts
+ */
+ mcdma_glue_irq_disable(sc->txDmaChan);
+ mcdma_glue_irq_disable(sc->rxDmaChan);
+
+ /*
+ * Disable the Ethernet Controller
+ */
+ MCF548X_FEC_ECR(chan) &= ~(MCF548X_FEC_ECR_ETHER_EN);
+}
+
+/*
+ * MCF548X FEC interrupt handler
+ */
+void mcf548x_fec_irq_handler(rtems_vector_number vector)
+{
+ struct mcf548x_enet_struct *sc;
+ volatile uint32_t ievent;
+ int chan;
+
+ sc = &(enet_driver[MCF548X_FEC_VECTOR2CHAN(vector)]);
+ chan = sc->chan;
+ ievent = MCF548X_FEC_EIR(chan);
+
+ MCF548X_FEC_EIR(chan) = ievent;
+ /*
+ * check errors, update statistics
+ */
+ if (ievent & MCF548X_FEC_EIR_LC) {
+ sc->txLateCollision++;
+ }
+ if (ievent & MCF548X_FEC_EIR_RL) {
+ sc->txRetryLimit++;
+ }
+ if (ievent & MCF548X_FEC_EIR_XFUN) {
+ sc->txUnderrun++;
+ }
+ if (ievent & MCF548X_FEC_EIR_XFERR) {
+ sc->txFIFOError++;
+ }
+ if (ievent & MCF548X_FEC_EIR_RFERR) {
+ sc->rxFIFOError++;
+ }
+ /*
+ * fatal error occurred?
+ */
+ if (ievent & (MCF548X_FEC_EIR_RFERR | MCF548X_FEC_EIR_XFERR)) {
+ MCF548X_FEC_EIMR(chan) &=~(MCF548X_FEC_EIMR_RFERR | MCF548X_FEC_EIMR_XFERR);
+ printk("fifo\n");
+ mcf548x_fec_request_restart(sc);
+ }
+}
+
+/*
+ * MCF548X DMA ethernet interrupt handler
+ */
+void mcf548x_mcdma_rx_irq_handler(void * param)
+{
+ struct mcf548x_enet_struct *sc = (struct mcf548x_enet_struct *)param;
+ /* Frame received? */
+ if(MCDMA_GET_PENDING(sc->rxDmaChan)) {
+ MCDMA_CLR_PENDING(sc->rxDmaChan);
+
+ mcdma_glue_irq_disable(sc->rxDmaChan);/*Disable receive ints*/
+ sc->rxInterrupts++; /* Rx int has occurred */
+ fec_send_event(sc->rxDaemonTid);
+ }
+}
+
+/*
+ * MCF548X DMA ethernet interrupt handler
+ */
+void mcf548x_mcdma_tx_irq_handler(void * param)
+{
+ struct mcf548x_enet_struct *sc = (struct mcf548x_enet_struct *)param;
+
+ /* Buffer transmitted or transmitter error? */
+ if(MCDMA_GET_PENDING(sc->txDmaChan)) {
+
+ MCDMA_CLR_PENDING(sc->txDmaChan);
+
+ mcdma_glue_irq_disable(sc->txDmaChan);/*Disable tx ints*/
+
+ sc->txInterrupts++; /* Tx int has occurred */
+
+ fec_send_event(sc->txDaemonTid);
+ }
+}
+
+/*
+ * Function: mcf548x_fec_initialize_hardware
+ *
+ * Description: Configure the MCF548X FEC registers and enable the
+ * SmartComm tasks. This function "turns on" the driver.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mcf548x_fec_initialize_hardware(struct mcf548x_enet_struct *sc)
+ {
+ int chan = sc->chan;
+
+ /*
+ * Reset mcf548x FEC
+ */
+ mcf548x_fec_reset(sc);
+
+ /*
+ * Clear FEC-Lite interrupt event register (IEVENT)
+ */
+ MCF548X_FEC_EIR(chan) = MCF548X_FEC_EIR_CLEAR_ALL;
+
+ /*
+ * Set interrupt mask register
+ */
+ MCF548X_FEC_EIMR(chan) = FEC_INTR_MASK_USED;
+ /*
+ * Set FEC-Lite receive control register (R_CNTRL)
+ * frame length=1518, MII mode for 18-wire-transceiver
+ */
+ MCF548X_FEC_RCR(chan) = (MCF548X_FEC_RCR_MAX_FL(ETHER_MAX_LEN)
+ | MCF548X_FEC_RCR_FCE
+ | MCF548X_FEC_RCR_MII_MODE);
+
+ /*
+ * Set FEC-Lite transmit control register (X_CNTRL)
+ * full-duplex, heartbeat disabled
+ */
+ MCF548X_FEC_TCR(chan) = MCF548X_FEC_TCR_FDEN;
+
+
+
+ /*
+ * Set MII_SPEED = (1/(mii_speed * 2)) * System Clock(33Mhz)
+ * and do not drop the Preamble.
+ */
+ MCF548X_FEC_MSCR(chan) = MCF548X_FEC_MSCR_MII_SPEED(7); /* ipb_clk = 33 MHz */
+
+ /*
+ * Set Opcode/Pause Duration Register
+ */
+ MCF548X_FEC_PAUR(chan) = 0x00010020;
+
+ /*
+ * Set Rx FIFO alarm and granularity value
+ */
+ MCF548X_FEC_FECRFCR(chan) = (MCF548X_FEC_FECRFCR_FRM
+ | MCF548X_FEC_FECRFCR_GR(0x7));
+ MCF548X_FEC_FECRFAR(chan) = MCF548X_FEC_FECRFAR_ALARM(256);
+
+ /*
+ * Set Tx FIFO granularity value
+ */
+ MCF548X_FEC_FECTFCR(chan) = (MCF548X_FEC_FECTFCR_FRM
+ | MCF548X_FEC_FECTFCR_GR(7));
+
+ /*
+ * Set transmit fifo watermark register (X_WMRK), default = 64
+ */
+ MCF548X_FEC_FECTFAR(chan) = MCF548X_FEC_FECTFAR_ALARM(512);
+ MCF548X_FEC_FECTFWR(chan) = MCF548X_FEC_FECTFWR_X_WMRK_256;
+
+ /*
+ * Set individual address filter for unicast address
+ * and set physical address registers.
+ */
+ mcf548x_eth_addr_filter_set(sc);
+
+ /*
+ * Set multicast address filter
+ */
+ MCF548X_FEC_GAUR(chan) = 0x00000000;
+ MCF548X_FEC_GALR(chan) = 0x00000000;
+
+ /*
+ * enable CRC in finite state machine register
+ */
+ MCF548X_FEC_CTCWR(chan) = MCF548X_FEC_CTCWR_TFCW | MCF548X_FEC_CTCWR_CRC;
+ }
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void mcf548x_fec_tx_start(struct ifnet *ifp)
+ {
+
+ struct mcf548x_enet_struct *sc = ifp->if_softc;
+
+ ifp->if_flags |= IFF_OACTIVE;
+
+ fec_send_event(sc->txDaemonTid);
+
+ }
+
+static void fec_start_dma_and_controller(struct mcf548x_enet_struct *sc)
+{
+ int chan = sc->chan;
+ int mcdma_rc;
+ /*
+ * Enable the SmartDMA receive task.
+ */
+ mcdma_rc = MCD_startDma
+ (sc->rxDmaChan, /* the channel on which to run the DMA */
+ (void *)sc->rxBd, /* the address to move data from, or buffer-descriptor addr */
+ 0, /* the amount to increment the source address per transfer */
+ (void *)&MCF548X_FEC_FECRFDR(chan), /* the address to move data to */
+ 0, /* the amount to increment the destination address per transfer */
+ ETHER_MAX_LEN, /* the number of bytes to transfer independent of the transfer size */
+ 0, /* the number bytes in of each data movement (1, 2, or 4) */
+ MCF548X_FEC_RX_INITIATOR(chan), /* what device initiates the DMA */
+ 2, /* priority of the DMA */
+ 0 /* flags describing the DMA */
+ | MCD_FECRX_DMA
+ | MCD_INTERRUPT
+ | MCD_TT_FLAGS_CW
+ | MCD_TT_FLAGS_RL
+ | MCD_TT_FLAGS_SP
+ ,
+ 0 /* a description of byte swapping, bit swapping, and CRC actions */
+ | MCD_NO_CSUM
+ | MCD_NO_BYTE_SWAP
+ );
+ if (mcdma_rc != MCD_OK) {
+ rtems_panic("FEC: cannot start rx DMA");
+ }
+ mcdma_rc = MCD_startDma
+ (sc->txDmaChan, /* the channel on which to run the DMA */
+ (void *)sc->txBd, /* the address to move data from, or buffer-descriptor addr */
+ 0, /* the amount to increment the source address per transfer */
+ (void *)&MCF548X_FEC_FECTFDR(chan), /* the address to move data to */
+ 0, /* the amount to increment the destination address per transfer */
+ ETHER_MAX_LEN, /* the number of bytes to transfer independent of the transfer size */
+ 0, /* the number bytes in of each data movement (1, 2, or 4) */
+ MCF548X_FEC_TX_INITIATOR(chan), /* what device initiates the DMA */
+ 1, /* priority of the DMA */
+ 0 /* flags describing the DMA */
+ | MCD_FECTX_DMA
+ | MCD_INTERRUPT
+ | MCD_TT_FLAGS_CW
+ | MCD_TT_FLAGS_RL
+ | MCD_TT_FLAGS_SP
+ ,
+ 0 /* a description of byte swapping, bit swapping, and CRC actions */
+ | MCD_NO_CSUM
+ | MCD_NO_BYTE_SWAP
+ );
+ if (mcdma_rc != MCD_OK) {
+ rtems_panic("FEC: cannot start tx DMA");
+ }
+
+ /*
+ * Enable FEC-Lite controller
+ */
+ MCF548X_FEC_ECR(chan) |= MCF548X_FEC_ECR_ETHER_EN;
+}
+
+static void mcf548x_fec_restart(struct mcf548x_enet_struct *sc, rtems_id otherDaemon)
+{
+ if (sc->state == FEC_STATE_RESTART_1) {
+ mcf548x_fec_initialize_hardware(sc);
+ fec_start_dma_and_controller(sc);
+ sc->state = FEC_STATE_NORMAL;
+ } else {
+ sc->state = FEC_STATE_RESTART_1;
+ }
+
+ fec_send_event(otherDaemon);
+ while (sc->state != FEC_STATE_NORMAL) {
+ fec_wait_for_event();
+ }
+}
+
+static void fec_reset_bd_and_discard_tx_frames(
+ int bdCount,
+ MCD_bufDescFec *bdRing,
+ struct mbuf **mbufs
+)
+{
+ int bdIndex = 0;
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ bool bdIsLast = bdIndex == bdCount - 1;
+ struct mbuf *m = mbufs[bdIndex];
+
+ bdRing[bdIndex].statCtrl = bdIsLast ? MCF548X_FEC_TBD_WRAP : 0;
+
+ if (m != NULL) {
+ mbufs[bdIndex] = NULL;
+ m_free(m);
+ }
+ }
+}
+
+static void fec_reset_tx_dma(
+ int dmaChan,
+ int bdCount,
+ MCD_bufDescFec *bdRing,
+ struct mbuf **mbufs,
+ struct mbuf *m
+)
+{
+ if (m != NULL) {
+ m_freem(m);
+ }
+
+ MCD_killDma(dmaChan);
+
+ fec_reset_bd_and_discard_tx_frames(bdCount, bdRing, mbufs);
+}
+
+static struct mbuf *fec_next_fragment(
+ struct ifnet *ifp,
+ struct mbuf *m,
+ bool *isFirst
+)
+{
+ struct mbuf *n = NULL;
+
+ *isFirst = false;
+
+ while (true) {
+ if (m == NULL) {
+ IF_DEQUEUE(&ifp->if_snd, m);
+
+ if (m != NULL) {
+ *isFirst = true;
+ } else {
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ return NULL;
+ }
+ }
+
+ if (m->m_len > 0) {
+ break;
+ } else {
+ m = m_free(m);
+ }
+ }
+
+ n = m->m_next;
+ while (n != NULL && n->m_len <= 0) {
+ n = m_free(n);
+ }
+ m->m_next = n;
+
+ return m;
+}
+
+static bool fec_transmit(
+ struct ifnet *ifp,
+ int dmaChan,
+ int bdCount,
+ MCD_bufDescFec *bdRing,
+ struct mbuf **mbufs,
+ int *bdIndexPtr,
+ struct mbuf **mPtr,
+ MCD_bufDescFec **firstPtr
+)
+{
+ bool bdShortage = false;
+ int bdIndex = *bdIndexPtr;
+ struct mbuf *m = *mPtr;
+ MCD_bufDescFec *first = *firstPtr;
+
+ while (true) {
+ MCD_bufDescFec *bd = &bdRing[bdIndex];
+
+ MCDMA_CLR_PENDING(dmaChan);
+ if ((bd->statCtrl & MCF548X_FEC_TBD_READY) == 0) {
+ struct mbuf *done = mbufs[bdIndex];
+ bool isFirst = false;
+
+ if (done != NULL) {
+ m_free(done);
+ mbufs[bdIndex] = NULL;
+ }
+
+ m = fec_next_fragment(ifp, m, &isFirst);
+ if (m != NULL) {
+ bool bdIsLast = bdIndex == bdCount - 1;
+ u16 status = bdIsLast ? MCF548X_FEC_TBD_WRAP : 0;
+
+ bd->length = (u16) m->m_len;
+ bd->dataPointer = mtod(m, u32);
+
+ mbufs[bdIndex] = m;
+
+ rtems_cache_flush_multiple_data_lines(mtod(m, void *), m->m_len);
+
+ if (isFirst) {
+ first = bd;
+ } else {
+ status |= MCF548X_FEC_TBD_READY;
+ }
+
+ if (m->m_next != NULL) {
+ bd->statCtrl = status;
+ } else {
+ bd->statCtrl = status | MCF548X_FEC_TBD_INT | MCF548X_FEC_TBD_LAST;
+ first->statCtrl |= MCF548X_FEC_TBD_READY;
+ MCD_continDma(dmaChan);
+ }
+
+ m = m->m_next;
+ } else {
+ break;
+ }
+ } else {
+ bdShortage = true;
+ break;
+ }
+
+ if (bdIndex < bdCount - 1) {
+ ++bdIndex;
+ } else {
+ bdIndex = 0;
+ }
+ }
+
+ *bdIndexPtr = bdIndex;
+ *mPtr = m;
+ *firstPtr = first;
+
+ return bdShortage;
+}
+
+static MCD_bufDescFec *fec_init_tx_dma(
+ MCD_bufDescFec *bdRing,
+ int bdCount
+)
+{
+ int bdIndex;
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ bool bdIsLast = bdIndex == bdCount - 1;
+
+ bdRing[bdIndex].dataPointer = 0;
+ bdRing[bdIndex].length = 0;
+ bdRing[bdIndex].statCtrl = bdIsLast ? MCF548X_FEC_RBD_WRAP : 0;
+ }
+
+ return bdRing;
+}
+
+static void mcf548x_fec_txDaemon(void *arg)
+{
+ struct mcf548x_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ int dmaChan = sc->txDmaChan;
+ int bdIndex = 0;
+ int bdCount = sc->txBdCount;
+ struct mbuf **mbufs = &sc->txMbuf[0];
+ struct mbuf *m = NULL;
+ MCD_bufDescFec *bdRing = fec_init_tx_dma(sc->txBd, bdCount);
+ MCD_bufDescFec *first = NULL;
+ bool bdShortage = false;
+
+ memset(mbufs, 0, bdCount * sizeof(*mbufs));
+
+ while (true) {
+ if (bdShortage) {
+ mcdma_glue_irq_enable(dmaChan);
+ }
+ fec_wait_for_event();
+
+ if (sc->state != FEC_STATE_NORMAL) {
+ fec_reset_tx_dma(dmaChan, bdCount, bdRing, mbufs, m);
+ mcf548x_fec_restart(sc, sc->rxDaemonTid);
+ bdIndex = 0;
+ m = NULL;
+ first = NULL;
+ }
+
+ bdShortage = fec_transmit(
+ ifp,
+ dmaChan,
+ bdCount,
+ bdRing,
+ mbufs,
+ &bdIndex,
+ &m,
+ &first
+ );
+ }
+}
+
+static struct mbuf *fec_add_mbuf(
+ int how,
+ struct ifnet *ifp,
+ MCD_bufDescFec *bd,
+ bool bdIsLast
+)
+{
+ struct mbuf *m;
+
+ MGETHDR(m, how, MT_DATA);
+ if (m != NULL) {
+ MCLGET(m, how);
+ if ((m->m_flags & M_EXT) != 0) {
+ m->m_pkthdr.rcvif = ifp;
+
+ rtems_cache_invalidate_multiple_data_lines(mtod(m, void *), ETHER_MAX_LEN);
+
+ bd->dataPointer = mtod(m, u32);
+ bd->length = ETHER_MAX_LEN;
+ bd->statCtrl = MCF548X_FEC_RBD_EMPTY
+ | MCF548X_FEC_RBD_INT
+ | (bdIsLast ? MCF548X_FEC_RBD_WRAP : 0);
+ } else {
+ m_free(m);
+ }
+ }
+
+ return m;
+}
+
+static MCD_bufDescFec *fec_init_rx_dma(
+ MCD_bufDescFec *bdRing,
+ struct ifnet *ifp,
+ int bdCount,
+ struct mbuf **mbufs
+)
+{
+ int bdIndex;
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ bool bdIsLast = bdIndex == bdCount - 1;
+
+ mbufs[bdIndex] = fec_add_mbuf(M_WAIT, ifp, &bdRing[bdIndex], bdIsLast);
+ }
+
+ return bdRing;
+}
+
+static void fec_reset_rx_dma(
+ int dmaChan,
+ int bdCount,
+ MCD_bufDescFec *bdRing
+)
+{
+ int bdIndex;
+
+ MCD_killDma(dmaChan);
+
+ for (bdIndex = 0; bdIndex < bdCount - 1; ++bdIndex) {
+ bdRing[bdIndex].length = ETHER_MAX_LEN;
+ bdRing[bdIndex].statCtrl = MCF548X_FEC_RBD_EMPTY | MCF548X_FEC_RBD_INT;
+ }
+
+ bdRing[bdIndex].length = ETHER_MAX_LEN;
+ bdRing[bdIndex].statCtrl = MCF548X_FEC_RBD_EMPTY | MCF548X_FEC_RBD_INT | MCF548X_FEC_RBD_WRAP;
+}
+
+static int fec_ether_input(
+ struct ifnet *ifp,
+ int dmaChan,
+ int bdIndex,
+ int bdCount,
+ MCD_bufDescFec *bdRing,
+ struct mbuf **mbufs
+)
+{
+ while (true) {
+ bool bdIsLast = bdIndex == bdCount - 1;
+ MCD_bufDescFec *bd = &bdRing[bdIndex];
+ struct mbuf *m = mbufs[bdIndex];
+ struct mbuf *n;
+ u16 status;
+
+ MCDMA_CLR_PENDING(dmaChan);
+ status = bd->statCtrl;
+
+ if ((status & MCF548X_FEC_RBD_EMPTY) != 0) {
+ break;
+ }
+
+ n = fec_add_mbuf(0, ifp, bd, bdIsLast);
+ if (n != NULL) {
+ int len = bd->length - ETHER_HDR_LEN - ETHER_CRC_LEN;
+ struct ether_header *eh = mtod(m, struct ether_header *);
+
+ m->m_len = len;
+ m->m_pkthdr.len = len;
+ m->m_data = mtod(m, char *) + ETHER_HDR_LEN;
+
+ ether_input(ifp, eh, m);
+ } else {
+ n = m;
+ }
+
+ mbufs[bdIndex] = n;
+
+ if (bdIndex < bdCount - 1) {
+ ++bdIndex;
+ } else {
+ bdIndex = 0;
+ }
+ }
+
+ return bdIndex;
+}
+
+static void mcf548x_fec_rxDaemon(void *arg)
+{
+ struct mcf548x_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ int dmaChan = sc->rxDmaChan;
+ int bdIndex = 0;
+ int bdCount = sc->rxBdCount;
+ struct mbuf **mbufs = &sc->rxMbuf[0];
+ MCD_bufDescFec *bdRing = fec_init_rx_dma(sc->rxBd, ifp, bdCount, mbufs);
+
+ while (true) {
+ mcdma_glue_irq_enable(dmaChan);
+ fec_wait_for_event();
+
+ bdIndex = fec_ether_input(ifp, dmaChan, bdIndex, bdCount, bdRing, mbufs);
+
+ if (sc->state != FEC_STATE_NORMAL) {
+ fec_reset_rx_dma(dmaChan, bdCount, bdRing);
+ mcf548x_fec_restart(sc, sc->txDaemonTid);
+ bdIndex = 0;
+ }
+ }
+}
+
+/*
+ * Initialize and start the device
+ */
+static void mcf548x_fec_init(void *arg)
+{
+ struct mcf548x_enet_struct *sc = (struct mcf548x_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ int chan = sc->chan;
+ rtems_isr_entry old_handler;
+ char *txTaskName = "FTx0";
+ char *rxTaskName = "FRx0";
+ if(sc->txDaemonTid == 0)
+ {
+ /*
+ * Allocate a set of BDs
+ */
+ sc->rxBd = SRAM_RXBD_BASE(_SysSramBase,chan);
+ sc->txBd = SRAM_TXBD_BASE(_SysSramBase,chan);
+
+ if(!sc->rxBd || !sc->txBd)
+ rtems_panic ("No memory for BDs");
+ /*
+ * clear the BDs
+ */
+ memset((void *)sc->rxBd,0,sc->rxBdCount * sizeof *(sc->rxBd));
+ memset((void *)sc->txBd,0,sc->txBdCount * sizeof *(sc->txBd));
+ /*
+ * Allocate a set of mbuf pointers
+ */
+ sc->rxMbuf =
+ malloc(sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf =
+ malloc(sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+
+ if(!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ sc->txDmaChan = MCDMA_FEC_TX_CHAN(chan);
+ sc->rxDmaChan = MCDMA_FEC_RX_CHAN(chan);
+
+ mcdma_glue_init(SRAM_DMA_BASE(_SysSramBase));
+
+ /*
+ * Set up interrupts
+ */
+ mcdma_glue_irq_install(sc->rxDmaChan,
+ mcf548x_mcdma_rx_irq_handler,
+ sc);
+ mcdma_glue_irq_install(sc->txDmaChan,
+ mcf548x_mcdma_tx_irq_handler,
+ sc);
+ if(rtems_interrupt_catch(mcf548x_fec_irq_handler,
+ MCF548X_FEC_IRQ_VECTOR(chan),
+ &old_handler)) {
+ rtems_panic ("Can't attach MFC54xx FEX interrupt handler\n");
+ }
+
+ bsp_interrupt_vector_enable(MCF548X_IRQ_FEC(chan));
+
+ MCF548X_FEC_EIMR(chan) = FEC_INTR_MASK_USED;
+
+ /*
+ * Start driver tasks
+ */
+ txTaskName[3] = '0'+chan;
+ rxTaskName[3] = '0'+chan;
+ sc->txDaemonTid = rtems_bsdnet_newproc(txTaskName, 4096,
+ mcf548x_fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc(rxTaskName, 4096,
+ mcf548x_fec_rxDaemon, sc);
+ }
+
+ mcf548x_fec_request_restart(sc);
+
+ /*
+ * Set flags appropriately
+ */
+ if(ifp->if_flags & IFF_PROMISC)
+ MCF548X_FEC_RCR(chan) |= MCF548X_FEC_RCR_PROM;
+ else
+ MCF548X_FEC_RCR(chan) &= ~MCF548X_FEC_RCR_PROM;
+
+ /*
+ * init timer so the "watchdog function gets called periodically
+ */
+ ifp->if_timer = 1;
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+
+static void enet_stats (struct mcf548x_enet_struct *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Rx Not First:%-8lu", sc->rxNotFirst);
+ printf (" Rx Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Rx Giant:%-8lu", sc->rxGiant);
+ printf (" Rx Non-octet:%-8lu", sc->rxNonOctet);
+ printf (" Rx Bad CRC:%-8lu\n", sc->rxBadCRC);
+ printf (" Rx FIFO Error:%-8lu", sc->rxFIFOError);
+ printf (" Rx Collision:%-8lu", sc->rxCollision);
+
+ printf (" Tx Interrupts:%-8lu\n", sc->txInterrupts);
+ printf (" Tx Deferred:%-8lu", sc->txDeferred);
+ printf (" Tx Late Collision:%-8lu", sc->txLateCollision);
+ printf (" Tx Retransmit Limit:%-8lu\n", sc->txRetryLimit);
+ printf (" Tx Underrun:%-8lu", sc->txUnderrun);
+ printf (" Tx FIFO Error:%-8lu", sc->txFIFOError);
+ printf (" Tx Misaligned:%-8lu\n", sc->txMisaligned);
+
+}
+
+int32_t mcf548x_fec_setMultiFilter(struct ifnet *ifp)
+{
+ /*struct mcf548x_enet_struct *sc = ifp->if_softc; */
+ /* XXX anything to do? */
+ return 0;
+}
+
+
+/*
+ * Driver ioctl handler
+ */
+static int mcf548x_fec_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+ {
+ struct mcf548x_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch(command)
+ {
+
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ rtems_mii_ioctl (&(sc->mdio_info),sc,command,(void *)data);
+ break;
+
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+
+ ether_ioctl(ifp, command, data);
+
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI: {
+ struct ifreq* ifr = (struct ifreq*) data;
+ error = (command == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &sc->arpcom)
+ : ether_delmulti(ifr, &sc->arpcom);
+
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING)
+ error = mcf548x_fec_setMultiFilter(ifp);
+ else
+ error = 0;
+ }
+ break;
+ }
+
+ case SIOCSIFFLAGS:
+
+ switch(ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+
+ case IFF_RUNNING:
+
+ mcf548x_fec_off(sc);
+
+ break;
+
+ case IFF_UP:
+
+ mcf548x_fec_init(sc);
+
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+
+ mcf548x_fec_off(sc);
+ mcf548x_fec_init(sc);
+
+ break;
+
+ default:
+ break;
+
+ }
+
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+
+ enet_stats(sc);
+
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+
+ error = EINVAL;
+
+ break;
+
+ }
+
+ return error;
+
+ }
+
+
+/*
+ * init the PHY and adapt FEC settings
+ */
+int mcf548x_fec_mode_adapt(struct ifnet *ifp)
+{
+ int result = 0;
+ struct mcf548x_enet_struct *sc = ifp->if_softc;
+ int media = IFM_MAKEWORD( 0, 0, 0, sc->phy_default);
+ int chan = sc->chan;
+
+ /*
+ * fetch media status
+ */
+ result = mcf548x_fec_ioctl(ifp,SIOCGIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+ /*
+ * status is unchanged? then do nothing
+ */
+ if (media == sc->media_state) {
+ return 0;
+ }
+ /*
+ * otherwise: for the first call, try to negotiate mode
+ */
+ if (sc->media_state == 0) {
+ /*
+ * set media status: set auto negotiation -> start auto-negotiation
+ */
+ media = IFM_MAKEWORD(0,IFM_AUTO,0,sc->phy_default);
+ result = mcf548x_fec_ioctl(ifp,SIOCSIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+ /*
+ * wait for auto-negotiation to terminate
+ */
+ do {
+ media = IFM_MAKEWORD(0,0,0,sc->phy_default);
+ result = mcf548x_fec_ioctl(ifp,SIOCGIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+ } while (IFM_NONE == IFM_SUBTYPE(media));
+ }
+
+ /*
+ * now set HW according to media results:
+ */
+
+ /*
+ * if we are half duplex then switch to half duplex
+ */
+ if (0 == (IFM_FDX & IFM_OPTIONS(media))) {
+ MCF548X_FEC_TCR(chan) &= ~MCF548X_FEC_TCR_FDEN;
+ }
+ else {
+ MCF548X_FEC_TCR(chan) |= MCF548X_FEC_TCR_FDEN;
+ }
+ /*
+ * store current media state for future compares
+ */
+ sc->media_state = media;
+
+ return 0;
+}
+
+/*
+ * periodically poll the PHY. if mode has changed,
+ * then adjust the FEC settings
+ */
+static void mcf548x_fec_watchdog( struct ifnet *ifp)
+{
+ mcf548x_fec_mode_adapt(ifp);
+ ifp->if_timer = FEC_WATCHDOG_TIMEOUT;
+}
+
+/*
+ * Attach the MCF548X fec driver to the system
+ */
+int rtems_mcf548x_fec_driver_attach(struct rtems_bsdnet_ifconfig *config)
+ {
+ struct mcf548x_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+
+ /*
+ * Parse driver name
+ */
+ if((unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES))
+ {
+
+ printf ("Bad FEC unit number.\n");
+ return 0;
+
+ }
+
+ sc = &enet_driver[unitNumber - 1];
+ sc->chan = unitNumber-1;
+ ifp = &sc->arpcom.ac_if;
+
+ if(ifp->if_softc != NULL)
+ {
+
+ printf ("Driver already in use.\n");
+ return 0;
+
+ }
+
+ /*
+ * Process options
+ */
+#if NVRAM_CONFIGURE == 1
+
+ /* Configure from NVRAM */
+ if(addr = nvram->ipaddr)
+ {
+
+ /* We have a non-zero entry, copy the value */
+ if(pAddr = malloc(INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT))
+ config->ip_address = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1);
+ else
+ rtems_panic("Can't allocate ip_address buffer!\n");
+
+ }
+
+ if(addr = nvram->netmask)
+ {
+
+ /* We have a non-zero entry, copy the value */
+ if (pAddr = malloc (INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT))
+ config->ip_netmask = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1);
+ else
+ rtems_panic("Can't allocate ip_netmask buffer!\n");
+
+ }
+
+ /* Ethernet address requires special handling -- it must be copied into
+ * the arpcom struct. The following if construct serves only to give the
+ * User Area NVRAM parameter the highest priority.
+ *
+ * If the ethernet address is specified in NVRAM, go ahead and copy it.
+ * (ETHER_ADDR_LEN = 6 bytes).
+ */
+ if(nvram->enaddr[0] || nvram->enaddr[1] || nvram->enaddr[2])
+ {
+
+ /* Anything in the first three bytes indicates a non-zero entry, copy value */
+ memcpy((void *)sc->arpcom.ac_enaddr, &nvram->enaddr, ETHER_ADDR_LEN);
+
+ }
+ else
+ if(config->hardware_address)
+ {
+
+ /* There is no entry in NVRAM, but there is in the ifconfig struct, so use it. */
+ memcpy((void *)sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+
+#else /* NVRAM_CONFIGURE != 1 */
+
+ if(config->hardware_address)
+ {
+
+ memcpy(sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ }
+
+#endif /* NVRAM_CONFIGURE != 1 */
+#ifdef HAS_UBOOT
+ if ((sc->arpcom.ac_enaddr[0] == 0) &&
+ (sc->arpcom.ac_enaddr[1] == 0) &&
+ (sc->arpcom.ac_enaddr[2] == 0)) {
+ memcpy(
+ (void *)sc->arpcom.ac_enaddr,
+ bsp_uboot_board_info.bi_enetaddr,
+ ETHER_ADDR_LEN
+ );
+ }
+#endif
+#ifdef HAS_DBUG
+ if ((sc->arpcom.ac_enaddr[0] == 0) &&
+ (sc->arpcom.ac_enaddr[1] == 0) &&
+ (sc->arpcom.ac_enaddr[2] == 0)) {
+ memcpy(
+ (void *)sc->arpcom.ac_enaddr,
+ DBUG_SETTINGS.macaddr,
+ ETHER_ADDR_LEN
+ );
+ }
+#endif
+ if ((sc->arpcom.ac_enaddr[0] == 0) &&
+ (sc->arpcom.ac_enaddr[1] == 0) &&
+ (sc->arpcom.ac_enaddr[2] == 0)) {
+ /* There is no ethernet address provided, so it could be read
+ * from the Ethernet protocol block of SCC1 in DPRAM.
+ */
+ rtems_panic("No Ethernet address specified!\n");
+ }
+ if(config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ if(config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+
+ if(config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * setup info about mdio interface
+ */
+ sc->mdio_info.mdio_r = mcf548x_eth_mii_read;
+ sc->mdio_info.mdio_w = mcf548x_eth_mii_write;
+ sc->mdio_info.has_gmii = 0; /* we do not support gigabit IF */
+
+ /*
+ * XXX: Although most hardware builders will assign the PHY addresses
+ * like this, this should be more configurable
+ */
+ sc->phy_default = unitNumber-1;
+ sc->phy_chan = 0; /* assume all MII accesses are via FEC0 */
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = mcf548x_fec_init;
+ ifp->if_ioctl = mcf548x_fec_ioctl;
+ ifp->if_start = mcf548x_fec_tx_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = mcf548x_fec_watchdog; /* XXX: timer is set in "init" */
+ ifp->if_flags = IFF_BROADCAST | IFF_MULTICAST;
+ /*ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;*/
+
+ if(ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+
+ ether_ifattach(ifp);
+
+ return 1;
+ }
+
+
+int rtems_mcf548x_fec_driver_attach_detach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ if (attaching) {
+ return rtems_mcf548x_fec_driver_attach(config);
+ }
+ else {
+ return 0;
+ }
+}
+
+
diff --git a/bsps/m68k/mcf5235/net/network.c b/bsps/m68k/mcf5235/net/network.c
new file mode 100644
index 0000000..f352b66
--- /dev/null
+++ b/bsps/m68k/mcf5235/net/network.c
@@ -0,0 +1,879 @@
+/*
+ * RTEMS/TCPIP driver for MCF5235 Fast Ethernet Controller
+ *
+ * TO DO: Check network stack code -- force longword alignment of all tx mbufs?
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <string.h>
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/ethernet.h>
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+#define FEC_INTC0_TX_VECTOR (64+23)
+#define FEC_INTC0_RX_VECTOR (64+27)
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses three or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 20
+#define TX_BD_PER_BUF 3
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define TX_INTERRUPT_EVENT RTEMS_EVENT_1
+#define RX_INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+ #error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+typedef struct mcf5235BufferDescriptor_ {
+ volatile uint16_t status;
+ uint16_t length;
+ volatile void *buffer;
+} mcf5235BufferDescriptor_t;
+
+/*
+ * Per-device data
+ */
+struct mcf5235_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ mcf5235BufferDescriptor_t *rxBdBase;
+ mcf5235BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long txInterrupts;
+ unsigned long txRawWait;
+ unsigned long txRealign;
+};
+static struct mcf5235_enet_struct enet_driver[NIFACES];
+
+static rtems_isr
+mcf5235_fec_rx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_RXF;
+ MCF5235_FEC_EIMR &= ~MCF5235_FEC_EIMR_RXF;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].rxDaemonTid, RX_INTERRUPT_EVENT);
+}
+
+static rtems_isr
+mcf5235_fec_tx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_TXF;
+ MCF5235_FEC_EIMR &= ~MCF5235_FEC_EIMR_TXF;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].txDaemonTid, TX_INTERRUPT_EVENT);
+}
+
+/*
+ * Allocate buffer descriptors from (non-cached) on-chip static RAM
+ * Ensure 128-bit (16-byte) alignment
+ */
+extern char __SRAMBASE[];
+
+static mcf5235BufferDescriptor_t *
+mcf5235_bd_allocate(unsigned int count)
+{
+ static mcf5235BufferDescriptor_t *bdp = (mcf5235BufferDescriptor_t *)__SRAMBASE;
+ mcf5235BufferDescriptor_t *p = bdp;
+
+ bdp += count;
+ if ((int)bdp & 0xF)
+ bdp = (mcf5235BufferDescriptor_t *)((char *)bdp + (16 - ((int)bdp & 0xF)));
+ return p;
+}
+
+#if UNUSED
+/*
+ * Read MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static int
+getMII(int phyNumber, int regNumber)
+{
+ MCF5235_FEC_MMFR = (0x1 << 30) |
+ (0x2 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16);
+ while ((MCF5235_FEC_EIR & MCF5235_FEC_EIR_MII) == 0);
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_MII;
+ return MCF5235_FEC_MMFR & 0xFFFF;
+}
+#endif
+
+/*
+ * Write MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static void
+setMII(int phyNumber, int regNumber, int value)
+{
+ MCF5235_FEC_MMFR = (0x1 << 30) |
+ (0x1 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16) |
+ (value & 0xFFFF);
+ while ((MCF5235_FEC_EIR & MCF5235_FEC_EIR_MII) == 0);
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_MII;
+}
+
+static void
+mcf5235_fec_initialize_hardware(struct mcf5235_enet_struct *sc)
+{
+ int i;
+ const unsigned char *hwaddr = 0;
+ rtems_status_code status;
+ rtems_isr_entry old_handler;
+ uint32_t clock_speed = get_CPU_clock_speed();
+
+ /*
+ * Issue reset to FEC
+ */
+ MCF5235_FEC_ECR = MCF5235_FEC_ECR_RESET;
+ rtems_task_wake_after(1);
+ MCF5235_FEC_ECR = 0;
+
+ /*
+ * Configuration of I/O ports is done outside of this function
+ */
+#if 0
+ imm->gpio.pbcnt |= MCF5235_GPIO_PBCNT_SET_FEC; /* Set up port b FEC pins */
+#endif
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+ MCF5235_FEC_PALR = (hwaddr[0] << 24) | (hwaddr[1] << 16) |
+ (hwaddr[2] << 8) | (hwaddr[3] << 0);
+ MCF5235_FEC_PAUR = (hwaddr[4] << 24) | (hwaddr[5] << 16);
+
+
+ /*
+ * Clear the hash table
+ */
+ MCF5235_FEC_GAUR = 0;
+ MCF5235_FEC_GALR = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ MCF5235_FEC_EMRBR = 1520; /* Standard Ethernet */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc(sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc(sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = mcf5235_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = mcf5235_bd_allocate(sc->txBdCount);
+ MCF5235_FEC_ERDSR = (int)sc->rxBdBase;
+ MCF5235_FEC_ETDSR = (int)sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous
+ * MII mode
+ * Full duplex
+ * No loopback
+ */
+ MCF5235_FEC_RCR = MCF5235_FEC_RCR_MAX_FL(MAX_MTU_SIZE) |
+ MCF5235_FEC_RCR_MII_MODE;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full duplex
+ * No heartbeat
+ */
+ MCF5235_FEC_TCR = MCF5235_FEC_TCR_FDEN;
+
+ /*
+ * Initialize statistic counters
+ */
+ MCF5235_FEC_MIBC = MCF5235_FEC_MIBC_MIB_DISABLE;
+ {
+ vuint32 *vuip = &MCF5235_FEC_RMON_T_DROP;
+ while (vuip <= &MCF5235_FEC_IEEE_R_OCTETS_OK)
+ *vuip++ = 0;
+ }
+ MCF5235_FEC_MIBC = 0;
+
+ /*
+ * Set MII speed to <= 2.5 MHz
+ */
+ i = (clock_speed + 5000000 - 1) / 5000000;
+ MCF5235_FEC_MSCR = MCF5235_FEC_MSCR_MII_SPEED(i);
+
+ /*
+ * Set PHYS to 100 Mb/s, full duplex
+ */
+ setMII(1, 0, 0x2100);
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ sc->txBdBase[i].status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Set up interrupts
+ */
+ status = rtems_interrupt_catch( mcf5235_fec_tx_interrupt_handler, FEC_INTC0_TX_VECTOR, &old_handler );
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5235 FEC TX interrupt handler: %s\n",
+ rtems_status_text(status));
+ status = rtems_interrupt_catch(mcf5235_fec_rx_interrupt_handler, FEC_INTC0_RX_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5235 FEC RX interrupt handler: %s\n",
+ rtems_status_text(status));
+ MCF5235_INTC0_ICR23 = MCF5235_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5235_INTC_ICR_IP(FEC_IRQ_TX_PRIORITY);
+ MCF5235_INTC0_IMRL &= ~(MCF5235_INTC0_IMRL_INT23 | MCF5235_INTC0_IMRL_MASKALL);
+ MCF5235_INTC0_ICR27 = MCF5235_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5235_INTC_ICR_IP(FEC_IRQ_RX_PRIORITY);
+ MCF5235_INTC0_IMRL &= ~(MCF5235_INTC0_IMRL_INT27 | MCF5235_INTC0_IMRL_MASKALL);
+}
+
+/*
+ * Get the MAC address from the hardware.
+ */
+static void
+fec_get_mac_address(volatile struct mcf5235_enet_struct *sc, unsigned char* hwaddr)
+{
+ unsigned long addr;
+
+ addr = MCF5235_FEC_PALR;
+
+ hwaddr[0] = (addr >> 24) & 0xff;
+ hwaddr[1] = (addr >> 16) & 0xff;
+ hwaddr[2] = (addr >> 8) & 0xff;
+ hwaddr[3] = (addr >> 0) & 0xff;
+
+ addr = MCF5235_FEC_PAUR;
+
+ hwaddr[4] = (addr >> 24) & 0xff;
+ hwaddr[5] = (addr >> 16) & 0xff;
+}
+
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ */
+static void
+fec_retire_tx_bd(volatile struct mcf5235_enet_struct *sc )
+{
+ struct mbuf *m, *n;
+
+ while ((sc->txBdActiveCount != 0)
+ && ((sc->txBdBase[sc->txBdTail].status & MCF5235_FEC_TxBD_R) == 0)) {
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE(m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ sc->txBdActiveCount--;
+ }
+}
+
+static void
+fec_rxDaemon (void *arg)
+{
+ volatile struct mcf5235_enet_struct *sc = (volatile struct mcf5235_enet_struct *)arg;
+ struct ifnet *ifp = (struct ifnet* )&sc->arpcom.ac_if;
+ struct mbuf *m;
+ volatile uint16_t status;
+ volatile mcf5235BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ rxBd->status = MCF5235_FEC_RxBD_E;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= MCF5235_FEC_RxBD_W;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ /* Indicate we have some ready buffers available */
+ MCF5235_FEC_RDAR = MCF5235_FEC_RDAR_R_DES_ACTIVE;
+
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & MCF5235_FEC_RxBD_E) {
+ /*
+ * Clear old events.
+ */
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_RXF;
+
+ /*
+ * Wait for packet to arrive.
+ * Check the buffer descriptor before waiting for the event.
+ * This catches the case when a packet arrives between the
+ * `if' above, and the clearing of the RXF bit in the EIR.
+ */
+ while ((status = rxBd->status) & MCF5235_FEC_RxBD_E) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5235_FEC_EIMR |= MCF5235_FEC_EIMR_RXF;
+ rtems_interrupt_enable(level);
+ rtems_bsdnet_event_receive (RX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & MCF5235_FEC_RxBD_L) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+ int len = rxBd->length - sizeof(uint32_t);
+
+ /*
+ * Invalidate the cache and push the packet up.
+ * The cache is so small that it's more efficient to just
+ * invalidate the whole thing unless the packet is very small.
+ */
+ m = sc->rxMbuf[rxBdIndex];
+ if (len < 128)
+ rtems_cache_invalidate_multiple_data_lines(m->m_data, len);
+ else
+ rtems_cache_invalidate_entire_data();
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+ eh = mtod(m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input(ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & MCF5235_FEC_RxBD_W) | MCF5235_FEC_RxBD_E;
+ MCF5235_FEC_RDAR = MCF5235_FEC_RDAR_R_DES_ACTIVE;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void
+fec_sendpacket(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mcf5235_enet_struct *sc = ifp->if_softc;
+ volatile mcf5235BufferDescriptor_t *firstTxBd, *txBd;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ fec_retire_tx_bd(sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ firstTxBd = sc->txBdBase + sc->txBdHead;
+
+ for (;;) {
+ /*
+ * Wait for buffer descriptor to become available
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events.
+ */
+ MCF5235_FEC_EIR = MCF5235_FEC_EIR_TXF;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Check for buffer descriptors before waiting for the event.
+ * This catches the case when a buffer became available between
+ * the `if' above, and the clearing of the TXF bit in the EIR.
+ */
+ fec_retire_tx_bd(sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5235_FEC_EIMR |= MCF5235_FEC_EIMR_TXF;
+ rtems_interrupt_enable(level);
+ sc->txRawWait++;
+ rtems_bsdnet_event_receive(TX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ fec_retire_tx_bd(sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag on the first fragment
+ * until the whole packet has been readied.
+ */
+ status = nAdded ? MCF5235_FEC_TxBD_R : 0;
+
+ /*
+ * The IP fragmentation routine in ip_output
+ * can produce fragments with zero length.
+ */
+ txBd = sc->txBdBase + sc->txBdHead;
+ if (m->m_len) {
+ char *p = mtod(m, char *);
+ /*
+ * Stupid FEC can't handle misaligned data!
+ * Given the way that mbuf's are layed out it should be
+ * safe to shuffle the data down like this.....
+ * Perhaps this code could be improved with a "Duff's Device".
+ */
+ if ((int)p & 0x3) {
+ int l = m->m_len;
+ char *dest = p - ((int)p & 0x3);
+ uint16_t *o = (uint16_t *)dest, *i = (uint16_t *)p;
+ while (l > 0) {
+ *o++ = *i++;
+ l -= sizeof(uint16_t);
+ }
+ p = dest;
+ sc->txRealign++;
+ }
+ txBd->buffer = p;
+ txBd->length = m->m_len;
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= MCF5235_FEC_TxBD_W;
+ sc->txBdHead = 0;
+ }
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE(m, n);
+ m = n;
+ }
+ if (m == NULL) {
+ if (nAdded) {
+ txBd->status = status | MCF5235_FEC_TxBD_R
+ | MCF5235_FEC_TxBD_L
+ | MCF5235_FEC_TxBD_TC;
+ if (nAdded > 1)
+ firstTxBd->status |= MCF5235_FEC_TxBD_R;
+ MCF5235_FEC_TDAR = MCF5235_FEC_TDAR_X_DES_ACTIVE;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ }
+}
+
+void
+fec_txDaemon(void *arg)
+{
+ struct mcf5235_enet_struct *sc = (struct mcf5235_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ fec_sendpacket(ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+mcf5235_enet_start(struct ifnet *ifp)
+{
+ struct mcf5235_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void
+fec_init(void *arg)
+{
+ struct mcf5235_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+ /*
+ * Set up hardware
+ */
+ mcf5235_fec_initialize_hardware(sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc("FECtx", 4096, fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc("FECrx", 4096, fec_rxDaemon, sc);
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ MCF5235_FEC_RCR |= MCF5235_FEC_RCR_PROM;
+ else
+ MCF5235_FEC_RCR &= ~MCF5235_FEC_RCR_PROM;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ MCF5235_FEC_ECR = MCF5235_FEC_ECR_ETHER_EN;
+}
+
+
+static void
+fec_stop(struct mcf5235_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ MCF5235_FEC_ECR = 0x0;
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+enet_stats(struct mcf5235_enet_struct *sc)
+{
+ printf(" Rx Interrupts:%-10lu", sc->rxInterrupts);
+ printf("Rx Packet Count:%-10lu", MCF5235_FEC_RMON_R_PACKETS);
+ printf(" Rx Broadcast:%-10lu\n", MCF5235_FEC_RMON_R_BC_PKT);
+ printf(" Rx Multicast:%-10lu", MCF5235_FEC_RMON_R_MC_PKT);
+ printf("CRC/Align error:%-10lu", MCF5235_FEC_RMON_R_CRC_ALIGN);
+ printf(" Rx Undersize:%-10lu\n", MCF5235_FEC_RMON_R_UNDERSIZE);
+ printf(" Rx Oversize:%-10lu", MCF5235_FEC_RMON_R_OVERSIZE);
+ printf(" Rx Fragment:%-10lu", MCF5235_FEC_RMON_R_FRAG);
+ printf(" Rx Jabber:%-10lu\n", MCF5235_FEC_RMON_R_JAB);
+ printf(" Rx 64:%-10lu", MCF5235_FEC_RMON_R_P64);
+ printf(" Rx 65-127:%-10lu", MCF5235_FEC_RMON_R_P65T0127);
+ printf(" Rx 128-255:%-10lu\n", MCF5235_FEC_RMON_R_P128TO255);
+ printf(" Rx 256-511:%-10lu", MCF5235_FEC_RMON_R_P256TO511);
+ printf(" Rx 511-1023:%-10lu", MCF5235_FEC_RMON_R_P512TO1023);
+ printf(" Rx 1024-2047:%-10lu\n", MCF5235_FEC_RMON_R_P1024TO2047);
+ printf(" Rx >=2048:%-10lu", MCF5235_FEC_RMON_R_GTE2048);
+ printf(" Rx Octets:%-10lu", MCF5235_FEC_RMON_R_OCTETS);
+ printf(" Rx Dropped:%-10lu\n", MCF5235_FEC_IEEE_R_DROP);
+ printf(" Rx frame OK:%-10lu", MCF5235_FEC_IEEE_R_FRAME_OK);
+ printf(" Rx CRC error:%-10lu", MCF5235_FEC_IEEE_R_CRC);
+ printf(" Rx Align error:%-10lu\n", MCF5235_FEC_IEEE_R_ALIGN);
+ printf(" FIFO Overflow:%-10lu", MCF5235_FEC_IEEE_R_MACERR);
+ printf("Rx Pause Frames:%-10lu", MCF5235_FEC_IEEE_R_FDXFC);
+ printf(" Rx Octets OK:%-10lu\n", MCF5235_FEC_IEEE_R_OCTETS_OK);
+ printf(" Tx Interrupts:%-10lu", sc->txInterrupts);
+ printf("Tx Output Waits:%-10lu", sc->txRawWait);
+ printf("Tx Realignments:%-10lu\n", sc->txRealign);
+ printf(" Tx Unaccounted:%-10lu", MCF5235_FEC_RMON_T_DROP);
+ printf("Tx Packet Count:%-10lu", MCF5235_FEC_RMON_T_PACKETS);
+ printf(" Tx Broadcast:%-10lu\n", MCF5235_FEC_RMON_T_BC_PKT);
+ printf(" Tx Multicast:%-10lu", MCF5235_FEC_RMON_T_MC_PKT);
+ printf("CRC/Align error:%-10lu", MCF5235_FEC_RMON_T_CRC_ALIGN);
+ printf(" Tx Undersize:%-10lu\n", MCF5235_FEC_RMON_T_UNDERSIZE);
+ printf(" Tx Oversize:%-10lu", MCF5235_FEC_RMON_T_OVERSIZE);
+ printf(" Tx Fragment:%-10lu", MCF5235_FEC_RMON_T_FRAG);
+ printf(" Tx Jabber:%-10lu\n", MCF5235_FEC_RMON_T_JAB);
+ printf(" Tx Collisions:%-10lu", MCF5235_FEC_RMON_T_COL);
+ printf(" Tx 64:%-10lu", MCF5235_FEC_RMON_T_P64);
+ printf(" Tx 65-127:%-10lu\n", MCF5235_FEC_RMON_T_P65TO127);
+ printf(" Tx 128-255:%-10lu", MCF5235_FEC_RMON_T_P128TO255);
+ printf(" Tx 256-511:%-10lu", MCF5235_FEC_RMON_T_P256TO511);
+ printf(" Tx 511-1023:%-10lu\n", MCF5235_FEC_RMON_T_P512TO1023);
+ printf(" Tx 1024-2047:%-10lu", MCF5235_FEC_RMON_T_P1024TO2047);
+ printf(" Tx >=2048:%-10lu", MCF5235_FEC_RMON_T_P_GTE2048);
+ printf(" Tx Octets:%-10lu\n", MCF5235_FEC_RMON_T_OCTETS);
+ printf(" Tx Dropped:%-10lu", MCF5235_FEC_IEEE_T_DROP);
+ printf(" Tx Frame OK:%-10lu", MCF5235_FEC_IEEE_T_FRAME_OK);
+ printf(" Tx 1 Collision:%-10lu\n", MCF5235_FEC_IEEE_T_1COL);
+ printf("Tx >1 Collision:%-10lu", MCF5235_FEC_IEEE_T_MCOL);
+ printf(" Tx Deferred:%-10lu", MCF5235_FEC_IEEE_T_DEF);
+ printf(" Late Collision:%-10lu\n", MCF5235_FEC_IEEE_T_LCOL);
+ printf(" Excessive Coll:%-10lu", MCF5235_FEC_IEEE_T_EXCOL);
+ printf(" FIFO Underrun:%-10lu", MCF5235_FEC_IEEE_T_MACERR);
+ printf(" Carrier Error:%-10lu\n", MCF5235_FEC_IEEE_T_CSERR);
+ printf(" Tx SQE Error:%-10lu", MCF5235_FEC_IEEE_T_SQE);
+ printf("Tx Pause Frames:%-10lu", MCF5235_FEC_IEEE_T_FDXFC);
+ printf(" Tx Octets OK:%-10lu\n", MCF5235_FEC_IEEE_T_OCTETS_OK);
+}
+
+static int
+fec_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct mcf5235_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ fec_stop(sc);
+ break;
+
+ case IFF_UP:
+ fec_init(sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ fec_stop(sc);
+ fec_init(sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats(sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+int
+rtems_fec_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching )
+{
+ struct mcf5235_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ unsigned char *hwaddr;
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber < 0) || (unitNumber >= NIFACES)) {
+ printf("mcf5235: bad FEC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf("mcf5235: driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address)
+ memcpy(sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ else
+ fec_get_mac_address(sc, sc->arpcom.ac_enaddr);
+
+ hwaddr = config->hardware_address;
+ printf("%s%d: mac: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ unitName, unitNumber,
+ hwaddr[0], hwaddr[1], hwaddr[2],
+ hwaddr[3], hwaddr[4], hwaddr[5]);
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = fec_init;
+ ifp->if_ioctl = fec_ioctl;
+ ifp->if_start = mcf5235_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ return 1;
+};
+
diff --git a/bsps/m68k/mcf5329/net/network.c b/bsps/m68k/mcf5329/net/network.c
new file mode 100644
index 0000000..21032a6
--- /dev/null
+++ b/bsps/m68k/mcf5329/net/network.c
@@ -0,0 +1,857 @@
+/*
+ * RTEMS/TCPIP driver for MCF5329 Fast Ethernet Controller
+ *
+ * TO DO: Check network stack code -- force longword alignment of all tx mbufs?
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <string.h>
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/ethernet.h>
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+#define FEC_INTC0_TX_VECTOR (64+36)
+#define FEC_INTC0_RX_VECTOR (64+40)
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses three or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 20
+#define TX_BD_PER_BUF 3
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define TX_INTERRUPT_EVENT RTEMS_EVENT_1
+#define RX_INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+typedef struct mcf5329BufferDescriptor_
+{
+ volatile uint16_t status;
+ uint16_t length;
+ volatile void *buffer;
+} mcf5329BufferDescriptor_t;
+
+/*
+ * Per-device data
+ */
+struct mcf5329_enet_struct
+{
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ mcf5329BufferDescriptor_t *rxBdBase;
+ mcf5329BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long txInterrupts;
+ unsigned long txRawWait;
+ unsigned long txRealign;
+};
+static struct mcf5329_enet_struct enet_driver[NIFACES];
+
+static rtems_isr mcf5329_fec_rx_interrupt_handler(rtems_vector_number v)
+{
+ MCF_FEC_EIR = MCF_FEC_EIR_RXF;
+ MCF_FEC_EIMR &= ~MCF_FEC_EIMR_RXF;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].rxDaemonTid, RX_INTERRUPT_EVENT);
+}
+
+static rtems_isr mcf5329_fec_tx_interrupt_handler(rtems_vector_number v)
+{
+ MCF_FEC_EIR = MCF_FEC_EIR_TXF;
+ MCF_FEC_EIMR &= ~MCF_FEC_EIMR_TXF;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].txDaemonTid, TX_INTERRUPT_EVENT);
+}
+
+extern char _CoreSRamBase[];
+
+/*
+ * Allocate buffer descriptors from (non-cached) on-chip static RAM
+ * Ensure 128-bit (16-byte) alignment
+ */
+static mcf5329BufferDescriptor_t *mcf5329_bd_allocate(unsigned int count)
+{
+ static mcf5329BufferDescriptor_t *bdp =
+ (mcf5329BufferDescriptor_t *) _CoreSRamBase;
+ mcf5329BufferDescriptor_t *p = bdp;
+
+ bdp += count;
+ if ((int) bdp & 0xF)
+ bdp =
+ (mcf5329BufferDescriptor_t *) ((char *) bdp + (16 - ((int) bdp & 0xF)));
+ return p;
+}
+
+#if UNUSED
+
+/*
+ * Read MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static int getMII(int phyNumber, int regNumber)
+{
+ MCF_FEC_MMFR = (0x1 << 30) |
+ (0x2 << 28) | (phyNumber << 23) | (regNumber << 18) | (0x2 << 16);
+ while ((MCF_FEC_EIR & MCF_FEC_EIR_MII) == 0) ;
+ MCF_FEC_EIR = MCF_FEC_EIR_MII;
+ return MCF_FEC_MMFR & 0xFFFF;
+}
+#endif
+
+/*
+ * Write MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static void setMII(int phyNumber, int regNumber, int value)
+{
+ MCF_FEC_MMFR = (0x1 << 30) |
+ (0x1 << 28) |
+ (phyNumber << 23) | (regNumber << 18) | (0x2 << 16) | (value & 0xFFFF);
+ while ((MCF_FEC_EIR & MCF_FEC_EIR_MII) == 0) ;
+ MCF_FEC_EIR = MCF_FEC_EIR_MII;
+}
+
+static void mcf5329_fec_initialize_hardware(struct mcf5329_enet_struct *sc)
+{
+ int i;
+ const unsigned char *hwaddr = 0;
+ rtems_status_code status;
+ rtems_isr_entry old_handler;
+ uint32_t clock_speed = bsp_get_BUS_clock_speed();
+
+ /*
+ * Issue reset to FEC
+ */
+ MCF_FEC_ECR = MCF_FEC_ECR_RESET;
+ rtems_task_wake_after(1);
+ MCF_FEC_ECR = 0;
+
+ /*
+ * Configuration of I/O ports is done outside of this function
+ */
+#if 0
+ imm->gpio.pbcnt |= MCF_GPIO_PBCNT_SET_FEC; /* Set up port b FEC pins */
+#endif
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+ MCF_FEC_PALR = (hwaddr[0] << 24) | (hwaddr[1] << 16) |
+ (hwaddr[2] << 8) | (hwaddr[3] << 0);
+ MCF_FEC_PAUR = (hwaddr[4] << 24) | (hwaddr[5] << 16);
+
+ /*
+ * Clear the hash table
+ */
+ MCF_FEC_GAUR = 0;
+ MCF_FEC_GALR = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ MCF_FEC_EMRBR = 1520; /* Standard Ethernet */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc(sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc(sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = mcf5329_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = mcf5329_bd_allocate(sc->txBdCount);
+ MCF_FEC_ERDSR = (int) sc->rxBdBase;
+ MCF_FEC_ETDSR = (int) sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous
+ * MII mode
+ * Full duplex
+ * No loopback
+ */
+ MCF_FEC_RCR = MCF_FEC_RCR_MAX_FL(MAX_MTU_SIZE) | MCF_FEC_RCR_MII_MODE;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full duplex
+ * No heartbeat
+ */
+ MCF_FEC_TCR = MCF_FEC_TCR_FDEN;
+
+ /*
+ * Initialize statistic counters
+ */
+ MCF_FEC_MIBC = MCF_FEC_MIBC_MIB_DISABLE;
+ {
+ vuint32 *vuip = &MCF_FEC_RMON_T_DROP;
+
+ while (vuip <= &MCF_FEC_IEEE_R_OCTETS_OK)
+ *vuip++ = 0;
+ }
+ MCF_FEC_MIBC = 0;
+
+ /*
+ * Set MII speed to <= 2.5 MHz
+ */
+ i = (clock_speed + 5000000 - 1) / 5000000;
+ MCF_FEC_MSCR = MCF_FEC_MSCR_MII_SPEED(i);
+
+ /*
+ * Set PHYS to 100 Mb/s, full duplex
+ */
+ setMII(1, 0, 0x2100);
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0; i < sc->rxBdCount; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0; i < sc->txBdCount; i++) {
+ sc->txBdBase[i].status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Set up interrupts
+ */
+ status =
+ rtems_interrupt_catch(mcf5329_fec_tx_interrupt_handler,
+ FEC_INTC0_TX_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic("Can't attach MCF FEC TX interrupt handler: %s\n",
+ rtems_status_text(status));
+ status =
+ rtems_interrupt_catch(mcf5329_fec_rx_interrupt_handler,
+ FEC_INTC0_RX_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic("Can't attach MCF FEC RX interrupt handler: %s\n",
+ rtems_status_text(status));
+ MCF_INTC0_ICR36 = MCF_INTC_ICR_IL(FEC_IRQ_LEVEL);
+ MCF_INTC0_IMRH &= ~(MCF_INTC_IMRH_INT_MASK36);
+ MCF_INTC0_ICR40 = MCF_INTC_ICR_IL(FEC_IRQ_LEVEL);
+ MCF_INTC0_IMRH &= ~(MCF_INTC_IMRH_INT_MASK40);
+}
+
+/*
+ * Get the MAC address from the hardware.
+ */
+static void
+fec_get_mac_address(volatile struct mcf5329_enet_struct *sc,
+ unsigned char *hwaddr)
+{
+ unsigned long addr;
+
+ addr = MCF_FEC_PALR;
+
+ hwaddr[0] = (addr >> 24) & 0xff;
+ hwaddr[1] = (addr >> 16) & 0xff;
+ hwaddr[2] = (addr >> 8) & 0xff;
+ hwaddr[3] = (addr >> 0) & 0xff;
+
+ addr = MCF_FEC_PAUR;
+
+ hwaddr[4] = (addr >> 24) & 0xff;
+ hwaddr[5] = (addr >> 16) & 0xff;
+}
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ */
+static void fec_retire_tx_bd(volatile struct mcf5329_enet_struct *sc)
+{
+ struct mbuf *m, *n;
+
+ while ((sc->txBdActiveCount != 0)
+ && ((sc->txBdBase[sc->txBdTail].status & MCF_FEC_TxBD_R) == 0)) {
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE(m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ sc->txBdActiveCount--;
+ }
+}
+
+static void fec_rxDaemon(void *arg)
+{
+ volatile struct mcf5329_enet_struct *sc =
+ (volatile struct mcf5329_enet_struct *) arg;
+ struct ifnet *ifp = (struct ifnet *) &sc->arpcom.ac_if;
+ struct mbuf *m;
+ volatile uint16_t status;
+ volatile mcf5329BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+
+ rxBd->status = MCF_FEC_RxBD_E;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= MCF_FEC_RxBD_W;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ /* Indicate we have some ready buffers available */
+ MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
+
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & MCF_FEC_RxBD_E) {
+ /*
+ * Clear old events.
+ */
+ MCF_FEC_EIR = MCF_FEC_EIR_RXF;
+
+ /*
+ * Wait for packet to arrive.
+ * Check the buffer descriptor before waiting for the event.
+ * This catches the case when a packet arrives between the
+ * `if' above, and the clearing of the RXF bit in the EIR.
+ */
+ while ((status = rxBd->status) & MCF_FEC_RxBD_E) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF_FEC_EIMR |= MCF_FEC_EIMR_RXF;
+ rtems_interrupt_enable(level);
+ rtems_bsdnet_event_receive(RX_INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT, &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & MCF_FEC_RxBD_L) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+ int len = rxBd->length - sizeof(uint32_t);
+
+ m = sc->rxMbuf[rxBdIndex];
+
+ rtems_cache_invalidate_multiple_data_lines(m->m_data, len);
+
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+ eh = mtod(m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input(ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & MCF_FEC_RxBD_W) | MCF_FEC_RxBD_E;
+ MCF_FEC_RDAR = MCF_FEC_RDAR_R_DES_ACTIVE;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void fec_sendpacket(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mcf5329_enet_struct *sc = ifp->if_softc;
+ volatile mcf5329BufferDescriptor_t *firstTxBd, *txBd;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ fec_retire_tx_bd(sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ firstTxBd = sc->txBdBase + sc->txBdHead;
+
+ for (;;) {
+ /*
+ * Wait for buffer descriptor to become available
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events.
+ */
+ MCF_FEC_EIR = MCF_FEC_EIR_TXF;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Check for buffer descriptors before waiting for the event.
+ * This catches the case when a buffer became available between
+ * the `if' above, and the clearing of the TXF bit in the EIR.
+ */
+ fec_retire_tx_bd(sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF_FEC_EIMR |= MCF_FEC_EIMR_TXF;
+ rtems_interrupt_enable(level);
+ sc->txRawWait++;
+ rtems_bsdnet_event_receive(TX_INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT, &events);
+ fec_retire_tx_bd(sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag on the first fragment
+ * until the whole packet has been readied.
+ */
+ status = nAdded ? MCF_FEC_TxBD_R : 0;
+
+ /*
+ * The IP fragmentation routine in ip_output
+ * can produce fragments with zero length.
+ */
+ txBd = sc->txBdBase + sc->txBdHead;
+ if (m->m_len) {
+ char *p = mtod(m, char *);
+
+ /*
+ * Stupid FEC can't handle misaligned data!
+ * Given the way that mbuf's are layed out it should be
+ * safe to shuffle the data down like this.....
+ * Perhaps this code could be improved with a "Duff's Device".
+ */
+ if ((int) p & 0x3) {
+ int l = m->m_len;
+ char *dest = p - ((int) p & 0x3);
+ uint16_t *o = (uint16_t *) dest, *i = (uint16_t *) p;
+
+ while (l > 0) {
+ *o++ = *i++;
+ l -= sizeof(uint16_t);
+ }
+ p = dest;
+ sc->txRealign++;
+ }
+
+ txBd->buffer = p;
+ txBd->length = m->m_len;
+
+ rtems_cache_flush_multiple_data_lines(txBd->buffer, txBd->length);
+
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= MCF_FEC_TxBD_W;
+ sc->txBdHead = 0;
+ }
+ m = m->m_next;
+ } else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+
+ MFREE(m, n);
+ m = n;
+ }
+ if (m == NULL) {
+ if (nAdded) {
+ txBd->status = status | MCF_FEC_TxBD_R
+ | MCF_FEC_TxBD_L | MCF_FEC_TxBD_TC;
+ if (nAdded > 1)
+ firstTxBd->status |= MCF_FEC_TxBD_R;
+ MCF_FEC_TDAR = MCF_FEC_TDAR_X_DES_ACTIVE;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ }
+}
+
+void fec_txDaemon(void *arg)
+{
+ struct mcf5329_enet_struct *sc = (struct mcf5329_enet_struct *) arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ fec_sendpacket(ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void mcf5329_enet_start(struct ifnet *ifp)
+{
+ struct mcf5329_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void fec_init(void *arg)
+{
+ struct mcf5329_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+ /*
+ * Set up hardware
+ */
+ mcf5329_fec_initialize_hardware(sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc("FECtx", 4096, fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc("FECrx", 4096, fec_rxDaemon, sc);
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ MCF_FEC_RCR |= MCF_FEC_RCR_PROM;
+ else
+ MCF_FEC_RCR &= ~MCF_FEC_RCR_PROM;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ MCF_FEC_ECR = MCF_FEC_ECR_ETHER_EN;
+}
+
+static void fec_stop(struct mcf5329_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ MCF_FEC_ECR = 0x0;
+}
+
+/*
+ * Show interface statistics
+ */
+static void enet_stats(struct mcf5329_enet_struct *sc)
+{
+ printf(" Rx Interrupts:%-10lu", sc->rxInterrupts);
+ printf("Rx Packet Count:%-10lu", MCF_FEC_RMON_R_PACKETS);
+ printf(" Rx Broadcast:%-10lu\n", MCF_FEC_RMON_R_BC_PKT);
+ printf(" Rx Multicast:%-10lu", MCF_FEC_RMON_R_MC_PKT);
+ printf("CRC/Align error:%-10lu", MCF_FEC_RMON_R_CRC_ALIGN);
+ printf(" Rx Undersize:%-10lu\n", MCF_FEC_RMON_R_UNDERSIZE);
+ printf(" Rx Oversize:%-10lu", MCF_FEC_RMON_R_OVERSIZE);
+ printf(" Rx Fragment:%-10lu", MCF_FEC_RMON_R_FRAG);
+ printf(" Rx Jabber:%-10lu\n", MCF_FEC_RMON_R_JAB);
+ printf(" Rx 64:%-10lu", MCF_FEC_RMON_R_P64);
+ printf(" Rx 65-127:%-10lu", MCF_FEC_RMON_R_P65TO127);
+ printf(" Rx 128-255:%-10lu\n", MCF_FEC_RMON_R_P128TO255);
+ printf(" Rx 256-511:%-10lu", MCF_FEC_RMON_R_P256TO511);
+ printf(" Rx 511-1023:%-10lu", MCF_FEC_RMON_R_512TO1023);
+ printf(" Rx 1024-2047:%-10lu\n", MCF_FEC_RMON_R_1024TO2047);
+ printf(" Rx >=2048:%-10lu", MCF_FEC_RMON_R_P_GTE2048);
+ printf(" Rx Octets:%-10lu", MCF_FEC_RMON_R_OCTETS);
+ printf(" Rx Dropped:%-10lu\n", MCF_FEC_IEEE_R_DROP);
+ printf(" Rx frame OK:%-10lu", MCF_FEC_IEEE_R_FRAME_OK);
+ printf(" Rx CRC error:%-10lu", MCF_FEC_IEEE_R_CRC);
+ printf(" Rx Align error:%-10lu\n", MCF_FEC_IEEE_R_ALIGN);
+ printf(" FIFO Overflow:%-10lu", MCF_FEC_IEEE_R_MACERR);
+ printf("Rx Pause Frames:%-10lu", MCF_FEC_IEEE_R_FDXFC);
+ printf(" Rx Octets OK:%-10lu\n", MCF_FEC_IEEE_R_OCTETS_OK);
+ printf(" Tx Interrupts:%-10lu", sc->txInterrupts);
+ printf("Tx Output Waits:%-10lu", sc->txRawWait);
+ printf("Tx Realignments:%-10lu\n", sc->txRealign);
+ printf(" Tx Unaccounted:%-10lu", MCF_FEC_RMON_T_DROP);
+ printf("Tx Packet Count:%-10lu", MCF_FEC_RMON_T_PACKETS);
+ printf(" Tx Broadcast:%-10lu\n", MCF_FEC_RMON_T_BC_PKT);
+ printf(" Tx Multicast:%-10lu", MCF_FEC_RMON_T_MC_PKT);
+ printf("CRC/Align error:%-10lu", MCF_FEC_RMON_T_CRC_ALIGN);
+ printf(" Tx Undersize:%-10lu\n", MCF_FEC_RMON_T_UNDERSIZE);
+ printf(" Tx Oversize:%-10lu", MCF_FEC_RMON_T_OVERSIZE);
+ printf(" Tx Fragment:%-10lu", MCF_FEC_RMON_T_FRAG);
+ printf(" Tx Jabber:%-10lu\n", MCF_FEC_RMON_T_JAB);
+ printf(" Tx Collisions:%-10lu", MCF_FEC_RMON_T_COL);
+ printf(" Tx 64:%-10lu", MCF_FEC_RMON_T_P64);
+ printf(" Tx 65-127:%-10lu\n", MCF_FEC_RMON_T_P65TO127);
+ printf(" Tx 128-255:%-10lu", MCF_FEC_RMON_T_P128TO255);
+ printf(" Tx 256-511:%-10lu", MCF_FEC_RMON_T_P256TO511);
+ printf(" Tx 511-1023:%-10lu\n", MCF_FEC_RMON_T_P512TO1023);
+ printf(" Tx 1024-2047:%-10lu", MCF_FEC_RMON_T_P1024TO2047);
+ printf(" Tx >=2048:%-10lu", MCF_FEC_RMON_T_P_GTE2048);
+ printf(" Tx Octets:%-10lu\n", MCF_FEC_RMON_T_OCTETS);
+ printf(" Tx Dropped:%-10lu", MCF_FEC_IEEE_T_DROP);
+ printf(" Tx Frame OK:%-10lu", MCF_FEC_IEEE_T_FRAME_OK);
+ printf(" Tx 1 Collision:%-10lu\n", MCF_FEC_IEEE_T_1COL);
+ printf("Tx >1 Collision:%-10lu", MCF_FEC_IEEE_T_MCOL);
+ printf(" Tx Deferred:%-10lu", MCF_FEC_IEEE_T_DEF);
+ printf(" Late Collision:%-10lu\n", MCF_FEC_IEEE_T_LCOL);
+ printf(" Excessive Coll:%-10lu", MCF_FEC_IEEE_T_EXCOL);
+ printf(" FIFO Underrun:%-10lu", MCF_FEC_IEEE_T_MACERR);
+ printf(" Carrier Error:%-10lu\n", MCF_FEC_IEEE_T_CSERR);
+ printf(" Tx SQE Error:%-10lu", MCF_FEC_IEEE_T_SQE);
+ printf("Tx Pause Frames:%-10lu", MCF_FEC_IEEE_T_FDXFC);
+ printf(" Tx Octets OK:%-10lu\n", MCF_FEC_IEEE_T_OCTETS_OK);
+}
+
+static int fec_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct mcf5329_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ fec_stop(sc);
+ break;
+
+ case IFF_UP:
+ fec_init(sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ fec_stop(sc);
+ fec_init(sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats(sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+int
+rtems_fec_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ struct mcf5329_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ unsigned char *hwaddr;
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber < 0) || (unitNumber >= NIFACES)) {
+ printf("mcf5329: bad FEC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf("mcf5329: driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address)
+ memcpy(sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ else
+ fec_get_mac_address(sc, sc->arpcom.ac_enaddr);
+
+ hwaddr = config->hardware_address;
+ printf("%s%d: mac: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ unitName, unitNumber,
+ hwaddr[0], hwaddr[1], hwaddr[2], hwaddr[3], hwaddr[4], hwaddr[5]);
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = fec_init;
+ ifp->if_ioctl = fec_ioctl;
+ ifp->if_start = mcf5329_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ return 1;
+};
diff --git a/bsps/m68k/mvme167/net/network.c b/bsps/m68k/mvme167/net/network.c
new file mode 100644
index 0000000..56d61dd
--- /dev/null
+++ b/bsps/m68k/mvme167/net/network.c
@@ -0,0 +1,3098 @@
+/* network.c: An 82596 ethernet driver for rtems-bsd.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+/*
+ * Selectively define to debug the network driver. If you define any of these
+ * you must run with polled console I/O.
+ */
+
+/*
+#define DBG_ADD_CMD
+#define DBG_WAIT
+#define DBG_SEND
+#define DBG_MEM
+#define DBG_SELFTEST_CMD
+#define DBG_DUMP_CMD
+#define DBG_RESET
+#define DBG_ATTACH
+#define DBG_START
+#define DBG_INIT
+#define DBG_STOP
+#define DBG_RX
+#define DBG_ISR
+#define DBG_IOCTL
+#define DBG_STAT
+#define DBG_PACKETS
+*/
+
+#define IGNORE_SPURIOUS_IRQ
+#define IGNORE_NO_RFA
+#define IGNORE_MULTIPLE_RF
+
+/*
+ * Default number of buffer descriptors and buffer sizes.
+ */
+#define RX_BUF_COUNT 15
+#define TX_BUF_COUNT 4
+#define TX_BD_PER_BUF 4
+
+#define RBUF_SIZE 1520
+
+#define UTI_596_ETH_MIN_SIZE 60
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS events
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+#define NIC_RESET_EVENT RTEMS_EVENT_3
+
+#include <bsp.h>
+#include <inttypes.h>
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+
+#include <rtems/error.h>
+#include <rtems/bspIo.h>
+#include <rtems/rtems_bsdnet.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/types.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include "uti596.h"
+
+/* If we are running interrupt driven I/O no debug output is printed */
+#if CD2401_IO_MODE == 0
+ #define printk(arglist) do { printk arglist; printk("\r"); } while (0);
+#else
+ #define printk(arglist)
+#endif
+
+#define UTI_596_ASSERT( condition, str ) if (!( condition ) ) { printk((str)) }
+
+/* Types of PORT commands */
+#define UTI596_RESET_PORT_FUNCTION 0
+#define UTI596_SELFTEST_PORT_FUNCTION 1
+#define UTI596_SCP_PORT_FUNCTION 2
+#define UTI596_DUMP_PORT_FUNCTION 3
+
+/* Types of waiting for commands */
+#define UTI596_NO_WAIT 0
+#define UTI596_WAIT_FOR_CU_ACCEPT 1
+#define UTI596_WAIT_FOR_INITIALIZATION 2
+#define UTI596_WAIT_FOR_STAT_C 3
+
+/* Device dependent data structure */
+static uti596_softc_ uti596_softc;
+
+/* Globals */
+int count_rx = 0;
+static int scbStatus;
+static rtems_status_code sc;
+static i596_cmd *pIsrCmd;
+static i596_rfd *pIsrRfd;
+
+/*
+ * Initial 596 configuration
+ */
+char uti596initSetup[] = {
+ 0x0E, /* Byte 0: length, prefetch off ( no RBD's ) */
+ 0xC8, /* Byte 1: fifo to 8, monitor off */
+ 0x40, /* Byte 2: don't save bad frames ( was save= 80, use intel's 40 )*/
+ 0x2E, /* Byte 3: No source address insertion, 8 byte preamble */
+ 0x00, /* Byte 4: priority and backoff defaults */
+ 0x60, /* Byte 5: interframe spacing */
+ 0x00, /* Byte 6: slot time LSB */
+ 0xf2, /* Byte 7: slot time and retries */
+ 0x0C, /* Byte 8: not promisc, enable bcast, tx no crs, crc inserted 32bit, 802.3 framing */
+ 0x08, /* Byte 9: collision detect */
+ 0x40, /* Byte 10: minimum frame length */
+ 0xfb, /* Byte 11: tried C8 same as byte 1 in bits 6-7, else ignored*/
+ 0x00, /* Byte 12: disable full duplex */
+ 0x3f /* Byte 13: no multi IA, backoff enabled */
+};
+
+/* Local Routines */
+
+static unsigned long word_swap ( unsigned long );
+static void * malloc_16byte_aligned ( void **, void ** adjusted_pointer, size_t );
+RTEMS_INLINE_ROUTINE void uti596_writePortFunction ( volatile void *, unsigned long );
+/* currently unused by RTEMS */
+#if 0
+RTEMS_INLINE_ROUTINE void uti596_portReset( void );
+static unsigned long uti596_portSelfTest( i596_selftest * );
+static int uti596_portDump ( i596_dump_result * );
+static void uti596_CU_dump ( i596_dump_result * );
+#endif
+static int uti596_wait ( uti596_softc_ *, uint8_t);
+static int uti596_issueCA ( uti596_softc_ *, uint8_t);
+static void uti596_addCmd ( i596_cmd * );
+static void uti596_addPolledCmd ( i596_cmd * );
+static int uti596_setScpAndScb ( uti596_softc_ * );
+static int uti596_diagnose ( void );
+static int uti596_configure ( uti596_softc_ * );
+static int uti596_IAsetup ( uti596_softc_ * );
+static int uti596_initTBD ( uti596_softc_ * );
+static int uti596_initRFA ( int );
+static void uti596_initMem ( uti596_softc_ * );
+static void uti596_initialize ( uti596_softc_ * );
+static void uti596_initialize_hardware ( uti596_softc_ * );
+static void uti596_reset_hardware ( uti596_softc_ *);
+static void uti596_reset ( void );
+static void uti596_clearListStatus ( i596_rfd * );
+static i596_rfd * uti596_dequeue ( i596_rfd ** );
+static void uti596_append ( i596_rfd ** , i596_rfd * );
+static void uti596_supplyFD ( i596_rfd * );
+static void send_packet ( struct ifnet *, struct mbuf * );
+
+/* Required RTEMS network driver functions and tasks (plus reset daemon) */
+
+static void uti596_start ( struct ifnet * );
+void uti596_init ( void * );
+void uti596_stop ( uti596_softc_ * );
+void uti596_txDaemon ( void * );
+void uti596_rxDaemon ( void * );
+void uti596_resetDaemon( void * );
+rtems_isr uti596_DynamicInterruptHandler ( rtems_vector_number );
+static int uti596_ioctl ( struct ifnet *, u_long, caddr_t );
+void uti596_stats ( uti596_softc_ * );
+
+#ifdef DBG_PACKETS
+static void dumpQ( void );
+static void show_buffers( void );
+static void show_queues( void );
+static void print_eth ( unsigned char * );
+static void print_hdr ( unsigned char * );
+static void print_pkt ( unsigned char * );
+static void print_echo ( unsigned char * );
+#endif
+
+/*
+ * word_swap
+ *
+ * Return a 32 bit value, swapping the upper and lower words first.
+ *
+ * Input parameters:
+ * val - 32 bit value to swap
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * Input value with upper and lower 16-bit words swapped
+ */
+static unsigned long word_swap(
+ unsigned long val
+)
+{
+ return (((val >> 16)&(0x0000ffff)) | ((val << 16)&(0xffff0000)));
+}
+
+/*
+ * malloc_16byte_aligned
+ *
+ * Allocate a block of a least nbytes aligned on a 16-byte boundary.
+ * Clients are responsible to store both the real address and the adjusted
+ * address. The real address must be used to free the block.
+ *
+ * Input parameters:
+ * real_pointer - pointer to a void * pointer in which to store the starting
+ * address of the block. Required for free.
+ * adjusted_pointer - pointer to a void * pointer in which to store the
+ * starting address of the block rounded up to the next
+ * 16 byte boundary.
+ * nbytes - number of bytes of storage requested
+ *
+ * Output parameters:
+ * real_pointer - starting address of the block.
+ * adjusted_pointer - starting address of the block rounded up to the next
+ * 16 byte boundary.
+ *
+ * Return value:
+ * starting address of the block rounded up to the next 16 byte boundary.
+ * NULL if no storage was allocated.
+ */
+static void * malloc_16byte_aligned(
+ void ** real_pointer,
+ void ** adjusted_pointer,
+ size_t nbytes
+)
+{
+ *real_pointer = malloc( nbytes + 0xF, 0, M_NOWAIT );
+ *adjusted_pointer = (void *)(((unsigned long)*real_pointer + 0xF ) & 0xFFFFFFF0 );
+ return *adjusted_pointer;
+}
+
+/*
+ * uti596_scp_alloc
+ *
+ * Allocate a new scp, possibly freeing a previously allocated one.
+ *
+ * Input parameters:
+ * sc - pointer to the global uti596_softc in which to store pointers
+ * to the newly allocated block.
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * Pointer to the newly allocated, 16-byte aligned scp.
+ */
+static i596_scp * uti596_scp_alloc(
+ uti596_softc_ * sc
+)
+{
+ if( sc->base_scp != NULL ) {
+ #ifdef DBG_MEM
+ printk(("uti596_scp_alloc: Already have an SCP at %p\n", sc->base_scp))
+ #endif
+ return sc->pScp;
+ }
+
+ /* allocate enough memory for the Scp block to be aligned on 16 byte boundary */
+ malloc_16byte_aligned( (void *)&(sc->base_scp), (void *)&(sc->pScp), sizeof( i596_scp ) );
+
+ #ifdef DBG_MEM
+ printk(("uti596_scp_alloc: Scp base address is %p\n", sc->base_scp))
+ printk(("uti596_scp_alloc: Scp aligned address is : %p\n",sc->pScp))
+ #endif
+
+ return sc->pScp;
+}
+
+/*
+ * uti596_writePortFunction
+ *
+ * Write the command into the PORT.
+ *
+ * Input parameters:
+ * addr - 16-byte aligned address to write into the PORT.
+ * cmd - 4-bit cmd to write into the PORT
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ *
+ * The Motorola manual swapped the high and low registers.
+ */
+RTEMS_INLINE_ROUTINE void uti596_writePortFunction(
+ volatile void * addr,
+ unsigned long cmd
+)
+{
+ i82596->port_lower = (unsigned short)(((unsigned long)addr & 0xFFF0) | cmd);
+ i82596->port_upper = (unsigned short)(((unsigned long)addr >> 16 ) & 0xFFFF);
+}
+
+/*
+ * uti596_portReset
+ *
+ * Issue a port Reset to the uti596
+ *
+ * Input parameters: NONE
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+RTEMS_INLINE_ROUTINE void uti596_portReset( void )
+{
+ uti596_writePortFunction( NULL, UTI596_RESET_PORT_FUNCTION );
+}
+
+/* currently unused by RTEMS */
+#if 0
+/*
+ * uti596_portSelfTest
+ *
+ * Perform a self-test. Wait for up to 1 second for the test to
+ * complete. Normally, the test should complete in a very short time,
+ * so busy waiting is not an issue.
+ *
+ * Input parameters:
+ * stp - pointer to a 16-byte aligned uti596_selftest structure.
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 32-bit result field if successful, -1 otherwise.
+ */
+static unsigned long uti596_portSelfTest(
+ i596_selftest * stp
+)
+{
+ rtems_interval ticks_per_second, start_ticks, end_ticks;
+
+ stp->results = 0xFFFFFFFF;
+ uti596_writePortFunction( stp, UTI596_SELFTEST_PORT_FUNCTION );
+
+ ticks_per_second = rtems_clock_get_ticks_per_second();
+
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ end_ticks = start_ticks + ticks_per_second;
+
+ do {
+ if( stp->results != 0xFFFFFFFF )
+ break;
+ else
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ } while (start_ticks <= end_ticks);
+
+ if (start_ticks > end_ticks ) {
+ #ifdef DBG_SELFTEST_CMD
+ printk(("uti596_selftest: Timed out\n" ))
+ #endif
+ return -1;
+ }
+ else {
+ #ifdef DBG_SELFTEST_CMD
+ printk(("uti596_selftest: Succeeded with signature = 0x%08x, result = 0x%08x\n",
+ stp->signature,
+ stp->results))
+ #endif
+ return stp->results;
+ }
+}
+#endif
+
+/* currently unused by RTEMS */
+#if 0
+/*
+ * uti596_portDump
+ *
+ * Perform a dump Wait for up to 1 second for the test to
+ * complete. Normally, the test should complete in a very short time,
+ * so busy waiting is not an issue.
+ *
+ * Input parameters:
+ * dp - pointer to a 16-byte aligned uti596_dump structure.
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 16-bit dump_status field if successful, -1 otherwise.
+ */
+static int uti596_portDump(
+ i596_dump_result * dp
+)
+{
+ rtems_interval ticks_per_second, start_ticks, end_ticks;
+
+ dp->dump_status = 0;
+ uti596_writePortFunction( dp, UTI596_DUMP_PORT_FUNCTION );
+
+ ticks_per_second = rtems_clock_get_ticks_per_second();
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ end_ticks = start_ticks + ticks_per_second;
+
+ do {
+ if( dp->dump_status != 0xA006 )
+ break;
+ else
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ } while (start_ticks <= end_ticks);
+
+ if (start_ticks > end_ticks ) {
+ #ifdef DBG_DUMP_CMD
+ printk(("uti596_dump: Timed out with dump at 0x%08x\n", (unsigned long)dp ))
+ #endif
+ return -1;
+ }
+ else {
+ #ifdef DBG_DUMP_CMD
+ printk(("uti596_dump: Succeeded with dump at = 0x%08x\n", (unsigned long)dp ))
+ #endif
+ return dp->dump_status;
+ }
+}
+#endif
+
+/*
+ * uti596_wait
+ *
+ * Wait for a certain condition.
+ *
+ * Input parameters:
+ * sc - pointer to the uti596_softc struct
+ * wait_type - UTI596_NO_WAIT
+ * UTI596_WAIT
+ * UTI596_WAIT_FOR_CU_ACCEPT
+ * UTI596_WAIT_FOR_INITIALIZATION
+ * UTI596_WAIT_FOR_STAT_C
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise.
+ */
+static int uti596_wait(
+ uti596_softc_ *sc,
+ uint8_t waitType
+)
+{
+ rtems_interval ticks_per_second, start_ticks, end_ticks;
+
+ ticks_per_second = rtems_clock_get_ticks_per_second();
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ end_ticks = start_ticks + ticks_per_second;
+
+ switch( waitType ) {
+
+ case UTI596_NO_WAIT:
+ return 0;
+
+ case UTI596_WAIT_FOR_CU_ACCEPT:
+ do {
+ if (sc->scb.command == 0)
+ break;
+ else
+
+ start_ticks = rtems_clock_get_ticks_since_boot();
+
+ } while (start_ticks <= end_ticks);
+
+ if( (sc->scb.command != 0) || (start_ticks > end_ticks) ) {
+ printf("i82596 timed out with status %x, cmd %x.\n",
+ sc->scb.status, sc->scb.command);
+ return -1;
+ }
+ else
+ return 0;
+
+ case UTI596_WAIT_FOR_INITIALIZATION:
+ do {
+ if( !sc->iscp.busy )
+ break;
+ else
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ } while (start_ticks <= end_ticks);
+
+ if (start_ticks > end_ticks ) {
+ #ifdef DBG_WAIT
+ printk(("uti596_setScpAndScb: Timed out\n" ))
+ #endif
+ return -1;
+ }
+ else {
+ #ifdef DBG_WAIT
+ printk(("uti596_setScpAndScb: Succeeded\n" ))
+ #endif
+ return 0;
+ }
+
+ case UTI596_WAIT_FOR_STAT_C:
+ do {
+ if( *sc->pCurrent_command_status & STAT_C )
+ break;
+ else
+ start_ticks = rtems_clock_get_ticks_since_boot();
+ } while (start_ticks <= end_ticks);
+
+ if (start_ticks > end_ticks ) {
+ #ifdef DBG_WAIT
+ printk(("uti596_initMem: timed out - STAT_C not obtained\n" ))
+ #endif
+ return -1;
+ }
+ else {
+ #ifdef DBG_WAIT
+ printk(("uti596_initMem: STAT_C obtained OK\n" ))
+ #endif
+ return 0;
+ }
+ }
+ return -1;
+}
+
+/*
+ * uti596_issueCA
+ *
+ * Issue a Channel Attention command. Possibly wait for the
+ * command to start or complete.
+ *
+ * Input parameters:
+ * sc - pointer to the uti596_softc
+ * wait_type - UTI596_NO_WAIT
+ * UTI596_WAIT_BEGIN
+ * UTI596_WAIT_COMPLETION
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise.
+ */
+static int uti596_issueCA(
+ uti596_softc_ *sc,
+ uint8_t waitType
+)
+{
+ /* Issue Channel Attention */
+ i82596->chan_attn = 0x00000000;
+
+ return (uti596_wait ( sc, waitType ));
+}
+
+/*
+ * uti596_addCmd
+ *
+ * Add a uti596_cmd onto the end of the CBL command chain,
+ * or to the start if the chain is empty.
+ *
+ * Input parameters:
+ * pCmd - a pointer to the command to be added.
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+static void uti596_addCmd(
+ i596_cmd *pCmd
+)
+{
+ ISR_Level level;
+
+ #ifdef DBG_ADD_CMD
+ printk(("uti596_addCmd: Adding command 0x%x\n", pCmd -> command ))
+ #endif
+
+ /* Mark command as last in list, to return an interrupt */
+ pCmd->command |= (CMD_EOL | CMD_INTR );
+ pCmd->status = 0;
+ pCmd->next = I596_NULL;
+
+ _ISR_Local_disable(level);
+
+ if (uti596_softc.pCmdHead == I596_NULL) {
+ uti596_softc.pCmdHead = uti596_softc.pCmdTail = uti596_softc.scb.pCmd = pCmd;
+ uti596_softc.scb.cmd_pointer = word_swap ((unsigned long)pCmd);
+
+ uti596_wait ( &uti596_softc, UTI596_WAIT_FOR_CU_ACCEPT );
+ uti596_softc.scb.command = CUC_START;
+ uti596_issueCA ( &uti596_softc, UTI596_NO_WAIT );
+
+ _ISR_Local_enable(level);
+ }
+ else {
+ uti596_softc.pCmdTail->next = (i596_cmd *) word_swap ((unsigned long)pCmd);
+ uti596_softc.pCmdTail = pCmd;
+ _ISR_Local_enable(level);
+ }
+
+ #ifdef DBG_ADD_CMD
+ printk(("uti596_addCmd: Scb status & command 0x%x 0x%x\n",
+ uti596_softc.scb.status,
+ uti596_softc.scb.command ))
+ #endif
+}
+
+/*
+ * uti596_addPolledCmd
+ *
+ * Add a single uti596_cmd to the end of the command block list
+ * for processing, send a CU_START and wait for its acceptance
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_addPolledCmd(
+ i596_cmd *pCmd
+)
+{
+
+ #ifdef DBG_ADD_CMD
+ printk(("uti596_addPolledCmd: Adding command 0x%x\n", pCmd -> command ))
+ #endif
+
+ pCmd->status = 0;
+ pCmd->command |= CMD_EOL ; /* only command in list*/
+ pCmd->next = I596_NULL;
+
+ uti596_wait ( &uti596_softc, UTI596_WAIT_FOR_CU_ACCEPT );
+
+ uti596_softc.pCmdHead = uti596_softc.pCmdTail = uti596_softc.scb.pCmd = pCmd;
+ uti596_softc.scb.cmd_pointer = word_swap((unsigned long)pCmd);
+ uti596_softc.scb.command = CUC_START;
+ uti596_issueCA ( &uti596_softc, UTI596_WAIT_FOR_CU_ACCEPT );
+
+ uti596_softc.pCmdHead = uti596_softc.pCmdTail = uti596_softc.scb.pCmd = I596_NULL;
+ uti596_softc.scb.cmd_pointer = (unsigned long) I596_NULL;
+
+ #ifdef DBG_ADD_CMD
+ printk(("uti596_addPolledCmd: Scb status & command 0x%x 0x%x\n",
+ uti596_softc.scb.status,
+ uti596_softc.scb.command ))
+ #endif
+}
+
+/* currently unused by RTEMS */
+#if 0
+/*
+ * uti596_CU_dump
+ *
+ * Dump the LANC 82596 registers
+ * The outcome is the same as the portDump() but executed
+ * via the CU instead of via a PORT access.
+ *
+ * Input parameters:
+ * drp - a pointer to a i596_dump_result structure.
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+static void uti596_CU_dump ( i596_dump_result * drp)
+{
+ i596_dump dumpCmd;
+
+ dumpCmd.cmd.command = CmdDump;
+ dumpCmd.cmd.next = I596_NULL;
+ dumpCmd.pData = (char *) drp;
+ uti596_softc.cmdOk = 0;
+ uti596_addCmd ( (i596_cmd *) &dumpCmd );
+
+}
+#endif
+
+#if defined(DBG_STAT) || !defined(IGNORE_NO_RFA)
+/*
+ * uti596_dump_scb
+ *
+ * Dump the system control block
+ * This function expands to nothing when using interrupt driven I/O
+ *
+ * Input parameters: NONE
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+static void uti596_dump_scb ( void )
+{
+ printk(("status 0x%x\n",uti596_softc.scb.status))
+ printk(("command 0x%x\n",uti596_softc.scb.command))
+ printk(("cmd 0x%x\n",(int)uti596_softc.scb.pCmd))
+ printk(("rfd 0x%x\n",(int)uti596_softc.scb.pRfd))
+ printk(("crc_err 0x%" PRIx32 "\n",uti596_softc.scb.crc_err))
+ printk(("align_err 0x%" PRIx32 "\n",uti596_softc.scb.align_err))
+ printk(("resource_err 0x%" PRIx32 "\n",uti596_softc.scb.resource_err ))
+ printk(("over_err 0x%" PRIx32 "\n",uti596_softc.scb.over_err))
+ printk(("rcvdt_err 0x%" PRIx32 "\n",uti596_softc.scb.rcvdt_err))
+ printk(("short_err 0x%" PRIx32 "\n",uti596_softc.scb.short_err))
+ printk(("t_on 0x%x\n",uti596_softc.scb.t_on))
+ printk(("t_off 0x%x\n",uti596_softc.scb.t_off))
+}
+#endif
+
+/*
+ * uti596_setScpAndScb
+ *
+ * Issue the first channel attention after reset and wait for the busy
+ * field to clear in the iscp.
+ *
+ * Input parameters:
+ * sc - pointer to the global uti596_softc
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise.
+ */
+static int uti596_setScpAndScb(
+ uti596_softc_ * sc
+)
+{
+ /* set the busy flag in the iscp */
+ sc->iscp.busy = 1;
+
+ /* the command block list (CBL) is empty */
+ sc->scb.command = 0;
+ sc->scb.cmd_pointer = (unsigned long) I596_NULL; /* all 1's */
+ sc->pCmdHead = sc->scb.pCmd = I596_NULL; /* all 1's */
+
+ uti596_writePortFunction( sc->pScp, UTI596_SCP_PORT_FUNCTION );
+
+ /* Issue CA: pass the scb address to the 596 */
+ return ( uti596_issueCA ( sc, UTI596_WAIT_FOR_INITIALIZATION ) );
+}
+
+/*
+ * uti596_diagnose
+ *
+ * Send a diagnose command to the CU
+ *
+ * Input parameters: NONE
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise
+ */
+static int uti596_diagnose( void )
+{
+ i596_cmd diagnose;
+
+ diagnose.command = CmdDiagnose;
+ diagnose.status = 0;
+ uti596_softc.pCurrent_command_status = (unsigned short *)&diagnose.status;
+ uti596_addPolledCmd(&diagnose);
+ return (uti596_wait ( &uti596_softc, UTI596_WAIT_FOR_STAT_C ));
+
+ #ifdef DBG_INIT
+ printk(("Status diagnostic: 0xa000 is a success ... 0x%2.2x\n", diagnose.status))
+ #endif
+}
+
+/*
+ * uti596_configure
+ *
+ * Send the CU a configure command with the desired
+ * configuration structure
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise
+ */
+static int uti596_configure (
+ uti596_softc_ * sc
+)
+{
+ sc->set_conf.cmd.command = CmdConfigure;
+ memcpy ( (void *)sc->set_conf.data, uti596initSetup, 14);
+ uti596_addPolledCmd( (i596_cmd *) &sc->set_conf);
+
+ /* Poll for successful command completion */
+ sc->pCurrent_command_status = (unsigned short *)&(sc->set_conf.cmd.status);
+ return ( uti596_wait ( sc, UTI596_WAIT_FOR_STAT_C ) );
+}
+
+/*
+ * uti596_IAsetup
+ *
+ * Send the CU an Individual Address setup command with
+ * the ethernet hardware address
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise
+ */
+static int uti596_IAsetup (
+ uti596_softc_ * sc
+)
+{
+ int i;
+
+ sc->set_add.cmd.command = CmdSASetup;
+ for ( i=0; i<6; i++) {
+ sc->set_add.data[i]=sc->arpcom.ac_enaddr[i];
+ }
+ sc->cmdOk = 0;
+ uti596_addPolledCmd((i596_cmd *)&sc->set_add);
+
+ /* Poll for successful command completion */
+ sc->pCurrent_command_status = (unsigned short *)&(sc->set_add.cmd.status);
+ return ( uti596_wait ( sc, UTI596_WAIT_FOR_STAT_C ) );
+}
+
+/*
+ * uti596_initTBD
+ *
+ * Initialize transmit buffer descriptors
+ * dynamically allocate mem for the number of tbd's required
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * 0 if successful, -1 otherwise
+ */
+static int uti596_initTBD ( uti596_softc_ * sc )
+{
+ int i;
+ i596_tbd *pTbd, *pPrev;
+
+ /* Set up a transmit command with a tbd ready */
+ sc->pLastUnkRFD = I596_NULL;
+ sc->pTxCmd = (i596_tx *) calloc (1,sizeof (struct i596_tx) );
+ sc->pTbd = (i596_tbd *) calloc (1,sizeof (struct i596_tbd) );
+ if ((sc->pTxCmd == NULL) || (sc->pTbd == NULL)) {
+ return -1;
+ }
+ sc->pTxCmd->pTbd = (i596_tbd *) word_swap ((unsigned long) sc->pTbd);
+ sc->pTxCmd->cmd.command = CMD_FLEX|CmdTx;
+ sc->pTxCmd->pad = 0;
+ sc->pTxCmd->count = 0; /* all bytes are in list of TBD's */
+
+ pPrev = pTbd = sc->pTbd;
+
+ /* Allocate a linked list of tbd's each with it's 'next' field written
+ * with upper and lower words swapped (for big endian), and mark the end.
+ */
+ for ( i=0; i<sc->txBdCount; i++) {
+ if ( (pTbd = (i596_tbd *) calloc (1,sizeof (struct i596_tbd) )) == NULL ) {
+ return -1;
+ }
+ pPrev->next = (i596_tbd *) word_swap ((unsigned long) pTbd);
+ pPrev = pTbd;
+ }
+ pTbd->next = I596_NULL;
+ return 0;
+}
+
+/*
+ * uti596_initRFA
+ *
+ * Initialize the Receive Frame Area
+ * dynamically allocate mem for the number of rfd's required
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * # of buffer descriptors successfully allocated
+ */
+static int uti596_initRFA( int num )
+{
+ i596_rfd *pRfd;
+ int i = 0;
+
+ #ifdef DBG_INIT
+ printk(("uti596_initRFA: begins\n Requested frame descriptors ... %d.\n", num))
+ #endif
+
+ /*
+ * Create the first RFD in the RFA
+ */
+ pRfd = (i596_rfd *) calloc (1, sizeof (struct i596_rfd));
+ if ( !pRfd ) {
+ printk(("Can't allocate first buffer.\n"))
+ return 0;
+ }
+ else {
+ uti596_softc.countRFD = 1;
+ uti596_softc.pBeginRFA = uti596_softc.pEndRFA = pRfd;
+ }
+
+ /* Create remaining RFDs */
+ for (i = 1; i < num; i++) {
+ pRfd = (i596_rfd *) calloc (1, sizeof (struct i596_rfd) );
+ if ( pRfd != NULL ) {
+ uti596_softc.countRFD++; /* update count */
+ uti596_softc.pEndRFA->next =
+ (i596_rfd *) word_swap ((unsigned long) pRfd); /* write the link */
+ uti596_softc.pEndRFA = pRfd; /* move the end */
+ }
+ else {
+ printk(("Can't allocate all buffers: only %d allocated\n", i))
+ break;
+ }
+ } /* end for */
+
+ uti596_softc.pEndRFA->next = I596_NULL;
+ UTI_596_ASSERT(uti596_softc.countRFD == num,"INIT:WRONG RFD COUNT\n" )
+
+ #ifdef DBG_INIT
+ printk (("uti596_initRFA: Head of RFA is buffer %p \n\
+ uti596_initRFA: End of RFA is buffer %p \n",
+ uti596_softc.pBeginRFA, uti596_softc.pEndRFA ))
+ #endif
+
+ /* Walk and initialize the RFD's */
+ for ( pRfd = uti596_softc.pBeginRFA;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd *) word_swap ((unsigned long)pRfd->next) )
+ {
+ pRfd->cmd = 0x0000;
+ pRfd->stat = 0x0000;
+ pRfd->pRbd = I596_NULL;
+ pRfd->count = 0; /* number of bytes in buffer: usually less than size */
+ pRfd->size = 1532; /* was 1532; buffer size ( All RBD ) */
+ } /* end for */
+
+ /* mark the last RFD as the last one in the RDL */
+ uti596_softc.pEndRFA -> cmd = CMD_EOL;
+ uti596_softc.pSavedRfdQueue =
+ uti596_softc.pEndSavedQueue = I596_NULL; /* initially empty */
+
+ uti596_softc.savedCount = 0;
+ uti596_softc.nop.cmd.command = CmdNOp; /* initialize the nop command */
+
+ return (i); /* the number of allocated buffers */
+}
+
+/*
+ * uti596_initMem
+ *
+ * Initialize the 82596 memory structures for Tx and Rx
+ * dynamically allocate mem for the number of tbd's required
+ *
+ * Input parameters:
+ * sc - a pointer to the uti596_softc struct
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_initMem(
+ uti596_softc_ * sc
+)
+{
+ int i;
+
+ #ifdef DBG_INIT
+ printk(("uti596_initMem: begins\n"))
+ #endif
+
+ sc->resetDone = 0;
+
+ /*
+ * Set up receive frame area (RFA)
+ */
+ i = uti596_initRFA( sc->rxBdCount );
+ if ( i < sc->rxBdCount ) {
+ printk(("init_rfd: only able to allocate %d receive frame descriptors\n", i))
+ }
+
+ /*
+ * Write the SCB with a pointer to the receive frame area
+ * and keep a pointer for our use.
+ */
+ sc->scb.rfd_pointer = word_swap((unsigned long)sc->pBeginRFA);
+ sc->scb.pRfd = sc->pBeginRFA;
+
+ /*
+ * Diagnose the health of the board
+ */
+ uti596_diagnose();
+
+ /*
+ * Configure the 82596
+ */
+ uti596_configure( sc );
+
+ /*
+ * Set up the Individual (hardware) Address
+ */
+ uti596_IAsetup ( sc );
+
+ /*
+ * Initialize the transmit buffer descriptors
+ */
+ uti596_initTBD( sc );
+
+ /* Padding used to fill short tx frames */
+ memset ( RTEMS_DEVOLATILE( char *, sc->zeroes ), 0, 64);
+
+ /* now need ISR */
+ sc->resetDone = 1;
+}
+
+/*
+ * uti596_initialize
+ *
+ * Reset the 82596 and initialize it with a new SCP.
+ *
+ * Input parameters:
+ * sc - pointer to the uti596_softc
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_initialize(
+ uti596_softc_ *sc
+)
+{
+ /* Reset the device. Stops it from doing whatever it might be doing. */
+ uti596_portReset();
+
+ /* Get a new System Configuration Pointer */
+ uti596_scp_alloc( sc );
+
+ /* write the SYSBUS: interrupt pin active high, LOCK disabled,
+ * internal triggering, linear mode
+ */
+ sc->pScp->sysbus = 0x44;
+
+ /* provide the iscp to the scp, keep a pointer for our use */
+ sc->pScp->iscp_pointer = word_swap((unsigned long)&sc->iscp);
+ sc->pScp->iscp = &sc->iscp;
+
+ /* provide the scb to the iscp, keep a pointer for our use */
+ sc->iscp.scb_pointer = word_swap((unsigned long)&sc->scb);
+ sc->iscp.scb = &sc->scb;
+
+ #ifdef DBG_INIT
+ printk(("uti596_initialize: Starting i82596.\n"))
+ #endif
+
+ /* Set up the 82596 */
+ uti596_setScpAndScb( sc );
+
+ /* clear the scb command word */
+ sc->scb.command = 0;
+}
+
+/*
+ * uti596_initialize_hardware
+ *
+ * Reset the 82596 and initialize it with a new SCP. Enable bus snooping.
+ * Install the interrupt handlers.
+ *
+ * Input parameters:
+ * sc - pointer to the uti596_softc
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_initialize_hardware(
+ uti596_softc_ *sc
+)
+{
+ printk(("uti596_initialize_hardware: begins\n"))
+
+ /* Get the PCCChip2 to assert bus snooping signals on behalf of the i82596 */
+ pccchip2->LANC_berr_ctl = 0x40;
+
+ uti596_initialize( sc );
+
+ /*
+ * Configure interrupt control in PCCchip2
+ */
+ pccchip2->LANC_error = 0xff; /* clear status register */
+ pccchip2->LANC_int_ctl = 0x5d; /* lvl 5, enabled, edge-sensitive rising */
+ pccchip2->LANC_berr_ctl = 0x5d; /* bus error: lvl 5, enabled, snoop control
+ * will supply dirty data and leave dirty data
+ * on read access and sink any data on write
+ */
+ /*
+ * Install the interrupt handler
+ * calls rtems_interrupt_catch
+ */
+ set_vector( uti596_DynamicInterruptHandler, 0x57, 1 );
+
+ /* Initialize the 82596 memory */
+ uti596_initMem(sc);
+
+ #ifdef DBG_INIT
+ printk(("uti596_initialize_hardware: After attach, status of board = 0x%x\n", sc->scb.status ))
+ #endif
+}
+
+/*
+ * uti596_reset_hardware
+ *
+ * Reset the 82596 and initialize it with an SCP.
+ *
+ * Input parameters:
+ * sc - pointer to the uti596_softc
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_reset_hardware(
+ uti596_softc_ *sc
+)
+{
+ rtems_status_code status_code;
+ i596_cmd *pCmd;
+
+ pCmd = sc->pCmdHead; /* This is a tx command for sure (99.99999%) */
+
+ /* the command block list (CBL) is empty */
+ sc->scb.cmd_pointer = (unsigned long) I596_NULL; /* all 1's */
+ sc->pCmdHead = sc->scb.pCmd = I596_NULL; /* all 1's */
+
+ #ifdef DBG_RESET
+ printk(("uti596_reset_hardware\n"))
+ #endif
+ uti596_initialize( sc );
+
+ /*
+ * Wake the transmitter if needed.
+ */
+ if ( sc->txDaemonTid && pCmd != I596_NULL ) {
+ printk(("****RESET: wakes transmitter!\n"))
+ status_code = rtems_bsdnet_event_send (sc->txDaemonTid,
+ INTERRUPT_EVENT);
+
+ if ( status_code != RTEMS_SUCCESSFUL ) {
+ printk(("****ERROR:Could NOT send event to tid 0x%" PRIx32 " : %s\n",
+ sc->txDaemonTid, rtems_status_text (status_code) ))
+ }
+ }
+
+ #ifdef DBG_RESET
+ printk(("uti596_reset_hardware: After reset_hardware, status of board = 0x%x\n", sc->scb.status ))
+ #endif
+}
+
+/*
+ * uti596_clearListStatus
+ *
+ * Clear the stat fields for all RFDs
+ *
+ * Input parameters:
+ * pRfd - a pointer to the head of the RFA
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_clearListStatus(
+ i596_rfd *pRfd
+)
+{
+ while ( pRfd != I596_NULL ) {
+ pRfd -> stat = 0;
+ pRfd = (i596_rfd *) word_swap((unsigned long)pRfd-> next);
+ }
+}
+
+/*
+ * uti596_reset
+ *
+ * Reset the 82596 and reconfigure
+ *
+ * Input parameters: NONE
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_reset( void )
+{
+ uti596_softc_ *sc = &uti596_softc;
+
+ #ifdef DBG_RESET
+ printk(("uti596_reset: begin\n"))
+ #endif
+
+ /* Wait for the CU to be available, then
+ * reset the ethernet hardware. Must re-config.
+ */
+ sc->resetDone = 0;
+ uti596_wait ( sc, UTI596_WAIT_FOR_CU_ACCEPT );
+ uti596_reset_hardware ( &uti596_softc );
+
+ #ifdef DBG_RESET
+ uti596_diagnose();
+ #endif
+
+ /*
+ * Configure the 82596
+ */
+ uti596_configure( sc );
+
+ /*
+ * Set up the Individual (hardware) Address
+ */
+ uti596_IAsetup ( sc );
+
+ sc->pCmdHead = sc->pCmdTail = sc->scb.pCmd = I596_NULL;
+
+ /* restore the RFA */
+
+ if ( sc->pLastUnkRFD != I596_NULL ) {
+ sc-> pEndRFA = sc->pLastUnkRFD; /* The end position can be updated */
+ sc-> pLastUnkRFD = I596_NULL;
+ }
+
+ sc->pEndRFA->next = (i596_rfd*)word_swap((uint32_t)sc->pSavedRfdQueue);
+ if ( sc->pSavedRfdQueue != I596_NULL ) {
+ sc->pEndRFA = sc->pEndSavedQueue;
+ sc->pSavedRfdQueue = sc->pEndSavedQueue = I596_NULL;
+ sc -> countRFD = sc->rxBdCount ;
+ }
+
+ /* Re-address the head of the RFA in the SCB */
+ sc->scb.pRfd = sc->pBeginRFA;
+ sc->scb.rfd_pointer = word_swap((unsigned long)sc->pBeginRFA);
+
+ /* Clear the status of all RFDs */
+ uti596_clearListStatus( sc->pBeginRFA );
+
+ printk(("uti596_reset: Starting NIC\n"))
+
+ /* Start the receiver */
+ sc->scb.command = RX_START;
+ sc->started = 1; /* assume that the start is accepted */
+ sc->resetDone = 1;
+ uti596_issueCA ( sc, UTI596_WAIT_FOR_CU_ACCEPT );
+
+ UTI_596_ASSERT(sc->pCmdHead == I596_NULL, "Reset: CMD not cleared\n")
+
+ #ifdef DBG_RESET
+ printk(("uti596_reset: completed\n"))
+ #endif
+}
+
+/*
+ * uti596_dequeue
+ *
+ * Remove an RFD from the received fram queue
+ *
+ * Input parameters:
+ * ppQ - a pointer to a i596_rfd pointer
+ *
+ * Output parameters: NONE
+ *
+ * Return value:
+ * pRfd - a pointer to the dequeued RFD
+ */
+i596_rfd * uti596_dequeue(
+ i596_rfd ** ppQ
+)
+{
+ ISR_Level level;
+ i596_rfd * pRfd;
+
+ _ISR_Local_disable(level);
+
+ /* invalid address, or empty queue or emptied queue */
+ if( ppQ == NULL || *ppQ == NULL || *ppQ == I596_NULL) {
+ _ISR_Local_enable(level);
+ return I596_NULL;
+ }
+
+ /*
+ * Point to the dequeued buffer, then
+ * adjust the queue pointer and detach the buffer
+ */
+ pRfd = *ppQ;
+ *ppQ = (i596_rfd *) word_swap ((unsigned long) pRfd->next);
+ pRfd->next = I596_NULL; /* unlink the rfd being returned */
+
+ _ISR_Local_enable(level);
+ return pRfd;
+}
+
+/*
+ * uti596_append
+ *
+ * Remove an RFD buffer from the RFA and tack it on to
+ * the received frame queue for processing.
+ *
+ * Input parameters:
+ * ppQ - a pointer to the queue pointer
+ * pRfd - a pointer to the buffer to be returned
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+
+void uti596_append(
+ i596_rfd ** ppQ,
+ i596_rfd * pRfd
+)
+{
+
+ i596_rfd *p;
+
+ if ( pRfd != NULL && pRfd != I596_NULL) {
+ pRfd -> next = I596_NULL;
+ pRfd -> cmd |= CMD_EOL; /* set EL bit */
+
+ if ( *ppQ == NULL || *ppQ == I596_NULL ) {
+ /* empty list */
+ *ppQ = pRfd;
+ }
+ else {
+ /* walk to the end of the list */
+ for ( p=*ppQ;
+ p->next != I596_NULL;
+ p=(i596_rfd *) word_swap ((unsigned long)p->next) );
+
+ /* append the rfd */
+ p->cmd &= ~CMD_EOL; /* Clear EL bit at end */
+ p->next = (i596_rfd *) word_swap ((unsigned long)pRfd);
+ }
+ }
+ else {
+ printk(("Illegal attempt to append: %p\n", pRfd))
+ }
+}
+
+/*
+ * uti596_supplyFD
+ *
+ * Return a buffer (RFD) to the receive frame area (RFA).
+ * Call with interrupts disabled.
+ *
+ * Input parameters:
+ * pRfd - a pointer to the buffer to be returned
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void uti596_supplyFD (
+ i596_rfd * pRfd
+)
+{
+ i596_rfd *pLastRfd;
+
+ UTI_596_ASSERT(pRfd != I596_NULL, "Supplying NULL RFD!\n")
+
+ pRfd -> cmd = CMD_EOL;
+ pRfd -> pRbd = I596_NULL;
+ pRfd -> next = I596_NULL;
+ pRfd -> stat = 0x0000; /* clear STAT_C and STAT_B bits */
+
+ /*
+ * Check if the list is empty:
+ */
+ if ( uti596_softc.pBeginRFA == I596_NULL ) {
+
+ /* Start a list with one entry */
+ uti596_softc.pBeginRFA = uti596_softc.pEndRFA = pRfd;
+ UTI_596_ASSERT(uti596_softc.countRFD == 0, "Null begin, but non-zero count\n")
+ if ( uti596_softc.pLastUnkRFD != I596_NULL ) {
+ printk(("LastUnkRFD is NOT NULL!!\n"))
+ }
+ uti596_softc.countRFD = 1;
+ return;
+ }
+
+ /*
+ * Check if the last RFD is used/read by the 596.
+ */
+ pLastRfd = uti596_softc.pEndRFA;
+
+ /* C = complete, B = busy (prefetched) */
+ if ( pLastRfd != I596_NULL && ! (pLastRfd -> stat & ( STAT_C | STAT_B ) )) {
+
+ /*
+ * Not yet too late to add it
+ */
+ pLastRfd -> next = (i596_rfd *) word_swap ((unsigned long)pRfd);
+ pLastRfd -> cmd &= ~CMD_EOL; /* RESET_EL : reset EL bit to 0 */
+ uti596_softc.countRFD++; /* Lets assume we add it successfully
+ If not, the RFD may be used, and may
+ decrement countRFD < 0 !! */
+ /*
+ * Check if the last RFD was used while appending.
+ */
+ if ( pLastRfd -> stat & ( STAT_C | STAT_B ) ) { /* completed or was prefetched */
+ /*
+ * Either the EL bit of the last rfd has been read by the 82596,
+ * and it will stop after reception,( true when RESET_EL not reached ) or
+ * the EL bit was NOT read by the 82596 and it will use the linked
+ * RFD for the next reception. ( true when RESET_EL was reached )
+ * So, it is unknown whether or not the linked rfd will be used.
+ * Therefore, the end of list CANNOT be updated.
+ */
+ UTI_596_ASSERT ( uti596_softc.pLastUnkRFD == I596_NULL, "Too many Unk RFD's\n" )
+ uti596_softc.pLastUnkRFD = pRfd;
+ return;
+ }
+ else {
+ /*
+ * The RFD being added was not touched by the 82596
+ */
+ if (uti596_softc.pLastUnkRFD != I596_NULL ) {
+
+ uti596_append((i596_rfd **)&uti596_softc.pSavedRfdQueue, pRfd); /* Only here! saved Q */
+ uti596_softc.pEndSavedQueue = pRfd;
+ uti596_softc.savedCount++;
+ uti596_softc.countRFD--;
+
+ }
+ else {
+
+ uti596_softc.pEndRFA = pRfd; /* the RFA has been extended */
+
+ if ( ( uti596_softc.scb.status & SCB_STAT_RNR ||
+ uti596_softc.scb.status & RU_NO_RESOURCES ) &&
+ uti596_softc.countRFD > 1 ) {
+
+ /* Ensure that beginRFA is not EOL */
+ uti596_softc.pBeginRFA -> cmd &= ~CMD_EOL;
+
+ UTI_596_ASSERT(uti596_softc.pEndRFA -> next == I596_NULL, "supply: List buggered\n")
+ UTI_596_ASSERT(uti596_softc.pEndRFA -> cmd & CMD_EOL, "supply: No EOL at end.\n")
+ UTI_596_ASSERT(uti596_softc.scb.command == 0, "Supply: scb command must be zero\n")
+
+ #ifdef DBG_MEM
+ printk(("uti596_supplyFD: starting receiver"))
+ #endif
+
+ /* start the receiver */
+ UTI_596_ASSERT(uti596_softc.pBeginRFA != I596_NULL, "rx start w/ NULL begin! \n")
+ uti596_softc.scb.pRfd = uti596_softc.pBeginRFA;
+ uti596_softc.scb.rfd_pointer = word_swap ((unsigned long) uti596_softc.pBeginRFA);
+
+ /* Don't ack RNR! The receiver should be stopped in this case */
+ uti596_softc.scb.command = RX_START | SCB_STAT_RNR;
+
+ UTI_596_ASSERT( !(uti596_softc.scb.status & SCB_STAT_FR),"FRAME RECEIVED INT COMING!\n")
+
+ /* send CA signal */
+ uti596_issueCA ( &uti596_softc, UTI596_NO_WAIT );
+ }
+ }
+ return;
+ }
+ }
+ else {
+ /*
+ * too late , pLastRfd in use ( or NULL ),
+ * in either case, EL bit has been read, and RNR condition will occur
+ */
+ uti596_append( (i596_rfd **)&uti596_softc.pSavedRfdQueue, pRfd); /* save it for RNR */
+
+ uti596_softc.pEndSavedQueue = pRfd; /* reset end of saved queue */
+ uti596_softc.savedCount++;
+
+ return;
+ }
+}
+
+/*
+ * send_packet
+ *
+ * Send a raw ethernet packet, add a
+ * transmit command to the CBL
+ *
+ * Input parameters:
+ * ifp - a pointer to the ifnet structure
+ * m - a pointer to the mbuf being sent
+ *
+ * Output parameters: NONE
+ *
+ * Return value: NONE
+ */
+void send_packet(
+ struct ifnet *ifp, struct mbuf *m
+)
+{
+ i596_tbd *pPrev = I596_NULL;
+ i596_tbd *pRemainingTbdList;
+ i596_tbd *pTbd;
+ struct mbuf *n, *input_m = m;
+ uti596_softc_ *sc = ifp->if_softc;
+ struct mbuf *l = NULL;
+ unsigned int length = 0;
+ rtems_status_code status;
+ int bd_count = 0;
+ rtems_event_set events;
+
+ /*
+ * For all mbufs in the chain,
+ * fill a transmit buffer descriptor for each
+ */
+ pTbd = (i596_tbd*) word_swap ((unsigned long)sc->pTxCmd->pTbd);
+
+ do {
+ if (m->m_len) {
+ /*
+ * Fill in the buffer descriptor
+ */
+ length += m->m_len;
+ pTbd->data = (char *) word_swap ((unsigned long) mtod (m, void *));
+ pTbd->size = m->m_len;
+ pPrev = pTbd;
+ pTbd = (i596_tbd *) word_swap ((unsigned long) pTbd->next);
+ l = m;
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ MFREE (m, n);
+ m = n;
+ if (l != NULL)
+ l->m_next = m;
+ }
+ } while( m != NULL && ++bd_count < 16 );
+
+ if ( length < UTI_596_ETH_MIN_SIZE ) {
+ pTbd->data = (char *) word_swap ((unsigned long) sc->zeroes); /* add padding to pTbd */
+ pTbd->size = UTI_596_ETH_MIN_SIZE - length; /* zeroes have no effect on the CRC */
+ }
+ else /* Don't use pTbd in the send routine */
+ pTbd = pPrev;
+
+ /* Disconnect the packet from the list of Tbd's */
+ pRemainingTbdList = (i596_tbd *) word_swap ((unsigned long)pTbd->next);
+ pTbd->next = I596_NULL;
+ pTbd->size |= UTI_596_END_OF_FRAME;
+
+ sc->rawsndcnt++;
+
+ #ifdef DBG_SEND
+ printk(("send_packet: sending packet\n"))
+ #endif
+
+ /* Sending Zero length packet: shouldn't happen */
+ if (pTbd->size <= 0) return;
+
+ #ifdef DBG_PACKETS
+ printk (("\nsend_packet: Transmitter adds packet\n"))
+ print_hdr ( sc->pTxCmd->pTbd->data ); /* print the first part */
+ print_pkt ( sc->pTxCmd->pTbd->next->data ); /* print the first part */
+ print_echo (sc->pTxCmd->pTbd->data);
+ #endif
+
+ /* add the command to the output command queue */
+ uti596_addCmd ( (i596_cmd *) sc->pTxCmd );
+
+ /* sleep until the command has been processed or Timeout encountered. */
+ status= rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ if ( status != RTEMS_SUCCESSFUL ) {
+ printk(("Could not sleep %s\n", rtems_status_text(status)))
+ }
+
+ #ifdef DBG_SEND
+ printk(("send_packet: RAW - wake\n"))
+ #endif
+
+ sc->txInterrupts++;
+
+ if ( sc->pTxCmd -> cmd.status & STAT_OK ) {
+ sc->stats.tx_packets++;
+ }
+ else {
+
+ printk(("*** send_packet: Driver Error 0x%x\n", sc->pTxCmd -> cmd.status ))
+
+ sc->stats.tx_errors++;
+ if ( sc->pTxCmd->cmd.status & 0x0020 )
+ sc->stats.tx_retries_exceeded++;
+ if (!(sc->pTxCmd->cmd.status & 0x0040))
+ sc->stats.tx_heartbeat_errors++;
+ if ( sc->pTxCmd->cmd.status & 0x0400 )
+ sc->stats.tx_carrier_errors++;
+ if ( sc->pTxCmd->cmd.status & 0x0800 )
+ sc->stats.collisions++;
+ if ( sc->pTxCmd->cmd.status & 0x1000 )
+ sc->stats.tx_aborted_errors++;
+ } /* end if stat_ok */
+
+ /*
+ * Restore the transmitted buffer descriptor chain.
+ */
+ pTbd -> next = (i596_tbd *) word_swap ((unsigned long)pRemainingTbdList);
+
+ /*
+ * Free the mbufs used by the sender.
+ */
+ m = input_m;
+ while ( m != NULL ) {
+ MFREE(m,n);
+ m = n;
+ }
+}
+
+/***********************************************************************
+ * Function: uti596_attach
+ *
+ * Description:
+ * Configure the driver, and connect to the network stack
+ *
+ * Algorithm:
+ *
+ * Check parameters in the ifconfig structure, and
+ * set driver parameters accordingly.
+ * Initialize required rx and tx buffers.
+ * Link driver data structure onto device list.
+ * Return 1 on successful completion.
+ *
+ ***********************************************************************/
+
+int uti596_attach(
+ struct rtems_bsdnet_ifconfig * pConfig,
+ int attaching
+)
+{
+ uti596_softc_ *sc = &uti596_softc; /* device dependent data structure */
+ struct ifnet * ifp = (struct ifnet *)&sc->arpcom.ac_if; /* ifnet structure */
+ int unitNumber;
+ char *unitName;
+#if defined(mvme167)
+ unsigned char j1; /* State of J1 jumpers */
+ char *pAddr;
+ int addr;
+#endif
+
+ #ifdef DBG_ATTACH
+ printk(("uti596_attach: begins\n"))
+ #endif
+
+ /* The NIC is not started yet */
+ sc->started = 0;
+
+ /* Indicate to ULCS that this is initialized */
+ ifp->if_softc = (void *)sc;
+ sc->pScp = NULL;
+
+ /* Parse driver name */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (pConfig, &unitName)) < 0)
+ return 0;
+
+ ifp->if_name = unitName;
+ ifp->if_unit = unitNumber;
+
+ /* Assign mtu */
+ if ( pConfig -> mtu )
+ ifp->if_mtu = pConfig -> mtu;
+ else
+ ifp->if_mtu = ETHERMTU;
+
+ /*
+ * Check whether parameters should be obtained from NVRAM. If
+ * yes, and if an IP address, netmask, or ethernet address are
+ * provided in NVRAM, cheat, and stuff them into the ifconfig
+ * structure, OVERRIDING and existing or NULL values.
+ *
+ * Warning: If values are provided in NVRAM, the ifconfig entries
+ * must be NULL because buffer memory allocated to hold the
+ * structure values is unrecoverable and would be lost here.
+ */
+
+#if defined(mvme167)
+ /* Read the J1 header */
+ j1 = (unsigned char)(lcsr->vector_base & 0xFF);
+
+ if ( !(j1 & 0x10) ) {
+ /* Jumper J1-4 is on, configure from NVRAM */
+
+ if ( (addr = nvram->ipaddr) ) {
+ /* We have a non-zero entry, copy the value */
+ if ( (pAddr = malloc ( INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT )) )
+ pConfig->ip_address = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1 );
+ else
+ rtems_panic("Can't allocate ip_address buffer!\n");
+ }
+
+ if ( (addr = nvram->netmask) ) {
+ /* We have a non-zero entry, copy the value */
+ if ( (pAddr = malloc ( INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT )) )
+ pConfig->ip_netmask = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1 );
+ else
+ rtems_panic("Can't allocate ip_netmask buffer!\n");
+ }
+
+ /* Ethernet address requires special handling -- it must be copied into
+ * the arpcom struct. The following if construct serves only to give the
+ * NVRAM parameter the highest priority if J1-4 indicates we are configuring
+ * from NVRAM.
+ *
+ * If the ethernet address is specified in NVRAM, go ahead and copy it.
+ * (ETHER_ADDR_LEN = 6 bytes).
+ */
+ if ( nvram->enaddr[0] || nvram->enaddr[1] || nvram->enaddr[2] ) {
+ /* Anything in the first three bytes indicates a non-zero entry, copy value */
+ memcpy ((void *)sc->arpcom.ac_enaddr, &nvram->enaddr, ETHER_ADDR_LEN);
+ }
+ else if ( pConfig->hardware_address) {
+ /* There is no entry in NVRAM, but there is in the ifconfig struct, so use it. */
+ memcpy ((void *)sc->arpcom.ac_enaddr, pConfig->hardware_address, ETHER_ADDR_LEN);
+ }
+ else {
+ /* There is no ethernet address provided, so it will be read
+ * from BBRAM at $FFFC1F2C by default. [mvme167 manual p. 1-47]
+ */
+ memcpy ((void *)sc->arpcom.ac_enaddr, (char *)0xFFFC1F2C, ETHER_ADDR_LEN);
+ }
+ }
+ else if ( pConfig->hardware_address) {
+ /* We are not configuring from NVRAM (J1-4 is off), and the ethernet address
+ * is given in the ifconfig structure. Copy it.
+ */
+ memcpy ((void *)sc->arpcom.ac_enaddr, pConfig->hardware_address, ETHER_ADDR_LEN);
+ }
+ else
+#endif
+ {
+ /* We are not configuring from NVRAM (J1-4 is off), and there is no ethernet
+ * address provided in the ifconfig struct, so it will be read from BBRAM at
+ * $FFFC1F2C by default. [mvme167 manual p. 1-47]
+ */
+ memcpy ((void *)sc->arpcom.ac_enaddr, (char *)0xFFFC1F2C, ETHER_ADDR_LEN);
+ }
+
+ /* Possibly override default acceptance of broadcast packets */
+ if (pConfig->ignore_broadcast)
+ uti596initSetup[8] |= 0x02;
+
+ /* Assign requested receive buffer descriptor count */
+ if (pConfig->rbuf_count)
+ sc->rxBdCount = pConfig->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+
+ /* Assign requested tx buffer descriptor count */
+ if (pConfig->xbuf_count)
+ sc->txBdCount = pConfig->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ /* Set up fields in the ifnet structure*/
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ ifp->if_init = uti596_init;
+ ifp->if_ioctl = uti596_ioctl;
+ ifp->if_start = uti596_start;
+ ifp->if_output = ether_output;
+
+ /* uti596_softc housekeeping */
+ sc->started = 1;
+ sc->pInboundFrameQueue = I596_NULL;
+ sc->scb.command = 0;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+}
+
+/***********************************************************************
+ * Function: uti596_start
+ *
+ * Description:
+ * start the driver
+ *
+ * Algorithm:
+ * send an event to the tx task
+ * set the if_flags
+ *
+ ***********************************************************************/
+static void uti596_start(
+ struct ifnet *ifp
+)
+{
+ uti596_softc_ *sc = ifp->if_softc;
+
+ #ifdef DBG_START
+ printk(("uti596_start: begins\n"))
+ #endif
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/***********************************************************************
+ * Function: uti596_init
+ *
+ * Description:
+ * driver initialization
+ *
+ * Algorithm:
+ * initialize the 82596
+ * start driver tx and rx tasks, and reset task
+ * send the RX_START command the the RU
+ * set if_flags
+ *
+ *
+ ***********************************************************************/
+void uti596_init(
+ void * arg
+)
+{
+ uti596_softc_ *sc = arg;
+ struct ifnet *ifp = (struct ifnet *)&sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Initialize the 82596
+ */
+ #ifdef DBG_INIT
+ printk(("uti596_init: begins\nuti596_init: initializing the 82596...\n"))
+ #endif
+ uti596_initialize_hardware(sc);
+
+ /*
+ * Start driver tasks
+ */
+ #ifdef DBG_INIT
+ printk(("uti596_init: starting driver tasks...\n"))
+ #endif
+ sc->txDaemonTid = rtems_bsdnet_newproc ("UTtx", 2*4096, uti596_txDaemon, (void *)sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("UTrx", 2*4096, uti596_rxDaemon, (void *)sc);
+ sc->resetDaemonTid = rtems_bsdnet_newproc ("UTrt", 2*4096, uti596_resetDaemon, (void *)sc);
+
+ #ifdef DBG_INIT
+ printk(("uti596_init: After attach, status of board = 0x%x\n", sc->scb.status ))
+ #endif
+ }
+
+ /*
+ * In case the ISR discovers there are no resources it reclaims
+ * them and restarts
+ */
+ sc->started = 1;
+
+ /*
+ * Enable receiver
+ */
+ #ifdef DBG_INIT
+ printk(("uti596_init: enabling the reciever...\n" ))
+ #endif
+ sc->scb.command = RX_START;
+ uti596_issueCA ( sc, UTI596_WAIT_FOR_CU_ACCEPT );
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+ #ifdef DBG_INIT
+ printk(("uti596_init: completed.\n"))
+ #endif
+}
+
+/***********************************************************************
+ * Function: uti596stop
+ *
+ * Description:
+ * stop the driver
+ *
+ * Algorithm:
+ * mark driver as not started,
+ * mark transmitter as busy
+ * abort any transmissions/receptions
+ * clean-up all buffers ( RFD's et. al. )
+ *
+ *
+ ***********************************************************************/
+
+/* static */ void uti596_stop(
+ uti596_softc_ *sc
+)
+{
+ struct ifnet *ifp = (struct ifnet *)&sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+ sc->started = 0;
+
+ #ifdef DBG_STOP
+ printk(("uti596stop: %s: Shutting down ethercard, status was %4.4x.\n",
+ uti596_softc.arpcom.ac_if.if_name, uti596_softc.scb.status))
+ #endif
+
+ printk(("Stopping interface\n"))
+ sc->scb.command = CUC_ABORT | RX_ABORT;
+ i82596->chan_attn = 0x00000000;
+}
+
+/***********************************************************************
+ * Function: void uti596_txDaemon
+ *
+ * Description: Transmit task
+ *
+ * Algorithm: Get mbufs to be transmitted, stuff into RFDs, send
+ *
+ ***********************************************************************/
+
+void uti596_txDaemon(
+ void *arg
+)
+{
+ uti596_softc_ *sc = (uti596_softc_ *)arg;
+ struct ifnet *ifp = (struct ifnet *)&sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet from stack
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty.
+ * Ensure that irq is on before sending.
+ */
+ for (;;) {
+ /* Get the next mbuf chain to transmit. */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+
+ send_packet (ifp, m); /* blocks */
+ }
+ ifp->if_flags &= ~IFF_OACTIVE; /* no more to send, mark output inactive */
+ }
+}
+
+/***********************************************************************
+ * Function: uti596_rxDaemon
+ *
+ * Description: Receiver task
+ *
+ * Algorithm: Extract the packet from an RFD, and place into an
+ * mbuf chain. Place the mbuf chain in the network task
+ * queue. Assumes that the frame check sequence is removed
+ * by the 82596.
+ *
+ ***********************************************************************/
+
+/* static */ void uti596_rxDaemon(
+ void *arg
+)
+{
+ uti596_softc_ *sc = (uti596_softc_ *)arg;
+ struct ifnet *ifp = (struct ifnet *)&sc->arpcom.ac_if;
+ struct mbuf *m;
+
+ i596_rfd *pRfd;
+ ISR_Level level;
+ rtems_id tid;
+ rtems_event_set events;
+ struct ether_header *eh;
+
+ int frames = 0;
+
+ #ifdef DBG_RX
+ printk(("uti596_rxDaemon: begin\n"))
+ printk(("&scb = %p, pRfd = %p\n", &sc->scb,sc->scb.pRfd))
+ #endif
+
+ rtems_task_ident (0, 0, &tid);
+
+ for(;;) {
+ /*
+ * Wait for packet.
+ */
+ #ifdef DBG_RX
+ printk(("uti596_rxDaemon: Receiver sleeps\n"))
+ #endif
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ #ifdef DBG_RX
+ printk(("uti596_rxDaemon: Receiver wakes\n"))
+ #endif
+ /*
+ * While received frames are available. Note that the frame may be
+ * a fragment, so it is NOT a complete packet.
+ */
+ pRfd = uti596_dequeue( (i596_rfd **)&sc->pInboundFrameQueue);
+ while ( pRfd &&
+ pRfd != I596_NULL &&
+ pRfd -> stat & STAT_C )
+ {
+
+ if ( pRfd->stat & STAT_OK) { /* a good frame */
+ int pkt_len = pRfd->count & 0x3fff; /* the actual # of bytes received */
+
+ #ifdef DBG_RX
+ printk(("uti596_rxDaemon: Good frame, @%p, data @%p length %d\n", pRfd, pRfd -> data , pkt_len))
+ #endif
+ frames++;
+
+ /*
+ * Allocate an mbuf to give to the stack
+ * The format of the data portion of the RFD is:
+ * <ethernet header, payload>.
+ * The FRAME CHECK SEQUENCE / CRC is stripped by the uti596.
+ * This is to be optimized later.... should not have to memcopy!
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+
+ m->m_pkthdr.rcvif = ifp;
+ /* move everything into an mbuf */
+ memcpy(m->m_data, (const char *)pRfd->data, pkt_len);
+ m->m_len = m->m_pkthdr.len = pkt_len - sizeof(struct ether_header) - 4;
+
+ /* move the header to an mbuf */
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+
+ #ifdef DBG_PACKETS
+ {
+ int i;
+ printk(("uti596_rxDaemon: mbuf contains:\n"))
+ print_eth( (char *) (((int)m->m_data)-sizeof(struct ether_header)));
+ for ( i = 0; i<20; i++) {
+ printk(("."))
+ }
+ }
+ #endif
+
+ ether_input (ifp, eh, m);
+
+ } /* end if STAT_OK */
+
+ else {
+ /*
+ * A bad frame is present: Note that this could be the last RFD!
+ */
+ #ifdef DBG_RX
+ printk(("uti596_rxDaemon: Bad frame\n"))
+ #endif
+ /*
+ * FIX ME: use the statistics from the SCB
+ */
+ sc->stats.rx_errors++;
+ if ((sc->scb.pRfd->stat) & 0x0001)
+ sc->stats.collisions++;
+ if ((sc->scb.pRfd->stat) & 0x0080)
+ sc->stats.rx_length_errors++;
+ if ((sc->scb.pRfd->stat) & 0x0100)
+ sc->stats.rx_over_errors++;
+ if ((sc->scb.pRfd->stat) & 0x0200)
+ sc->stats.rx_fifo_errors++;
+ if ((sc->scb.pRfd->stat) & 0x0400)
+ sc->stats.rx_frame_errors++;
+ if ((sc->scb.pRfd->stat) & 0x0800)
+ sc->stats.rx_crc_errors++;
+ if ((sc->scb.pRfd->stat) & 0x1000)
+ sc->stats.rx_length_errors++;
+ }
+
+ UTI_596_ASSERT(pRfd != I596_NULL, "Supplying NULL RFD\n")
+
+ _ISR_Local_disable(level);
+ uti596_supplyFD ( pRfd ); /* Return RFD to RFA. */
+ _ISR_Local_enable(level);
+
+ pRfd = uti596_dequeue( (i596_rfd **)&sc->pInboundFrameQueue); /* grab next frame */
+
+ } /* end while */
+ } /* end for() */
+
+ #ifdef DBG_RX
+ printk (("uti596_rxDaemon: frames ... %d\n", frames))
+ #endif
+}
+
+/***********************************************************************
+ * Function: void uti596_resetDaemon
+ *
+ * Description:
+ ***********************************************************************/
+void uti596_resetDaemon(
+ void *arg
+)
+{
+ uti596_softc_ *sc = (uti596_softc_ *)arg;
+ rtems_event_set events;
+ rtems_time_of_day tm_struct;
+
+ /* struct ifnet *ifp = &sc->arpcom.ac_if; */
+
+ for (;;) {
+ /* Wait for reset event from ISR */
+ rtems_bsdnet_event_receive (NIC_RESET_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT, &events);
+
+ rtems_clock_get_tod(&tm_struct);
+ printk(("reset daemon: Resetting NIC @ %" PRIu32 ":%" PRIu32 ":%" PRIu32 " \n",
+ tm_struct.hour, tm_struct.minute, tm_struct.second))
+
+ sc->stats.nic_reset_count++;
+ /* Reinitialize the LANC */
+ rtems_bsdnet_semaphore_obtain ();
+ uti596_reset();
+ rtems_bsdnet_semaphore_release ();
+ }
+}
+
+/***********************************************************************
+ * Function: uti596_DynamicInterruptHandler
+ *
+ * Description:
+ * This is the interrupt handler for the uti596 board
+ *
+ ***********************************************************************/
+
+/* static */ rtems_isr uti596_DynamicInterruptHandler(
+ rtems_vector_number irq
+)
+{
+int fullStatus;
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: begins"))
+ #endif
+
+ uti596_wait (&uti596_softc, UTI596_WAIT_FOR_CU_ACCEPT);
+
+ scbStatus = (fullStatus = uti596_softc.scb.status) & 0xf000;
+
+ if ( scbStatus ) {
+ /* acknowledge interrupts */
+
+ /* Write to the ICLR bit in the PCCchip2 control registers to clear
+ * the INT status bit. Clearing INT here *before* sending the CA signal
+ * to the 82596 should ensure that interrupts won't be lost.
+ */
+ pccchip2->LANC_int_ctl |=0x08;
+ pccchip2->LANC_berr_ctl |=0x08;
+
+ /* printk(("***INFO: ACK %x\n", scbStatus))*/
+
+ /* Send the CA signal to acknowledge interrupt */
+ uti596_softc.scb.command = scbStatus;
+ uti596_issueCA ( &uti596_softc, UTI596_NO_WAIT );
+
+ if( uti596_softc.resetDone ) {
+ /* stack is attached */
+ uti596_wait ( &uti596_softc, UTI596_WAIT_FOR_CU_ACCEPT );
+ }
+ else {
+ printk(("***INFO: ACK'd w/o processing. status = %x\n", scbStatus))
+ return;
+ }
+ }
+ else {
+#ifndef IGNORE_SPURIOUS_IRQ
+ printk(("\n***ERROR: Spurious interrupt (full status 0x%x). Resetting...\n", fullStatus))
+ uti596_softc.nic_reset = 1;
+#endif
+ }
+
+ if ( (scbStatus & SCB_STAT_CX) && !(scbStatus & SCB_STAT_CNA) ) {
+ printk(("\n*****ERROR: Command Complete, and CNA available: 0x%x\nResetting...", scbStatus))
+ uti596_softc.nic_reset = 1;
+ return;
+ }
+
+ if ( !(scbStatus & SCB_STAT_CX) && (scbStatus & SCB_STAT_CNA) ) {
+ printk(("\n*****ERROR: CNA, NO CX:0x%x\nResetting...",scbStatus))
+ uti596_softc.nic_reset = 1;
+ return;
+ }
+
+ if ( scbStatus & SCB_CUS_SUSPENDED ) {
+ printk(("\n*****ERROR: Command unit suspended!:0x%x\nResetting...",scbStatus))
+ uti596_softc.nic_reset = 1;
+ return;
+ }
+
+ if ( scbStatus & RU_SUSPENDED ) {
+ printk(("\n*****ERROR: Receive unit suspended!:0x%x\nResetting...",scbStatus))
+ uti596_softc.nic_reset = 1;
+ return;
+ }
+
+ if ( scbStatus & SCB_STAT_RNR ) {
+ printk(("\n*****WARNING: RNR %x\n",scbStatus))
+ if (uti596_softc.pBeginRFA != I596_NULL) {
+ printk(("*****INFO: RFD cmd: %x status:%x\n", uti596_softc.pBeginRFA->cmd,
+ uti596_softc.pBeginRFA->stat))
+ }
+ else {
+ printk(("*****WARNING: RNR condition with NULL BeginRFA\n"))
+ }
+ }
+
+ /*
+ * Receive Unit Control
+ * a frame is received
+ */
+ if ( scbStatus & SCB_STAT_FR ) {
+ uti596_softc.rxInterrupts++;
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: Frame received\n"))
+ #endif
+ if ( uti596_softc.pBeginRFA == I596_NULL ||
+ !( uti596_softc.pBeginRFA -> stat & STAT_C)) {
+#ifndef IGNORE_NO_RFA
+ uti596_dump_scb();
+ uti596_softc.nic_reset = 1;
+#endif
+ }
+ else {
+ while ( uti596_softc.pBeginRFA != I596_NULL &&
+ ( uti596_softc.pBeginRFA -> stat & STAT_C)) {
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: pBeginRFA != NULL\n"))
+ #endif
+ count_rx ++;
+#ifndef IGNORE_MULTIPLE_RF
+ if ( count_rx > 1) {
+ printk(("****WARNING: Received %i frames on 1 interrupt \n", count_rx))
+ }
+#endif
+ /* Give Received Frame to the ULCS */
+ uti596_softc.countRFD--;
+
+ if ( uti596_softc.countRFD < 0 ) {
+ printk(("ISR: Count < 0 !!! count == %d, beginRFA = %p\n",
+ uti596_softc.countRFD, uti596_softc.pBeginRFA))
+ }
+ uti596_softc.stats.rx_packets++;
+ /* the rfd next link is stored with upper and lower words swapped so read it that way */
+ pIsrRfd = (i596_rfd *) word_swap ((unsigned long)uti596_softc.pBeginRFA->next);
+ /* the append destroys the link */
+ uti596_append( (i596_rfd **)&uti596_softc.pInboundFrameQueue , uti596_softc.pBeginRFA );
+
+ /*
+ * if we have just received the a frame in the last unknown RFD,
+ * then it is certain that the RFA is empty.
+ */
+ if ( uti596_softc.pLastUnkRFD == uti596_softc.pBeginRFA ) {
+ UTI_596_ASSERT(uti596_softc.pLastUnkRFD != I596_NULL,"****ERROR:LastUnk is NULL, begin ptr @ end!\n")
+ uti596_softc.pEndRFA = uti596_softc.pLastUnkRFD = I596_NULL;
+ }
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: Wake %#x\n",uti596_softc.rxDaemonTid))
+ #endif
+ sc = rtems_bsdnet_event_send(uti596_softc.rxDaemonTid, INTERRUPT_EVENT);
+ if ( sc != RTEMS_SUCCESSFUL ) {
+ rtems_panic("Can't notify rxDaemon: %s\n",
+ rtems_status_text (sc));
+ }
+ #ifdef DBG_ISR
+ else {
+ printk(("uti596_DynamicInterruptHandler: Rx Wake: %#x\n",uti596_softc.rxDaemonTid))
+ }
+ #endif
+
+ uti596_softc.pBeginRFA = pIsrRfd;
+ } /* end while */
+ } /* end if */
+
+ if ( uti596_softc.pBeginRFA == I596_NULL ) {
+ /* adjust the pEndRFA to reflect an empty list */
+ if ( uti596_softc.pLastUnkRFD == I596_NULL && uti596_softc.countRFD != 0 ) {
+ printk(("Last Unk is NULL, BeginRFA is null, and count == %d\n",
+ uti596_softc.countRFD))
+ }
+ uti596_softc.pEndRFA = I596_NULL;
+ if ( uti596_softc.countRFD != 0 ) {
+ printk(("****ERROR:Count is %d, but begin ptr is NULL\n",
+ uti596_softc.countRFD ))
+ }
+ }
+ } /* end if ( scbStatus & SCB_STAT_FR ) */
+
+ /*
+ * Command Unit Control
+ * a command is completed
+ */
+ if ( scbStatus & SCB_STAT_CX ) {
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: CU\n"))
+ #endif
+
+ pIsrCmd = uti596_softc.pCmdHead;
+
+ /* For ALL completed commands */
+ if ( pIsrCmd != I596_NULL && pIsrCmd->status & STAT_C ) {
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: pIsrCmd != NULL\n"))
+ #endif
+
+ /* Adjust the command block list */
+ uti596_softc.pCmdHead = (i596_cmd *) word_swap ((unsigned long)pIsrCmd->next);
+
+ /*
+ * If there are MORE commands to process,
+ * the serialization in the raw routine has failed.
+ * ( Perhaps AddCmd is bad? )
+ */
+ UTI_596_ASSERT(uti596_softc.pCmdHead == I596_NULL, "****ERROR: command serialization failed\n")
+
+ /* What if the command did not complete OK? */
+ switch ( pIsrCmd->command & 0x7) {
+ case CmdConfigure:
+
+ uti596_softc.cmdOk = 1;
+ break;
+
+ case CmdDump:
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: dump!\n"))
+ #endif
+ uti596_softc.cmdOk = 1;
+ break;
+
+ case CmdDiagnose:
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: diagnose!\n"))
+ #endif
+ uti596_softc.cmdOk = 1;
+ break;
+
+ case CmdSASetup:
+ /* printk(("****INFO:Set address interrupt\n")) */
+ if ( pIsrCmd -> status & STAT_OK ) {
+ uti596_softc.cmdOk = 1;
+ }
+ else {
+ printk(("****ERROR:SET ADD FAILED\n"))
+ }
+ break;
+
+ case CmdTx:
+ UTI_596_ASSERT(uti596_softc.txDaemonTid, "****ERROR:Null txDaemonTid\n")
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: wake TX:0x%x\n",uti596_softc.txDaemonTid))
+ #endif
+ if ( uti596_softc.txDaemonTid ) {
+ /* Ensure that the transmitter is present */
+ sc = rtems_bsdnet_event_send (uti596_softc.txDaemonTid,
+ INTERRUPT_EVENT);
+
+ if ( sc != RTEMS_SUCCESSFUL ) {
+ printk(("****ERROR:Could NOT send event to tid 0x%" PRIu32 " : %s\n",
+ uti596_softc.txDaemonTid, rtems_status_text (sc) ))
+ }
+ #ifdef DBG_ISR
+ else {
+ printk(("****INFO:Tx wake: %#x\n",uti596_softc.txDaemonTid))
+ }
+ #endif
+ }
+ break;
+
+ case CmdMulticastList:
+ printk(("***ERROR:Multicast?!\n"))
+ pIsrCmd->next = I596_NULL;
+ break;
+
+ case CmdTDR: {
+ unsigned long status = *( (unsigned long *)pIsrCmd)+1;
+ printk(("****ERROR:TDR?!\n"))
+
+ if (status & STAT_C) {
+ /* mark the TDR command successful */
+ uti596_softc.cmdOk = 1;
+ }
+ else {
+ if (status & 0x4000) {
+ printk(("****WARNING:Transceiver problem.\n"))
+ }
+ if (status & 0x2000) {
+ printk(("****WARNING:Termination problem.\n"))
+ }
+ if (status & 0x1000) {
+ printk(("****WARNING:Short circuit.\n"))
+ /* printk(("****INFO:Time %ld.\n", status & 0x07ff)) */
+ }
+ }
+ }
+ break;
+
+ default: {
+ /*
+ * This should never be reached
+ */
+ printk(("CX but NO known command\n"))
+ }
+ } /* end switch */
+
+ pIsrCmd = uti596_softc.pCmdHead; /* next command */
+ if ( pIsrCmd != I596_NULL ) {
+ printk(("****WARNING: more commands in list, but no start to NIC\n"))
+ }
+ } /* end if pIsrCmd != NULL && pIsrCmd->stat & STAT_C */
+
+ else {
+ if ( pIsrCmd != I596_NULL ) {
+ /* The command MAY be NULL from a RESET */
+ /* Reset the ethernet card, and wake the transmitter (if necessary) */
+ printk(("****INFO: Request board reset ( tx )\n"))
+ uti596_softc.nic_reset = 1;
+ if ( uti596_softc.txDaemonTid) {
+ /* Ensure that a transmitter is present */
+ sc = rtems_bsdnet_event_send (uti596_softc.txDaemonTid,
+ INTERRUPT_EVENT);
+ if ( sc != RTEMS_SUCCESSFUL ) {
+ printk(("****ERROR:Could NOT send event to tid 0x%" PRIu32 " : %s\n",
+ uti596_softc.txDaemonTid, rtems_status_text (sc) ))
+ }
+ #ifdef DBG_ISR
+ else {
+ printk(("uti596_DynamicInterruptHandler: ****INFO:Tx wake: %#x\n",
+ uti596_softc.txDaemonTid))
+ }
+ #endif
+ }
+ }
+ }
+ } /* end if command complete */
+
+ /*
+ * If the receiver has stopped,
+ * check if this is a No Resources scenario,
+ * Try to add more RFD's ( no RBDs are used )
+ */
+ if ( uti596_softc.started ) {
+ if ( scbStatus & SCB_STAT_RNR ) {
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: INFO:RNR: status %#x \n",
+ uti596_softc.scb.status ))
+ #endif
+ /*
+ * THE RECEIVER IS OFF!
+ */
+ if ( uti596_softc.pLastUnkRFD != I596_NULL ) {
+ /* We have an unknown RFD, it is not inbound */
+ if ( uti596_softc.pLastUnkRFD -> stat & (STAT_C | STAT_B )) { /* in use */
+ uti596_softc.pEndRFA = uti596_softc.pLastUnkRFD; /* update end */
+ }
+ else {
+ /*
+ * It is NOT in use, and since RNR, we know EL bit of pEndRFA was read!
+ * So, unlink it from the RFA and move it to the saved queue.
+ * But pBegin can equal LastUnk!
+ */
+
+ if ( uti596_softc.pEndRFA != I596_NULL ) {
+ /* check added feb24. */
+ #ifdef DBG_ISR
+ if ((i596_rfd *)word_swap((unsigned long)uti596_softc.pEndRFA->next) != uti596_softc.pLastUnkRFD) {
+ printk(("***ERROR:UNK: %p not end->next: %p, end: %p\n",
+ uti596_softc.pLastUnkRFD,
+ uti596_softc.pEndRFA -> next,
+ uti596_softc.pEndRFA))
+ printk(("***INFO:countRFD now %d\n",
+ uti596_softc.countRFD))
+ printk(("\n\n"))
+ }
+ #endif
+ uti596_softc.pEndRFA -> next = I596_NULL; /* added feb 16 */
+ }
+ uti596_append( (i596_rfd **)&uti596_softc.pSavedRfdQueue, uti596_softc.pLastUnkRFD );
+ uti596_softc.savedCount++;
+ uti596_softc.pEndSavedQueue = uti596_softc.pLastUnkRFD;
+ uti596_softc.countRFD--; /* It was not in the RFA */
+ /*
+ * The Begin pointer CAN advance this far. We must resynch the CPU side
+ * with the chip.
+ */
+ if ( uti596_softc.pBeginRFA == uti596_softc.pLastUnkRFD ) {
+ #ifdef DBG_ISR
+ if ( uti596_softc.countRFD != 0 ) {
+ printk(("****INFO:About to set begin to NULL, with count == %d\n\n",
+ uti596_softc.countRFD ))
+ }
+ #endif
+ uti596_softc.pBeginRFA = I596_NULL;
+ UTI_596_ASSERT(uti596_softc.countRFD == 0, "****ERROR:Count must be zero here!\n")
+ }
+ }
+ uti596_softc.pLastUnkRFD = I596_NULL;
+ } /* end if exists UnkRFD */
+
+ /*
+ * Append the saved queue to the RFA.
+ * Any further RFD's being supplied will be added to
+ * this new list.
+ */
+ if ( uti596_softc.pSavedRfdQueue != I596_NULL ) {
+ /* entries to add */
+ if ( uti596_softc.pBeginRFA == I596_NULL ) {
+ /* add at beginning to list */
+ #ifdef DBG_ISR
+ if(uti596_softc.countRFD != 0) {
+ printk(("****ERROR:Begin pointer is NULL, but count == %d\n",
+ uti596_softc.countRFD))
+ }
+ #endif
+ uti596_softc.pBeginRFA = uti596_softc.pSavedRfdQueue;
+ uti596_softc.pEndRFA = uti596_softc.pEndSavedQueue;
+ uti596_softc.pSavedRfdQueue = uti596_softc.pEndSavedQueue = I596_NULL; /* Reset the End */
+ }
+ else {
+ #ifdef DBG_ISR
+ if ( uti596_softc.countRFD <= 0) {
+ printk(("****ERROR:Begin pointer is not NULL, but count == %d\n",
+ uti596_softc.countRFD))
+ }
+ #endif
+ UTI_596_ASSERT( uti596_softc.pEndRFA != I596_NULL, "****WARNING: END RFA IS NULL\n")
+ UTI_596_ASSERT( uti596_softc.pEndRFA->next == I596_NULL, "****ERROR:END RFA -> next must be NULL\n")
+
+ uti596_softc.pEndRFA->next = (i596_rfd *)word_swap((unsigned long)uti596_softc.pSavedRfdQueue);
+ uti596_softc.pEndRFA->cmd &= ~CMD_EOL; /* clear the end of list */
+ uti596_softc.pEndRFA = uti596_softc.pEndSavedQueue;
+ uti596_softc.pSavedRfdQueue = uti596_softc.pEndSavedQueue = I596_NULL; /* Reset the End */
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: count... %d, saved ... %d \n",
+ uti596_softc.countRFD,
+ uti596_softc.savedCount))
+ #endif
+ }
+ /* printk(("Isr: countRFD = %d\n",uti596_softc.countRFD)) */
+ uti596_softc.countRFD += uti596_softc.savedCount;
+ /* printk(("Isr: after countRFD = %d\n",uti596_softc.countRFD)) */
+ uti596_softc.savedCount = 0;
+ }
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: The list starts here %p\n",uti596_softc.pBeginRFA ))
+ #endif
+
+ if ( uti596_softc.countRFD > 1) {
+ printk(("****INFO: pBeginRFA -> stat = 0x%x\n",uti596_softc.pBeginRFA -> stat))
+ printk(("****INFO: pBeginRFA -> cmd = 0x%x\n",uti596_softc.pBeginRFA -> cmd))
+ uti596_softc.pBeginRFA -> stat = 0;
+ UTI_596_ASSERT(uti596_softc.scb.command == 0, "****ERROR:scb command must be zero\n")
+ uti596_softc.scb.pRfd = uti596_softc.pBeginRFA;
+ uti596_softc.scb.rfd_pointer = word_swap((unsigned long)uti596_softc.pBeginRFA);
+ /* start RX here */
+ printk(("****INFO: ISR Starting receiver\n"))
+ uti596_softc.scb.command = RX_START; /* should this also be CU start? */
+ i82596->chan_attn = 0x00000000;
+ }
+ } /* end stat_rnr */
+ } /* end if receiver started */
+
+ #ifdef DBG_ISR
+ printk(("uti596_DynamicInterruptHandler: X\n"))
+ #endif
+ count_rx=0;
+
+ /* Do this last, to ensure that the reset is called at the right time. */
+ if ( uti596_softc.nic_reset ) {
+ uti596_softc.nic_reset = 0;
+ sc = rtems_bsdnet_event_send(uti596_softc.resetDaemonTid, NIC_RESET_EVENT);
+ if ( sc != RTEMS_SUCCESSFUL )
+ rtems_panic ("Can't notify resetDaemon: %s\n", rtems_status_text (sc));
+ }
+ return;
+}
+
+/***********************************************************************
+ * Function: uti596_ioctl
+ *
+ * Description:
+ * driver ioctl function
+ * handles SIOCGIFADDR, SIOCSIFADDR, SIOCSIFFLAGS
+ *
+ ***********************************************************************/
+
+static int uti596_ioctl(
+ struct ifnet *ifp,
+ u_long command,
+ caddr_t data
+)
+{
+ uti596_softc_ *sc = ifp->if_softc;
+ int error = 0;
+
+ #ifdef DBG_IOCTL
+ printk(("uti596_ioctl: begins\n", sc->pScp))
+ #endif
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ printk(("SIOCSIFADDR\n"))
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ printk(("SIOCSIFFLAGS\n"))
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ printk(("IFF_RUNNING\n"))
+ uti596_stop (sc);
+ break;
+
+ case IFF_UP:
+ printk(("IFF_UP\n"))
+ uti596_init ( (void *)sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ printk(("IFF_UP and RUNNING\n"))
+ uti596_stop (sc);
+ uti596_init ( (void *)sc);
+ break;
+
+ default:
+ printk(("default\n"))
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ printk(("show stats\n"))
+ uti596_stats (sc);
+ break;
+
+ /* FIXME: All sorts of multicast commands need to be added here! */
+ default:
+ printk(("default: EINVAL\n"))
+ error = EINVAL;
+ break;
+ }
+
+ return error;
+}
+
+/***********************************************************************
+ * Function: uti596_stats
+ *
+ * Description:
+ * print out the collected data
+ *
+ * Algorithm:
+ * use printf
+ *
+ ***********************************************************************/
+
+void uti596_stats(
+ uti596_softc_ *sc
+)
+{
+ printf ("CPU Reports:\n");
+ printf (" Tx raw send count:%-8lu", sc->rawsndcnt);
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Tx Interrupts:%-8lu\n", sc->txInterrupts);
+ printf (" Rx Packets:%-8u", sc->stats.rx_packets);
+ printf (" Tx Attempts:%-u\n", sc->stats.tx_packets);
+
+ printf (" Rx Dropped:%-8u", sc->stats.rx_dropped);
+ printf (" Rx IP Packets:%-8u", sc->stats.rx_packets);
+ printf (" Tx Errors:%-8u\n", sc->stats.tx_errors);
+ printf (" Tx aborted:%-8u", sc->stats.tx_aborted_errors);
+ printf (" Tx Dropped:%-8u\n", sc->stats.tx_dropped);
+ printf (" Tx IP packets:%-8u", sc->stats.tx_packets);
+
+ printf (" Collisions Detected:%-8u\n", sc->stats.collisions);
+ printf (" Tx Heartbeat Errors:%-8u", sc->stats.tx_heartbeat_errors);
+ printf (" Tx Carrier Errors:%-8u\n", sc->stats.tx_carrier_errors);
+ printf (" Tx Aborted Errors:%-8u", sc->stats.tx_aborted_errors);
+ printf (" Rx Length Errors:%-8u\n", sc->stats.rx_length_errors);
+ printf (" Rx Overrun Errors:%-8u", sc->stats.rx_over_errors);
+ printf (" Rx Fifo Errors:%-8u\n", sc->stats.rx_fifo_errors);
+ printf (" Rx Framing Errors:%-8u", sc->stats.rx_frame_errors);
+ printf (" Rx crc errors:%-8u\n", sc->stats.rx_crc_errors);
+
+ printf (" TX WAITS: %-8lu\n", sc->txRawWait);
+
+ printf (" NIC resets: %-8u\n", sc->stats.nic_reset_count);
+
+ printf (" NIC reports\n");
+
+ #ifdef DBG_STAT
+ uti596_dump_scb();
+ #endif
+}
+
+/************************ PACKET DEBUG ROUTINES ************************/
+
+#ifdef DBG_PACKETS
+
+/*
+ * dumpQ
+ *
+ * Dumps frame queues for debugging
+ */
+static void dumpQ( void )
+{
+ i596_rfd *pRfd;
+
+ printk(("savedQ:\n"))
+
+ for( pRfd = uti596_softc.pSavedRfdQueue;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd*)word_swap((uint32_t)pRfd -> next)) {
+ printk(("pRfd: %p, stat: 0x%x cmd: 0x%x\n",pRfd,pRfd -> stat,pRfd -> cmd))
+ }
+
+ printk(("Inbound:\n"))
+
+ for( pRfd = uti596_softc.pInboundFrameQueue;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd*)word_swap((uint32_t)pRfd -> next)) {
+ printk(("pRfd: %p, stat: 0x%x cmd: 0x%x\n",pRfd,pRfd -> stat,pRfd -> cmd))
+ }
+
+ printk(("Last Unk: %p\n", uti596_softc.pLastUnkRFD ))
+ printk(("RFA:\n"))
+
+ for( pRfd = uti596_softc.pBeginRFA;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd*)word_swap((uint32_t)pRfd -> next)) {
+ printk(("pRfd: %p, stat: 0x%x cmd: 0x%x\n",pRfd,pRfd -> stat,pRfd -> cmd))
+ }
+}
+
+/*
+ * show_buffers
+ *
+ * Print out the RFA and frame queues
+ */
+static void show_buffers (void)
+{
+ i596_rfd *pRfd;
+
+ printk(("82596 cmd: 0x%x, status: 0x%x RFA len: %d\n",
+ uti596_softc.scb.command,
+ uti596_softc.scb.status,
+ uti596_softc.countRFD))
+
+ printk(("\nRFA: \n"))
+
+ for ( pRfd = uti596_softc.pBeginRFA;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd *)word_swap((uint32_t)pRfd->next) ) {
+ printk(("Frame @ %p, status: %2.2x, cmd: %2.2x\n",
+ pRfd, pRfd->stat, pRfd->cmd))
+ }
+ printk(("\nInbound: \n"))
+
+ for ( pRfd = uti596_softc.pInboundFrameQueue;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd *)word_swap((uint32_t)pRfd->next) ) {
+ printk(("Frame @ %p, status: %2.2x, cmd: %2.2x\n",
+ pRfd, pRfd->stat, pRfd->cmd))
+ }
+
+ printk(("\nSaved: \n"))
+
+ for ( pRfd = uti596_softc.pSavedRfdQueue;
+ pRfd != I596_NULL;
+ pRfd = (i596_rfd *)word_swap((uint32_t)pRfd->next) ) {
+ printk(("Frame @ %p, status: %2.2x, cmd: %2.2x\n",
+ pRfd, pRfd->stat, pRfd->cmd))
+ }
+
+ printk(("\nUnknown: %p\n",uti596_softc.pLastUnkRFD))
+}
+
+/*
+ * show_queues
+ *
+ * Print out the saved frame queue and the RFA
+ */
+static void show_queues(void)
+{
+ i596_rfd *pRfd;
+
+ printk(("CMD: 0x%x, Status: 0x%x\n",
+ uti596_softc.scb.command,
+ uti596_softc.scb.status))
+ printk(("saved Q\n"))
+
+ for ( pRfd = uti596_softc.pSavedRfdQueue;
+ pRfd != I596_NULL &&
+ pRfd != NULL;
+ pRfd = (i596_rfd *)word_swap((uint32_t)pRfd->next) ) {
+ printk(("0x%p\n", pRfd))
+ }
+
+ printk(("End saved Q 0x%p\n", uti596_softc.pEndSavedQueue))
+
+ printk(("\nRFA:\n"))
+
+ for ( pRfd = uti596_softc.pBeginRFA;
+ pRfd != I596_NULL &&
+ pRfd != NULL;
+ pRfd = (i596_rfd *)word_swap((uint32_t)pRfd->next) ) {
+ printk(("0x%p\n", pRfd))
+ }
+
+ printk(("uti596_softc.pEndRFA: %p\n",uti596_softc.pEndRFA))
+}
+
+/*
+ * print_eth
+ *
+ * Print the contents of an ethernet packet
+ * CANNOT BE CALLED FROM ISR
+ */
+static void print_eth(
+ unsigned char *add
+)
+{
+ int i;
+ short int length;
+
+ printk (("Packet Location %p\n", add))
+ printk (("Dest "))
+
+ for (i = 0; i < 6; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+ printk (("\n"))
+ printk (("Source"))
+
+ for (i = 6; i < 12; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+
+ printk (("\n"))
+ printk (("frame type %2.2X%2.2X\n", add[12], add[13]))
+
+ if ( add[12] == 0x08 && add[13] == 0x06 ) {
+ /* an ARP */
+ printk (("Hardware type : %2.2X%2.2X\n", add[14],add[15]))
+ printk (("Protocol type : %2.2X%2.2X\n", add[16],add[17]))
+ printk (("Hardware size : %2.2X\n", add[18]))
+ printk (("Protocol size : %2.2X\n", add[19]))
+ printk (("op : %2.2X%2.2X\n", add[20],add[21]))
+ printk (("Sender Enet addr: "))
+
+ for ( i=0; i< 5 ; i++) {
+ printk (("%x:", add[22 + i]))
+ }
+ printk (("%x\n", add[27]))
+ printk (("Sender IP addr: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[28 + i]))
+ }
+ printk (("%u\n", add[31]))
+ printk (("Target Enet addr: "))
+
+ for ( i=0; i< 5 ; i++) {
+ printk (( "%x:", add[32 + i]))
+ }
+ printk (("%x\n", add[37]))
+ printk (("Target IP addr: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (( "%u.", add[38 + i]))
+ }
+ printk (("%u\n", add[41]))
+ }
+
+ if ( add[12] == 0x08 && add[13] == 0x00 ) {
+ /* an IP packet */
+ printk (("*********************IP HEADER******************\n"))
+ printk (("IP version/IPhdr length: %2.2X TOS: %2.2X\n", add[14] , add[15]))
+ printk (("IP total length: %2.2X %2.2X, decimal %d\n", add[16], add[17], length = (add[16]<<8 | add[17] )))
+ printk (("IP identification: %2.2X %2.2X, 3-bit flags and offset %2.2X %2.2X\n",
+ add[18],add[19], add[20], add[21]))
+ printk (("IP TTL: %2.2X, protocol: %2.2X, checksum: %2.2X %2.2X \n",
+ add[22],add[23],add[24],add[25]))
+ printk (("IP packet type: %2.2X code %2.2X\n", add[34],add[35]))
+ printk (("Source IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[26 + i]))
+ }
+ printk (("%u\n", add[29]))
+ printk (("Destination IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[30 + i]))
+ }
+ printk (("%u\n", add[33]))
+ }
+}
+
+/*
+ * print_hdr
+ *
+ * Print the contents of an ethernet packet header
+ * CANNOT BE CALLED FROM ISR
+ */
+static void print_hdr(
+ unsigned char *add
+)
+{
+ int i;
+
+ printk (("print_hdr: begins\n"))
+ printk (("Header Location %p\n", add))
+ printk (("Dest "))
+
+ for (i = 0; i < 6; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+ printk (("\nSource"))
+
+ for (i = 6; i < 12; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+ printk (("\nframe type %2.2X%2.2X\n", add[12], add[13]))
+ printk (("print_hdr: completed"))
+}
+
+/*
+ * Function: print_pkt
+ *
+ * Print the contents of an ethernet packet & data
+ * CANNOT BE CALLED FROM ISR
+ */
+static void print_pkt(
+ unsigned char *add
+)
+{
+ int i;
+ short int length;
+
+ printk (("print_pkt: begins"))
+ printk (("Data Location %p\n", add))
+
+ if ( add[0] == 0x08 && add[1] == 0x06 ) {
+ /* an ARP */
+ printk (("Hardware type : %2.2X%2.2X\n", add[14],add[15]))
+ printk (("Protocol type : %2.2X%2.2X\n", add[16],add[17]))
+ printk (("Hardware size : %2.2X\n", add[18]))
+ printk (("Protocol size : %2.2X\n", add[19]))
+ printk (("op : %2.2X%2.2X\n", add[20],add[21]))
+ printk (("Sender Enet addr: "))
+
+ for ( i=0; i< 5 ; i++) {
+ printk (( "%x:", add[22 + i]))
+ }
+ printk (("%x\n", add[27]))
+ printk (("Sender IP addr: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[28 + i]))
+ }
+ printk (("%u\n", add[31]))
+ printk (("Target Enet addr: "))
+
+ for ( i=0; i< 5 ; i++) {
+ printk (( "%x:", add[32 + i]))
+ }
+ printk (("%x\n", add[37]))
+ printk (("Target IP addr: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (( "%u.", add[38 + i]))
+ }
+ printk (("%u\n", add[41]))
+ }
+
+ if ( add[0] == 0x08 && add[1] == 0x00 ) {
+ /* an IP packet */
+ printk (("*********************IP HEADER******************\n"))
+ printk (("IP version/IPhdr length: %2.2X TOS: %2.2X\n", add[14] , add[15]))
+ printk (("IP total length: %2.2X %2.2X, decimal %d\n", add[16], add[17], length = (add[16]<<8 | add[17] )))
+ printk (("IP identification: %2.2X %2.2X, 3-bit flags and offset %2.2X %2.2X\n",
+ add[18],add[19], add[20], add[21]))
+ printk (("IP TTL: %2.2X, protocol: %2.2X, checksum: %2.2X %2.2X \n",
+ add[22],add[23],add[24],add[25]))
+ printk (("IP packet type: %2.2X code %2.2X\n", add[34],add[35]))
+ printk (("Source IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk(( "%u.", add[26 + i]))
+ }
+ printk(("%u\n", add[29]))
+ printk(("Destination IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk(( "%u.", add[30 + i]))
+ }
+ printk(("%u\n", add[33]))
+ printk(("********************IP Packet Data*******************\n"))
+ length -=20;
+
+ for ( i=0; i < length ; i++) {
+ printk(("0x%2.2x ", add[34+i]))
+ }
+ printk(("\n"))
+ printk(("ICMP checksum: %2.2x %2.2x\n", add[36], add[37]))
+ printk(("ICMP identifier: %2.2x %2.2x\n", add[38], add[39]))
+ printk(("ICMP sequence nbr: %2.2x %2.2x\n", add[40], add[41]))
+ printk(("print_pkt: completed"))
+ }
+}
+
+/*
+ * print_echo
+ *
+ * Print the contents of an echo packet
+ * CANNOT BE CALLED FROM ISR
+ */
+static void print_echo(
+ unsigned char *add
+)
+{
+ int i;
+ short int length;
+
+ printk (("print_echo: begins"))
+
+ if ( add[12] == 0x08 && add[13] == 0x00 ) {
+ /* an IP packet */
+ printk (("Packet Location %p\n", add))
+ printk (("Dest "))
+
+ for (i = 0; i < 6; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+ printk (("\n"))
+ printk (("Source"))
+
+ for (i = 6; i < 12; i++) {
+ printk ((" %2.2X", add[i]))
+ }
+ printk (("\n"))
+ printk (("frame type %2.2X%2.2X\n", add[12], add[13]))
+
+ printk (("*********************IP HEADER******************\n"))
+ printk (("IP version/IPhdr length: %2.2X TOS: %2.2X\n", add[14] , add[15]))
+ printk (("IP total length: %2.2X %2.2X, decimal %d\n", add[16], add[17], length = (add[16]<<8 | add[17] )))
+ printk (("IP identification: %2.2X %2.2X, 3-bit flags and offset %2.2X %2.2X\n",
+ add[18],add[19], add[20], add[21]))
+ printk (("IP TTL: %2.2X, protocol: %2.2X, checksum: %2.2X %2.2X \n",
+ add[22],add[23],add[24],add[25]))
+ printk (("IP packet type: %2.2X code %2.2X\n", add[34],add[35]))
+ printk (("Source IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[26 + i]))
+ }
+ printk (("%u\n", add[29]))
+ printk (("Destination IP address: "))
+
+ for ( i=0; i< 3 ; i++) {
+ printk (("%u.", add[30 + i]))
+ }
+ printk (("%u\n", add[33]))
+ printk(("********************IP Packet Data*******************\n"))
+ length -=20;
+
+ for ( i=0; i < length ; i++) {
+ printk(("0x%2.2x ", add[34+i]))
+ }
+ printk(("\n"))
+ printk(("ICMP checksum: %2.2x %2.2x\n", add[36], add[37]))
+ printk(("ICMP identifier: %2.2x %2.2x\n", add[38], add[39]))
+ printk(("ICMP sequence nbr: %2.2x %2.2x\n", add[40], add[41]))
+ printk(("print_echo: completed"))
+ }
+}
+
+#endif
diff --git a/bsps/m68k/mvme167/net/uti596.h b/bsps/m68k/mvme167/net/uti596.h
new file mode 100644
index 0000000..29e4fed
--- /dev/null
+++ b/bsps/m68k/mvme167/net/uti596.h
@@ -0,0 +1,369 @@
+/* uti596.h: Contains the defines and structures used by the uti596 driver */
+
+/*
+ * EII: March 11: Created v. 0.0
+ */
+
+#ifndef UTI596_H
+#define UTI596_H
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+/* Ethernet statistics */
+
+struct enet_statistics{
+ int rx_packets; /* total packets received */
+ int tx_packets; /* total packets transmitted */
+ int rx_errors; /* bad packets received */
+ int tx_errors; /* packet transmit problems */
+ int rx_dropped; /* no space in buffers */
+ int tx_dropped;
+ int tx_retries_exceeded; /* excessive retries */
+ int multicast; /* multicast packets received */
+ int collisions;
+
+ /* detailed rx_errors: */
+ int rx_length_errors;
+ int rx_over_errors; /* receiver ring buff overflow */
+ int rx_crc_errors; /* recved pkt with crc error */
+ int rx_frame_errors; /* recv'd frame alignment error */
+ int rx_fifo_errors; /* recv'r fifo overrun */
+ int rx_missed_errors; /* receiver missed packet */
+
+ /* detailed tx_errors */
+ int tx_aborted_errors;
+ int tx_carrier_errors;
+ int tx_fifo_errors;
+ int tx_heartbeat_errors;
+ int tx_window_errors;
+
+ /* NIC reset errors */
+ int nic_reset_count; /* The number of times uti596reset() has been called. */
+};
+
+#define CMD_EOL 0x8000 /* The last command of the list, stop. */
+#define CMD_SUSP 0x4000 /* Suspend after doing cmd. */
+#define CMD_INTR 0x2000 /* Interrupt after doing cmd. */
+
+#define CMD_FLEX 0x0008 /* Enable flexible memory model */
+
+#define SCB_STAT_CX 0x8000 /* Cmd completes with 'I' bit set */
+#define SCB_STAT_FR 0x4000 /* Frame Received */
+#define SCB_STAT_CNA 0x2000 /* Cmd unit Not Active */
+#define SCB_STAT_RNR 0x1000 /* Receiver Not Ready */
+
+#define SCB_CUS_SUSPENDED 0x0100
+#define SCB_CUS_ACTIVE 0x0200
+
+#define STAT_C 0x8000 /* Set to 1 after execution */
+#define STAT_B 0x4000 /* 1 : Cmd being executed, 0 : Cmd done. */
+#define STAT_OK 0x2000 /* 1: Command executed ok 0 : Error */
+#define STAT_A 0x1000 /* command has been aborted */
+
+#define STAT_S11 0x0800
+#define STAT_S10 0x0400
+#define STAT_S9 0x0200
+#define STAT_S8 0x0100
+#define STAT_S7 0x0080
+#define STAT_S6 0x0040
+#define STAT_S5 0x0020
+#define STAT_MAX_COLLS 0x000F
+
+#define RBD_STAT_P 0x4000 /* prefetch */
+#define RBD_STAT_F 0x4000 /* used */
+
+#define CUC_START 0x0100
+#define CUC_RESUME 0x0200
+#define CUC_SUSPEND 0x0300
+#define CUC_ABORT 0x0400
+#define RX_START 0x0010
+#define RX_RESUME 0x0020
+#define RX_SUSPEND 0x0030
+#define RX_ABORT 0x0040
+
+#define RU_SUSPENDED 0x0010
+#define RU_NO_RESOURCES 0x0020
+#define RU_READY 0x0040
+
+#define I596_NULL ( ( void * ) 0xffffffff)
+#define UTI_596_END_OF_FRAME 0x8000
+
+struct i596_tbd; /* necessary forward declaration */
+
+enum commands {
+ CmdNOp = 0,
+ CmdSASetup = 1,
+ CmdConfigure = 2,
+ CmdMulticastList = 3,
+ CmdTx = 4,
+ CmdTDR = 5,
+ CmdDump = 6,
+ CmdDiagnose = 7
+};
+
+/*
+ * 82596 Dump Command Result
+ */
+typedef volatile struct i596_dump_result {
+ unsigned char bf;
+ unsigned char config_bytes[11];
+ unsigned char reserved1[2];
+ unsigned char ia_bytes[6];
+ unsigned short last_tx_status;
+ unsigned short tx_crc_byte01;
+ unsigned short tx_crc_byte23;
+ unsigned short rx_crc_byte01;
+ unsigned short rx_crc_byte23;
+ unsigned short rx_temp_mem01;
+ unsigned short rx_temp_mem23;
+ unsigned short rx_temp_mem45;
+ unsigned short last_rx_status;
+ unsigned short hash_reg01;
+ unsigned short hash_reg23;
+ unsigned short hash_reg45;
+ unsigned short hash_reg67;
+ unsigned short slot_time_counter;
+ unsigned short wait_time_counter;
+ unsigned short rx_frame_length;
+ unsigned long reserved2;
+ unsigned long cb_in3;
+ unsigned long cb_in2;
+ unsigned long cb_in1;
+ unsigned long la_cb_addr;
+ unsigned long rdb_pointer;
+ unsigned long int_memory;
+ unsigned long rfd_size;
+ unsigned long tbd_pointer;
+ unsigned long base_addr;
+ unsigned long ru_temp_reg;
+ unsigned long tcb_count;
+ unsigned long next_rb_size;
+ unsigned long next_rb_addr;
+ unsigned long curr_rb_size;
+ unsigned long la_rbd_addr;
+ unsigned long next_rbd_addr;
+ unsigned long curr_rbd_addr;
+ unsigned long curr_rb_count;
+ unsigned long next_fd_addr;
+ unsigned long curr_fd_add;
+ unsigned long temp_cu_reg;
+ unsigned long next_tb_count;
+ unsigned long buffer_addr;
+ unsigned long la_tbd_addr;
+ unsigned long next_tbd_addr;
+ unsigned long cb_command;
+ unsigned long next_cb_addr;
+ unsigned long curr_cb_addr;
+ unsigned long scb_cmd_word;
+ unsigned long scb_pointer;
+ unsigned long cb_stat_word;
+ unsigned long mm_lfsr;
+ unsigned char micro_machine_bit_array[28];
+ unsigned char cu_port[16];
+ unsigned long mm_alu;
+ unsigned long reserved3;
+ unsigned long mm_temp_a_rr;
+ unsigned long mm_temp_a;
+ unsigned long tx_dma_b_cnt;
+ unsigned long mm_input_port_addr_reg;
+ unsigned long tx_dma_addr;
+ unsigned long mm_port_reg1;
+ unsigned long rx_dma_b_cnt;
+ unsigned long mm_port_reg2;
+ unsigned long rx_dma_addr;
+ unsigned long reserved4;
+ unsigned long bus_t_timers;
+ unsigned long diu_cntrl_reg;
+ unsigned long reserved5;
+ unsigned long sysbus;
+ unsigned long biu_cntrl_reg;
+ unsigned long mm_disp_reg;
+ unsigned long mm_status_reg;
+ unsigned short dump_status;
+} i596_dump_result;
+
+typedef volatile struct i596_selftest {
+ unsigned long rom_signature;
+ unsigned long results;
+} i596_selftest;
+
+/*
+ * Action commands
+ * (big endian, linear mode)
+ */
+typedef volatile struct i596_cmd {
+ unsigned short status;
+ unsigned short command;
+ volatile struct i596_cmd *next;
+} i596_cmd;
+
+typedef volatile struct i596_nop {
+ i596_cmd cmd;
+} i596_nop;
+
+typedef volatile struct i596_set_add {
+ i596_cmd cmd;
+ char data[8];
+} i596_set_add;
+
+typedef volatile struct i596_configure {
+ i596_cmd cmd;
+ char data[16];
+} i596_configure;
+
+typedef volatile struct i596_tx {
+ i596_cmd cmd;
+ volatile struct i596_tbd *pTbd;
+ unsigned short count;
+ unsigned short pad;
+ char data[6];
+ unsigned short length;
+} i596_tx;
+
+typedef volatile struct i596_tdr {
+ i596_cmd cmd;
+ unsigned long data;
+} i596_tdr;
+
+typedef volatile struct i596_dump {
+ i596_cmd cmd;
+ char *pData;
+} i596_dump;
+
+/*
+ * Transmit buffer descriptor
+ */
+typedef volatile struct i596_tbd {
+ unsigned short size;
+ unsigned short pad;
+ volatile struct i596_tbd *next;
+ char *data;
+} i596_tbd;
+
+/*
+ * Receive buffer descriptor
+ * (flexible memory structure)
+ */
+typedef volatile struct i596_rbd {
+ unsigned short count;
+ unsigned short offset;
+ volatile struct i596_rbd *next;
+ char *data;
+ unsigned short size;
+ unsigned short pad;
+} i596_rbd;
+
+/*
+ * Receive Frame Descriptor
+ */
+typedef volatile struct i596_rfd {
+ unsigned short stat;
+ unsigned short cmd;
+ volatile struct i596_rfd *next;
+ i596_rbd *pRbd;
+ unsigned short count;
+ unsigned short size;
+ char data [1532];
+} i596_rfd;
+
+/*
+ * System Control Block
+ */
+typedef volatile struct i596_scb {
+ unsigned short status;
+ unsigned short command;
+ unsigned long cmd_pointer;
+ unsigned long rfd_pointer;
+ unsigned long crc_err;
+ unsigned long align_err;
+ unsigned long resource_err;
+ unsigned long over_err;
+ unsigned long rcvdt_err;
+ unsigned long short_err;
+ unsigned short t_off;
+ unsigned short t_on;
+ i596_cmd *pCmd;
+ i596_rfd *pRfd;
+} i596_scb;
+
+/*
+ * Intermediate System Configuration Pointer
+ */
+typedef volatile struct i596_iscp {
+ uint8_t null1; /* Always zero */
+ uint8_t busy; /* Busy byte */
+ unsigned short scb_offset; /* Not used in linear mode */
+ unsigned long scb_pointer; /* Swapped pointer to scb */
+ i596_scb *scb; /* Real pointer to scb */
+} i596_iscp;
+
+/*
+ * System Configuration Pointer
+ */
+typedef volatile struct i596_scp {
+ unsigned long sysbus; /* Only low 8 bits are used */
+ unsigned long pad; /* Must be zero */
+ unsigned long iscp_pointer; /* Swapped pointer to iscp */
+ i596_iscp *iscp; /* Real pointer to iscp */
+} i596_scp;
+
+/*
+ * Device Dependent Data Structure
+ */
+typedef volatile struct uti596_softc {
+ struct arpcom arpcom;
+ i596_scp *pScp; /* Block aligned on 16 byte boundary */
+ i596_scp *base_scp; /* Unaligned block. Need for free() */
+ i596_iscp iscp;
+ i596_scb scb;
+ i596_set_add set_add;
+ i596_configure set_conf;
+ i596_tdr tdr;
+ i596_nop nop;
+ i596_tx *pTxCmd;
+ i596_tbd *pTbd;
+
+ i596_rfd *pBeginRFA;
+ i596_rfd *pEndRFA;
+ i596_rfd *pLastUnkRFD;
+ i596_rbd *pLastUnkRBD;
+ i596_rfd *pEndSavedQueue;
+ i596_cmd *pCmdHead;
+ i596_cmd *pCmdTail; /* unneeded, as chaining not used, but implemented */
+
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+ rtems_id resetDaemonTid;
+
+ struct enet_statistics stats;
+ int started;
+ unsigned long rxInterrupts;
+ unsigned long txInterrupts;
+ volatile int cmdOk;
+ unsigned short * pCurrent_command_status;
+ int resetDone;
+ unsigned long txRawWait;
+ i596_rfd *pInboundFrameQueue;
+ short int rxBdCount;
+ short int txBdCount;
+ short int countRFD;
+ short int savedCount;
+ i596_rfd *pSavedRfdQueue;
+ rtems_name semaphore_name;
+ rtems_id semaphore_id;
+ char zeroes[64];
+ unsigned long rawsndcnt;
+ int nic_reset; /* flag for requesting that ISR issue a reset quest */
+} uti596_softc_;
+
+#endif /* UTI596_H */
diff --git a/bsps/m68k/uC5282/net/network.c b/bsps/m68k/uC5282/net/network.c
new file mode 100644
index 0000000..49ce98a
--- /dev/null
+++ b/bsps/m68k/uC5282/net/network.c
@@ -0,0 +1,1013 @@
+/*
+ * RTEMS driver for MCF5282 Fast Ethernet Controller
+ *
+ * Author: W. Eric Norum <norume@aps.anl.gov>
+ *
+ * COPYRIGHT (c) 2005.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <string.h>
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/ethernet.h>
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+#define FEC_INTC0_TX_VECTOR (64+23)
+#define FEC_INTC0_RX_VECTOR (64+27)
+#define MII_VECTOR (64+7) /* IRQ7* pin connected to external transceiver */
+#define MII_EPPAR MCF5282_EPORT_EPPAR_EPPA7_LEVEL
+#define MII_EPDDR MCF5282_EPORT_EPDDR_EPDD7
+#define MII_EPIER MCF5282_EPORT_EPIER_EPIE7
+#define MII_EPPDR MCF5282_EPORT_EPPDR_EPPD7
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses three or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 20
+#define TX_BD_PER_BUF 3
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define TX_INTERRUPT_EVENT RTEMS_EVENT_1
+#define RX_INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+ #error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+/*
+ * Per-device data
+ */
+struct mcf5282_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ mcf5282BufferDescriptor_t *rxBdBase;
+ mcf5282BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long txInterrupts;
+ unsigned long miiInterrupts;
+ unsigned long txRawWait;
+ unsigned long txRealign;
+ unsigned long txRealignDrop;
+
+ /*
+ * Link parameters
+ */
+ enum { link_auto, link_100Full, link_10Half } link;
+ uint16_t mii_cr;
+ uint16_t mii_sr2;
+};
+static struct mcf5282_enet_struct enet_driver[NIFACES];
+
+/*
+ * Read MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static int
+getMII(int phyNumber, int regNumber)
+{
+ MCF5282_FEC_MMFR = (0x1 << 30) |
+ (0x2 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16);
+ while ((MCF5282_FEC_EIR & MCF5282_FEC_EIR_MII) == 0);
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_MII;
+ return MCF5282_FEC_MMFR & 0xFFFF;
+}
+
+/*
+ * Write MII register
+ * Busy-waits, but transfer time should be short!
+ */
+static void
+setMII(int phyNumber, int regNumber, int value)
+{
+ MCF5282_FEC_MMFR = (0x1 << 30) |
+ (0x1 << 28) |
+ (phyNumber << 23) |
+ (regNumber << 18) |
+ (0x2 << 16) |
+ (value & 0xFFFF);
+ while ((MCF5282_FEC_EIR & MCF5282_FEC_EIR_MII) == 0);
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_MII;
+}
+
+static rtems_isr
+mcf5282_fec_rx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_RXF;
+ MCF5282_FEC_EIMR &= ~MCF5282_FEC_EIMR_RXF;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].rxDaemonTid, RX_INTERRUPT_EVENT);
+}
+
+static rtems_isr
+mcf5282_fec_tx_interrupt_handler( rtems_vector_number v )
+{
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_TXF;
+ MCF5282_FEC_EIMR &= ~MCF5282_FEC_EIMR_TXF;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send(enet_driver[0].txDaemonTid, TX_INTERRUPT_EVENT);
+}
+
+static rtems_isr
+mcf5282_mii_interrupt_handler( rtems_vector_number v )
+{
+ uint16 sr2;
+
+ enet_driver[0].miiInterrupts++;
+ getMII(1, 19); /* Read and clear interrupt status bits */
+ enet_driver[0].mii_sr2 = sr2 = getMII(1, 17);
+ if (((sr2 & 0x200) != 0)
+ && ((MCF5282_FEC_TCR & MCF5282_FEC_TCR_FDEN) == 0))
+ MCF5282_FEC_TCR |= MCF5282_FEC_TCR_FDEN;
+ else if (((sr2 & 0x200) == 0)
+ && ((MCF5282_FEC_TCR & MCF5282_FEC_TCR_FDEN) != 0))
+ MCF5282_FEC_TCR &= ~MCF5282_FEC_TCR_FDEN;
+}
+
+/*
+ * Allocate buffer descriptors from (non-cached) on-chip static RAM
+ * Ensure 128-bit (16-byte) alignment
+ * Allow some space at the beginning for other diagnostic counters
+ */
+static mcf5282BufferDescriptor_t *
+mcf5282_bd_allocate(unsigned int count)
+{
+ static mcf5282BufferDescriptor_t *bdp = __SRAMBASE.fec_descriptors;
+ mcf5282BufferDescriptor_t *p = bdp;
+
+ bdp += count;
+ if ((int)bdp & 0xF)
+ bdp = (mcf5282BufferDescriptor_t *)((char *)bdp + (16 - ((int)bdp & 0xF)));
+ return p;
+}
+
+static void
+mcf5282_fec_initialize_hardware(struct mcf5282_enet_struct *sc)
+{
+ int i;
+ const unsigned char *hwaddr;
+ rtems_status_code status;
+ rtems_isr_entry old_handler;
+ uint32_t clock_speed = bsp_get_CPU_clock_speed();
+
+ /*
+ * Issue reset to FEC
+ */
+ MCF5282_FEC_ECR = MCF5282_FEC_ECR_RESET;
+ rtems_task_wake_after(2);
+ MCF5282_FEC_ECR = 0;
+
+ /*
+ * Configuration of I/O ports is done outside of this function
+ */
+#if 0
+ imm->gpio.pbcnt |= MCF5282_GPIO_PBCNT_SET_FEC; /* Set up port b FEC pins */
+#endif
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+ MCF5282_FEC_PALR = (hwaddr[0] << 24) | (hwaddr[1] << 16) |
+ (hwaddr[2] << 8) | (hwaddr[3] << 0);
+ MCF5282_FEC_PAUR = (hwaddr[4] << 24) | (hwaddr[5] << 16);
+
+
+ /*
+ * Clear the hash table
+ */
+ MCF5282_FEC_GAUR = 0;
+ MCF5282_FEC_GALR = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ MCF5282_FEC_EMRBR = 1520; /* Standard Ethernet */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc(sc->rxBdCount * sizeof *sc->rxMbuf, M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc(sc->txBdCount * sizeof *sc->txMbuf, M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = mcf5282_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = mcf5282_bd_allocate(sc->txBdCount);
+ MCF5282_FEC_ERDSR = (int)sc->rxBdBase;
+ MCF5282_FEC_ETDSR = (int)sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous
+ * MII mode
+ * Full duplex
+ * No loopback
+ */
+ MCF5282_FEC_RCR = MCF5282_FEC_RCR_MAX_FL(MAX_MTU_SIZE) |
+ MCF5282_FEC_RCR_MII_MODE;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full or half duplex
+ * No heartbeat
+ */
+ if (sc->link == link_10Half)
+ MCF5282_FEC_TCR = 0;
+ else
+ MCF5282_FEC_TCR = MCF5282_FEC_TCR_FDEN;
+
+ /*
+ * Initialize statistic counters
+ */
+ MCF5282_FEC_MIBC = MCF5282_FEC_MIBC_MIB_DISABLE;
+ {
+ vuint32 *vuip = &MCF5282_FEC_RMON_T_DROP;
+ while (vuip <= &MCF5282_FEC_IEEE_R_OCTETS_OK)
+ *vuip++ = 0;
+ }
+ MCF5282_FEC_MIBC = 0;
+
+ /*
+ * Set MII speed to <= 2.5 MHz
+ */
+ i = (clock_speed + 5000000 - 1) / 5000000;
+ MCF5282_FEC_MSCR = MCF5282_FEC_MSCR_MII_SPEED(i);
+
+ /*
+ * Set PHYS
+ * LED1 receive status, LED2 link status, LEDs stretched
+ * Advertise 100 Mb/s, full-duplex, IEEE-802.3
+ * Turn off auto-negotiate
+ * Clear status
+ */
+ setMII(1, 20, 0x24F2);
+ setMII(1, 4, 0x0181);
+ setMII(1, 0, 0x0);
+ rtems_task_wake_after(2);
+ sc->mii_sr2 = getMII(1, 17);
+ switch (sc->link) {
+ case link_auto:
+ /*
+ * Enable speed-change, duplex-change and link-status-change interrupts
+ * Enable auto-negotiate (start at 100/FULL)
+ */
+ setMII(1, 18, 0x0072);
+ setMII(1, 0, 0x3100);
+ break;
+
+ case link_10Half:
+ /*
+ * Force 10/HALF
+ */
+ setMII(1, 0, 0x0);
+ break;
+
+ case link_100Full:
+ /*
+ * Force 100/FULL
+ */
+ setMII(1, 0, 0x2100);
+ break;
+ }
+ sc->mii_cr = getMII(1, 0);
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ sc->txBdBase[i].status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Set up interrupts
+ */
+ status = rtems_interrupt_catch( mcf5282_fec_tx_interrupt_handler, FEC_INTC0_TX_VECTOR, &old_handler );
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC TX interrupt handler: %s\n",
+ rtems_status_text(status));
+ bsp_allocate_interrupt(FEC_IRQ_LEVEL, FEC_IRQ_TX_PRIORITY);
+ MCF5282_INTC0_ICR23 = MCF5282_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5282_INTC_ICR_IP(FEC_IRQ_TX_PRIORITY);
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT23 | MCF5282_INTC_IMRL_MASKALL);
+
+ status = rtems_interrupt_catch(mcf5282_fec_rx_interrupt_handler, FEC_INTC0_RX_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC RX interrupt handler: %s\n",
+ rtems_status_text(status));
+ bsp_allocate_interrupt(FEC_IRQ_LEVEL, FEC_IRQ_RX_PRIORITY);
+ MCF5282_INTC0_ICR27 = MCF5282_INTC_ICR_IL(FEC_IRQ_LEVEL) |
+ MCF5282_INTC_ICR_IP(FEC_IRQ_RX_PRIORITY);
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT27 | MCF5282_INTC_IMRL_MASKALL);
+
+ status = rtems_interrupt_catch(mcf5282_mii_interrupt_handler, MII_VECTOR, &old_handler);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_panic ("Can't attach MCF5282 FEC MII interrupt handler: %s\n",
+ rtems_status_text(status));
+ MCF5282_EPORT_EPPAR &= ~MII_EPPAR;
+ MCF5282_EPORT_EPDDR &= ~MII_EPDDR;
+ MCF5282_EPORT_EPIER |= MII_EPIER;
+ MCF5282_INTC0_IMRL &= ~(MCF5282_INTC_IMRL_INT7 | MCF5282_INTC_IMRL_MASKALL);
+}
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ */
+static void
+fec_retire_tx_bd(volatile struct mcf5282_enet_struct *sc )
+{
+ struct mbuf *m, *n;
+ uint16_t status;
+
+ while ((sc->txBdActiveCount != 0)
+ && (((status = sc->txBdBase[sc->txBdTail].status) & MCF5282_FEC_TxBD_R) == 0)) {
+ if ((status & MCF5282_FEC_TxBD_TO1) == 0) {
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE(m, n);
+ }
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ sc->txBdActiveCount--;
+ }
+}
+
+static void
+fec_rxDaemon (void *arg)
+{
+ volatile struct mcf5282_enet_struct *sc = (volatile struct mcf5282_enet_struct *)arg;
+ struct ifnet *ifp = (struct ifnet* )&sc->arpcom.ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ volatile mcf5282BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ rxBd->status = MCF5282_FEC_RxBD_E;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= MCF5282_FEC_RxBD_W;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ MCF5282_FEC_RDAR = 0;
+
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & MCF5282_FEC_RxBD_E) {
+ /*
+ * Clear old events.
+ */
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_RXF;
+
+ /*
+ * Wait for packet to arrive.
+ * Check the buffer descriptor before waiting for the event.
+ * This catches the case when a packet arrives between the
+ * `if' above, and the clearing of the RXF bit in the EIR.
+ */
+ while ((status = rxBd->status) & MCF5282_FEC_RxBD_E) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5282_FEC_EIMR |= MCF5282_FEC_EIMR_RXF;
+ rtems_interrupt_enable(level);
+ rtems_bsdnet_event_receive (RX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & MCF5282_FEC_RxBD_L) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+ int len = rxBd->length - sizeof(uint32_t);
+
+ m = sc->rxMbuf[rxBdIndex];
+#ifdef RTEMS_MCF5282_BSP_ENABLE_DATA_CACHE
+ /*
+ * Invalidate the cache. The cache is so small that it's
+ * reasonable to simply invalidate the whole thing.
+ */
+ rtems_cache_invalidate_entire_data();
+#endif
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+ eh = mtod(m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input(ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod(m, void *);
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & MCF5282_FEC_RxBD_W) | MCF5282_FEC_RxBD_E;
+ MCF5282_FEC_RDAR = 0;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void
+fec_sendpacket(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+ volatile mcf5282BufferDescriptor_t *firstTxBd, *txBd;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ fec_retire_tx_bd(sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ firstTxBd = sc->txBdBase + sc->txBdHead;
+
+ while (m != NULL) {
+ /*
+ * Wait for buffer descriptor to become available
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events.
+ */
+ MCF5282_FEC_EIR = MCF5282_FEC_EIR_TXF;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Check for buffer descriptors before waiting for the event.
+ * This catches the case when a buffer became available between
+ * the `if' above, and the clearing of the TXF bit in the EIR.
+ */
+ fec_retire_tx_bd(sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+ int level;
+
+ rtems_interrupt_disable(level);
+ MCF5282_FEC_EIMR |= MCF5282_FEC_EIMR_TXF;
+ rtems_interrupt_enable(level);
+ sc->txRawWait++;
+ rtems_bsdnet_event_receive(TX_INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ fec_retire_tx_bd(sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag on the first fragment
+ * until the whole packet has been readied.
+ */
+ status = nAdded ? MCF5282_FEC_TxBD_R : 0;
+
+ /*
+ * The IP fragmentation routine in ip_output
+ * can produce fragments with zero length.
+ */
+ txBd = sc->txBdBase + sc->txBdHead;
+ if (m->m_len) {
+ char *p = mtod(m, char *);
+ int offset = (int)p & 0x3;
+ if (offset == 0) {
+ txBd->buffer = p;
+ txBd->length = m->m_len;
+ sc->txMbuf[sc->txBdHead] = m;
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Stupid FEC can't handle misaligned data!
+ * Move offending bytes to a local buffer.
+ * Use buffer descriptor TO1 bit to indicate this.
+ */
+ int nmove = 4 - offset;
+ char *d = (char *)&sc->txMbuf[sc->txBdHead];
+ status |= MCF5282_FEC_TxBD_TO1;
+ sc->txRealign++;
+ if (nmove > m->m_len)
+ nmove = m->m_len;
+ m->m_data += nmove;
+ m->m_len -= nmove;
+ txBd->buffer = d;
+ txBd->length = nmove;
+ while (nmove--)
+ *d++ = *p++;
+ if (m->m_len == 0) {
+ struct mbuf *n;
+ sc->txRealignDrop++;
+ MFREE(m, n);
+ m = n;
+ }
+ }
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= MCF5282_FEC_TxBD_W;
+ sc->txBdHead = 0;
+ }
+ txBd->status = status;
+ }
+ else {
+ /*
+ * Toss empty mbufs.
+ */
+ struct mbuf *n;
+ MFREE(m, n);
+ m = n;
+ }
+ }
+ if (nAdded) {
+ txBd->status = status | MCF5282_FEC_TxBD_R
+ | MCF5282_FEC_TxBD_L
+ | MCF5282_FEC_TxBD_TC;
+ if (nAdded > 1)
+ firstTxBd->status |= MCF5282_FEC_TxBD_R;
+ MCF5282_FEC_TDAR = 0;
+ sc->txBdActiveCount += nAdded;
+ }
+}
+
+void
+fec_txDaemon(void *arg)
+{
+ struct mcf5282_enet_struct *sc = (struct mcf5282_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive(START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ fec_sendpacket(ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+mcf5282_enet_start(struct ifnet *ifp)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void
+fec_init(void *arg)
+{
+ struct mcf5282_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+ /*
+ * Set up hardware
+ */
+ mcf5282_fec_initialize_hardware(sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc("FECtx", 4096, fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc("FECrx", 4096, fec_rxDaemon, sc);
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ MCF5282_FEC_RCR |= MCF5282_FEC_RCR_PROM;
+ else
+ MCF5282_FEC_RCR &= ~MCF5282_FEC_RCR_PROM;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ MCF5282_FEC_ECR = MCF5282_FEC_ECR_ETHER_EN;
+}
+
+
+static void
+fec_stop(struct mcf5282_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ MCF5282_FEC_ECR = 0x0;
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+enet_stats(struct mcf5282_enet_struct *sc)
+{
+ printf(" Rx Interrupts:%-10lu", sc->rxInterrupts);
+ printf("Rx Packet Count:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_PACKETS);
+ printf(" Rx Broadcast:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_BC_PKT);
+ printf(" Rx Multicast:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_MC_PKT);
+ printf("CRC/Align error:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_CRC_ALIGN);
+ printf(" Rx Undersize:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_UNDERSIZE);
+ printf(" Rx Oversize:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_OVERSIZE);
+ printf(" Rx Fragment:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_FRAG);
+ printf(" Rx Jabber:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_JAB);
+ printf(" Rx 64:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P64);
+ printf(" Rx 65-127:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P65T0127);
+ printf(" Rx 128-255:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_P128TO255);
+ printf(" Rx 256-511:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P256TO511);
+ printf(" Rx 511-1023:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_P512TO1023);
+ printf(" Rx 1024-2047:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_R_P1024TO2047);
+ printf(" Rx >=2048:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_GTE2048);
+ printf(" Rx Octets:%-10lu", (uint32_t) MCF5282_FEC_RMON_R_OCTETS);
+ printf(" Rx Dropped:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_DROP);
+ printf(" Rx frame OK:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_FRAME_OK);
+ printf(" Rx CRC error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_CRC);
+ printf(" Rx Align error:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_ALIGN);
+ printf(" FIFO Overflow:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_MACERR);
+ printf("Rx Pause Frames:%-10lu", (uint32_t) MCF5282_FEC_IEEE_R_FDXFC);
+ printf(" Rx Octets OK:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_R_OCTETS_OK);
+ printf(" Tx Interrupts:%-10lu", sc->txInterrupts);
+ printf("Tx Output Waits:%-10lu", sc->txRawWait);
+ printf("Tx mbuf realign:%-10lu\n", sc->txRealign);
+ printf("Tx realign drop:%-10lu", sc->txRealignDrop);
+ printf(" Tx Unaccounted:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_DROP);
+ printf("Tx Packet Count:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_PACKETS);
+ printf(" Tx Broadcast:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_BC_PKT);
+ printf(" Tx Multicast:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_MC_PKT);
+ printf("CRC/Align error:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_CRC_ALIGN);
+ printf(" Tx Undersize:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_UNDERSIZE);
+ printf(" Tx Oversize:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_OVERSIZE);
+ printf(" Tx Fragment:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_FRAG);
+ printf(" Tx Jabber:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_JAB);
+ printf(" Tx Collisions:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_COL);
+ printf(" Tx 64:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P64);
+ printf(" Tx 65-127:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P65TO127);
+ printf(" Tx 128-255:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P128TO255);
+ printf(" Tx 256-511:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P256TO511);
+ printf(" Tx 511-1023:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P512TO1023);
+ printf(" Tx 1024-2047:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_P1024TO2047);
+ printf(" Tx >=2048:%-10lu\n", (uint32_t) MCF5282_FEC_RMON_T_P_GTE2048);
+ printf(" Tx Octets:%-10lu", (uint32_t) MCF5282_FEC_RMON_T_OCTETS);
+ printf(" Tx Dropped:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_DROP);
+ printf(" Tx Frame OK:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_FRAME_OK);
+ printf(" Tx 1 Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_1COL);
+ printf("Tx >1 Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_MCOL);
+ printf(" Tx Deferred:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_DEF);
+ printf(" Late Collision:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_LCOL);
+ printf(" Excessive Coll:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_EXCOL);
+ printf(" FIFO Underrun:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_MACERR);
+ printf(" Carrier Error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_CSERR);
+ printf(" Tx SQE Error:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_SQE);
+ printf("Tx Pause Frames:%-10lu\n", (uint32_t) MCF5282_FEC_IEEE_T_FDXFC);
+ printf(" Tx Octets OK:%-10lu", (uint32_t) MCF5282_FEC_IEEE_T_OCTETS_OK);
+ printf(" MII interrupts:%-10lu\n", sc->miiInterrupts);
+ if ((sc->mii_sr2 & 0x400) == 0) {
+ printf("LINK DOWN!\n");
+ }
+ else {
+ int speed;
+ int full;
+ int fixed;
+ if (sc->mii_cr & 0x1000) {
+ fixed = 0;
+ speed = sc->mii_sr2 & 0x4000 ? 100 : 10;
+ full = sc->mii_sr2 & 0x200 ? 1 : 0;
+ }
+ else {
+ fixed = 1;
+ speed = sc->mii_cr & 0x2000 ? 100 : 10;
+ full = sc->mii_cr & 0x100 ? 1 : 0;
+ }
+ printf("Link %s %d Mb/s, %s-duplex.\n",
+ fixed ? "fixed" : "auto-negotiate",
+ speed,
+ full ? "full" : "half");
+ }
+ printf(" EIR:%8.8lx ", (uint32_t) MCF5282_FEC_EIR);
+ printf("EIMR:%8.8lx ", (uint32_t) MCF5282_FEC_EIMR);
+ printf("RDAR:%8.8lx ", (uint32_t) MCF5282_FEC_RDAR);
+ printf("TDAR:%8.8lx\n", (uint32_t) MCF5282_FEC_TDAR);
+ printf(" ECR:%8.8lx ", (uint32_t) MCF5282_FEC_ECR);
+ printf(" RCR:%8.8lx ", (uint32_t) MCF5282_FEC_RCR);
+ printf(" TCR:%8.8lx\n", (uint32_t) MCF5282_FEC_TCR);
+ printf("FRBR:%8.8lx ", (uint32_t) MCF5282_FEC_FRBR);
+ printf("FRSR:%8.8lx\n", (uint32_t) MCF5282_FEC_FRSR);
+ if (sc->txBdActiveCount != 0) {
+ int i, n;
+ /*
+ * Yes, there are races here with adding and retiring descriptors,
+ * but this diagnostic is more for when things have backed up.
+ */
+ printf("Transmit Buffer Descriptors (Tail %d, Head %d, Unretired %d):\n",
+ sc->txBdTail,
+ sc->txBdHead,
+ sc->txBdActiveCount);
+ i = sc->txBdTail;
+ for (n = 0 ; n < sc->txBdCount ; n++) {
+ if ((sc->txBdBase[i].status & MCF5282_FEC_TxBD_R) != 0)
+ printf(" %3d: status:%4.4x length:%-4d buffer:%p\n",
+ i,
+ sc->txBdBase[i].status,
+ sc->txBdBase[i].length,
+ sc->txBdBase[i].buffer);
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+ }
+}
+
+static int
+fec_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct mcf5282_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ fec_stop(sc);
+ break;
+
+ case IFF_UP:
+ fec_init(sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ fec_stop(sc);
+ fec_init(sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats(sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+int
+rtems_fec_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching )
+{
+ struct mcf5282_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ const unsigned char *hwaddr;
+ const char *env;
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES)) {
+ printf("Bad FEC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address) {
+ hwaddr = config->hardware_address;
+ } else if ((hwaddr = bsp_gethwaddr(unitNumber - 1)) == NULL) {
+ /* Locally-administered address */
+ static const unsigned char defaultAddress[ETHER_ADDR_LEN] = {
+ 0x06, 'R', 'T', 'E', 'M', 'S'};
+ printf ("WARNING -- No %s%d Ethernet address specified "
+ "-- Using default address.\n", unitName, unitNumber);
+ hwaddr = defaultAddress;
+ }
+ printf("%s%d: Ethernet address: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ unitName, unitNumber,
+ hwaddr[0], hwaddr[1], hwaddr[2],
+ hwaddr[3], hwaddr[4], hwaddr[5]);
+ memcpy(sc->arpcom.ac_enaddr, hwaddr, ETHER_ADDR_LEN);
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = fec_init;
+ ifp->if_ioctl = fec_ioctl;
+ ifp->if_start = mcf5282_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Check for environment overrides
+ */
+ if (((env = bsp_getbenv("IPADDR0_100FULL")) != NULL)
+ && ((*env == 'y') || (*env == 'Y')))
+ sc->link = link_100Full;
+ else if (((env = bsp_getbenv("IPADDR0_10HALF")) != NULL)
+ && ((*env == 'y') || (*env == 'Y')))
+ sc->link = link_10Half;
+ else
+ sc->link = link_auto;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ return 1;
+};
diff --git a/bsps/mips/csb350/net/network.c b/bsps/mips/csb350/net/network.c
new file mode 100644
index 0000000..ba3b697
--- /dev/null
+++ b/bsps/mips/csb350/net/network.c
@@ -0,0 +1,909 @@
+/**
+ * @file
+ *
+ * Au1x00 ethernet driver
+ */
+
+/*
+ * Copyright (c) 2005 by Cogent Computer Systems
+ * Written by Jay Monkman <jtm@lopingdog.com>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <bsp.h>
+#include <rtems/bspIo.h>
+#include <libcpu/au1x00.h>
+#include <bsp/irq.h>
+
+#include <stdio.h>
+#include <string.h>
+
+#include <errno.h>
+#include <rtems/error.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <assert.h>
+
+#define NUM_IFACES 1
+#define NUM_TX_DMA_BUFS 4
+#define NUM_RX_DMA_BUFS 4
+
+/* RTEMS event used to start tx daemon. */
+#define START_TX_EVENT RTEMS_EVENT_1
+/* RTEMS event used to start rx daemon. */
+#define START_RX_EVENT RTEMS_EVENT_2
+
+rtems_isr au1x00_emac_isr(rtems_vector_number vector);
+
+#define TX_BUF_SIZE 2048
+
+char tx_buf_base[(4 * TX_BUF_SIZE) + 32];
+
+volatile int wait_count;
+/*
+ * Hardware-specific storage
+ */
+typedef struct
+{
+ /*
+ * Connection to networking code
+ * This entry *must* be the first in the sonic_softc structure.
+ */
+ struct arpcom arpcom;
+
+ /*
+ * Interrupt vector
+ */
+ rtems_vector_number vector;
+
+ /*
+ * Indicates configuration
+ */
+ int acceptBroadcast;
+
+ /*
+ * Tasks waiting for interrupts
+ */
+ rtems_id rx_daemon_tid;
+ rtems_id tx_daemon_tid;
+
+ /*
+ * Buffers
+ */
+ au1x00_macdma_rx_t *rx_dma;
+ au1x00_macdma_tx_t *tx_dma;
+ int rx_head;
+ int rx_tail;
+ int tx_head;
+ int tx_tail;
+ struct mbuf *rx_mbuf[NUM_RX_DMA_BUFS];
+
+ unsigned char *tx_buf[4];
+
+ /*
+ * register addresses
+ */
+ uint32_t ctrl_regs;
+ uint32_t *en_reg;
+ uint32_t int_mask;
+ uint32_t int_ctrlr;
+
+ /*
+ * device
+ */
+ int unitnumber;
+
+ /*
+ * Statistics
+ */
+ unsigned long interrupts;
+ unsigned long rx_interrupts;
+ unsigned long tx_interrupts;
+ unsigned long rx_missed;
+ unsigned long rx_bcast;
+ unsigned long rx_mcast;
+ unsigned long rx_unsupp;
+ unsigned long rx_ctrl;
+ unsigned long rx_len_err;
+ unsigned long rx_crc_err;
+ unsigned long rx_dribble;
+ unsigned long rx_mii_err;
+ unsigned long rx_collision;
+ unsigned long rx_too_long;
+ unsigned long rx_runt;
+ unsigned long rx_watchdog;
+ unsigned long rx_pkts;
+ unsigned long rx_dropped;
+
+ unsigned long tx_deferred;
+ unsigned long tx_underrun;
+ unsigned long tx_aborted;
+ unsigned long tx_pkts;
+} au1x00_emac_softc_t;
+
+static au1x00_emac_softc_t softc[NUM_IFACES];
+
+
+/* function prototypes */
+int rtems_au1x00_emac_attach (struct rtems_bsdnet_ifconfig *config,
+ int attaching);
+void au1x00_emac_init(void *arg);
+void au1x00_emac_init_hw(au1x00_emac_softc_t *sc);
+void au1x00_emac_start(struct ifnet *ifp);
+void au1x00_emac_stop (au1x00_emac_softc_t *sc);
+void au1x00_emac_tx_daemon (void *arg);
+void au1x00_emac_rx_daemon (void *arg);
+void au1x00_emac_sendpacket (struct ifnet *ifp, struct mbuf *m);
+void au1x00_emac_stats (au1x00_emac_softc_t *sc);
+static int au1x00_emac_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data);
+static void mii_write(au1x00_emac_softc_t *sc, uint8_t reg, uint16_t val);
+static void mii_read(au1x00_emac_softc_t *sc, uint8_t reg, uint16_t *val);
+static void mii_init(au1x00_emac_softc_t *sc);
+
+static void mii_write(au1x00_emac_softc_t *sc, uint8_t reg, uint16_t val)
+{
+ /* wait for the interface to get unbusy */
+ while (AU1X00_MAC_MIICTRL(sc->ctrl_regs) & AU1X00_MAC_MIICTRL_MB) {
+ continue;
+ }
+
+ /* write to address 0 - we only support address 0 */
+ AU1X00_MAC_MIIDATA(sc->ctrl_regs) = val;
+ AU1X00_MAC_MIICTRL(sc->ctrl_regs) = (((reg & 0x1f) << 6) |
+ AU1X00_MAC_MIICTRL_MW);
+ au_sync();
+
+ /* wait for it to complete */
+ while (AU1X00_MAC_MIICTRL(sc->ctrl_regs) & AU1X00_MAC_MIICTRL_MB) {
+ continue;
+ }
+}
+
+static void mii_read(au1x00_emac_softc_t *sc, uint8_t reg, uint16_t *val)
+{
+ /* wait for the interface to get unbusy */
+ while (AU1X00_MAC_MIICTRL(sc->ctrl_regs) & AU1X00_MAC_MIICTRL_MB) {
+ continue;
+ }
+
+ /* write to address 0 - we only support address 0 */
+ AU1X00_MAC_MIICTRL(sc->ctrl_regs) = ((reg & 0x1f) << 6);
+ au_sync();
+
+ /* wait for it to complete */
+ while (AU1X00_MAC_MIICTRL(sc->ctrl_regs) & AU1X00_MAC_MIICTRL_MB) {
+ continue;
+ }
+ *val = AU1X00_MAC_MIIDATA(sc->ctrl_regs);
+}
+
+static void mii_init(au1x00_emac_softc_t *sc)
+{
+ uint16_t data;
+
+ mii_write(sc, 0, 0x8000); /* reset */
+ do {
+ mii_read(sc, 0, &data);
+ } while (data & 0x8000);
+
+ mii_write(sc, 0, 0x3200); /* reset autonegotiation */
+ mii_write(sc, 17, 0xffc0); /* setup LEDs */
+
+}
+
+
+
+int rtems_au1x00_emac_attach (
+ struct rtems_bsdnet_ifconfig *config,
+ int attaching
+ )
+{
+ struct ifnet *ifp;
+ int mtu;
+ int unitnumber;
+ char *unitname;
+ static au1x00_emac_softc_t *sc;
+
+ /*
+ * Parse driver name
+ */
+ if ((unitnumber = rtems_bsdnet_parse_driver_name (config, &unitname)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if (unitnumber > NUM_IFACES) {
+ printf ("Bad AU1X00 EMAC unit number.\n");
+ return 0;
+ }
+
+ sc = &softc[unitnumber];
+
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * zero out the control structure
+ */
+
+ memset((void *)sc, 0, sizeof(*sc));
+
+ sc->unitnumber = unitnumber;
+ sc->int_ctrlr = AU1X00_IC0_ADDR;
+
+ if (unitnumber == 0) {
+ sc->ctrl_regs = AU1100_MAC0_ADDR;
+ sc->en_reg = (void *)(AU1100_MACEN_ADDR + 0);
+
+ sc->tx_dma = (void *)(AU1X00_MACDMA0_ADDR + 0x000);
+ sc->rx_dma = (void *)(AU1X00_MACDMA0_ADDR + 0x100);
+ sc->int_mask = AU1X00_IC_IRQ_MAC0;
+ } else {
+ printk("Unknown network device: %d\n", unitnumber);
+ return 0;
+ }
+
+ /* If the ethernet controller is already set up, read the MAC address */
+ if ((*sc->en_reg & 0x33) == 0x33) {
+ sc->arpcom.ac_enaddr[5] = ((AU1X00_MAC_ADDRHIGH(sc->ctrl_regs) >> 8) &
+ 0xff);
+ sc->arpcom.ac_enaddr[4] = ((AU1X00_MAC_ADDRHIGH(sc->ctrl_regs) >> 0) &
+ 0xff);
+ sc->arpcom.ac_enaddr[3] = ((AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 24) &
+ 0xff);
+ sc->arpcom.ac_enaddr[2] = ((AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 16) &
+ 0xff);
+ sc->arpcom.ac_enaddr[1] = ((AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 8) &
+ 0xff);
+ sc->arpcom.ac_enaddr[0] = ((AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 0) &
+ 0xff);
+ } else {
+ /* It's not set up yet, so we set a MAC address */
+ sc->arpcom.ac_enaddr[5] = 0x05;
+ sc->arpcom.ac_enaddr[4] = 0xc0;
+ sc->arpcom.ac_enaddr[3] = 0x50;
+ sc->arpcom.ac_enaddr[2] = 0x31;
+ sc->arpcom.ac_enaddr[1] = 0x23;
+ sc->arpcom.ac_enaddr[0] = 0x00;
+ }
+
+
+ if (config->mtu) {
+ mtu = config->mtu;
+ } else {
+ mtu = ETHERMTU;
+ }
+
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitnumber;
+ ifp->if_name = unitname;
+ ifp->if_mtu = mtu;
+ ifp->if_init = au1x00_emac_init;
+ ifp->if_ioctl = au1x00_emac_ioctl;
+ ifp->if_start = au1x00_emac_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST;
+ if (ifp->if_snd.ifq_maxlen == 0) {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+}
+
+void au1x00_emac_init(void *arg)
+{
+ au1x00_emac_softc_t *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ /*
+ *This is for stuff that only gets done once (au1x00_emac_init()
+ * gets called multiple times
+ */
+ if (sc->tx_daemon_tid == 0)
+ {
+ /* Set up EMAC hardware */
+ au1x00_emac_init_hw(sc);
+
+
+ /* install the interrupt handler */
+ if (sc->unitnumber == 0) {
+ rtems_interrupt_handler_install(
+ AU1X00_IRQ_MAC0,
+ "NIC0",
+ 0,
+ (rtems_interrupt_handler)au1x00_emac_isr,
+ NULL
+ );
+ } else {
+ rtems_interrupt_handler_install(
+ AU1X00_IRQ_MAC1,
+ "NIC1",
+ 0,
+ (rtems_interrupt_handler)au1x00_emac_isr,
+ NULL
+ );
+ }
+ AU1X00_IC_MASKCLR(sc->int_ctrlr) = sc->int_mask;
+ au_sync();
+
+ /* set src bit */
+ AU1X00_IC_SRCSET(sc->int_ctrlr) = sc->int_mask;
+
+ /* high level */
+ AU1X00_IC_CFG0SET(sc->int_ctrlr) = sc->int_mask;
+ AU1X00_IC_CFG1CLR(sc->int_ctrlr) = sc->int_mask;
+ AU1X00_IC_CFG2SET(sc->int_ctrlr) = sc->int_mask;
+
+ /* assign to request 0 - negative logic */
+ AU1X00_IC_ASSIGNSET(sc->int_ctrlr) = sc->int_mask;
+ au_sync();
+
+ /* Start driver tasks */
+ sc->tx_daemon_tid = rtems_bsdnet_newproc("ENTx",
+ 4096,
+ au1x00_emac_tx_daemon,
+ sc);
+
+ sc->rx_daemon_tid = rtems_bsdnet_newproc("ENRx",
+ 4096,
+ au1x00_emac_rx_daemon,
+ sc);
+
+
+ }
+ /* EMAC doesn't support promiscuous, so ignore requests */
+ if (ifp->if_flags & IFF_PROMISC)
+ printf ("Warning - AU1X00 EMAC doesn't support Promiscuous Mode!\n");
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * start tx, rx
+ */
+ AU1X00_MAC_CONTROL(sc->ctrl_regs) |= (AU1X00_MAC_CTRL_TE |
+ AU1X00_MAC_CTRL_RE);
+ au_sync();
+
+
+} /* au1x00_emac_init() */
+
+void au1x00_emac_init_hw(au1x00_emac_softc_t *sc)
+{
+ int i;
+ struct mbuf *m;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ /* reset the MAC */
+ *sc->en_reg = 0x40;
+ au_sync();
+ for (i = 0; i < 10000; i++) {
+ continue;
+ }
+
+/* *sc->en_reg = AU1X00_MAC_EN_CE; */
+ *sc->en_reg = 41;
+ au_sync();
+ for (i = 0; i < 10000; i++) {
+ continue;
+ }
+
+/*
+ *sc->en_reg = (AU1X00_MAC_EN_CE |
+ AU1X00_MAC_EN_E2 |
+ AU1X00_MAC_EN_E1 |
+ AU1X00_MAC_EN_E0);
+*/
+ *sc->en_reg = 0x33;
+ au_sync();
+ mii_init(sc);
+
+ /* set the mac address */
+ AU1X00_MAC_ADDRHIGH(sc->ctrl_regs) = ((sc->arpcom.ac_enaddr[5] << 8) |
+ (sc->arpcom.ac_enaddr[4] << 0));
+ AU1X00_MAC_ADDRLOW(sc->ctrl_regs) = ((sc->arpcom.ac_enaddr[3] << 24) |
+ (sc->arpcom.ac_enaddr[2] << 16) |
+ (sc->arpcom.ac_enaddr[1] << 8) |
+ (sc->arpcom.ac_enaddr[0] << 0));
+
+
+ /* get the MAC address from the chip */
+ sc->arpcom.ac_enaddr[5] = (AU1X00_MAC_ADDRHIGH(sc->ctrl_regs) >> 8) & 0xff;
+ sc->arpcom.ac_enaddr[4] = (AU1X00_MAC_ADDRHIGH(sc->ctrl_regs) >> 0) & 0xff;
+ sc->arpcom.ac_enaddr[3] = (AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 24) & 0xff;
+ sc->arpcom.ac_enaddr[2] = (AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 16) & 0xff;
+ sc->arpcom.ac_enaddr[1] = (AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 8) & 0xff;
+ sc->arpcom.ac_enaddr[0] = (AU1X00_MAC_ADDRLOW(sc->ctrl_regs) >> 0) & 0xff;
+
+ printk("Setting mac_control to 0x%x\n",
+ (AU1X00_MAC_CTRL_F |
+ AU1X00_MAC_CTRL_PM |
+ AU1X00_MAC_CTRL_RA |
+ AU1X00_MAC_CTRL_DO |
+ AU1X00_MAC_CTRL_EM));
+
+ AU1X00_MAC_CONTROL(sc->ctrl_regs) = (AU1X00_MAC_CTRL_F | /* full duplex */
+ AU1X00_MAC_CTRL_PM | /* pass mcast */
+ AU1X00_MAC_CTRL_RA | /* recv all */
+ AU1X00_MAC_CTRL_DO | /* disable own */
+ AU1X00_MAC_CTRL_EM); /* Big endian */
+ au_sync();
+ printk("mac_control was set to 0x%x\n", AU1X00_MAC_CONTROL(sc->ctrl_regs));
+ printk("mac_control addr is 0x%x\n", &AU1X00_MAC_CONTROL(sc->ctrl_regs));
+
+ /* initialize our receive buffer descriptors */
+ for (i = 0; i < NUM_RX_DMA_BUFS; i++) {
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+
+ m->m_pkthdr.rcvif = ifp;
+ m->m_nextpkt = 0;
+
+ /*
+ * The receive buffer must be aligned with a cache line
+ * boundary.
+ */
+ if (mtod(m, uint32_t) & 0x1f) {
+ uint32_t *p = mtod(m, uint32_t *);
+ *p = (mtod(m, uint32_t) + 0x1f) & 0x1f;
+ }
+ sc->rx_dma[i].addr = (mtod(m, uint32_t) & ~0xe0000000);
+ sc->rx_mbuf[i] = m;
+ }
+
+ /* Initialize transmit buffer descriptors */
+ for (i = 0; i < NUM_TX_DMA_BUFS; i++) {
+ sc->tx_dma[i].addr = 0;
+ }
+
+ /* initialize the transmit buffers */
+ sc->tx_buf[0] = (void *)((((int)&tx_buf_base[0]) + 0x1f) & ~0x1f);
+ sc->tx_buf[1] = (void *)(((int)sc->tx_buf[0]) + TX_BUF_SIZE);
+ sc->tx_buf[2] = (void *)(((int)sc->tx_buf[1]) + TX_BUF_SIZE);
+ sc->tx_buf[3] = (void *)(((int)sc->tx_buf[2]) + TX_BUF_SIZE);
+
+ sc->rx_head = (sc->rx_dma[0].addr >> 2) & 0x3;
+ sc->rx_tail = (sc->rx_dma[0].addr >> 2) & 0x3;
+ sc->tx_head = (sc->tx_dma[0].addr >> 2) & 0x3;
+ sc->tx_tail = (sc->tx_dma[0].addr >> 2) & 0x3;
+
+ for (i = 0; i < NUM_RX_DMA_BUFS; i++) {
+ sc->rx_dma[i].addr |= AU1X00_MAC_DMA_RXADDR_EN;
+ }
+
+} /* au1x00_emac_init_hw() */
+
+void au1x00_emac_start(struct ifnet *ifp)
+{
+ au1x00_emac_softc_t *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send(sc->tx_daemon_tid, START_TX_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+void au1x00_emac_stop (au1x00_emac_softc_t *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Stop the transmitter and receiver.
+ */
+
+ /* Disable TX/RX */
+ AU1X00_MAC_CONTROL(sc->ctrl_regs) &= ~(AU1X00_MAC_CTRL_TE |
+ AU1X00_MAC_CTRL_RE);
+ au_sync();
+}
+
+/*
+ * Driver tx daemon
+ */
+void au1x00_emac_tx_daemon (void *arg)
+{
+ au1x00_emac_softc_t *sc = (au1x00_emac_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+ uint32_t ic_base; /* interrupt controller */
+
+ ic_base = AU1X00_IC0_ADDR;
+
+ /* turn on interrupt, then wait for one */
+ if (sc->unitnumber == 0) {
+ AU1X00_IC_MASKSET(ic_base) = AU1X00_IC_IRQ_MAC0;
+ } else {
+ AU1X00_IC_MASKSET(ic_base) = AU1X00_IC_IRQ_MAC1;
+ }
+ au_sync();
+
+ for (;;)
+ {
+ rtems_bsdnet_event_receive(
+ START_TX_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* Send packets till queue is empty */
+ for (;;)
+ {
+ /* Get the next mbuf chain to transmit. */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+
+ sc->tx_pkts++;
+ au1x00_emac_sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Driver rx daemon
+ */
+void au1x00_emac_rx_daemon (void *arg)
+{
+ au1x00_emac_softc_t *sc = (au1x00_emac_softc_t *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ struct ether_header *eh;
+ rtems_event_set events;
+ uint32_t status;
+
+ while (1) {
+ rtems_bsdnet_event_receive(
+ START_RX_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /* while there are packets to receive */
+
+ while (!(sc->rx_dma[sc->rx_head].addr & (AU1X00_MAC_DMA_RXADDR_DN |
+ AU1X00_MAC_DMA_RXADDR_EN))) {
+ status = sc->rx_dma[sc->rx_head].stat;
+ if (status & AU1X00_MAC_DMA_RXSTAT_MI) {
+ sc->rx_missed++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_BF) {
+ sc->rx_bcast++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_MF) {
+ sc->rx_mcast++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_UC) {
+ sc->rx_unsupp++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_CF) {
+ sc->rx_ctrl++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_LE) {
+ sc->rx_len_err++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_CR) {
+ sc->rx_crc_err++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_DB) {
+ sc->rx_dribble++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_ME) {
+ sc->rx_mii_err++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_CS) {
+ sc->rx_collision++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_FL) {
+ sc->rx_too_long++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_RF) {
+ sc->rx_runt++;
+ }
+ if (status & AU1X00_MAC_DMA_RXSTAT_WT) {
+ sc->rx_watchdog++;
+ }
+
+ /* If no errrors, accept packet */
+ if ((status & (AU1X00_MAC_DMA_RXSTAT_CR |
+ AU1X00_MAC_DMA_RXSTAT_DB |
+ AU1X00_MAC_DMA_RXSTAT_RF)) == 0) {
+
+ sc->rx_pkts++;
+
+ /* find the start of the mbuf */
+ m = sc->rx_mbuf[sc->rx_head];
+
+ /* set the length of the mbuf */
+ m->m_len = AU1X00_MAC_DMA_RXSTAT_LEN(sc->rx_dma[sc->rx_head].stat);
+ m->m_len -= 4; /* remove ethernet CRC */
+
+ m->m_pkthdr.len = m->m_len;
+
+ /* strip off the ethernet header from the mbuf */
+ /* but save the pointer to it */
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+
+ /* give the received packet to the stack */
+ ether_input(ifp, eh, m);
+ /* get a new buf and make it ready for the MAC */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+
+ m->m_pkthdr.rcvif = ifp;
+ m->m_nextpkt = 0;
+
+ /*
+ * The receive buffer must be aligned with a cache line
+ * boundary.
+ */
+ {
+ uint32_t *p = mtod(m, uint32_t *);
+ *p = (mtod(m, uint32_t) + 0x1f) & ~0x1f;
+ }
+
+ } else {
+ sc->rx_dropped++;
+
+ /* find the mbuf so we can reuse it*/
+ m = sc->rx_mbuf[sc->rx_head];
+ }
+
+ /* set up the receive dma to use the mbuf's cluster */
+ sc->rx_dma[sc->rx_head].addr = (mtod(m, uint32_t) & ~0xe0000000);
+ au_sync();
+ sc->rx_mbuf[sc->rx_head] = m;
+
+ sc->rx_dma[sc->rx_head].addr |= AU1X00_MAC_DMA_RXADDR_EN;
+ au_sync();
+
+
+ /* increment the buffer index */
+ sc->rx_head++;
+ if (sc->rx_head >= NUM_RX_DMA_BUFS) {
+ sc->rx_head = 0;
+ }
+ }
+ }
+}
+
+/* Send packet */
+void au1x00_emac_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct mbuf *l = NULL;
+ unsigned int pkt_offset = 0;
+ au1x00_emac_softc_t *sc = (au1x00_emac_softc_t *)ifp->if_softc;
+ uint32_t txbuf;
+
+ /* Wait for EMAC Transmit Queue to become available. */
+ while((sc->tx_dma[sc->tx_head].addr & (AU1X00_MAC_DMA_TXADDR_EN ||
+ AU1X00_MAC_DMA_TXADDR_DN)) != 0) {
+ continue;
+ }
+
+ /* copy the mbuf chain into the transmit buffer */
+ l = m;
+
+ txbuf = (uint32_t)sc->tx_buf[sc->tx_head];
+ while (l != NULL)
+ {
+
+ memcpy(((char *)txbuf + pkt_offset), /* offset into pkt for mbuf */
+ (char *)mtod(l, void *), /* cast to void */
+ l->m_len); /* length of this mbuf */
+
+ pkt_offset += l->m_len; /* update offset */
+ l = l->m_next; /* get next mbuf, if any */
+ }
+
+ /* Pad if necessary */
+ if (pkt_offset < 60) {
+ memset((char *)(txbuf + pkt_offset), 0, (60 - pkt_offset));
+ pkt_offset = 60;
+ }
+
+ /* send it off */
+ sc->tx_dma[sc->tx_head].stat = 0;
+ sc->tx_dma[sc->tx_head].len = pkt_offset;
+ sc->tx_dma[sc->tx_head].addr = ((txbuf & ~0xe0000000) |
+ AU1X00_MAC_DMA_TXADDR_EN);
+ au_sync();
+
+
+ /*
+ *Without this delay, some outgoing packets never
+ * make it out the device. Nothing in the documentation
+ * explains this.
+ */
+ for (wait_count = 0; wait_count < 5000; wait_count++){
+ continue;
+ }
+
+ /* free the mbuf chain we just copied */
+ m_freem(m);
+
+ sc->tx_head++;
+ if (sc->tx_head >= NUM_TX_DMA_BUFS) {
+ sc->tx_head = 0;
+ }
+
+} /* au1x00_emac_sendpacket () */
+
+
+
+/* Show interface statistics */
+void au1x00_emac_stats (au1x00_emac_softc_t *sc)
+{
+ printf("Interrupts:%-8lu", sc->interrupts);
+ printf(" RX Interrupts:%-8lu", sc->rx_interrupts);
+ printf(" TX Interrupts:%-8lu\n", sc->tx_interrupts);
+ printf("RX Packets:%-8lu", sc->rx_pkts);
+ printf(" RX Control:%-8lu", sc->rx_ctrl);
+ printf(" RX broadcast:%-8lu\n", sc->rx_bcast);
+ printf("RX Mcast:%-8lu", sc->rx_mcast);
+ printf(" RX missed:%-8lu", sc->rx_missed);
+ printf(" RX Unsupported ctrl:%-8lu\n", sc->rx_unsupp);
+ printf("RX Len err:%-8lu", sc->rx_len_err);
+ printf(" RX CRC err:%-8lu", sc->rx_crc_err);
+ printf(" RX dribble:%-8lu\n", sc->rx_dribble);
+ printf("RX MII err:%-8lu", sc->rx_mii_err);
+ printf(" RX collision:%-8lu", sc->rx_collision);
+ printf(" RX too long:%-8lu\n", sc->rx_too_long);
+ printf("RX runt:%-8lu", sc->rx_runt);
+ printf(" RX watchdog:%-8lu", sc->rx_watchdog);
+ printf(" RX dropped:%-8lu\n", sc->rx_dropped);
+
+ printf("TX Packets:%-8lu", sc->tx_pkts);
+ printf(" TX Deferred:%-8lu", sc->tx_deferred);
+ printf(" TX Underrun:%-8lu\n", sc->tx_underrun);
+ printf("TX Aborted:%-8lu\n", sc->tx_aborted);
+
+}
+
+
+/* Driver ioctl handler */
+static int
+au1x00_emac_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ au1x00_emac_softc_t *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+ case IFF_RUNNING:
+ au1x00_emac_stop (sc);
+ break;
+
+ case IFF_UP:
+ au1x00_emac_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ au1x00_emac_stop (sc);
+ au1x00_emac_init (sc);
+ break;
+
+ default:
+ break;
+ } /* switch (if_flags) */
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ au1x00_emac_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ } /* switch (command) */
+ return error;
+}
+
+/* interrupt handler */
+rtems_isr au1x00_emac_isr (rtems_vector_number v)
+{
+ volatile au1x00_emac_softc_t *sc;
+ int tx_flag = 0;
+ int rx_flag = 0;
+
+ sc = &softc[0];
+ if (v != AU1X00_IRQ_MAC0) {
+ assert(v == AU1X00_IRQ_MAC0);
+ }
+
+ sc->interrupts++;
+
+ /*
+ * Since there's no easy way to find out the source of the
+ * interrupt, we have to look at the tx and rx dma buffers
+ */
+ /* receive interrupt */
+ while(sc->rx_dma[sc->rx_tail].addr & AU1X00_MAC_DMA_RXADDR_DN) {
+ rx_flag = 1;
+ sc->rx_interrupts++;
+ sc->rx_dma[sc->rx_tail].addr &= ~AU1X00_MAC_DMA_RXADDR_DN;
+ au_sync();
+
+ sc->rx_tail++;
+ if (sc->rx_tail >= NUM_RX_DMA_BUFS) {
+ sc->rx_tail = 0;
+ }
+ }
+ if (rx_flag != 0) {
+ rtems_bsdnet_event_send(sc->rx_daemon_tid, START_RX_EVENT);
+ }
+
+ /* transmit interrupt */
+ while (sc->tx_dma[sc->tx_tail].addr & AU1X00_MAC_DMA_TXADDR_DN) {
+ uint32_t status;
+ tx_flag = 1;
+ sc->tx_interrupts++;
+
+ status = sc->tx_dma[sc->tx_tail].stat;
+ if (status & AU1X00_MAC_DMA_TXSTAT_DF) {
+ sc->tx_deferred++;
+ }
+ if (status & AU1X00_MAC_DMA_TXSTAT_UR) {
+ sc->tx_underrun++;
+ }
+ if (status & AU1X00_MAC_DMA_TXSTAT_FA) {
+ sc->tx_aborted++;
+ }
+
+ sc->tx_dma[sc->tx_tail].addr = 0;
+ au_sync();
+
+ sc->tx_tail++;
+ if (sc->tx_tail >= NUM_TX_DMA_BUFS) {
+ sc->tx_tail = 0;
+ }
+ }
+ if (tx_flag != 0) {
+ rtems_bsdnet_event_send(sc->tx_daemon_tid, START_TX_EVENT);
+ }
+}
+
diff --git a/bsps/powerpc/beatnik/net/if_em/LICENSE b/bsps/powerpc/beatnik/net/if_em/LICENSE
new file mode 100644
index 0000000..ba90c4a
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/LICENSE
@@ -0,0 +1,31 @@
+$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/LICENSE,v 1.3 2005/01/06 01:42:38 imp Exp $
+/*-
+Copyright (c) 2001-2003, Intel Corporation
+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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+*/
diff --git a/bsps/powerpc/beatnik/net/if_em/README b/bsps/powerpc/beatnik/net/if_em/README
new file mode 100644
index 0000000..b4eef8d
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/README
@@ -0,0 +1,332 @@
+$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/README,v 1.10 2005/07/11 02:33:25 delphij Exp $
+FreeBSD* Driver for the Intel(R) PRO/1000 Family of Adapters
+============================================================
+
+March 18, 2005
+
+
+Contents
+========
+
+- Overview
+- Identifying Your Adapter
+- Building and Installation
+- Speed and Duplex Configuration
+- Additional Configurations
+- Known Limitations
+- Support
+- License
+
+
+Overview
+========
+
+This file describes the FreeBSD* driver, version 2.1.x, for the Intel(R)
+PRO/1000 Family of Adapters. This driver has been developed for use with
+FreeBSD, version 5.x.
+
+For questions related to hardware requirements, refer to the documentation
+supplied with your Intel PRO/1000 adapter. All hardware requirements listed
+apply to use with FreeBSD.
+
+
+Identifying Your Adapter
+========================
+
+For information on how to identify your adapter, go to the Adapter &
+Driver ID Guide at:
+
+http://support.intel.com/support/network/adapter/pro100/21397.htm
+
+
+For the latest Intel network drivers for FreeBSD, see:
+
+http://appsr.intel.com/scripts-df/support_intel.asp
+
+
+NOTE: Mobile adapters are not fully supported.
+
+
+Building and Installation
+=========================
+
+NOTE: The driver can be installed as a dynamic loadable kernel module or
+ compiled into the kernel. You must have kernel sources installed in
+ order to compile the driver module.
+
+In the instructions below, x.x.x is the driver version as indicated in the
+name of the driver tar file.
+
+1. Move the base driver tar file to the directory of your choice. For
+ example, use /home/username/em or /usr/local/src/em.
+
+2. Untar/unzip the archive:
+
+ tar xvfz em-x.x.x.tar.gz
+
+ This will create an em-x.x.x directory.
+
+3. To create a loadable module, perform the following steps.
+ NOTE: To compile the driver into the kernel, go directly to step 4.
+
+ a. To compile the module
+
+ cd em-x.x.x
+ make
+
+ b. To install the compiled module in system directory:
+
+ make install
+
+ c. If you want the driver to load automatically when the system is booted:
+
+ 1. Edit /boot/loader.conf, and add the following line:
+
+ if_em_load="YES"
+
+4. To compile the driver into the kernel:
+
+ cd em-x.x.x/src
+
+ cp if_em* /usr/src/sys/dev/em
+
+ cp Makefile.kernel /usr/src/sys/modules/em/Makefile
+
+ Edit the /usr/src/sys/conf/files.i386 file, and add the following lines only if
+ they don't already exist:
+
+ dev/em/if_em.c optional em
+
+ dev/em/if_em_hw.c optional em
+
+ Remove the following lines from the /usr/src/sys/conf/files.i386 file,
+ if they exist:
+
+ dev/em/if_em_fxhw.c optional em
+ dev/em/if_em_phy.c optional em
+
+ Edit the kernel configuration file (i.e., GENERIC or MYKERNEL) in
+ /usr/src/sys/i386/conf, and ensure the following line is present:
+
+ device em
+
+ Compile and install the kernel. The system must be rebooted for the kernel
+ updates to take effect. For additional information on compiling the
+ kernel, consult the FreeBSD operating system documentation.
+
+5. To assign an IP address to the interface, enter the following:
+
+ ifconfig em<interface_num> <IP_address>
+
+6. Verify that the interface works. Enter the following, where <IP_address>
+ is the IP address for another machine on the same subnet as the interface
+ that is being tested:
+
+ ping <IP_address>
+
+7. To configure the IP address to remain after reboot, edit /etc/rc.conf,
+ and create the appropriate ifconfig_em<interface_num>entry:
+
+ ifconfig_em<interface_num>="<ifconfig_settings>"
+
+ Example usage:
+
+ ifconfig_em0="inet 192.168.10.1 netmask 255.255.255.0"
+
+ NOTE: For assistance, see the ifconfig man page.
+
+
+Speed and Duplex Configuration
+==============================
+
+By default, the adapter auto-negotiates the speed and duplex of the
+connection. If there is a specific need, the ifconfig utility can be used to
+configure the speed and duplex settings on the adapter. Example usage:
+
+ ifconfig em<interface_num> <IP_address> media 100baseTX mediaopt
+ full-duplex
+
+ NOTE: Only use mediaopt to set the driver to full-duplex. If mediaopt is
+ not specified and you are not running at gigabit speed, the driver
+ defaults to half-duplex.
+
+
+This driver supports the following media type options:
+
+ autoselect - Enables auto-negotiation for speed and duplex.
+
+ 10baseT/UTP - Sets speed to 10 Mbps. Use the ifconfig mediaopt
+ option to select full-duplex mode.
+
+ 100baseTX - Sets speed to 100 Mbps. Use the ifconfig mediaopt
+ option to select full-duplex mode.
+
+ 1000baseTX - Sets speed to 1000 Mbps. In this case, the driver
+ supports only full-duplex mode.
+
+ 1000baseSX - Sets speed to 1000 Mbps. In this case, the driver
+ supports only full-duplex mode.
+
+For more information on the ifconfig utility, see the ifconfig man page.
+
+
+Additional Configurations
+=========================
+
+The driver supports Transmit/Receive Checksum Offload and Jumbo Frames on
+all but the 82542-based adapters. For specific adapters, refer to the
+Identifying Your Adapter section.
+
+ Jumbo Frames
+ ------------
+ To enable Jumbo Frames, use the ifconfig utility to increase the MTU
+ beyond 1500 bytes.
+
+ NOTES: Only enable Jumbo Frames if your network infrastructure supports
+ them.
+
+ The Jumbo Frames setting on the switch must be set to at least
+ 22 bytes larger than that of the MTU.
+
+ The Intel PRO/1000 PM Network Connection does not support jumbo
+ frames.
+
+
+ The Jumbo Frames MTU range for Intel Adapters is 1500 to 16114. The default
+ MTU range is 1500. To modify the setting, enter the following:
+
+ ifconfig em<interface_num> <hostname or IP address> mtu 9000
+
+ To confirm the MTU used between two specific devices, use:
+
+ route get <destination_IP_address>
+
+ VLANs
+ -----
+ To create a new VLAN interface:
+
+ ifconfig <vlan_name> create
+
+ To associate the VLAN interface with a physical interface and
+ assign a VLAN ID, IP address, and netmask:
+
+ ifconfig <vlan_name> <ip_address> netmask <subnet_mask> vlan
+ <vlan_id> vlandev <physical_interface>
+
+ Example:
+
+ ifconfig vlan10 10.0.0.1 netmask 255.255.255.0 vlan10 vlandev em0
+
+ In this example, all packets will be marked on egress with 802.1Q VLAN
+ tags, specifying a VLAN ID of 10.
+
+ To remove a VLAN interface:
+
+ ifconfig <vlan_name> destroy
+
+ Polling
+ -------
+ NOTES: DEVICE POLLING is only valid for non-SMP kernels.
+
+ The driver has to be compiled into the kernel for DEVICE POLLING to be
+ enabled in the driver.
+
+ To enable polling in the driver, add the following options to the kernel
+ configuration, and then recompile the kernel:
+
+ options DEVICE_POLLING
+ options HZ=1000
+
+ At runtime use:
+ sysctl kern.polling.enable=1 to turn polling on
+ Use:
+ sysctl kern.polling.enable=0 to turn polling off
+
+ Checksum Offload
+ ----------------
+ Checksum offloading is not supported on 82542 Gigabit adapters.
+
+ Checksum offloading supports both TCP and UDP packets and is
+ supported for both transmit and receive.
+
+ Checksum offloading can be enabled or disabled using ifconfig.
+ Both transmit and receive offloading will be either enabled or
+ disabled together. You cannot enable/disable one without the other.
+
+ To enable checksum offloading:
+
+ ifconfig <interface_num> rxcsum
+
+ To disable checksum offloading:
+
+ ifconfig <interface_num> -rxcsum
+
+ To confirm the current setting:
+
+ ifconfig <interface_num>
+
+ Look for the presence or absence of the following line:
+
+ options=3 <RXCSUM,TXCSUM>
+
+ See the ifconfig man page for further information.
+
+Known Limitations
+=================
+
+ There are known performance issues with this driver when running UDP traffic
+ with Jumbo Frames.
+
+ There is a known compatibility issue where time to link is slow or link is not
+ established between 82541/82547 controllers and some switches. Known switches
+ include:
+ Planex FXG-08TE
+ I-O Data ETG-SH8
+
+ The driver can be compiled with the following changes:
+
+ Edit ./em.x.x.x/src/if_em.h to uncomment the #define EM_MASTER_SLAVE
+ from within the comments. For example, change from:
+
+ /* #define EM_MASTER_SLAVE 2 */
+ to:
+ #define EM_MASTER_SLAVE 2
+
+ Use one of the following options:
+ 1 = Master mode
+ 2 = Slave mode
+ 3 = Auto master/slave
+ Setting 2 is recommended.
+
+ Recompile the module:
+ a. To compile the module
+ cd em-x.x.x
+ make clean
+ make
+
+ b. To install the compiled module in system directory:
+ make install
+
+
+Support
+=======
+
+For general information and support, go to the Intel support website at:
+
+ http://support.intel.com
+
+If an issue is identified, support is through email only at:
+freebsdnic@mailbox.intel.com
+
+License
+=======
+
+This software program is released under the terms of a license agreement
+between you ('Licensee') and Intel. Do not use or load this software or any
+associated materials (collectively, the 'Software') until you have carefully
+read the full terms and conditions of the LICENSE located in this software
+package. By loading or using the Software, you agree to the terms of this
+Agreement. If you do not agree with the terms of this Agreement, do not
+install or use the Software.
+
+* Other names and brands may be claimed as the property of others.
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em.c b/bsps/powerpc/beatnik/net/if_em/if_em.c
new file mode 100644
index 0000000..db3607a
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em.c
@@ -0,0 +1,3847 @@
+/**************************************************************************
+
+Copyright (c) 2001-2005, Intel Corporation
+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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+
+***************************************************************************/
+
+/*$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/if_em.c,v 1.67 2005/08/03 00:18:29 rwatson Exp $*/
+#ifndef __rtems__
+#include <dev/em/if_em.h>
+#else
+#include <rtems.h>
+#include "rtemscompat_defs.h"
+#include "../porting/rtemscompat.h"
+#include "if_em.h"
+#include "../porting/rtemscompat1.h"
+#include <inttypes.h>
+#endif
+
+/*********************************************************************
+ * Set this to one to display debug statistics
+ *********************************************************************/
+int em_display_debug_stats = 0;
+
+/*********************************************************************
+ * Linked list of board private structures for all NICs found
+ *********************************************************************/
+
+struct adapter *em_adapter_list = NULL;
+
+
+/*********************************************************************
+ * Driver version
+ *********************************************************************/
+
+char em_driver_version[] = "2.1.7";
+
+
+/*********************************************************************
+ * PCI Device ID Table
+ *
+ * Used by probe to select devices to load on
+ * Last field stores an index into em_strings
+ * Last entry must be all 0s
+ *
+ * { Vendor ID, Device ID, SubVendor ID, SubDevice ID, String Index }
+ *********************************************************************/
+
+static em_vendor_info_t em_vendor_info_array[] =
+{
+ /* Intel(R) PRO/1000 Network Connection */
+ { 0x8086, E1000_DEV_ID_82540EM, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82540EM_LOM, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82540EP, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82540EP_LOM, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82540EP_LP, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82541EI, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541ER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541ER_LOM, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541EI_MOBILE, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541GI, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541GI_LF, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82541GI_MOBILE, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82542, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82543GC_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82543GC_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82544EI_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82544EI_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82544GC_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82544GC_LOM, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82545EM_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82545EM_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82545GM_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82545GM_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82545GM_SERDES, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82546EB_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546EB_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546EB_QUAD_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546GB_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546GB_FIBER, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546GB_SERDES, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546GB_PCIE, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82546GB_QUAD_COPPER, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82547EI, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82547EI_MOBILE, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82547GI, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ { 0x8086, E1000_DEV_ID_82573E, PCI_ANY_ID, PCI_ANY_ID, 0},
+ { 0x8086, E1000_DEV_ID_82573E_IAMT, PCI_ANY_ID, PCI_ANY_ID, 0},
+
+ /* required last entry */
+ { 0, 0, 0, 0, 0}
+};
+
+/*********************************************************************
+ * Table of branding strings for all supported NICs.
+ *********************************************************************/
+
+static char *em_strings[] = {
+ "Intel(R) PRO/1000 Network Connection"
+};
+
+/*********************************************************************
+ * Function prototypes
+ *********************************************************************/
+static int em_probe(device_t);
+static int em_attach(device_t);
+#if !defined(__rtems__) || defined(DEBUG_MODULAR)
+static int em_detach(device_t);
+#endif
+#ifndef __rtems__
+static int em_shutdown(device_t);
+#endif
+static void em_intr(void *);
+static void em_start(struct ifnet *);
+#ifndef __rtems__
+static int em_ioctl(struct ifnet *, u_long, caddr_t);
+#else
+static int em_ioctl(struct ifnet *, ioctl_command_t, caddr_t);
+#endif
+static void em_watchdog(struct ifnet *);
+static void em_init(void *);
+static void em_init_locked(struct adapter *);
+static void em_stop(void *);
+static void em_media_status(struct ifnet *, struct ifmediareq *);
+#ifndef __rtems__
+static int em_media_change(struct ifnet *);
+#else
+static int em_media_change(struct ifnet *ifp, struct rtems_ifmedia *ifm);
+#endif
+static void em_identify_hardware(struct adapter *);
+static int em_allocate_pci_resources(struct adapter *);
+#ifndef __rtems__
+static void em_free_pci_resources(struct adapter *);
+static void em_local_timer(void *);
+#endif
+static int em_hardware_init(struct adapter *);
+static void em_setup_interface(device_t, struct adapter *);
+static int em_setup_transmit_structures(struct adapter *);
+static void em_initialize_transmit_unit(struct adapter *);
+static int em_setup_receive_structures(struct adapter *);
+static void em_initialize_receive_unit(struct adapter *);
+static void em_enable_intr(struct adapter *);
+static void em_disable_intr(struct adapter *);
+static void em_free_transmit_structures(struct adapter *);
+static void em_free_receive_structures(struct adapter *);
+static void em_update_stats_counters(struct adapter *);
+static void em_clean_transmit_interrupts(struct adapter *);
+static int em_allocate_receive_structures(struct adapter *);
+static int em_allocate_transmit_structures(struct adapter *);
+static void em_process_receive_interrupts(struct adapter *, int);
+#ifndef __rtems__
+static void em_receive_checksum(struct adapter *,
+ struct em_rx_desc *,
+ struct mbuf *);
+static void em_transmit_checksum_setup(struct adapter *,
+ struct mbuf *,
+ u_int32_t *,
+ u_int32_t *);
+#endif
+static void em_set_promisc(struct adapter *);
+static void em_disable_promisc(struct adapter *);
+static void em_set_multi(struct adapter *);
+static void em_print_hw_stats(struct adapter *);
+static void em_print_link_status(struct adapter *);
+static int em_get_buf(int i, struct adapter *,
+ struct mbuf *);
+#ifndef __rtems__
+static void em_enable_vlans(struct adapter *);
+static void em_disable_vlans(struct adapter *);
+#endif
+static int em_encap(struct adapter *, struct mbuf **);
+#ifndef __rtems__
+static void em_smartspeed(struct adapter *);
+#endif
+static int em_82547_fifo_workaround(struct adapter *, int);
+static void em_82547_update_fifo_head(struct adapter *, int);
+static int em_82547_tx_fifo_reset(struct adapter *);
+#ifndef __rtems__
+static void em_82547_move_tail(void *arg);
+#endif
+static void em_82547_move_tail_locked(struct adapter *);
+static int em_dma_malloc(struct adapter *, bus_size_t,
+ struct em_dma_alloc *, int);
+static void em_dma_free(struct adapter *, struct em_dma_alloc *);
+#ifndef __rtems__
+static void em_print_debug_info(struct adapter *);
+#endif
+static int em_is_valid_ether_addr(u_int8_t *);
+#ifndef __rtems__
+static int em_sysctl_stats(SYSCTL_HANDLER_ARGS);
+static int em_sysctl_debug_info(SYSCTL_HANDLER_ARGS);
+#endif
+static u_int32_t em_fill_descriptors (u_int64_t address,
+ u_int32_t length,
+ PDESC_ARRAY desc_array);
+#ifndef __rtems__
+static int em_sysctl_int_delay(SYSCTL_HANDLER_ARGS);
+static void em_add_int_delay_sysctl(struct adapter *, const char *,
+ const char *, struct em_int_delay_info *,
+ int, int);
+#endif
+
+/*********************************************************************
+ * FreeBSD Device Interface Entry Points
+ *********************************************************************/
+
+#ifndef __rtems__
+static device_method_t em_methods[] = {
+ /* Device interface */
+ DEVMETHOD(device_probe, em_probe),
+ DEVMETHOD(device_attach, em_attach),
+ DEVMETHOD(device_detach, em_detach),
+ DEVMETHOD(device_shutdown, em_shutdown),
+ {0, 0}
+};
+
+static driver_t em_driver = {
+ "em", em_methods, sizeof(struct adapter ),
+};
+
+static devclass_t em_devclass;
+DRIVER_MODULE(em, pci, em_driver, em_devclass, 0, 0);
+MODULE_DEPEND(em, pci, 1, 1, 1);
+MODULE_DEPEND(em, ether, 1, 1, 1);
+#else
+net_drv_tbl_t METHODS = {
+ n_probe : em_probe,
+ n_attach : em_attach,
+#ifdef DEBUG_MODULAR
+ n_detach : em_detach,
+#else
+ n_detach: 0,
+#endif
+ n_intr : em_intr,
+};
+#endif
+
+/*********************************************************************
+ * Tunable default values.
+ *********************************************************************/
+
+#define E1000_TICKS_TO_USECS(ticks) ((1024 * (ticks) + 500) / 1000)
+#define E1000_USECS_TO_TICKS(usecs) ((1000 * (usecs) + 512) / 1024)
+
+#ifndef __rtems__
+static int em_tx_int_delay_dflt = E1000_TICKS_TO_USECS(EM_TIDV);
+static int em_rx_int_delay_dflt = E1000_TICKS_TO_USECS(EM_RDTR);
+static int em_tx_abs_int_delay_dflt = E1000_TICKS_TO_USECS(EM_TADV);
+static int em_rx_abs_int_delay_dflt = E1000_TICKS_TO_USECS(EM_RADV);
+
+TUNABLE_INT("hw.em.tx_int_delay", &em_tx_int_delay_dflt);
+TUNABLE_INT("hw.em.rx_int_delay", &em_rx_int_delay_dflt);
+TUNABLE_INT("hw.em.tx_abs_int_delay", &em_tx_abs_int_delay_dflt);
+TUNABLE_INT("hw.em.rx_abs_int_delay", &em_rx_abs_int_delay_dflt);
+#endif
+
+/*********************************************************************
+ * Device identification routine
+ *
+ * em_probe determines if the driver should be loaded on
+ * adapter based on PCI vendor/device id of the adapter.
+ *
+ * return BUS_PROBE_DEFAULT on success, positive on failure
+ *********************************************************************/
+
+static int
+em_probe(device_t dev)
+{
+ em_vendor_info_t *ent;
+
+ u_int16_t pci_vendor_id = 0;
+ u_int16_t pci_device_id = 0;
+ u_int16_t pci_subvendor_id = 0;
+ u_int16_t pci_subdevice_id = 0;
+ char adapter_name[60];
+
+ INIT_DEBUGOUT("em_probe: begin");
+
+ pci_vendor_id = pci_get_vendor(dev);
+ if (pci_vendor_id != EM_VENDOR_ID)
+ return(ENXIO);
+
+ pci_device_id = pci_get_device(dev);
+ pci_subvendor_id = pci_get_subvendor(dev);
+ pci_subdevice_id = pci_get_subdevice(dev);
+
+ ent = em_vendor_info_array;
+ while (ent->vendor_id != 0) {
+ if ((pci_vendor_id == ent->vendor_id) &&
+ (pci_device_id == ent->device_id) &&
+
+ ((pci_subvendor_id == ent->subvendor_id) ||
+ (ent->subvendor_id == PCI_ANY_ID)) &&
+
+ ((pci_subdevice_id == ent->subdevice_id) ||
+ (ent->subdevice_id == PCI_ANY_ID))) {
+ sprintf(adapter_name, "%s, Version - %s",
+ em_strings[ent->index],
+ em_driver_version);
+ device_set_desc_copy(dev, adapter_name);
+ return(BUS_PROBE_DEFAULT);
+ }
+ ent++;
+ }
+
+ return(ENXIO);
+}
+
+/*********************************************************************
+ * Device initialization routine
+ *
+ * The attach entry point is called when the driver is being loaded.
+ * This routine identifies the type of hardware, allocates all resources
+ * and initializes the hardware.
+ *
+ * return 0 on success, positive on failure
+ *********************************************************************/
+
+static int
+em_attach(device_t dev)
+{
+ struct adapter * adapter;
+ int tsize, rsize;
+ int error = 0;
+
+ INIT_DEBUGOUT("em_attach: begin");
+
+ /* Allocate, clear, and link in our adapter structure */
+ if (!(adapter = device_get_softc(dev))) {
+ printf("em: adapter structure allocation failed\n");
+ return(ENOMEM);
+ }
+#ifndef __rtems__
+ bzero(adapter, sizeof(struct adapter ));
+#else
+ /* softc structure is maintained outside of this
+ * and the osdep already contains vital fields (memory address)
+ */
+#endif
+ adapter->dev = dev;
+ adapter->osdep.dev = dev;
+ adapter->unit = device_get_unit(dev);
+ EM_LOCK_INIT(adapter, device_get_nameunit(dev));
+
+ if (em_adapter_list != NULL)
+ em_adapter_list->prev = adapter;
+ adapter->next = em_adapter_list;
+ em_adapter_list = adapter;
+
+#ifndef __rtems__
+ /* SYSCTL stuff */
+ SYSCTL_ADD_PROC(device_get_sysctl_ctx(dev),
+ SYSCTL_CHILDREN(device_get_sysctl_tree(dev)),
+ OID_AUTO, "debug_info", CTLTYPE_INT|CTLFLAG_RW,
+ (void *)adapter, 0,
+ em_sysctl_debug_info, "I", "Debug Information");
+
+ SYSCTL_ADD_PROC(device_get_sysctl_ctx(dev),
+ SYSCTL_CHILDREN(device_get_sysctl_tree(dev)),
+ OID_AUTO, "stats", CTLTYPE_INT|CTLFLAG_RW,
+ (void *)adapter, 0,
+ em_sysctl_stats, "I", "Statistics");
+#endif
+
+ callout_init(&adapter->timer, CALLOUT_MPSAFE);
+ callout_init(&adapter->tx_fifo_timer, CALLOUT_MPSAFE);
+
+ /* Determine hardware revision */
+ em_identify_hardware(adapter);
+
+#ifndef __rtems__
+ /* Set up some sysctls for the tunable interrupt delays */
+ em_add_int_delay_sysctl(adapter, "rx_int_delay",
+ "receive interrupt delay in usecs", &adapter->rx_int_delay,
+ E1000_REG_OFFSET(&adapter->hw, RDTR), em_rx_int_delay_dflt);
+ em_add_int_delay_sysctl(adapter, "tx_int_delay",
+ "transmit interrupt delay in usecs", &adapter->tx_int_delay,
+ E1000_REG_OFFSET(&adapter->hw, TIDV), em_tx_int_delay_dflt);
+ if (adapter->hw.mac_type >= em_82540) {
+ em_add_int_delay_sysctl(adapter, "rx_abs_int_delay",
+ "receive interrupt delay limit in usecs",
+ &adapter->rx_abs_int_delay,
+ E1000_REG_OFFSET(&adapter->hw, RADV),
+ em_rx_abs_int_delay_dflt);
+ em_add_int_delay_sysctl(adapter, "tx_abs_int_delay",
+ "transmit interrupt delay limit in usecs",
+ &adapter->tx_abs_int_delay,
+ E1000_REG_OFFSET(&adapter->hw, TADV),
+ em_tx_abs_int_delay_dflt);
+ }
+#endif
+
+ /* Parameters (to be read from user) */
+ adapter->num_tx_desc = EM_MAX_TXD;
+ adapter->num_rx_desc = EM_MAX_RXD;
+#ifdef __rtems__
+ if ( dev->d_ifconfig->rbuf_count > 0 ) {
+ adapter->num_rx_desc = dev->d_ifconfig->rbuf_count;
+ }
+ if ( adapter->num_rx_desc < 80 )
+ adapter->num_rx_desc = 80;
+ if ( adapter->num_rx_desc > 256 )
+ adapter->num_rx_desc = 256;
+ if ( dev->d_ifconfig->xbuf_count > 0 ) {
+ adapter->num_tx_desc = dev->d_ifconfig->xbuf_count;
+ }
+ if ( adapter->num_tx_desc < 80 )
+ adapter->num_tx_desc = 80;
+ if ( adapter->num_tx_desc > 256 )
+ adapter->num_tx_desc = 256;
+ adapter->tx_cleanup_threshold = adapter->num_tx_desc/8;
+#endif
+ adapter->hw.autoneg = DO_AUTO_NEG;
+ adapter->hw.wait_autoneg_complete = WAIT_FOR_AUTO_NEG_DEFAULT;
+ adapter->hw.autoneg_advertised = AUTONEG_ADV_DEFAULT;
+ adapter->hw.tbi_compatibility_en = TRUE;
+ adapter->rx_buffer_len = EM_RXBUFFER_2048;
+
+ /*
+ * These parameters control the automatic generation(Tx) and
+ * response(Rx) to Ethernet PAUSE frames.
+ */
+ adapter->hw.fc_high_water = FC_DEFAULT_HI_THRESH;
+ adapter->hw.fc_low_water = FC_DEFAULT_LO_THRESH;
+ adapter->hw.fc_pause_time = FC_DEFAULT_TX_TIMER;
+ adapter->hw.fc_send_xon = TRUE;
+ adapter->hw.fc = em_fc_full;
+
+ adapter->hw.phy_init_script = 1;
+ adapter->hw.phy_reset_disable = FALSE;
+
+#ifndef EM_MASTER_SLAVE
+ adapter->hw.master_slave = em_ms_hw_default;
+#else
+ adapter->hw.master_slave = EM_MASTER_SLAVE;
+#endif
+ /*
+ * Set the max frame size assuming standard ethernet
+ * sized frames
+ */
+ adapter->hw.max_frame_size =
+ ETHERMTU + ETHER_HDR_LEN + ETHER_CRC_LEN;
+
+ adapter->hw.min_frame_size =
+ MINIMUM_ETHERNET_PACKET_SIZE + ETHER_CRC_LEN;
+
+ /*
+ * This controls when hardware reports transmit completion
+ * status.
+ */
+ adapter->hw.report_tx_early = 1;
+
+
+ if (em_allocate_pci_resources(adapter)) {
+ printf("em%d: Allocation of PCI resources failed\n",
+ adapter->unit);
+ error = ENXIO;
+ goto err_pci;
+ }
+
+
+ /* Initialize eeprom parameters */
+ em_init_eeprom_params(&adapter->hw);
+
+ tsize = EM_ROUNDUP(adapter->num_tx_desc *
+ sizeof(struct em_tx_desc), 4096);
+
+ /* Allocate Transmit Descriptor ring */
+ if (em_dma_malloc(adapter, tsize, &adapter->txdma, BUS_DMA_NOWAIT)) {
+ printf("em%d: Unable to allocate tx_desc memory\n",
+ adapter->unit);
+ error = ENOMEM;
+ goto err_tx_desc;
+ }
+ adapter->tx_desc_base = (struct em_tx_desc *) adapter->txdma.dma_vaddr;
+
+ rsize = EM_ROUNDUP(adapter->num_rx_desc *
+ sizeof(struct em_rx_desc), 4096);
+
+ /* Allocate Receive Descriptor ring */
+ if (em_dma_malloc(adapter, rsize, &adapter->rxdma, BUS_DMA_NOWAIT)) {
+ printf("em%d: Unable to allocate rx_desc memory\n",
+ adapter->unit);
+ error = ENOMEM;
+ goto err_rx_desc;
+ }
+ adapter->rx_desc_base = (struct em_rx_desc *) adapter->rxdma.dma_vaddr;
+
+ /* Initialize the hardware */
+ if (em_hardware_init(adapter)) {
+ printf("em%d: Unable to initialize the hardware\n",
+ adapter->unit);
+ error = EIO;
+ goto err_hw_init;
+ }
+
+ /* Copy the permanent MAC address out of the EEPROM */
+ if (em_read_mac_addr(&adapter->hw) < 0) {
+ printf("em%d: EEPROM read error while reading mac address\n",
+ adapter->unit);
+ error = EIO;
+ goto err_mac_addr;
+ }
+
+#ifdef __rtems__
+ /* if the configuration has not set a mac address, copy the permanent
+ * address from the device to the arpcom struct.
+ */
+ {
+ int i;
+ for ( i=0; i<ETHER_ADDR_LEN; i++ ) {
+ if ( adapter->arpcom.ac_enaddr[i] )
+ break;
+ }
+ if ( i >= ETHER_ADDR_LEN ) {
+ /* all nulls */
+ bcopy(adapter->hw.mac_addr, adapter->arpcom.ac_enaddr,
+ ETHER_ADDR_LEN);
+ }
+ }
+#endif
+
+ if (!em_is_valid_ether_addr(adapter->hw.mac_addr)) {
+ printf("em%d: Invalid mac address\n", adapter->unit);
+ error = EIO;
+ goto err_mac_addr;
+ }
+
+ /* Setup OS specific network interface */
+ em_setup_interface(dev, adapter);
+
+ /* Initialize statistics */
+ em_clear_hw_cntrs(&adapter->hw);
+ em_update_stats_counters(adapter);
+ adapter->hw.get_link_status = 1;
+#ifndef __rtems__
+ em_check_for_link(&adapter->hw);
+#else
+ /* first check during hw init usually fails - probably we need to wait longer;
+ * could take a while till the link is up, depends on the partner?
+ * in any case, rather than waiting here we just proceed...
+ */
+ em_check_for_link(&adapter->hw);
+ /* em_check_for_link doesn't update 'link_active'
+ * -- they usually call em_print_link_status() right
+ * after check_for_link, so let's repeat this
+ * algorithm here.
+ */
+ em_print_link_status(adapter);
+#endif
+
+ /* Print the link status */
+ if (adapter->link_active == 1) {
+ em_get_speed_and_duplex(&adapter->hw, &adapter->link_speed,
+ &adapter->link_duplex);
+ printf("em%d: Speed:%d Mbps Duplex:%s\n",
+ adapter->unit,
+ adapter->link_speed,
+ adapter->link_duplex == FULL_DUPLEX ? "Full" : "Half");
+ } else
+ printf("em%d: Speed:N/A Duplex:N/A\n", adapter->unit);
+
+ /* Identify 82544 on PCIX */
+ em_get_bus_info(&adapter->hw);
+ if(adapter->hw.bus_type == em_bus_type_pcix &&
+ adapter->hw.mac_type == em_82544) {
+ adapter->pcix_82544 = TRUE;
+ }
+ else {
+ adapter->pcix_82544 = FALSE;
+ }
+ INIT_DEBUGOUT("em_attach: end");
+ return(0);
+
+err_mac_addr:
+err_hw_init:
+ em_dma_free(adapter, &adapter->rxdma);
+err_rx_desc:
+ em_dma_free(adapter, &adapter->txdma);
+err_tx_desc:
+err_pci:
+#ifndef __rtems__
+ em_free_pci_resources(adapter);
+#endif
+ return(error);
+
+}
+
+/*********************************************************************
+ * Device removal routine
+ *
+ * The detach entry point is called when the driver is being removed.
+ * This routine stops the adapter and deallocates all the resources
+ * that were allocated for driver operation.
+ *
+ * return 0 on success, positive on failure
+ *********************************************************************/
+
+#if !defined(__rtems__) || defined(DEBUG_MODULAR)
+
+static int
+em_detach(device_t dev)
+{
+ struct adapter * adapter = device_get_softc(dev);
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+
+ INIT_DEBUGOUT("em_detach: begin");
+
+ EM_LOCK(adapter);
+ adapter->in_detach = 1;
+ em_stop(adapter);
+ em_phy_hw_reset(&adapter->hw);
+ EM_UNLOCK(adapter);
+#ifndef __rtems__
+#if __FreeBSD_version < 500000
+ ether_ifdetach(adapter->ifp, ETHER_BPF_SUPPORTED);
+#else
+ ether_ifdetach(adapter->ifp);
+ if_free(ifp);
+#endif
+ em_free_pci_resources(adapter);
+ bus_generic_detach(dev);
+#else
+ ether_ifdetach(ifp);
+#endif
+
+ /* Free Transmit Descriptor ring */
+ if (adapter->tx_desc_base) {
+ em_dma_free(adapter, &adapter->txdma);
+ adapter->tx_desc_base = NULL;
+ }
+
+ /* Free Receive Descriptor ring */
+ if (adapter->rx_desc_base) {
+ em_dma_free(adapter, &adapter->rxdma);
+ adapter->rx_desc_base = NULL;
+ }
+
+ /* Remove from the adapter list */
+ if (em_adapter_list == adapter)
+ em_adapter_list = adapter->next;
+ if (adapter->next != NULL)
+ adapter->next->prev = adapter->prev;
+ if (adapter->prev != NULL)
+ adapter->prev->next = adapter->next;
+
+ EM_LOCK_DESTROY(adapter);
+
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+ ifp->if_timer = 0;
+
+ return(0);
+}
+
+#endif
+
+#ifndef __rtems__
+/*********************************************************************
+ *
+ * Shutdown entry point
+ *
+ **********************************************************************/
+
+static int
+em_shutdown(device_t dev)
+{
+ struct adapter *adapter = device_get_softc(dev);
+ EM_LOCK(adapter);
+ em_stop(adapter);
+ EM_UNLOCK(adapter);
+ return(0);
+}
+#endif
+
+/*********************************************************************
+ * Transmit entry point
+ *
+ * em_start is called by the stack to initiate a transmit.
+ * The driver will remain in this routine as long as there are
+ * packets to transmit and transmit resources are available.
+ * In case resources are not available stack is notified and
+ * the packet is requeued.
+ **********************************************************************/
+
+static void
+em_start_locked(struct ifnet *ifp)
+{
+ struct mbuf *m_head;
+ struct adapter *adapter = ifp->if_softc;
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ if (!adapter->link_active)
+ return;
+
+ while (!IFQ_DRV_IS_EMPTY(&ifp->if_snd)) {
+
+ IFQ_DRV_DEQUEUE(&ifp->if_snd, m_head);
+
+ if (m_head == NULL) break;
+
+ /*
+ * em_encap() can modify our pointer, and or make it NULL on
+ * failure. In that event, we can't requeue.
+ */
+ if (em_encap(adapter, &m_head)) {
+ if (m_head == NULL)
+ break;
+ ifp->if_flags |= IFF_OACTIVE;
+ IFQ_DRV_PREPEND(&ifp->if_snd, m_head);
+ break;
+ }
+
+ /* Send a copy of the frame to the BPF listener */
+#if __FreeBSD_version < 500000 && !defined(__rtems__)
+ if (ifp->if_bpf)
+ bpf_mtap(ifp, m_head);
+#else
+ BPF_MTAP(ifp, m_head);
+#endif
+
+ /* Set timeout in case hardware has problems transmitting */
+ ifp->if_timer = EM_TX_TIMEOUT;
+
+ }
+ return;
+}
+
+static void
+em_start(struct ifnet *ifp)
+{
+ struct adapter *adapter RTEMS_UNUSED = ifp->if_softc;
+
+ EM_LOCK(adapter);
+ em_start_locked(ifp);
+ EM_UNLOCK(adapter);
+ return;
+}
+
+/*********************************************************************
+ * Ioctl entry point
+ *
+ * em_ioctl is called when the user wants to configure the
+ * interface.
+ *
+ * return 0 on success, positive on failure
+ **********************************************************************/
+
+#ifndef __rtems__
+static int
+em_ioctl(struct ifnet *ifp, u_long command, caddr_t data)
+#else
+static int
+em_ioctl(struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+#endif
+{
+#ifndef __rtems__
+ int mask, reinit, error = 0;
+#else
+ int error = 0;
+#endif
+ struct ifreq *ifr = (struct ifreq *) data;
+ struct adapter * adapter = ifp->if_softc;
+
+ if (adapter->in_detach) return(error);
+
+ switch (command) {
+ case SIOCSIFADDR:
+ case SIOCGIFADDR:
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOCxIFADDR (Get/Set Interface Addr)");
+ ether_ioctl(ifp, command, data);
+ break;
+ case SIOCSIFMTU:
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOCSIFMTU (Set Interface MTU)");
+ if (ifr->ifr_mtu > MAX_JUMBO_FRAME_SIZE - ETHER_HDR_LEN || \
+ /* 82573 does not support jumbo frames */
+ (adapter->hw.mac_type == em_82573 && ifr->ifr_mtu > ETHERMTU) ) {
+ error = EINVAL;
+ } else {
+ EM_LOCK(adapter);
+ ifp->if_mtu = ifr->ifr_mtu;
+ adapter->hw.max_frame_size =
+ ifp->if_mtu + ETHER_HDR_LEN + ETHER_CRC_LEN;
+ em_init_locked(adapter);
+ EM_UNLOCK(adapter);
+ }
+ break;
+ case SIOCSIFFLAGS:
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOCSIFFLAGS (Set Interface Flags)");
+ EM_LOCK(adapter);
+ if (ifp->if_flags & IFF_UP) {
+ if (!(ifp->if_flags & IFF_RUNNING)) {
+ em_init_locked(adapter);
+ }
+
+ em_disable_promisc(adapter);
+ em_set_promisc(adapter);
+ } else {
+ if (ifp->if_flags & IFF_RUNNING) {
+ em_stop(adapter);
+ }
+ }
+ EM_UNLOCK(adapter);
+ break;
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+#ifdef __rtems__
+ if ( (error = ( SIOCADDMULTI == command ?
+ ether_addmulti( ifr, (struct arpcom*)ifp ) :
+ ether_delmulti( ifr, (struct arpcom*)ifp ) ) ) ) {
+ if ( ENETRESET == error )
+ error = 0;
+ else
+ break;
+ }
+#endif
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOC(ADD|DEL)MULTI");
+ if (ifp->if_flags & IFF_RUNNING) {
+ EM_LOCK(adapter);
+ em_disable_intr(adapter);
+ em_set_multi(adapter);
+ if (adapter->hw.mac_type == em_82542_rev2_0) {
+ em_initialize_receive_unit(adapter);
+ }
+#ifdef DEVICE_POLLING
+ if (!(ifp->if_flags & IFF_POLLING))
+#endif
+ em_enable_intr(adapter);
+ EM_UNLOCK(adapter);
+ }
+ break;
+#ifndef __rtems__
+ case SIOCSIFMEDIA:
+ case SIOCGIFMEDIA:
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOCxIFMEDIA (Get/Set Interface Media)");
+ error = ifmedia_ioctl(ifp, ifr, &adapter->media, command);
+ break;
+#else
+ case SIOCSIFMEDIA:
+ {
+ struct rtems_ifmedia mhack;
+ mhack.ifm_media = ifr->ifr_media;
+ error = em_media_change(ifp, &mhack);
+ }
+ break;
+ case SIOCGIFMEDIA:
+ {
+ struct ifmediareq ifmr;
+ em_media_status(ifp, &ifmr);
+ ifr->ifr_media = ifmr.ifm_active;
+ /* add-in rtems flags */
+ if ( adapter->link_active )
+ ifr->ifr_media |= IFM_LINK_OK;
+ if ( !adapter->hw.autoneg )
+ ifr->ifr_media |= IFM_ANEG_DIS;
+ error = 0;
+ }
+ break;
+#endif
+#ifndef __rtems__
+ case SIOCSIFCAP:
+ IOCTL_DEBUGOUT("ioctl rcv'd: SIOCSIFCAP (Set Capabilities)");
+ reinit = 0;
+ mask = ifr->ifr_reqcap ^ ifp->if_capenable;
+ if (mask & IFCAP_POLLING)
+ ifp->if_capenable ^= IFCAP_POLLING;
+ if (mask & IFCAP_HWCSUM) {
+ ifp->if_capenable ^= IFCAP_HWCSUM;
+ reinit = 1;
+ }
+ if (mask & IFCAP_VLAN_HWTAGGING) {
+ ifp->if_capenable ^= IFCAP_VLAN_HWTAGGING;
+ reinit = 1;
+ }
+ if (reinit && (ifp->if_flags & IFF_RUNNING))
+ em_init(adapter);
+ break;
+#endif
+
+#ifdef __rtems__
+ case SIO_RTEMS_SHOW_STATS:
+ em_print_hw_stats(adapter);
+ error = 0;
+ break;
+#endif
+
+ default:
+ IOCTL_DEBUGOUT1("ioctl received: UNKNOWN (0x%x)", (int)command);
+ error = EINVAL;
+ }
+
+ return(error);
+}
+
+/*********************************************************************
+ * Watchdog entry point
+ *
+ * This routine is called whenever hardware quits transmitting.
+ *
+ **********************************************************************/
+
+static void
+em_watchdog(struct ifnet *ifp)
+{
+ struct adapter * adapter;
+ adapter = ifp->if_softc;
+
+ /* If we are in this routine because of pause frames, then
+ * don't reset the hardware.
+ */
+ if (E1000_READ_REG(&adapter->hw, STATUS) & E1000_STATUS_TXOFF) {
+ ifp->if_timer = EM_TX_TIMEOUT;
+ return;
+ }
+
+ if (em_check_for_link(&adapter->hw))
+ printf("em%d: watchdog timeout -- resetting\n", adapter->unit);
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ em_init(adapter);
+
+ ifp->if_oerrors++;
+ return;
+}
+
+/*********************************************************************
+ * Init entry point
+ *
+ * This routine is used in two ways. It is used by the stack as
+ * init entry point in network interface structure. It is also used
+ * by the driver as a hw/sw initialization routine to get to a
+ * consistent state.
+ *
+ * return 0 on success, positive on failure
+ **********************************************************************/
+
+static void
+em_init_locked(struct adapter * adapter)
+{
+ struct ifnet *ifp;
+
+ uint32_t pba;
+ ifp = &adapter->arpcom.ac_if;
+
+ INIT_DEBUGOUT("em_init: begin");
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ em_stop(adapter);
+
+ /* Packet Buffer Allocation (PBA)
+ * Writing PBA sets the receive portion of the buffer
+ * the remainder is used for the transmit buffer.
+ *
+ * Devices before the 82547 had a Packet Buffer of 64K.
+ * Default allocation: PBA=48K for Rx, leaving 16K for Tx.
+ * After the 82547 the buffer was reduced to 40K.
+ * Default allocation: PBA=30K for Rx, leaving 10K for Tx.
+ * Note: default does not leave enough room for Jumbo Frame >10k.
+ */
+ if(adapter->hw.mac_type < em_82547) {
+ /* Total FIFO is 64K */
+ if(adapter->rx_buffer_len > EM_RXBUFFER_8192)
+ pba = E1000_PBA_40K; /* 40K for Rx, 24K for Tx */
+ else
+ pba = E1000_PBA_48K; /* 48K for Rx, 16K for Tx */
+ } else {
+ /* Total FIFO is 40K */
+ if(adapter->hw.max_frame_size > EM_RXBUFFER_8192) {
+ pba = E1000_PBA_22K; /* 22K for Rx, 18K for Tx */
+ } else {
+ pba = E1000_PBA_30K; /* 30K for Rx, 10K for Tx */
+ }
+ adapter->tx_fifo_head = 0;
+ adapter->tx_head_addr = pba << EM_TX_HEAD_ADDR_SHIFT;
+ adapter->tx_fifo_size = (E1000_PBA_40K - pba) << EM_PBA_BYTES_SHIFT;
+ }
+ INIT_DEBUGOUT1("em_init: pba=%" PRId32 "K",pba);
+ E1000_WRITE_REG(&adapter->hw, PBA, pba);
+
+ /* Get the latest mac address, User can use a LAA */
+ bcopy(adapter->arpcom.ac_enaddr, adapter->hw.mac_addr,
+ ETHER_ADDR_LEN);
+
+ /* Initialize the hardware */
+ if (em_hardware_init(adapter)) {
+ printf("em%d: Unable to initialize the hardware\n",
+ adapter->unit);
+ return;
+ }
+
+#ifndef __rtems__
+ if (ifp->if_capenable & IFCAP_VLAN_HWTAGGING)
+ em_enable_vlans(adapter);
+#endif
+
+ /* Prepare transmit descriptors and buffers */
+ if (em_setup_transmit_structures(adapter)) {
+ printf("em%d: Could not setup transmit structures\n",
+ adapter->unit);
+ em_stop(adapter);
+ return;
+ }
+ em_initialize_transmit_unit(adapter);
+
+ /* Setup Multicast table */
+ em_set_multi(adapter);
+
+ /* Prepare receive descriptors and buffers */
+ if (em_setup_receive_structures(adapter)) {
+ printf("em%d: Could not setup receive structures\n",
+ adapter->unit);
+ em_stop(adapter);
+ return;
+ }
+ em_initialize_receive_unit(adapter);
+
+ /* Don't loose promiscuous settings */
+ em_set_promisc(adapter);
+
+ ifp->if_flags |= IFF_RUNNING;
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+#ifndef __rtems__
+ if (adapter->hw.mac_type >= em_82543) {
+ if (ifp->if_capenable & IFCAP_TXCSUM)
+ ifp->if_hwassist = EM_CHECKSUM_FEATURES;
+ else
+ ifp->if_hwassist = 0;
+ }
+#endif
+
+ callout_reset(&adapter->timer, hz, em_local_timer, adapter);
+ em_clear_hw_cntrs(&adapter->hw);
+#ifdef DEVICE_POLLING
+ /*
+ * Only enable interrupts if we are not polling, make sure
+ * they are off otherwise.
+ */
+ if (ifp->if_flags & IFF_POLLING)
+ em_disable_intr(adapter);
+ else
+#endif /* DEVICE_POLLING */
+ em_enable_intr(adapter);
+
+ /* Don't reset the phy next time init gets called */
+ adapter->hw.phy_reset_disable = TRUE;
+
+ return;
+}
+
+static void
+em_init(void *arg)
+{
+ struct adapter * adapter = arg;
+
+ EM_LOCK(adapter);
+ em_init_locked(adapter);
+ EM_UNLOCK(adapter);
+ return;
+}
+
+
+#ifdef DEVICE_POLLING
+static poll_handler_t em_poll;
+
+static void
+em_poll_locked(struct ifnet *ifp, enum poll_cmd cmd, int count)
+{
+ struct adapter *adapter = ifp->if_softc;
+ u_int32_t reg_icr;
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ if (!(ifp->if_capenable & IFCAP_POLLING)) {
+ ether_poll_deregister(ifp);
+ cmd = POLL_DEREGISTER;
+ }
+ if (cmd == POLL_DEREGISTER) { /* final call, enable interrupts */
+ em_enable_intr(adapter);
+ return;
+ }
+ if (cmd == POLL_AND_CHECK_STATUS) {
+ reg_icr = E1000_READ_REG(&adapter->hw, ICR);
+ if (reg_icr & (E1000_ICR_RXSEQ | E1000_ICR_LSC)) {
+ callout_stop(&adapter->timer);
+ adapter->hw.get_link_status = 1;
+ em_check_for_link(&adapter->hw);
+ em_print_link_status(adapter);
+ callout_reset(&adapter->timer, hz, em_local_timer, adapter);
+ }
+ }
+ if (ifp->if_flags & IFF_RUNNING) {
+ em_process_receive_interrupts(adapter, count);
+ em_clean_transmit_interrupts(adapter);
+ }
+
+ if (ifp->if_flags & IFF_RUNNING && !IFQ_DRV_IS_EMPTY(&ifp->if_snd))
+ em_start_locked(ifp);
+}
+
+static void
+em_poll(struct ifnet *ifp, enum poll_cmd cmd, int count)
+{
+ struct adapter *adapter = ifp->if_softc;
+
+ EM_LOCK(adapter);
+ em_poll_locked(ifp, cmd, count);
+ EM_UNLOCK(adapter);
+}
+#endif /* DEVICE_POLLING */
+
+/*********************************************************************
+ *
+ * Interrupt Service routine
+ *
+ **********************************************************************/
+static void
+em_intr(void *arg)
+{
+ u_int32_t loop_cnt = EM_MAX_INTR;
+ u_int32_t reg_icr;
+ struct ifnet *ifp;
+ struct adapter *adapter = arg;
+
+ EM_LOCK(adapter);
+
+ ifp = &adapter->arpcom.ac_if;
+
+#ifdef DEVICE_POLLING
+ if (ifp->if_flags & IFF_POLLING) {
+ EM_UNLOCK(adapter);
+ return;
+ }
+
+ if ((ifp->if_capenable & IFCAP_POLLING) &&
+ ether_poll_register(em_poll, ifp)) {
+ em_disable_intr(adapter);
+ em_poll_locked(ifp, 0, 1);
+ EM_UNLOCK(adapter);
+ return;
+ }
+#endif /* DEVICE_POLLING */
+
+ reg_icr = E1000_READ_REG(&adapter->hw, ICR);
+ if (!reg_icr) {
+ EM_UNLOCK(adapter);
+ return;
+ }
+
+ /* Link status change */
+ if (reg_icr & (E1000_ICR_RXSEQ | E1000_ICR_LSC)) {
+ callout_stop(&adapter->timer);
+ adapter->hw.get_link_status = 1;
+ em_check_for_link(&adapter->hw);
+ em_print_link_status(adapter);
+ callout_reset(&adapter->timer, hz, em_local_timer, adapter);
+ }
+
+ while (loop_cnt > 0) {
+ if (ifp->if_flags & IFF_RUNNING) {
+ em_process_receive_interrupts(adapter, -1);
+ em_clean_transmit_interrupts(adapter);
+ }
+ loop_cnt--;
+ }
+
+ if (ifp->if_flags & IFF_RUNNING && !IFQ_DRV_IS_EMPTY(&ifp->if_snd))
+ em_start_locked(ifp);
+
+ EM_UNLOCK(adapter);
+ return;
+}
+
+
+
+/*********************************************************************
+ *
+ * Media Ioctl callback
+ *
+ * This routine is called whenever the user queries the status of
+ * the interface using ifconfig.
+ *
+ **********************************************************************/
+static void
+em_media_status(struct ifnet *ifp, struct ifmediareq *ifmr)
+{
+ struct adapter * adapter = ifp->if_softc;
+
+ INIT_DEBUGOUT("em_media_status: begin");
+
+ em_check_for_link(&adapter->hw);
+ if (E1000_READ_REG(&adapter->hw, STATUS) & E1000_STATUS_LU) {
+ if (adapter->link_active == 0) {
+ em_get_speed_and_duplex(&adapter->hw,
+ &adapter->link_speed,
+ &adapter->link_duplex);
+ adapter->link_active = 1;
+ }
+ } else {
+ if (adapter->link_active == 1) {
+ adapter->link_speed = 0;
+ adapter->link_duplex = 0;
+ adapter->link_active = 0;
+ }
+ }
+
+ ifmr->ifm_status = IFM_AVALID;
+ ifmr->ifm_active = IFM_ETHER;
+
+ if (!adapter->link_active)
+ return;
+
+ ifmr->ifm_status |= IFM_ACTIVE;
+
+ if (adapter->hw.media_type == em_media_type_fiber) {
+ ifmr->ifm_active |= IFM_1000_SX | IFM_FDX;
+ } else {
+ switch (adapter->link_speed) {
+ case 10:
+ ifmr->ifm_active |= IFM_10_T;
+ break;
+ case 100:
+ ifmr->ifm_active |= IFM_100_TX;
+ break;
+ case 1000:
+#if __FreeBSD_version < 500000 && !defined(__rtems__)
+ ifmr->ifm_active |= IFM_1000_TX;
+#else
+ ifmr->ifm_active |= IFM_1000_T;
+#endif
+ break;
+ }
+ if (adapter->link_duplex == FULL_DUPLEX)
+ ifmr->ifm_active |= IFM_FDX;
+ else
+ ifmr->ifm_active |= IFM_HDX;
+ }
+ return;
+}
+
+/*********************************************************************
+ *
+ * Media Ioctl callback
+ *
+ * This routine is called when the user changes speed/duplex using
+ * media/mediopt option with ifconfig.
+ *
+ **********************************************************************/
+static int
+#ifndef __rtems__
+em_media_change(struct ifnet *ifp)
+#else
+em_media_change(struct ifnet *ifp, struct rtems_ifmedia *ifm)
+#endif
+{
+ struct adapter * adapter = ifp->if_softc;
+#ifndef __rtems__
+ struct ifmedia *ifm = &adapter->media;
+#endif
+
+ INIT_DEBUGOUT("em_media_change: begin");
+
+ if (IFM_TYPE(ifm->ifm_media) != IFM_ETHER)
+ return(EINVAL);
+
+ switch (IFM_SUBTYPE(ifm->ifm_media)) {
+ case IFM_AUTO:
+ adapter->hw.autoneg = DO_AUTO_NEG;
+ adapter->hw.autoneg_advertised = AUTONEG_ADV_DEFAULT;
+ break;
+ case IFM_1000_SX:
+#if __FreeBSD_version < 500000 && !defined(__rtems__)
+ case IFM_1000_TX:
+#else
+ case IFM_1000_T:
+#endif
+ adapter->hw.autoneg = DO_AUTO_NEG;
+ adapter->hw.autoneg_advertised = ADVERTISE_1000_FULL;
+ break;
+ case IFM_100_TX:
+ adapter->hw.autoneg = FALSE;
+ adapter->hw.autoneg_advertised = 0;
+ if ((ifm->ifm_media & IFM_GMASK) == IFM_FDX)
+ adapter->hw.forced_speed_duplex = em_100_full;
+ else
+ adapter->hw.forced_speed_duplex = em_100_half;
+ break;
+ case IFM_10_T:
+ adapter->hw.autoneg = FALSE;
+ adapter->hw.autoneg_advertised = 0;
+ if ((ifm->ifm_media & IFM_GMASK) == IFM_FDX)
+ adapter->hw.forced_speed_duplex = em_10_full;
+ else
+ adapter->hw.forced_speed_duplex = em_10_half;
+ break;
+ default:
+ printf("em%d: Unsupported media type\n", adapter->unit);
+ }
+
+ /* As the speed/duplex settings my have changed we need to
+ * reset the PHY.
+ */
+ adapter->hw.phy_reset_disable = FALSE;
+
+ em_init(adapter);
+
+ return(0);
+}
+
+/*********************************************************************
+ *
+ * This routine maps the mbufs to tx descriptors.
+ *
+ * return 0 on success, positive on failure
+ **********************************************************************/
+static int
+em_encap(struct adapter *adapter, struct mbuf **m_headp)
+{
+ u_int32_t txd_upper;
+ u_int32_t txd_lower, txd_used = 0, txd_saved = 0;
+ int i, j, error;
+ u_int64_t address;
+
+ struct mbuf *m_head;
+
+ /* For 82544 Workaround */
+ DESC_ARRAY desc_array;
+ u_int32_t array_elements;
+ u_int32_t counter;
+
+#ifndef __rtems__
+#if __FreeBSD_version < 500000
+ struct ifvlan *ifv = NULL;
+#else
+ struct m_tag *mtag;
+#endif
+#endif
+ bus_dma_segment_t segs[EM_MAX_SCATTER];
+#ifndef __rtems__
+ bus_dmamap_t map;
+#endif
+ int nsegs;
+ struct em_buffer *tx_buffer = NULL;
+ struct em_tx_desc *current_tx_desc = NULL;
+#ifndef __rtems__
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+#endif
+
+ m_head = *m_headp;
+
+ /*
+ * Force a cleanup if number of TX descriptors
+ * available hits the threshold
+ */
+ if (adapter->num_tx_desc_avail <= EM_TX_CLEANUP_THRESHOLD) {
+ em_clean_transmit_interrupts(adapter);
+ if (adapter->num_tx_desc_avail <= EM_TX_CLEANUP_THRESHOLD) {
+ adapter->no_tx_desc_avail1++;
+ return(ENOBUFS);
+ }
+ }
+
+#ifndef __rtems__
+ /*
+ * Map the packet for DMA.
+ */
+ if (bus_dmamap_create(adapter->txtag, BUS_DMA_NOWAIT, &map)) {
+ adapter->no_tx_map_avail++;
+ return (ENOMEM);
+ }
+ error = bus_dmamap_load_mbuf_sg(adapter->txtag, map, m_head, segs,
+ &nsegs, BUS_DMA_NOWAIT);
+ if (error != 0) {
+ adapter->no_tx_dma_setup++;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (error);
+ }
+#else
+ (void)error;
+ {
+ struct mbuf *m;
+ for ( m=m_head, nsegs=0; m; m=m->m_next, nsegs++ ) {
+ if ( nsegs >= sizeof(segs)/sizeof(segs[0]) ) {
+ break;
+ }
+ segs[nsegs].ds_addr = mtod(m, unsigned);
+ segs[nsegs].ds_len = m->m_len;
+ }
+ }
+#endif
+ KASSERT(nsegs != 0, ("em_encap: empty packet"));
+
+ if (nsegs > adapter->num_tx_desc_avail) {
+ adapter->no_tx_desc_avail2++;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (ENOBUFS);
+ }
+
+
+#ifndef __rtems__
+ if (ifp->if_hwassist > 0) {
+ em_transmit_checksum_setup(adapter, m_head,
+ &txd_upper, &txd_lower);
+ } else
+#endif
+ txd_upper = txd_lower = 0;
+
+
+#ifndef __rtems__
+ /* Find out if we are in vlan mode */
+#if __FreeBSD_version < 500000
+ if ((m_head->m_flags & (M_PROTO1|M_PKTHDR)) == (M_PROTO1|M_PKTHDR) &&
+ m_head->m_pkthdr.rcvif != NULL &&
+ m_head->m_pkthdr.rcvif->if_type == IFT_L2VLAN)
+ ifv = m_head->m_pkthdr.rcvif->if_softc;
+#else
+ mtag = VLAN_OUTPUT_TAG(ifp, m_head);
+#endif
+
+ /*
+ * When operating in promiscuous mode, hardware encapsulation for
+ * packets is disabled. This means we have to add the vlan
+ * encapsulation in the driver, since it will have come down from the
+ * VLAN layer with a tag instead of a VLAN header.
+ */
+ if (mtag != NULL && adapter->em_insert_vlan_header) {
+ struct ether_vlan_header *evl;
+ struct ether_header eh;
+
+ m_head = m_pullup(m_head, sizeof(eh));
+ if (m_head == NULL) {
+ *m_headp = NULL;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (ENOBUFS);
+ }
+ eh = *mtod(m_head, struct ether_header *);
+ M_PREPEND(m_head, sizeof(*evl), M_DONTWAIT);
+ if (m_head == NULL) {
+ *m_headp = NULL;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (ENOBUFS);
+ }
+ m_head = m_pullup(m_head, sizeof(*evl));
+ if (m_head == NULL) {
+ *m_headp = NULL;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (ENOBUFS);
+ }
+ evl = mtod(m_head, struct ether_vlan_header *);
+ bcopy(&eh, evl, sizeof(*evl));
+ evl->evl_proto = evl->evl_encap_proto;
+ evl->evl_encap_proto = htons(ETHERTYPE_VLAN);
+ evl->evl_tag = htons(VLAN_TAG_VALUE(mtag));
+ m_tag_delete(m_head, mtag);
+ mtag = NULL;
+ *m_headp = m_head;
+ }
+#endif
+
+ i = adapter->next_avail_tx_desc;
+ if (adapter->pcix_82544) {
+ txd_saved = i;
+ txd_used = 0;
+ }
+ for (j = 0; j < nsegs; j++) {
+ /* If adapter is 82544 and on PCIX bus */
+ if(adapter->pcix_82544) {
+ array_elements = 0;
+ address = htole64(segs[j].ds_addr);
+ /*
+ * Check the Address and Length combination and
+ * split the data accordingly
+ */
+ array_elements = em_fill_descriptors(address,
+ htole32(segs[j].ds_len),
+ &desc_array);
+ for (counter = 0; counter < array_elements; counter++) {
+ if (txd_used == adapter->num_tx_desc_avail) {
+ adapter->next_avail_tx_desc = txd_saved;
+ adapter->no_tx_desc_avail2++;
+ bus_dmamap_destroy(adapter->txtag, map);
+ return (ENOBUFS);
+ }
+ tx_buffer = &adapter->tx_buffer_area[i];
+ current_tx_desc = &adapter->tx_desc_base[i];
+ current_tx_desc->buffer_addr = htole64(
+ desc_array.descriptor[counter].address);
+ current_tx_desc->lower.data = htole32(
+ (adapter->txd_cmd | txd_lower |
+ (u_int16_t)desc_array.descriptor[counter].length));
+ current_tx_desc->upper.data = htole32((txd_upper));
+ if (++i == adapter->num_tx_desc)
+ i = 0;
+
+ tx_buffer->m_head = NULL;
+ txd_used++;
+ }
+ } else {
+ tx_buffer = &adapter->tx_buffer_area[i];
+ current_tx_desc = &adapter->tx_desc_base[i];
+
+ current_tx_desc->buffer_addr = htole64(segs[j].ds_addr);
+ current_tx_desc->lower.data = htole32(
+ adapter->txd_cmd | txd_lower | segs[j].ds_len);
+ current_tx_desc->upper.data = htole32(txd_upper);
+
+ if (++i == adapter->num_tx_desc)
+ i = 0;
+
+ tx_buffer->m_head = NULL;
+ }
+ }
+
+ adapter->next_avail_tx_desc = i;
+ if (adapter->pcix_82544) {
+ adapter->num_tx_desc_avail -= txd_used;
+ }
+ else {
+ adapter->num_tx_desc_avail -= nsegs;
+ }
+
+#ifndef __rtems__
+#if __FreeBSD_version < 500000
+ if (ifv != NULL) {
+ /* Set the vlan id */
+ current_tx_desc->upper.fields.special = htole16(ifv->ifv_tag);
+#else
+ if (mtag != NULL) {
+ /* Set the vlan id */
+ current_tx_desc->upper.fields.special = htole16(VLAN_TAG_VALUE(mtag));
+#endif
+
+ /* Tell hardware to add tag */
+ current_tx_desc->lower.data |= htole32(E1000_TXD_CMD_VLE);
+ }
+#endif
+
+ tx_buffer->m_head = m_head;
+#ifndef __rtems__
+ tx_buffer->map = map;
+#endif
+ bus_dmamap_sync(adapter->txtag, map, BUS_DMASYNC_PREWRITE);
+
+ /*
+ * Last Descriptor of Packet needs End Of Packet (EOP)
+ */
+ current_tx_desc->lower.data |= htole32(E1000_TXD_CMD_EOP);
+
+ /*
+ * Advance the Transmit Descriptor Tail (Tdt), this tells the E1000
+ * that this frame is available to transmit.
+ */
+ bus_dmamap_sync(adapter->txdma.dma_tag, adapter->txdma.dma_map,
+ BUS_DMASYNC_PREREAD | BUS_DMASYNC_PREWRITE);
+ if (adapter->hw.mac_type == em_82547 &&
+ adapter->link_duplex == HALF_DUPLEX) {
+ em_82547_move_tail_locked(adapter);
+ } else {
+ E1000_WRITE_REG(&adapter->hw, TDT, i);
+ if (adapter->hw.mac_type == em_82547) {
+ em_82547_update_fifo_head(adapter, m_head->m_pkthdr.len);
+ }
+ }
+
+ return(0);
+}
+
+/*********************************************************************
+ *
+ * 82547 workaround to avoid controller hang in half-duplex environment.
+ * The workaround is to avoid queuing a large packet that would span
+ * the internal Tx FIFO ring boundary. We need to reset the FIFO pointers
+ * in this case. We do that only when FIFO is quiescent.
+ *
+ **********************************************************************/
+static void
+em_82547_move_tail_locked(struct adapter *adapter)
+{
+ uint16_t hw_tdt;
+ uint16_t sw_tdt;
+ struct em_tx_desc *tx_desc;
+ uint16_t length = 0;
+ boolean_t eop = 0;
+
+ EM_LOCK_ASSERT(adapter);
+
+ hw_tdt = E1000_READ_REG(&adapter->hw, TDT);
+ sw_tdt = adapter->next_avail_tx_desc;
+
+ while (hw_tdt != sw_tdt) {
+ tx_desc = &adapter->tx_desc_base[hw_tdt];
+ length += tx_desc->lower.flags.length;
+ eop = tx_desc->lower.data & E1000_TXD_CMD_EOP;
+ if(++hw_tdt == adapter->num_tx_desc)
+ hw_tdt = 0;
+
+ if(eop) {
+ if (em_82547_fifo_workaround(adapter, length)) {
+ adapter->tx_fifo_wrk_cnt++;
+ callout_reset(&adapter->tx_fifo_timer, 1,
+ em_82547_move_tail, adapter);
+ break;
+ }
+ E1000_WRITE_REG(&adapter->hw, TDT, hw_tdt);
+ em_82547_update_fifo_head(adapter, length);
+ length = 0;
+ }
+ }
+ return;
+}
+
+#ifndef __rtems__
+static void
+em_82547_move_tail(void *arg)
+{
+ struct adapter *adapter = arg;
+
+ EM_LOCK(adapter);
+ em_82547_move_tail_locked(adapter);
+ EM_UNLOCK(adapter);
+}
+#endif
+
+static int
+em_82547_fifo_workaround(struct adapter *adapter, int len)
+{
+ int fifo_space, fifo_pkt_len;
+
+ fifo_pkt_len = EM_ROUNDUP(len + EM_FIFO_HDR, EM_FIFO_HDR);
+
+ if (adapter->link_duplex == HALF_DUPLEX) {
+ fifo_space = adapter->tx_fifo_size - adapter->tx_fifo_head;
+
+ if (fifo_pkt_len >= (EM_82547_PKT_THRESH + fifo_space)) {
+ if (em_82547_tx_fifo_reset(adapter)) {
+ return(0);
+ }
+ else {
+ return(1);
+ }
+ }
+ }
+
+ return(0);
+}
+
+static void
+em_82547_update_fifo_head(struct adapter *adapter, int len)
+{
+ int fifo_pkt_len = EM_ROUNDUP(len + EM_FIFO_HDR, EM_FIFO_HDR);
+
+ /* tx_fifo_head is always 16 byte aligned */
+ adapter->tx_fifo_head += fifo_pkt_len;
+ if (adapter->tx_fifo_head >= adapter->tx_fifo_size) {
+ adapter->tx_fifo_head -= adapter->tx_fifo_size;
+ }
+
+ return;
+}
+
+
+static int
+em_82547_tx_fifo_reset(struct adapter *adapter)
+{
+ uint32_t tctl;
+
+ if ( (E1000_READ_REG(&adapter->hw, TDT) ==
+ E1000_READ_REG(&adapter->hw, TDH)) &&
+ (E1000_READ_REG(&adapter->hw, TDFT) ==
+ E1000_READ_REG(&adapter->hw, TDFH)) &&
+ (E1000_READ_REG(&adapter->hw, TDFTS) ==
+ E1000_READ_REG(&adapter->hw, TDFHS)) &&
+ (E1000_READ_REG(&adapter->hw, TDFPC) == 0)) {
+
+ /* Disable TX unit */
+ tctl = E1000_READ_REG(&adapter->hw, TCTL);
+ E1000_WRITE_REG(&adapter->hw, TCTL, tctl & ~E1000_TCTL_EN);
+
+ /* Reset FIFO pointers */
+ E1000_WRITE_REG(&adapter->hw, TDFT, adapter->tx_head_addr);
+ E1000_WRITE_REG(&adapter->hw, TDFH, adapter->tx_head_addr);
+ E1000_WRITE_REG(&adapter->hw, TDFTS, adapter->tx_head_addr);
+ E1000_WRITE_REG(&adapter->hw, TDFHS, adapter->tx_head_addr);
+
+ /* Re-enable TX unit */
+ E1000_WRITE_REG(&adapter->hw, TCTL, tctl);
+ E1000_WRITE_FLUSH(&adapter->hw);
+
+ adapter->tx_fifo_head = 0;
+ adapter->tx_fifo_reset_cnt++;
+
+ return(TRUE);
+ }
+ else {
+ return(FALSE);
+ }
+}
+
+static void
+em_set_promisc(struct adapter * adapter)
+{
+
+ u_int32_t reg_rctl;
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+
+ reg_rctl = E1000_READ_REG(&adapter->hw, RCTL);
+
+ if (ifp->if_flags & IFF_PROMISC) {
+ reg_rctl |= (E1000_RCTL_UPE | E1000_RCTL_MPE);
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+#ifndef __rtems__
+ /* Disable VLAN stripping in promiscous mode
+ * This enables bridging of vlan tagged frames to occur
+ * and also allows vlan tags to be seen in tcpdump
+ */
+ if (ifp->if_capenable & IFCAP_VLAN_HWTAGGING)
+ em_disable_vlans(adapter);
+ adapter->em_insert_vlan_header = 1;
+#endif
+ } else if (ifp->if_flags & IFF_ALLMULTI) {
+ reg_rctl |= E1000_RCTL_MPE;
+ reg_rctl &= ~E1000_RCTL_UPE;
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+#ifndef __rtems__
+ adapter->em_insert_vlan_header = 0;
+ } else
+ adapter->em_insert_vlan_header = 0;
+#else
+ }
+#endif
+
+ return;
+}
+
+static void
+em_disable_promisc(struct adapter * adapter)
+{
+ u_int32_t reg_rctl;
+#ifndef __rtems__
+ struct ifnet *ifp = adapter->ifp;
+#endif
+
+ reg_rctl = E1000_READ_REG(&adapter->hw, RCTL);
+
+ reg_rctl &= (~E1000_RCTL_UPE);
+ reg_rctl &= (~E1000_RCTL_MPE);
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+
+#ifndef __rtems__
+ if (ifp->if_capenable & IFCAP_VLAN_HWTAGGING)
+ em_enable_vlans(adapter);
+ adapter->em_insert_vlan_header = 0;
+#endif
+
+ return;
+}
+
+
+/*********************************************************************
+ * Multicast Update
+ *
+ * This routine is called whenever multicast address list is updated.
+ *
+ **********************************************************************/
+
+static void
+em_set_multi(struct adapter * adapter)
+{
+ u_int32_t reg_rctl = 0;
+ u_int8_t mta[MAX_NUM_MULTICAST_ADDRESSES * ETH_LENGTH_OF_ADDRESS];
+#ifndef __rtems__
+ struct ifmultiaddr *ifma;
+#endif
+ int mcnt = 0;
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+
+ IOCTL_DEBUGOUT("em_set_multi: begin");
+
+ if (adapter->hw.mac_type == em_82542_rev2_0) {
+ reg_rctl = E1000_READ_REG(&adapter->hw, RCTL);
+ if (adapter->hw.pci_cmd_word & CMD_MEM_WRT_INVALIDATE) {
+ em_pci_clear_mwi(&adapter->hw);
+ }
+ reg_rctl |= E1000_RCTL_RST;
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+ msec_delay(5);
+ }
+
+#ifndef __rtems__
+ IF_ADDR_LOCK(ifp);
+#if __FreeBSD_version < 500000
+ LIST_FOREACH(ifma, &ifp->if_multiaddrs, ifma_link) {
+#else
+ TAILQ_FOREACH(ifma, &ifp->if_multiaddrs, ifma_link) {
+#endif
+ if (ifma->ifma_addr->sa_family != AF_LINK)
+ continue;
+
+ if (mcnt == MAX_NUM_MULTICAST_ADDRESSES) break;
+
+ bcopy(LLADDR((struct sockaddr_dl *)ifma->ifma_addr),
+ &mta[mcnt*ETH_LENGTH_OF_ADDRESS], ETH_LENGTH_OF_ADDRESS);
+ mcnt++;
+ }
+ IF_ADDR_UNLOCK(ifp);
+#else
+ {
+ /* Don't know how to handle address ranges - we warn and ignore
+ * for now...
+ */
+ struct ether_multi *enm;
+ struct ether_multistep step;
+
+ ETHER_FIRST_MULTI(step, (struct arpcom*)ifp, enm);
+ while ( enm != NULL ) {
+ if ( mcnt == MAX_NUM_MULTICAST_ADDRESSES )
+ break;
+ if ( memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN) ) {
+ printk("if_em: Unable to handle multicast wildcard (not ported yet); skipping/ignoring\n");
+ goto skiptonext;
+ } else {
+ bcopy(enm->enm_addrlo, &mta[mcnt * ETHER_ADDR_LEN], ETHER_ADDR_LEN);
+ }
+ mcnt++;
+skiptonext:
+ ETHER_NEXT_MULTI( step, enm );
+ }
+ }
+#endif
+
+ if (mcnt >= MAX_NUM_MULTICAST_ADDRESSES) {
+ reg_rctl = E1000_READ_REG(&adapter->hw, RCTL);
+ reg_rctl |= E1000_RCTL_MPE;
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+ } else
+ em_mc_addr_list_update(&adapter->hw, mta, mcnt, 0, 1);
+
+ if (adapter->hw.mac_type == em_82542_rev2_0) {
+ reg_rctl = E1000_READ_REG(&adapter->hw, RCTL);
+ reg_rctl &= ~E1000_RCTL_RST;
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+ msec_delay(5);
+ if (adapter->hw.pci_cmd_word & CMD_MEM_WRT_INVALIDATE) {
+ em_pci_set_mwi(&adapter->hw);
+ }
+ }
+
+ return;
+}
+
+#ifndef __rtems__
+/*********************************************************************
+ * Timer routine
+ *
+ * This routine checks for link status and updates statistics.
+ *
+ **********************************************************************/
+
+static void
+em_local_timer(void *arg)
+{
+ struct ifnet *ifp;
+ struct adapter * adapter = arg;
+ ifp = &adapter->arpcom.ac_if;
+
+ EM_LOCK(adapter);
+
+ em_check_for_link(&adapter->hw);
+ em_print_link_status(adapter);
+ em_update_stats_counters(adapter);
+ if (em_display_debug_stats && ifp->if_flags & IFF_RUNNING) {
+ em_print_hw_stats(adapter);
+ }
+ em_smartspeed(adapter);
+
+ callout_reset(&adapter->timer, hz, em_local_timer, adapter);
+
+ EM_UNLOCK(adapter);
+ return;
+}
+#endif
+
+static void
+em_print_link_status(struct adapter * adapter)
+{
+#ifndef __rtems__
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+#endif
+
+ if (E1000_READ_REG(&adapter->hw, STATUS) & E1000_STATUS_LU) {
+ if (adapter->link_active == 0) {
+ em_get_speed_and_duplex(&adapter->hw,
+ &adapter->link_speed,
+ &adapter->link_duplex);
+ if (bootverbose)
+ printf("em%d: Link is up %d Mbps %s\n",
+ adapter->unit,
+ adapter->link_speed,
+ ((adapter->link_duplex == FULL_DUPLEX) ?
+ "Full Duplex" : "Half Duplex"));
+ adapter->link_active = 1;
+ adapter->smartspeed = 0;
+#ifndef __rtems__
+ if_link_state_change(ifp, LINK_STATE_UP);
+#endif
+ }
+ } else {
+ if (adapter->link_active == 1) {
+ adapter->link_speed = 0;
+ adapter->link_duplex = 0;
+ if (bootverbose)
+ printf("em%d: Link is Down\n", adapter->unit);
+ adapter->link_active = 0;
+#ifndef __rtems__
+ if_link_state_change(ifp, LINK_STATE_UP);
+ if_link_state_change(ifp, LINK_STATE_DOWN);
+#endif
+ }
+ }
+
+ return;
+}
+
+/*********************************************************************
+ *
+ * This routine disables all traffic on the adapter by issuing a
+ * global reset on the MAC and deallocates TX/RX buffers.
+ *
+ **********************************************************************/
+
+static void
+em_stop(void *arg)
+{
+ struct ifnet *ifp;
+ struct adapter * adapter = arg;
+ ifp = &adapter->arpcom.ac_if;
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ INIT_DEBUGOUT("em_stop: begin");
+#ifdef DEVICE_POLLING
+ ether_poll_deregister(ifp);
+#endif
+ em_disable_intr(adapter);
+ em_reset_hw(&adapter->hw);
+ callout_stop(&adapter->timer);
+ callout_stop(&adapter->tx_fifo_timer);
+ em_free_transmit_structures(adapter);
+ em_free_receive_structures(adapter);
+
+
+ /* Tell the stack that the interface is no longer active */
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+
+ return;
+}
+
+
+/*********************************************************************
+ *
+ * Determine hardware revision.
+ *
+ **********************************************************************/
+static void
+em_identify_hardware(struct adapter * adapter)
+{
+ device_t dev = adapter->dev;
+
+ /* Make sure our PCI config space has the necessary stuff set */
+ adapter->hw.pci_cmd_word = pci_read_config(dev, PCIR_COMMAND, 2);
+ if (!((adapter->hw.pci_cmd_word & PCIM_CMD_BUSMASTEREN) &&
+ (adapter->hw.pci_cmd_word & PCIM_CMD_MEMEN))) {
+ printf("em%d: Memory Access and/or Bus Master bits were not set!\n",
+ adapter->unit);
+ adapter->hw.pci_cmd_word |=
+ (PCIM_CMD_BUSMASTEREN | PCIM_CMD_MEMEN);
+ pci_write_config(dev, PCIR_COMMAND, adapter->hw.pci_cmd_word, 2);
+ }
+
+ /* Save off the information about this board */
+ adapter->hw.vendor_id = pci_get_vendor(dev);
+ adapter->hw.device_id = pci_get_device(dev);
+ adapter->hw.revision_id = pci_read_config(dev, PCIR_REVID, 1);
+ adapter->hw.subsystem_vendor_id = pci_read_config(dev, PCIR_SUBVEND_0, 2);
+ adapter->hw.subsystem_id = pci_read_config(dev, PCIR_SUBDEV_0, 2);
+
+ /* Identify the MAC */
+ if (em_set_mac_type(&adapter->hw))
+ printf("em%d: Unknown MAC Type\n", adapter->unit);
+
+ if(adapter->hw.mac_type == em_82541 ||
+ adapter->hw.mac_type == em_82541_rev_2 ||
+ adapter->hw.mac_type == em_82547 ||
+ adapter->hw.mac_type == em_82547_rev_2)
+ adapter->hw.phy_init_script = TRUE;
+
+ return;
+}
+
+static int
+em_allocate_pci_resources(struct adapter * adapter)
+{
+ int i, val, rid;
+ device_t dev = adapter->dev;
+
+ rid = EM_MMBA;
+
+#ifndef __rtems__
+ adapter->res_memory = bus_alloc_resource_any(dev, SYS_RES_MEMORY,
+ &rid, RF_ACTIVE);
+ if (!(adapter->res_memory)) {
+ printf("em%d: Unable to allocate bus resource: memory\n",
+ adapter->unit);
+ return(ENXIO);
+ }
+ adapter->osdep.mem_bus_space_tag =
+ rman_get_bustag(adapter->res_memory);
+ adapter->osdep.mem_bus_space_handle =
+ rman_get_bushandle(adapter->res_memory);
+#endif
+
+ adapter->hw.hw_addr = (uint8_t *)&adapter->osdep.mem_bus_space_handle;
+
+
+ if (adapter->hw.mac_type > em_82543) {
+ /* Figure our where our IO BAR is ? */
+ rid = EM_MMBA;
+ for (i = 0; i < 5; i++) {
+ val = pci_read_config(dev, rid, 4);
+ if (val & 0x00000001) {
+#ifndef __rtems__
+ adapter->io_rid = rid;
+#endif
+ break;
+ }
+ rid += 4;
+ }
+
+#ifndef __rtems__
+ adapter->res_ioport = bus_alloc_resource_any(dev,
+ SYS_RES_IOPORT,
+ &adapter->io_rid,
+ RF_ACTIVE);
+ if (!(adapter->res_ioport)) {
+ printf("em%d: Unable to allocate bus resource: ioport\n",
+ adapter->unit);
+ return(ENXIO);
+ }
+
+ adapter->hw.io_base =
+ rman_get_start(adapter->res_ioport);
+#else
+ adapter->hw.io_base = val & PCI_BASE_ADDRESS_IO_MASK;
+#endif
+ }
+
+#ifndef __rtems__
+ rid = 0x0;
+ adapter->res_interrupt = bus_alloc_resource_any(dev, SYS_RES_IRQ, &rid,
+ RF_SHAREABLE |
+ RF_ACTIVE);
+ if (!(adapter->res_interrupt)) {
+ printf("em%d: Unable to allocate bus resource: interrupt\n",
+ adapter->unit);
+ return(ENXIO);
+ }
+ if (bus_setup_intr(dev, adapter->res_interrupt,
+ INTR_TYPE_NET | INTR_MPSAFE,
+ (void (*)(void *)) em_intr, adapter,
+ &adapter->int_handler_tag)) {
+ printf("em%d: Error registering interrupt handler!\n",
+ adapter->unit);
+ return(ENXIO);
+ }
+#endif
+
+ adapter->hw.back = &adapter->osdep;
+
+ return(0);
+}
+
+#ifndef __rtems__
+static void
+em_free_pci_resources(struct adapter * adapter)
+{
+ device_t dev = adapter->dev;
+
+ if (adapter->res_interrupt != NULL) {
+ bus_teardown_intr(dev, adapter->res_interrupt,
+ adapter->int_handler_tag);
+ bus_release_resource(dev, SYS_RES_IRQ, 0,
+ adapter->res_interrupt);
+ }
+ if (adapter->res_memory != NULL) {
+ bus_release_resource(dev, SYS_RES_MEMORY, EM_MMBA,
+ adapter->res_memory);
+ }
+
+ if (adapter->res_ioport != NULL) {
+ bus_release_resource(dev, SYS_RES_IOPORT, adapter->io_rid,
+ adapter->res_ioport);
+ }
+ return;
+}
+#endif
+
+/*********************************************************************
+ *
+ * Initialize the hardware to a configuration as specified by the
+ * adapter structure. The controller is reset, the EEPROM is
+ * verified, the MAC address is set, then the shared initialization
+ * routines are called.
+ *
+ **********************************************************************/
+static int
+em_hardware_init(struct adapter * adapter)
+{
+ INIT_DEBUGOUT("em_hardware_init: begin");
+ /* Issue a global reset */
+ em_reset_hw(&adapter->hw);
+
+ /* When hardware is reset, fifo_head is also reset */
+ adapter->tx_fifo_head = 0;
+
+ /* Make sure we have a good EEPROM before we read from it */
+ if (em_validate_eeprom_checksum(&adapter->hw) < 0) {
+ printf("em%d: The EEPROM Checksum Is Not Valid\n",
+ adapter->unit);
+ return(EIO);
+ }
+
+ if (em_read_part_num(&adapter->hw, &(adapter->part_num)) < 0) {
+ printf("em%d: EEPROM read error while reading part number\n",
+ adapter->unit);
+ return(EIO);
+ }
+
+ if (em_init_hw(&adapter->hw) < 0) {
+ printf("em%d: Hardware Initialization Failed",
+ adapter->unit);
+ return(EIO);
+ }
+
+ em_check_for_link(&adapter->hw);
+ if (E1000_READ_REG(&adapter->hw, STATUS) & E1000_STATUS_LU)
+ adapter->link_active = 1;
+ else
+ adapter->link_active = 0;
+
+ if (adapter->link_active) {
+ em_get_speed_and_duplex(&adapter->hw,
+ &adapter->link_speed,
+ &adapter->link_duplex);
+ } else {
+ adapter->link_speed = 0;
+ adapter->link_duplex = 0;
+ }
+
+ return(0);
+}
+
+/*********************************************************************
+ *
+ * Setup networking device structure and register an interface.
+ *
+ **********************************************************************/
+static void
+em_setup_interface(device_t dev, struct adapter * adapter)
+{
+ struct ifnet *ifp = &device_get_softc(dev)->arpcom.ac_if;
+ INIT_DEBUGOUT("em_setup_interface: begin");
+
+ if_initname(ifp, device_get_name(dev), device_get_unit(dev));
+ ifp->if_mtu = ETHERMTU;
+ ifp->if_baudrate = 1000000000;
+ ifp->if_init = em_init;
+ ifp->if_softc = adapter;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+#ifdef __rtems__
+ ifp->if_output = ether_output;
+#endif
+ ifp->if_ioctl = em_ioctl;
+ ifp->if_start = em_start;
+ ifp->if_watchdog = em_watchdog;
+#ifndef __rtems__
+ IFQ_SET_MAXLEN(&ifp->if_snd, adapter->num_tx_desc - 1);
+ ifp->if_snd.ifq_drv_maxlen = adapter->num_tx_desc - 1;
+ IFQ_SET_READY(&ifp->if_snd);
+#else
+ ifp->if_snd.ifq_maxlen = adapter->num_tx_desc - 1;
+#endif
+
+#ifndef __rtems__
+#if __FreeBSD_version < 500000
+ ether_ifattach(ifp, ETHER_BPF_SUPPORTED);
+#else
+ ether_ifattach(ifp, adapter->hw.mac_addr);
+#endif
+#else
+ if ( !ifp->if_addrlist ) /* reattach hack */
+ {
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ }
+#endif
+
+#ifndef __rtems__
+ ifp->if_capabilities = ifp->if_capenable = 0;
+
+ if (adapter->hw.mac_type >= em_82543) {
+ ifp->if_capabilities |= IFCAP_HWCSUM;
+ ifp->if_capenable |= IFCAP_HWCSUM;
+ }
+
+ /*
+ * Tell the upper layer(s) we support long frames.
+ */
+ ifp->if_data.ifi_hdrlen = sizeof(struct ether_vlan_header);
+#if __FreeBSD_version >= 500000
+ ifp->if_capabilities |= IFCAP_VLAN_HWTAGGING | IFCAP_VLAN_MTU;
+ ifp->if_capenable |= IFCAP_VLAN_MTU;
+#endif
+
+#ifdef DEVICE_POLLING
+ ifp->if_capabilities |= IFCAP_POLLING;
+ ifp->if_capenable |= IFCAP_POLLING;
+#endif
+
+ /*
+ * Specify the media types supported by this adapter and register
+ * callbacks to update media and link information
+ */
+ ifmedia_init(&adapter->media, IFM_IMASK, em_media_change,
+ em_media_status);
+ if (adapter->hw.media_type == em_media_type_fiber) {
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_SX | IFM_FDX,
+ 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_SX,
+ 0, NULL);
+ } else {
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_10_T, 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_10_T | IFM_FDX,
+ 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_100_TX,
+ 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_100_TX | IFM_FDX,
+ 0, NULL);
+#if __FreeBSD_version < 500000
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_TX | IFM_FDX,
+ 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_TX, 0, NULL);
+#else
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_T | IFM_FDX,
+ 0, NULL);
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_1000_T, 0, NULL);
+#endif
+ }
+ ifmedia_add(&adapter->media, IFM_ETHER | IFM_AUTO, 0, NULL);
+ ifmedia_set(&adapter->media, IFM_ETHER | IFM_AUTO);
+#endif
+
+ return;
+}
+
+#ifndef __rtems__
+/*********************************************************************
+ *
+ * Workaround for SmartSpeed on 82541 and 82547 controllers
+ *
+ **********************************************************************/
+static void
+em_smartspeed(struct adapter *adapter)
+{
+ uint16_t phy_tmp;
+
+ if(adapter->link_active || (adapter->hw.phy_type != em_phy_igp) ||
+ !adapter->hw.autoneg || !(adapter->hw.autoneg_advertised & ADVERTISE_1000_FULL))
+ return;
+
+ if(adapter->smartspeed == 0) {
+ /* If Master/Slave config fault is asserted twice,
+ * we assume back-to-back */
+ em_read_phy_reg(&adapter->hw, PHY_1000T_STATUS, &phy_tmp);
+ if(!(phy_tmp & SR_1000T_MS_CONFIG_FAULT)) return;
+ em_read_phy_reg(&adapter->hw, PHY_1000T_STATUS, &phy_tmp);
+ if(phy_tmp & SR_1000T_MS_CONFIG_FAULT) {
+ em_read_phy_reg(&adapter->hw, PHY_1000T_CTRL,
+ &phy_tmp);
+ if(phy_tmp & CR_1000T_MS_ENABLE) {
+ phy_tmp &= ~CR_1000T_MS_ENABLE;
+ em_write_phy_reg(&adapter->hw,
+ PHY_1000T_CTRL, phy_tmp);
+ adapter->smartspeed++;
+ if(adapter->hw.autoneg &&
+ !em_phy_setup_autoneg(&adapter->hw) &&
+ !em_read_phy_reg(&adapter->hw, PHY_CTRL,
+ &phy_tmp)) {
+ phy_tmp |= (MII_CR_AUTO_NEG_EN |
+ MII_CR_RESTART_AUTO_NEG);
+ em_write_phy_reg(&adapter->hw,
+ PHY_CTRL, phy_tmp);
+ }
+ }
+ }
+ return;
+ } else if(adapter->smartspeed == EM_SMARTSPEED_DOWNSHIFT) {
+ /* If still no link, perhaps using 2/3 pair cable */
+ em_read_phy_reg(&adapter->hw, PHY_1000T_CTRL, &phy_tmp);
+ phy_tmp |= CR_1000T_MS_ENABLE;
+ em_write_phy_reg(&adapter->hw, PHY_1000T_CTRL, phy_tmp);
+ if(adapter->hw.autoneg &&
+ !em_phy_setup_autoneg(&adapter->hw) &&
+ !em_read_phy_reg(&adapter->hw, PHY_CTRL, &phy_tmp)) {
+ phy_tmp |= (MII_CR_AUTO_NEG_EN |
+ MII_CR_RESTART_AUTO_NEG);
+ em_write_phy_reg(&adapter->hw, PHY_CTRL, phy_tmp);
+ }
+ }
+ /* Restart process after EM_SMARTSPEED_MAX iterations */
+ if(adapter->smartspeed++ == EM_SMARTSPEED_MAX)
+ adapter->smartspeed = 0;
+
+ return;
+}
+
+
+/*
+ * Manage DMA'able memory.
+ */
+static void
+em_dmamap_cb(void *arg, bus_dma_segment_t *segs, int nseg, int error)
+{
+ if (error)
+ return;
+ *(bus_addr_t*) arg = segs->ds_addr;
+ return;
+}
+#endif
+
+static int
+em_dma_malloc(struct adapter *adapter, bus_size_t size,
+ struct em_dma_alloc *dma, int mapflags)
+{
+ int r;
+
+#ifndef __rtems__
+ r = bus_dma_tag_create(NULL, /* parent */
+ PAGE_SIZE, 0, /* alignment, bounds */
+ BUS_SPACE_MAXADDR, /* lowaddr */
+ BUS_SPACE_MAXADDR, /* highaddr */
+ NULL, NULL, /* filter, filterarg */
+ size, /* maxsize */
+ 1, /* nsegments */
+ size, /* maxsegsize */
+ BUS_DMA_ALLOCNOW, /* flags */
+ NULL, /* lockfunc */
+ NULL, /* lockarg */
+ &dma->dma_tag);
+ if (r != 0) {
+ printf("em%d: em_dma_malloc: bus_dma_tag_create failed; "
+ "error %u\n", adapter->unit, r);
+ goto fail_0;
+ }
+
+ r = bus_dmamem_alloc(dma->dma_tag, (void**) &dma->dma_vaddr,
+ BUS_DMA_NOWAIT, &dma->dma_map);
+#else
+ if ( (dma->malloc_base = malloc( size + PAGE_SIZE, M_DEVBUF, M_NOWAIT )) ) {
+ r = 0;
+ dma->dma_vaddr = (caddr_t)_DO_ALIGN(dma->malloc_base, PAGE_SIZE);
+ } else {
+ r = -1;
+ }
+#endif
+ if (r != 0) {
+#ifndef __rtems__
+ printf("em%d: em_dma_malloc: bus_dmammem_alloc failed; "
+ "size %ju, error %d\n", adapter->unit,
+ (uintmax_t)size, r);
+#else
+ printf("em%d: em_dma_malloc: bus_dmammem_alloc failed; "
+ "size %u, error %d\n", adapter->unit,
+ size, r);
+#endif
+ goto fail_2;
+ }
+
+#ifndef __rtems__
+ r = bus_dmamap_load(dma->dma_tag, dma->dma_map, dma->dma_vaddr,
+ size,
+ em_dmamap_cb,
+ &dma->dma_paddr,
+ mapflags | BUS_DMA_NOWAIT);
+#else
+ dma->dma_paddr = kvtop(dma->dma_vaddr);
+#endif
+ if (r != 0) {
+ printf("em%d: em_dma_malloc: bus_dmamap_load failed; "
+ "error %u\n", adapter->unit, r);
+ goto fail_3;
+ }
+
+#ifndef __rtems__
+ dma->dma_size = size;
+#endif
+ return (0);
+
+fail_3:
+ bus_dmamap_unload(dma->dma_tag, dma->dma_map);
+fail_2:
+#ifndef __rtems__
+ bus_dmamem_free(dma->dma_tag, dma->dma_vaddr, dma->dma_map);
+#else
+ free(dma->malloc_base, M_DEVBUF);
+ dma->dma_vaddr = dma->malloc_base = 0;
+ dma->dma_paddr = 0;
+#endif
+ bus_dma_tag_destroy(dma->dma_tag);
+#ifndef __rtems__
+fail_0:
+ dma->dma_map = NULL;
+ dma->dma_tag = NULL;
+#endif
+ return (r);
+}
+
+static void
+em_dma_free(struct adapter *adapter, struct em_dma_alloc *dma)
+{
+ bus_dmamap_unload(dma->dma_tag, dma->dma_map);
+#ifndef __rtems__
+ bus_dmamem_free(dma->dma_tag, dma->dma_vaddr, dma->dma_map);
+#else
+ free(dma->malloc_base, M_DEVBUF);
+ dma->dma_vaddr = dma->malloc_base = 0;
+ dma->dma_paddr = 0;
+#endif
+ bus_dma_tag_destroy(dma->dma_tag);
+}
+
+
+/*********************************************************************
+ *
+ * Allocate memory for tx_buffer structures. The tx_buffer stores all
+ * the information needed to transmit a packet on the wire.
+ *
+ **********************************************************************/
+static int
+em_allocate_transmit_structures(struct adapter * adapter)
+{
+ if (!(adapter->tx_buffer_area =
+ (struct em_buffer *) malloc(sizeof(struct em_buffer) *
+ adapter->num_tx_desc, M_DEVBUF,
+ M_NOWAIT))) {
+ printf("em%d: Unable to allocate tx_buffer memory\n",
+ adapter->unit);
+ return ENOMEM;
+ }
+
+ bzero(adapter->tx_buffer_area,
+ sizeof(struct em_buffer) * adapter->num_tx_desc);
+
+ return 0;
+}
+
+/*********************************************************************
+ *
+ * Allocate and initialize transmit structures.
+ *
+ **********************************************************************/
+static int
+em_setup_transmit_structures(struct adapter * adapter)
+{
+#ifndef __rtems__
+ /*
+ * Setup DMA descriptor areas.
+ */
+ if (bus_dma_tag_create(NULL, /* parent */
+ 1, 0, /* alignment, bounds */
+ BUS_SPACE_MAXADDR, /* lowaddr */
+ BUS_SPACE_MAXADDR, /* highaddr */
+ NULL, NULL, /* filter, filterarg */
+ MCLBYTES * 8, /* maxsize */
+ EM_MAX_SCATTER, /* nsegments */
+ MCLBYTES * 8, /* maxsegsize */
+ BUS_DMA_ALLOCNOW, /* flags */
+ NULL, /* lockfunc */
+ NULL, /* lockarg */
+ &adapter->txtag)) {
+ printf("em%d: Unable to allocate TX DMA tag\n", adapter->unit);
+ return (ENOMEM);
+ }
+#endif
+
+ if (em_allocate_transmit_structures(adapter))
+ return (ENOMEM);
+
+ bzero((void *) adapter->tx_desc_base,
+ (sizeof(struct em_tx_desc)) * adapter->num_tx_desc);
+
+ adapter->next_avail_tx_desc = 0;
+ adapter->oldest_used_tx_desc = 0;
+
+ /* Set number of descriptors available */
+ adapter->num_tx_desc_avail = adapter->num_tx_desc;
+
+ /* Set checksum context */
+ adapter->active_checksum_context = OFFLOAD_NONE;
+
+ return (0);
+}
+
+/*********************************************************************
+ *
+ * Enable transmit unit.
+ *
+ **********************************************************************/
+static void
+em_initialize_transmit_unit(struct adapter * adapter)
+{
+ u_int32_t reg_tctl;
+ u_int32_t reg_tipg = 0;
+ u_int64_t bus_addr;
+
+ INIT_DEBUGOUT("em_initialize_transmit_unit: begin");
+ /* Setup the Base and Length of the Tx Descriptor Ring */
+ bus_addr = adapter->txdma.dma_paddr;
+ E1000_WRITE_REG(&adapter->hw, TDBAL, (u_int32_t)bus_addr);
+ E1000_WRITE_REG(&adapter->hw, TDBAH, (u_int32_t)(bus_addr >> 32));
+ E1000_WRITE_REG(&adapter->hw, TDLEN,
+ adapter->num_tx_desc *
+ sizeof(struct em_tx_desc));
+
+ /* Setup the HW Tx Head and Tail descriptor pointers */
+ E1000_WRITE_REG(&adapter->hw, TDH, 0);
+ E1000_WRITE_REG(&adapter->hw, TDT, 0);
+
+
+ HW_DEBUGOUT2("Base = %" PRIx32 ", Length = %" PRIx32 "\n",
+ E1000_READ_REG(&adapter->hw, TDBAL),
+ E1000_READ_REG(&adapter->hw, TDLEN));
+
+ /* Set the default values for the Tx Inter Packet Gap timer */
+ switch (adapter->hw.mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ reg_tipg = DEFAULT_82542_TIPG_IPGT;
+ reg_tipg |= DEFAULT_82542_TIPG_IPGR1 << E1000_TIPG_IPGR1_SHIFT;
+ reg_tipg |= DEFAULT_82542_TIPG_IPGR2 << E1000_TIPG_IPGR2_SHIFT;
+ break;
+ default:
+ if (adapter->hw.media_type == em_media_type_fiber)
+ reg_tipg = DEFAULT_82543_TIPG_IPGT_FIBER;
+ else
+ reg_tipg = DEFAULT_82543_TIPG_IPGT_COPPER;
+ reg_tipg |= DEFAULT_82543_TIPG_IPGR1 << E1000_TIPG_IPGR1_SHIFT;
+ reg_tipg |= DEFAULT_82543_TIPG_IPGR2 << E1000_TIPG_IPGR2_SHIFT;
+ }
+
+ E1000_WRITE_REG(&adapter->hw, TIPG, reg_tipg);
+ E1000_WRITE_REG(&adapter->hw, TIDV, adapter->tx_int_delay.value);
+ if(adapter->hw.mac_type >= em_82540)
+ E1000_WRITE_REG(&adapter->hw, TADV,
+ adapter->tx_abs_int_delay.value);
+
+ /* Program the Transmit Control Register */
+ reg_tctl = E1000_TCTL_PSP | E1000_TCTL_EN |
+ (E1000_COLLISION_THRESHOLD << E1000_CT_SHIFT);
+ if (adapter->hw.mac_type >= em_82573)
+ reg_tctl |= E1000_TCTL_MULR;
+ if (adapter->link_duplex == 1) {
+ reg_tctl |= E1000_FDX_COLLISION_DISTANCE << E1000_COLD_SHIFT;
+ } else {
+ reg_tctl |= E1000_HDX_COLLISION_DISTANCE << E1000_COLD_SHIFT;
+ }
+ E1000_WRITE_REG(&adapter->hw, TCTL, reg_tctl);
+
+ /* Setup Transmit Descriptor Settings for this adapter */
+ adapter->txd_cmd = E1000_TXD_CMD_IFCS | E1000_TXD_CMD_RS;
+
+ if (adapter->tx_int_delay.value > 0)
+ adapter->txd_cmd |= E1000_TXD_CMD_IDE;
+
+ return;
+}
+
+/*********************************************************************
+ *
+ * Free all transmit related data structures.
+ *
+ **********************************************************************/
+static void
+em_free_transmit_structures(struct adapter * adapter)
+{
+ struct em_buffer *tx_buffer;
+ int i;
+
+ INIT_DEBUGOUT("free_transmit_structures: begin");
+
+ if (adapter->tx_buffer_area != NULL) {
+ tx_buffer = adapter->tx_buffer_area;
+ for (i = 0; i < adapter->num_tx_desc; i++, tx_buffer++) {
+ if (tx_buffer->m_head != NULL) {
+ bus_dmamap_unload(adapter->txtag, tx_buffer->map);
+ bus_dmamap_destroy(adapter->txtag, tx_buffer->map);
+ m_freem(tx_buffer->m_head);
+ }
+ tx_buffer->m_head = NULL;
+ }
+ }
+ if (adapter->tx_buffer_area != NULL) {
+ free(adapter->tx_buffer_area, M_DEVBUF);
+ adapter->tx_buffer_area = NULL;
+ }
+#ifndef __rtems__
+ if (adapter->txtag != NULL) {
+ bus_dma_tag_destroy(adapter->txtag);
+ adapter->txtag = NULL;
+ }
+#endif
+ return;
+}
+
+#ifndef __rtems__
+/*********************************************************************
+ *
+ * The offload context needs to be set when we transfer the first
+ * packet of a particular protocol (TCP/UDP). We change the
+ * context only if the protocol type changes.
+ *
+ **********************************************************************/
+static void
+em_transmit_checksum_setup(struct adapter * adapter,
+ struct mbuf *mp,
+ u_int32_t *txd_upper,
+ u_int32_t *txd_lower)
+{
+ struct em_context_desc *TXD;
+ struct em_buffer *tx_buffer;
+ int curr_txd;
+
+ if (mp->m_pkthdr.csum_flags) {
+
+ if (mp->m_pkthdr.csum_flags & CSUM_TCP) {
+ *txd_upper = E1000_TXD_POPTS_TXSM << 8;
+ *txd_lower = E1000_TXD_CMD_DEXT | E1000_TXD_DTYP_D;
+ if (adapter->active_checksum_context == OFFLOAD_TCP_IP)
+ return;
+ else
+ adapter->active_checksum_context = OFFLOAD_TCP_IP;
+
+ } else if (mp->m_pkthdr.csum_flags & CSUM_UDP) {
+ *txd_upper = E1000_TXD_POPTS_TXSM << 8;
+ *txd_lower = E1000_TXD_CMD_DEXT | E1000_TXD_DTYP_D;
+ if (adapter->active_checksum_context == OFFLOAD_UDP_IP)
+ return;
+ else
+ adapter->active_checksum_context = OFFLOAD_UDP_IP;
+ } else {
+ *txd_upper = 0;
+ *txd_lower = 0;
+ return;
+ }
+ } else {
+ *txd_upper = 0;
+ *txd_lower = 0;
+ return;
+ }
+
+ /* If we reach this point, the checksum offload context
+ * needs to be reset.
+ */
+ curr_txd = adapter->next_avail_tx_desc;
+ tx_buffer = &adapter->tx_buffer_area[curr_txd];
+ TXD = (struct em_context_desc *) &adapter->tx_desc_base[curr_txd];
+
+ TXD->lower_setup.ip_fields.ipcss = ETHER_HDR_LEN;
+ TXD->lower_setup.ip_fields.ipcso =
+ ETHER_HDR_LEN + offsetof(struct ip, ip_sum);
+ TXD->lower_setup.ip_fields.ipcse =
+ htole16(ETHER_HDR_LEN + sizeof(struct ip) - 1);
+
+ TXD->upper_setup.tcp_fields.tucss =
+ ETHER_HDR_LEN + sizeof(struct ip);
+ TXD->upper_setup.tcp_fields.tucse = htole16(0);
+
+ if (adapter->active_checksum_context == OFFLOAD_TCP_IP) {
+ TXD->upper_setup.tcp_fields.tucso =
+ ETHER_HDR_LEN + sizeof(struct ip) +
+ offsetof(struct tcphdr, th_sum);
+ } else if (adapter->active_checksum_context == OFFLOAD_UDP_IP) {
+ TXD->upper_setup.tcp_fields.tucso =
+ ETHER_HDR_LEN + sizeof(struct ip) +
+ offsetof(struct udphdr, uh_sum);
+ }
+
+ TXD->tcp_seg_setup.data = htole32(0);
+ TXD->cmd_and_length = htole32(adapter->txd_cmd | E1000_TXD_CMD_DEXT);
+
+ tx_buffer->m_head = NULL;
+
+ if (++curr_txd == adapter->num_tx_desc)
+ curr_txd = 0;
+
+ adapter->num_tx_desc_avail--;
+ adapter->next_avail_tx_desc = curr_txd;
+
+ return;
+}
+#endif
+
+/**********************************************************************
+ *
+ * Examine each tx_buffer in the used queue. If the hardware is done
+ * processing the packet then free associated resources. The
+ * tx_buffer is put back on the free queue.
+ *
+ **********************************************************************/
+static void
+em_clean_transmit_interrupts(struct adapter * adapter)
+{
+ int i, num_avail;
+ struct em_buffer *tx_buffer;
+ struct em_tx_desc *tx_desc;
+ struct ifnet *ifp = &adapter->arpcom.ac_if;
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ if (adapter->num_tx_desc_avail == adapter->num_tx_desc)
+ return;
+
+ num_avail = adapter->num_tx_desc_avail;
+ i = adapter->oldest_used_tx_desc;
+
+ tx_buffer = &adapter->tx_buffer_area[i];
+ tx_desc = &adapter->tx_desc_base[i];
+
+ bus_dmamap_sync(adapter->txdma.dma_tag, adapter->txdma.dma_map,
+ BUS_DMASYNC_POSTREAD);
+ while (tx_desc->upper.fields.status & E1000_TXD_STAT_DD) {
+
+ tx_desc->upper.data = 0;
+ num_avail++;
+
+ if (tx_buffer->m_head) {
+ ifp->if_opackets++;
+ bus_dmamap_unload(adapter->txtag, tx_buffer->map);
+ bus_dmamap_destroy(adapter->txtag, tx_buffer->map);
+
+ m_freem(tx_buffer->m_head);
+ tx_buffer->m_head = NULL;
+ }
+
+ if (++i == adapter->num_tx_desc)
+ i = 0;
+
+ tx_buffer = &adapter->tx_buffer_area[i];
+ tx_desc = &adapter->tx_desc_base[i];
+ }
+ bus_dmamap_sync(adapter->txdma.dma_tag, adapter->txdma.dma_map,
+ BUS_DMASYNC_PREREAD | BUS_DMASYNC_PREWRITE);
+
+ adapter->oldest_used_tx_desc = i;
+
+ /*
+ * If we have enough room, clear IFF_OACTIVE to tell the stack
+ * that it is OK to send packets.
+ * If there are no pending descriptors, clear the timeout. Otherwise,
+ * if some descriptors have been freed, restart the timeout.
+ */
+ if (num_avail > EM_TX_CLEANUP_THRESHOLD) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ if (num_avail == adapter->num_tx_desc)
+ ifp->if_timer = 0;
+ else if (num_avail == adapter->num_tx_desc_avail)
+ ifp->if_timer = EM_TX_TIMEOUT;
+ }
+ adapter->num_tx_desc_avail = num_avail;
+ return;
+}
+
+/*********************************************************************
+ *
+ * Get a buffer from system mbuf buffer pool.
+ *
+ **********************************************************************/
+static int
+em_get_buf(int i, struct adapter *adapter,
+ struct mbuf *nmp)
+{
+ register struct mbuf *mp = nmp;
+ struct em_buffer *rx_buffer;
+ struct ifnet *ifp;
+ bus_addr_t paddr;
+#ifndef __rtems__
+ int error;
+#endif
+
+ ifp = &adapter->arpcom.ac_if;
+
+ if (mp == NULL) {
+#ifndef __rtems__
+ mp = m_getcl(M_DONTWAIT, MT_DATA, M_PKTHDR);
+#else
+ MGETHDR(mp, M_DONTWAIT, MT_DATA);
+ if ( mp ) {
+ MCLGET( mp, M_DONTWAIT );
+ if ( !(mp->m_flags & M_EXT) ) {
+ m_freem(mp);
+ mp = 0;
+ }
+ }
+#endif
+ if (mp == NULL) {
+ adapter->mbuf_cluster_failed++;
+ return(ENOBUFS);
+ }
+ mp->m_len = mp->m_pkthdr.len = MCLBYTES;
+ } else {
+ mp->m_len = mp->m_pkthdr.len = MCLBYTES;
+ mp->m_data = mp->m_ext.ext_buf;
+ mp->m_next = NULL;
+ }
+
+ if (ifp->if_mtu <= ETHERMTU) {
+ m_adj(mp, ETHER_ALIGN);
+ }
+
+ rx_buffer = &adapter->rx_buffer_area[i];
+
+#ifndef __rtems__
+ /*
+ * Using memory from the mbuf cluster pool, invoke the
+ * bus_dma machinery to arrange the memory mapping.
+ */
+ error = bus_dmamap_load(adapter->rxtag, rx_buffer->map,
+ mtod(mp, void *), mp->m_len,
+ em_dmamap_cb, &paddr, 0);
+ if (error) {
+ m_free(mp);
+ return(error);
+ }
+#else
+ paddr = kvtop(mtod(mp, void*));
+#endif
+
+ rx_buffer->m_head = mp;
+ adapter->rx_desc_base[i].buffer_addr = htole64(paddr);
+ bus_dmamap_sync(adapter->rxtag, rx_buffer->map, BUS_DMASYNC_PREREAD);
+
+ return(0);
+}
+
+/*********************************************************************
+ *
+ * Allocate memory for rx_buffer structures. Since we use one
+ * rx_buffer per received packet, the maximum number of rx_buffer's
+ * that we'll need is equal to the number of receive descriptors
+ * that we've allocated.
+ *
+ **********************************************************************/
+static int
+em_allocate_receive_structures(struct adapter * adapter)
+{
+ int i, error;
+#ifndef __rtems__
+ struct em_buffer *rx_buffer;
+#endif
+
+ if (!(adapter->rx_buffer_area =
+ (struct em_buffer *) malloc(sizeof(struct em_buffer) *
+ adapter->num_rx_desc, M_DEVBUF,
+ M_NOWAIT))) {
+ printf("em%d: Unable to allocate rx_buffer memory\n",
+ adapter->unit);
+ return(ENOMEM);
+ }
+
+ bzero(adapter->rx_buffer_area,
+ sizeof(struct em_buffer) * adapter->num_rx_desc);
+
+#ifndef __rtems__
+ error = bus_dma_tag_create(NULL, /* parent */
+ 1, 0, /* alignment, bounds */
+ BUS_SPACE_MAXADDR, /* lowaddr */
+ BUS_SPACE_MAXADDR, /* highaddr */
+ NULL, NULL, /* filter, filterarg */
+ MCLBYTES, /* maxsize */
+ 1, /* nsegments */
+ MCLBYTES, /* maxsegsize */
+ BUS_DMA_ALLOCNOW, /* flags */
+ NULL, /* lockfunc */
+ NULL, /* lockarg */
+ &adapter->rxtag);
+ if (error != 0) {
+ printf("em%d: em_allocate_receive_structures: "
+ "bus_dma_tag_create failed; error %u\n",
+ adapter->unit, error);
+ goto fail_0;
+ }
+ rx_buffer = adapter->rx_buffer_area;
+ for (i = 0; i < adapter->num_rx_desc; i++, rx_buffer++) {
+ error = bus_dmamap_create(adapter->rxtag, BUS_DMA_NOWAIT,
+ &rx_buffer->map);
+ if (error != 0) {
+ printf("em%d: em_allocate_receive_structures: "
+ "bus_dmamap_create failed; error %u\n",
+ adapter->unit, error);
+ goto fail_1;
+ }
+ }
+
+#else
+ error = 0;
+#endif
+
+ for (i = 0; i < adapter->num_rx_desc; i++) {
+ error = em_get_buf(i, adapter, NULL);
+ if (error != 0) {
+ adapter->rx_buffer_area[i].m_head = NULL;
+ adapter->rx_desc_base[i].buffer_addr = 0;
+ return(error);
+ }
+ }
+ bus_dmamap_sync(adapter->rxdma.dma_tag, adapter->rxdma.dma_map,
+ BUS_DMASYNC_PREREAD | BUS_DMASYNC_PREWRITE);
+
+ return(0);
+
+#ifndef __rtems__
+fail_1:
+ bus_dma_tag_destroy(adapter->rxtag);
+fail_0:
+ adapter->rxtag = NULL;
+#endif
+ free(adapter->rx_buffer_area, M_DEVBUF);
+ adapter->rx_buffer_area = NULL;
+ return (error);
+}
+
+/*********************************************************************
+ *
+ * Allocate and initialize receive structures.
+ *
+ **********************************************************************/
+static int
+em_setup_receive_structures(struct adapter * adapter)
+{
+ bzero((void *) adapter->rx_desc_base,
+ (sizeof(struct em_rx_desc)) * adapter->num_rx_desc);
+
+ if (em_allocate_receive_structures(adapter))
+ return ENOMEM;
+
+ /* Setup our descriptor pointers */
+ adapter->next_rx_desc_to_check = 0;
+ return(0);
+}
+
+/*********************************************************************
+ *
+ * Enable receive unit.
+ *
+ **********************************************************************/
+static void
+em_initialize_receive_unit(struct adapter * adapter)
+{
+ u_int32_t reg_rctl;
+#ifndef __rtems__
+ u_int32_t reg_rxcsum;
+#endif
+ struct ifnet *ifp;
+ u_int64_t bus_addr;
+
+ INIT_DEBUGOUT("em_initialize_receive_unit: begin");
+ ifp = &adapter->arpcom.ac_if;
+
+ /* Make sure receives are disabled while setting up the descriptor ring */
+ E1000_WRITE_REG(&adapter->hw, RCTL, 0);
+
+ /* Set the Receive Delay Timer Register */
+ E1000_WRITE_REG(&adapter->hw, RDTR,
+ adapter->rx_int_delay.value | E1000_RDT_FPDB);
+
+ if(adapter->hw.mac_type >= em_82540) {
+ E1000_WRITE_REG(&adapter->hw, RADV,
+ adapter->rx_abs_int_delay.value);
+
+ /* Set the interrupt throttling rate. Value is calculated
+ * as DEFAULT_ITR = 1/(MAX_INTS_PER_SEC * 256ns) */
+#define MAX_INTS_PER_SEC 8000
+#define DEFAULT_ITR 1000000000/(MAX_INTS_PER_SEC * 256)
+ E1000_WRITE_REG(&adapter->hw, ITR, DEFAULT_ITR);
+ }
+
+ /* Setup the Base and Length of the Rx Descriptor Ring */
+ bus_addr = adapter->rxdma.dma_paddr;
+ E1000_WRITE_REG(&adapter->hw, RDBAL, (u_int32_t)bus_addr);
+ E1000_WRITE_REG(&adapter->hw, RDBAH, (u_int32_t)(bus_addr >> 32));
+ E1000_WRITE_REG(&adapter->hw, RDLEN, adapter->num_rx_desc *
+ sizeof(struct em_rx_desc));
+
+ /* Setup the HW Rx Head and Tail Descriptor Pointers */
+ E1000_WRITE_REG(&adapter->hw, RDH, 0);
+ E1000_WRITE_REG(&adapter->hw, RDT, adapter->num_rx_desc - 1);
+
+ /* Setup the Receive Control Register */
+ reg_rctl = E1000_RCTL_EN | E1000_RCTL_BAM | E1000_RCTL_LBM_NO |
+ E1000_RCTL_RDMTS_HALF |
+ (adapter->hw.mc_filter_type << E1000_RCTL_MO_SHIFT);
+
+ if (adapter->hw.tbi_compatibility_on == TRUE)
+ reg_rctl |= E1000_RCTL_SBP;
+
+
+ switch (adapter->rx_buffer_len) {
+ default:
+ case EM_RXBUFFER_2048:
+ reg_rctl |= E1000_RCTL_SZ_2048;
+ break;
+ case EM_RXBUFFER_4096:
+ reg_rctl |= E1000_RCTL_SZ_4096 | E1000_RCTL_BSEX | E1000_RCTL_LPE;
+ break;
+ case EM_RXBUFFER_8192:
+ reg_rctl |= E1000_RCTL_SZ_8192 | E1000_RCTL_BSEX | E1000_RCTL_LPE;
+ break;
+ case EM_RXBUFFER_16384:
+ reg_rctl |= E1000_RCTL_SZ_16384 | E1000_RCTL_BSEX | E1000_RCTL_LPE;
+ break;
+ }
+
+ if (ifp->if_mtu > ETHERMTU)
+ reg_rctl |= E1000_RCTL_LPE;
+
+#ifndef __rtems__
+ /* Enable 82543 Receive Checksum Offload for TCP and UDP */
+ if ((adapter->hw.mac_type >= em_82543) &&
+ (ifp->if_capenable & IFCAP_RXCSUM)) {
+ reg_rxcsum = E1000_READ_REG(&adapter->hw, RXCSUM);
+ reg_rxcsum |= (E1000_RXCSUM_IPOFL | E1000_RXCSUM_TUOFL);
+ E1000_WRITE_REG(&adapter->hw, RXCSUM, reg_rxcsum);
+ }
+#endif
+
+ /* Enable Receives */
+ E1000_WRITE_REG(&adapter->hw, RCTL, reg_rctl);
+
+ return;
+}
+
+/*********************************************************************
+ *
+ * Free receive related data structures.
+ *
+ **********************************************************************/
+static void
+em_free_receive_structures(struct adapter *adapter)
+{
+ struct em_buffer *rx_buffer;
+ int i;
+
+ INIT_DEBUGOUT("free_receive_structures: begin");
+
+ if (adapter->rx_buffer_area != NULL) {
+ rx_buffer = adapter->rx_buffer_area;
+ for (i = 0; i < adapter->num_rx_desc; i++, rx_buffer++) {
+#ifndef __rtems__
+ if (rx_buffer->map != NULL) {
+ bus_dmamap_unload(adapter->rxtag, rx_buffer->map);
+ bus_dmamap_destroy(adapter->rxtag, rx_buffer->map);
+ }
+#endif
+ if (rx_buffer->m_head != NULL)
+ m_freem(rx_buffer->m_head);
+ rx_buffer->m_head = NULL;
+ }
+ }
+ if (adapter->rx_buffer_area != NULL) {
+ free(adapter->rx_buffer_area, M_DEVBUF);
+ adapter->rx_buffer_area = NULL;
+ }
+#ifndef __rtems__
+ if (adapter->rxtag != NULL) {
+ bus_dma_tag_destroy(adapter->rxtag);
+ adapter->rxtag = NULL;
+ }
+#endif
+ return;
+}
+
+/*********************************************************************
+ *
+ * This routine executes in interrupt context. It replenishes
+ * the mbufs in the descriptor and sends data which has been
+ * dma'ed into host memory to upper layer.
+ *
+ * We loop at most count times if count is > 0, or until done if
+ * count < 0.
+ *
+ *********************************************************************/
+static void
+em_process_receive_interrupts(struct adapter * adapter, int count)
+{
+ struct ifnet *ifp;
+ struct mbuf *mp;
+#if __FreeBSD_version < 500000
+ struct ether_header *eh;
+#endif
+ u_int8_t accept_frame = 0;
+ u_int8_t eop = 0;
+ u_int16_t len, desc_len, prev_len_adj;
+ int i;
+
+ /* Pointer to the receive descriptor being examined. */
+ struct em_rx_desc *current_desc;
+
+ mtx_assert(&adapter->mtx, MA_OWNED);
+
+ ifp = &adapter->arpcom.ac_if;
+ i = adapter->next_rx_desc_to_check;
+ current_desc = &adapter->rx_desc_base[i];
+ bus_dmamap_sync(adapter->rxdma.dma_tag, adapter->rxdma.dma_map,
+ BUS_DMASYNC_POSTREAD);
+
+ if (!((current_desc->status) & E1000_RXD_STAT_DD)) {
+ return;
+ }
+
+ while ((current_desc->status & E1000_RXD_STAT_DD) && (count != 0)) {
+
+ mp = adapter->rx_buffer_area[i].m_head;
+ bus_dmamap_sync(adapter->rxtag, adapter->rx_buffer_area[i].map,
+ BUS_DMASYNC_POSTREAD);
+
+ accept_frame = 1;
+ prev_len_adj = 0;
+ desc_len = le16toh(current_desc->length);
+ if (current_desc->status & E1000_RXD_STAT_EOP) {
+ count--;
+ eop = 1;
+ if (desc_len < ETHER_CRC_LEN) {
+ len = 0;
+ prev_len_adj = ETHER_CRC_LEN - desc_len;
+ }
+ else {
+ len = desc_len - ETHER_CRC_LEN;
+ }
+ } else {
+ eop = 0;
+ len = desc_len;
+ }
+
+ if (current_desc->errors & E1000_RXD_ERR_FRAME_ERR_MASK) {
+ u_int8_t last_byte;
+ u_int32_t pkt_len = desc_len;
+
+ if (adapter->fmp != NULL)
+ pkt_len += adapter->fmp->m_pkthdr.len;
+
+ last_byte = *(mtod(mp, caddr_t) + desc_len - 1);
+
+ if (TBI_ACCEPT(&adapter->hw, current_desc->status,
+ current_desc->errors,
+ pkt_len, last_byte)) {
+ em_tbi_adjust_stats(&adapter->hw,
+ &adapter->stats,
+ pkt_len,
+ adapter->hw.mac_addr);
+ if (len > 0) len--;
+ }
+ else {
+ accept_frame = 0;
+ }
+ }
+
+ if (accept_frame) {
+
+ if (em_get_buf(i, adapter, NULL) == ENOBUFS) {
+ adapter->dropped_pkts++;
+ em_get_buf(i, adapter, mp);
+ if (adapter->fmp != NULL)
+ m_freem(adapter->fmp);
+ adapter->fmp = NULL;
+ adapter->lmp = NULL;
+ break;
+ }
+
+ /* Assign correct length to the current fragment */
+ mp->m_len = len;
+
+ if (adapter->fmp == NULL) {
+ mp->m_pkthdr.len = len;
+ adapter->fmp = mp; /* Store the first mbuf */
+ adapter->lmp = mp;
+ } else {
+ /* Chain mbuf's together */
+ mp->m_flags &= ~M_PKTHDR;
+ /*
+ * Adjust length of previous mbuf in chain if we
+ * received less than 4 bytes in the last descriptor.
+ */
+ if (prev_len_adj > 0) {
+ adapter->lmp->m_len -= prev_len_adj;
+ adapter->fmp->m_pkthdr.len -= prev_len_adj;
+ }
+ adapter->lmp->m_next = mp;
+ adapter->lmp = adapter->lmp->m_next;
+ adapter->fmp->m_pkthdr.len += len;
+ }
+
+ if (eop) {
+ adapter->fmp->m_pkthdr.rcvif = ifp;
+ ifp->if_ipackets++;
+
+#if __FreeBSD_version < 500000
+ eh = mtod(adapter->fmp, struct ether_header *);
+ /* Remove ethernet header from mbuf */
+ m_adj(adapter->fmp, sizeof(struct ether_header));
+#ifndef __rtems__
+ em_receive_checksum(adapter, current_desc,
+ adapter->fmp);
+ if (current_desc->status & E1000_RXD_STAT_VP)
+ VLAN_INPUT_TAG(eh, adapter->fmp,
+ (current_desc->special &
+ E1000_RXD_SPC_VLAN_MASK));
+ else
+#endif
+ ether_input(ifp, eh, adapter->fmp);
+#else
+
+ em_receive_checksum(adapter, current_desc,
+ adapter->fmp);
+ if (current_desc->status & E1000_RXD_STAT_VP)
+ VLAN_INPUT_TAG(ifp, adapter->fmp,
+ (current_desc->special &
+ E1000_RXD_SPC_VLAN_MASK),
+ adapter->fmp = NULL);
+
+ if (adapter->fmp != NULL) {
+ EM_UNLOCK(adapter);
+ (*ifp->if_input)(ifp, adapter->fmp);
+ EM_LOCK(adapter);
+ }
+#endif
+ adapter->fmp = NULL;
+ adapter->lmp = NULL;
+ }
+ } else {
+ adapter->dropped_pkts++;
+ em_get_buf(i, adapter, mp);
+ if (adapter->fmp != NULL)
+ m_freem(adapter->fmp);
+ adapter->fmp = NULL;
+ adapter->lmp = NULL;
+ }
+
+ /* Zero out the receive descriptors status */
+ current_desc->status = 0;
+
+ /* Advance the E1000's Receive Queue #0 "Tail Pointer". */
+ E1000_WRITE_REG(&adapter->hw, RDT, i);
+
+ /* Advance our pointers to the next descriptor */
+ if (++i == adapter->num_rx_desc) {
+ i = 0;
+ current_desc = adapter->rx_desc_base;
+ } else
+ current_desc++;
+ }
+ bus_dmamap_sync(adapter->rxdma.dma_tag, adapter->rxdma.dma_map,
+ BUS_DMASYNC_PREREAD | BUS_DMASYNC_PREWRITE);
+ adapter->next_rx_desc_to_check = i;
+ return;
+}
+
+#ifndef __rtems__
+/*********************************************************************
+ *
+ * Verify that the hardware indicated that the checksum is valid.
+ * Inform the stack about the status of checksum so that stack
+ * doesn't spend time verifying the checksum.
+ *
+ *********************************************************************/
+static void
+em_receive_checksum(struct adapter *adapter,
+ struct em_rx_desc *rx_desc,
+ struct mbuf *mp)
+{
+ /* 82543 or newer only */
+ if ((adapter->hw.mac_type < em_82543) ||
+ /* Ignore Checksum bit is set */
+ (rx_desc->status & E1000_RXD_STAT_IXSM)) {
+ mp->m_pkthdr.csum_flags = 0;
+ return;
+ }
+
+ if (rx_desc->status & E1000_RXD_STAT_IPCS) {
+ /* Did it pass? */
+ if (!(rx_desc->errors & E1000_RXD_ERR_IPE)) {
+ /* IP Checksum Good */
+ mp->m_pkthdr.csum_flags = CSUM_IP_CHECKED;
+ mp->m_pkthdr.csum_flags |= CSUM_IP_VALID;
+
+ } else {
+ mp->m_pkthdr.csum_flags = 0;
+ }
+ }
+
+ if (rx_desc->status & E1000_RXD_STAT_TCPCS) {
+ /* Did it pass? */
+ if (!(rx_desc->errors & E1000_RXD_ERR_TCPE)) {
+ mp->m_pkthdr.csum_flags |=
+ (CSUM_DATA_VALID | CSUM_PSEUDO_HDR);
+ mp->m_pkthdr.csum_data = htons(0xffff);
+ }
+ }
+
+ return;
+}
+
+
+static void
+em_enable_vlans(struct adapter *adapter)
+{
+ uint32_t ctrl;
+
+ E1000_WRITE_REG(&adapter->hw, VET, ETHERTYPE_VLAN);
+
+ ctrl = E1000_READ_REG(&adapter->hw, CTRL);
+ ctrl |= E1000_CTRL_VME;
+ E1000_WRITE_REG(&adapter->hw, CTRL, ctrl);
+
+ return;
+}
+
+static void
+em_disable_vlans(struct adapter *adapter)
+{
+ uint32_t ctrl;
+
+ ctrl = E1000_READ_REG(&adapter->hw, CTRL);
+ ctrl &= ~E1000_CTRL_VME;
+ E1000_WRITE_REG(&adapter->hw, CTRL, ctrl);
+
+ return;
+}
+#endif
+
+static void
+em_enable_intr(struct adapter * adapter)
+{
+ E1000_WRITE_REG(&adapter->hw, IMS, (IMS_ENABLE_MASK));
+ return;
+}
+
+static void
+em_disable_intr(struct adapter *adapter)
+{
+ /*
+ * The first version of 82542 had an errata where when link was forced it
+ * would stay up even up even if the cable was disconnected. Sequence errors
+ * were used to detect the disconnect and then the driver would unforce the link.
+ * This code in the in the ISR. For this to work correctly the Sequence error
+ * interrupt had to be enabled all the time.
+ */
+
+ if (adapter->hw.mac_type == em_82542_rev2_0)
+ E1000_WRITE_REG(&adapter->hw, IMC,
+ (0xffffffff & ~E1000_IMC_RXSEQ));
+ else
+ E1000_WRITE_REG(&adapter->hw, IMC,
+ 0xffffffff);
+ return;
+}
+
+static int
+em_is_valid_ether_addr(u_int8_t *addr)
+{
+ char zero_addr[6] = { 0, 0, 0, 0, 0, 0 };
+
+ if ((addr[0] & 1) || (!bcmp(addr, zero_addr, ETHER_ADDR_LEN))) {
+ return (FALSE);
+ }
+
+ return(TRUE);
+}
+
+void
+em_write_pci_cfg(struct em_hw *hw,
+ uint32_t reg,
+ uint16_t *value)
+{
+ pci_write_config(((struct em_osdep *)hw->back)->dev, reg,
+ *value, 2);
+}
+
+void
+em_read_pci_cfg(struct em_hw *hw, uint32_t reg,
+ uint16_t *value)
+{
+ *value = pci_read_config(((struct em_osdep *)hw->back)->dev,
+ reg, 2);
+ return;
+}
+
+void
+em_pci_set_mwi(struct em_hw *hw)
+{
+ pci_write_config(((struct em_osdep *)hw->back)->dev,
+ PCIR_COMMAND,
+ (hw->pci_cmd_word | CMD_MEM_WRT_INVALIDATE), 2);
+ return;
+}
+
+void
+em_pci_clear_mwi(struct em_hw *hw)
+{
+ pci_write_config(((struct em_osdep *)hw->back)->dev,
+ PCIR_COMMAND,
+ (hw->pci_cmd_word & ~CMD_MEM_WRT_INVALIDATE), 2);
+ return;
+}
+
+uint32_t
+em_io_read(struct em_hw *hw, unsigned long port)
+{
+ return(inl(port));
+}
+
+void
+em_io_write(struct em_hw *hw, unsigned long port, uint32_t value)
+{
+#ifndef __rtems__
+ outl(port, value);
+#else
+ /* everybody else has this the other way round! */
+ outl(value, port);
+#endif
+ return;
+}
+
+/*********************************************************************
+* 82544 Coexistence issue workaround.
+* There are 2 issues.
+* 1. Transmit Hang issue.
+* To detect this issue, following equation can be used...
+* SIZE[3:0] + ADDR[2:0] = SUM[3:0].
+* If SUM[3:0] is in between 1 to 4, we will have this issue.
+*
+* 2. DAC issue.
+* To detect this issue, following equation can be used...
+* SIZE[3:0] + ADDR[2:0] = SUM[3:0].
+* If SUM[3:0] is in between 9 to c, we will have this issue.
+*
+*
+* WORKAROUND:
+* Make sure we do not have ending address as 1,2,3,4(Hang) or 9,a,b,c (DAC)
+*
+*** *********************************************************************/
+static u_int32_t
+em_fill_descriptors (u_int64_t address,
+ u_int32_t length,
+ PDESC_ARRAY desc_array)
+{
+ /* Since issue is sensitive to length and address.*/
+ /* Let us first check the address...*/
+ u_int32_t safe_terminator;
+ if (length <= 4) {
+ desc_array->descriptor[0].address = address;
+ desc_array->descriptor[0].length = length;
+ desc_array->elements = 1;
+ return desc_array->elements;
+ }
+ safe_terminator = (u_int32_t)((((u_int32_t)address & 0x7) + (length & 0xF)) & 0xF);
+ /* if it does not fall between 0x1 to 0x4 and 0x9 to 0xC then return */
+ if (safe_terminator == 0 ||
+ (safe_terminator > 4 &&
+ safe_terminator < 9) ||
+ (safe_terminator > 0xC &&
+ safe_terminator <= 0xF)) {
+ desc_array->descriptor[0].address = address;
+ desc_array->descriptor[0].length = length;
+ desc_array->elements = 1;
+ return desc_array->elements;
+ }
+
+ desc_array->descriptor[0].address = address;
+ desc_array->descriptor[0].length = length - 4;
+ desc_array->descriptor[1].address = address + (length - 4);
+ desc_array->descriptor[1].length = 4;
+ desc_array->elements = 2;
+ return desc_array->elements;
+}
+
+/**********************************************************************
+ *
+ * Update the board statistics counters.
+ *
+ **********************************************************************/
+static void
+em_update_stats_counters(struct adapter *adapter)
+{
+ struct ifnet *ifp;
+
+ if(adapter->hw.media_type == em_media_type_copper ||
+ (E1000_READ_REG(&adapter->hw, STATUS) & E1000_STATUS_LU)) {
+ adapter->stats.symerrs += E1000_READ_REG(&adapter->hw, SYMERRS);
+ adapter->stats.sec += E1000_READ_REG(&adapter->hw, SEC);
+ }
+ adapter->stats.crcerrs += E1000_READ_REG(&adapter->hw, CRCERRS);
+ adapter->stats.mpc += E1000_READ_REG(&adapter->hw, MPC);
+ adapter->stats.scc += E1000_READ_REG(&adapter->hw, SCC);
+ adapter->stats.ecol += E1000_READ_REG(&adapter->hw, ECOL);
+
+ adapter->stats.mcc += E1000_READ_REG(&adapter->hw, MCC);
+ adapter->stats.latecol += E1000_READ_REG(&adapter->hw, LATECOL);
+ adapter->stats.colc += E1000_READ_REG(&adapter->hw, COLC);
+ adapter->stats.dc += E1000_READ_REG(&adapter->hw, DC);
+ adapter->stats.rlec += E1000_READ_REG(&adapter->hw, RLEC);
+ adapter->stats.xonrxc += E1000_READ_REG(&adapter->hw, XONRXC);
+ adapter->stats.xontxc += E1000_READ_REG(&adapter->hw, XONTXC);
+ adapter->stats.xoffrxc += E1000_READ_REG(&adapter->hw, XOFFRXC);
+ adapter->stats.xofftxc += E1000_READ_REG(&adapter->hw, XOFFTXC);
+ adapter->stats.fcruc += E1000_READ_REG(&adapter->hw, FCRUC);
+ adapter->stats.prc64 += E1000_READ_REG(&adapter->hw, PRC64);
+ adapter->stats.prc127 += E1000_READ_REG(&adapter->hw, PRC127);
+ adapter->stats.prc255 += E1000_READ_REG(&adapter->hw, PRC255);
+ adapter->stats.prc511 += E1000_READ_REG(&adapter->hw, PRC511);
+ adapter->stats.prc1023 += E1000_READ_REG(&adapter->hw, PRC1023);
+ adapter->stats.prc1522 += E1000_READ_REG(&adapter->hw, PRC1522);
+ adapter->stats.gprc += E1000_READ_REG(&adapter->hw, GPRC);
+ adapter->stats.bprc += E1000_READ_REG(&adapter->hw, BPRC);
+ adapter->stats.mprc += E1000_READ_REG(&adapter->hw, MPRC);
+ adapter->stats.gptc += E1000_READ_REG(&adapter->hw, GPTC);
+
+ /* For the 64-bit byte counters the low dword must be read first. */
+ /* Both registers clear on the read of the high dword */
+
+ adapter->stats.gorcl += E1000_READ_REG(&adapter->hw, GORCL);
+ adapter->stats.gorch += E1000_READ_REG(&adapter->hw, GORCH);
+ adapter->stats.gotcl += E1000_READ_REG(&adapter->hw, GOTCL);
+ adapter->stats.gotch += E1000_READ_REG(&adapter->hw, GOTCH);
+
+ adapter->stats.rnbc += E1000_READ_REG(&adapter->hw, RNBC);
+ adapter->stats.ruc += E1000_READ_REG(&adapter->hw, RUC);
+ adapter->stats.rfc += E1000_READ_REG(&adapter->hw, RFC);
+ adapter->stats.roc += E1000_READ_REG(&adapter->hw, ROC);
+ adapter->stats.rjc += E1000_READ_REG(&adapter->hw, RJC);
+
+ adapter->stats.torl += E1000_READ_REG(&adapter->hw, TORL);
+ adapter->stats.torh += E1000_READ_REG(&adapter->hw, TORH);
+ adapter->stats.totl += E1000_READ_REG(&adapter->hw, TOTL);
+ adapter->stats.toth += E1000_READ_REG(&adapter->hw, TOTH);
+
+ adapter->stats.tpr += E1000_READ_REG(&adapter->hw, TPR);
+ adapter->stats.tpt += E1000_READ_REG(&adapter->hw, TPT);
+ adapter->stats.ptc64 += E1000_READ_REG(&adapter->hw, PTC64);
+ adapter->stats.ptc127 += E1000_READ_REG(&adapter->hw, PTC127);
+ adapter->stats.ptc255 += E1000_READ_REG(&adapter->hw, PTC255);
+ adapter->stats.ptc511 += E1000_READ_REG(&adapter->hw, PTC511);
+ adapter->stats.ptc1023 += E1000_READ_REG(&adapter->hw, PTC1023);
+ adapter->stats.ptc1522 += E1000_READ_REG(&adapter->hw, PTC1522);
+ adapter->stats.mptc += E1000_READ_REG(&adapter->hw, MPTC);
+ adapter->stats.bptc += E1000_READ_REG(&adapter->hw, BPTC);
+
+ if (adapter->hw.mac_type >= em_82543) {
+ adapter->stats.algnerrc +=
+ E1000_READ_REG(&adapter->hw, ALGNERRC);
+ adapter->stats.rxerrc +=
+ E1000_READ_REG(&adapter->hw, RXERRC);
+ adapter->stats.tncrs +=
+ E1000_READ_REG(&adapter->hw, TNCRS);
+ adapter->stats.cexterr +=
+ E1000_READ_REG(&adapter->hw, CEXTERR);
+ adapter->stats.tsctc +=
+ E1000_READ_REG(&adapter->hw, TSCTC);
+ adapter->stats.tsctfc +=
+ E1000_READ_REG(&adapter->hw, TSCTFC);
+ }
+ ifp = &adapter->arpcom.ac_if;
+
+ /* Fill out the OS statistics structure */
+ ifp->if_ibytes = adapter->stats.gorcl;
+ ifp->if_obytes = adapter->stats.gotcl;
+ ifp->if_imcasts = adapter->stats.mprc;
+ ifp->if_collisions = adapter->stats.colc;
+
+ /* Rx Errors */
+ ifp->if_ierrors =
+ adapter->dropped_pkts +
+ adapter->stats.rxerrc +
+ adapter->stats.crcerrs +
+ adapter->stats.algnerrc +
+ adapter->stats.rlec +
+ adapter->stats.mpc + adapter->stats.cexterr;
+
+ /* Tx Errors */
+ ifp->if_oerrors = adapter->stats.ecol + adapter->stats.latecol;
+
+}
+
+#ifndef __rtems__
+/**********************************************************************
+ *
+ * This routine is called only when em_display_debug_stats is enabled.
+ * This routine provides a way to take a look at important statistics
+ * maintained by the driver and hardware.
+ *
+ **********************************************************************/
+static void
+em_print_debug_info(struct adapter *adapter)
+{
+ int unit = adapter->unit;
+ uint8_t *hw_addr = adapter->hw.hw_addr;
+
+ printf("em%d: Adapter hardware address = %p \n", unit, hw_addr);
+ printf("em%d:CTRL = 0x%x\n", unit,
+ E1000_READ_REG(&adapter->hw, CTRL));
+ printf("em%d:RCTL = 0x%x PS=(0x8402)\n", unit,
+ E1000_READ_REG(&adapter->hw, RCTL));
+ printf("em%d:tx_int_delay = %d, tx_abs_int_delay = %d\n", unit,
+ E1000_READ_REG(&adapter->hw, TIDV),
+ E1000_READ_REG(&adapter->hw, TADV));
+ printf("em%d:rx_int_delay = %d, rx_abs_int_delay = %d\n", unit,
+ E1000_READ_REG(&adapter->hw, RDTR),
+ E1000_READ_REG(&adapter->hw, RADV));
+ printf("em%d: fifo workaround = %lld, fifo_reset = %lld\n", unit,
+ (long long)adapter->tx_fifo_wrk_cnt,
+ (long long)adapter->tx_fifo_reset_cnt);
+ printf("em%d: hw tdh = %d, hw tdt = %d\n", unit,
+ E1000_READ_REG(&adapter->hw, TDH),
+ E1000_READ_REG(&adapter->hw, TDT));
+ printf("em%d: Num Tx descriptors avail = %d\n", unit,
+ adapter->num_tx_desc_avail);
+ printf("em%d: Tx Descriptors not avail1 = %ld\n", unit,
+ adapter->no_tx_desc_avail1);
+ printf("em%d: Tx Descriptors not avail2 = %ld\n", unit,
+ adapter->no_tx_desc_avail2);
+ printf("em%d: Std mbuf failed = %ld\n", unit,
+ adapter->mbuf_alloc_failed);
+ printf("em%d: Std mbuf cluster failed = %ld\n", unit,
+ adapter->mbuf_cluster_failed);
+ printf("em%d: Driver dropped packets = %ld\n", unit,
+ adapter->dropped_pkts);
+
+ return;
+}
+#endif
+
+static void
+em_print_hw_stats(struct adapter *adapter)
+{
+ int unit = adapter->unit;
+
+ printf("em%d: Excessive collisions = %lld\n", unit,
+ (long long)adapter->stats.ecol);
+ printf("em%d: Symbol errors = %lld\n", unit,
+ (long long)adapter->stats.symerrs);
+ printf("em%d: Sequence errors = %lld\n", unit,
+ (long long)adapter->stats.sec);
+ printf("em%d: Defer count = %lld\n", unit,
+ (long long)adapter->stats.dc);
+
+ printf("em%d: Missed Packets = %lld\n", unit,
+ (long long)adapter->stats.mpc);
+ printf("em%d: Receive No Buffers = %lld\n", unit,
+ (long long)adapter->stats.rnbc);
+ printf("em%d: Receive length errors = %lld\n", unit,
+ (long long)adapter->stats.rlec);
+ printf("em%d: Receive errors = %lld\n", unit,
+ (long long)adapter->stats.rxerrc);
+ printf("em%d: Crc errors = %lld\n", unit,
+ (long long)adapter->stats.crcerrs);
+ printf("em%d: Alignment errors = %lld\n", unit,
+ (long long)adapter->stats.algnerrc);
+ printf("em%d: Carrier extension errors = %lld\n", unit,
+ (long long)adapter->stats.cexterr);
+
+ printf("em%d: XON Rcvd = %lld\n", unit,
+ (long long)adapter->stats.xonrxc);
+ printf("em%d: XON Xmtd = %lld\n", unit,
+ (long long)adapter->stats.xontxc);
+ printf("em%d: XOFF Rcvd = %lld\n", unit,
+ (long long)adapter->stats.xoffrxc);
+ printf("em%d: XOFF Xmtd = %lld\n", unit,
+ (long long)adapter->stats.xofftxc);
+
+ printf("em%d: Good Packets Rcvd = %lld\n", unit,
+ (long long)adapter->stats.gprc);
+ printf("em%d: Good Packets Xmtd = %lld\n", unit,
+ (long long)adapter->stats.gptc);
+
+ return;
+}
+
+#ifndef __rtems__
+static int
+em_sysctl_debug_info(SYSCTL_HANDLER_ARGS)
+{
+ int error;
+ int result;
+ struct adapter *adapter;
+
+ result = -1;
+ error = sysctl_handle_int(oidp, &result, 0, req);
+
+ if (error || !req->newptr)
+ return (error);
+
+ if (result == 1) {
+ adapter = (struct adapter *)arg1;
+ em_print_debug_info(adapter);
+ }
+
+ return error;
+}
+
+static int
+em_sysctl_stats(SYSCTL_HANDLER_ARGS)
+{
+ int error;
+ int result;
+ struct adapter *adapter;
+
+ result = -1;
+ error = sysctl_handle_int(oidp, &result, 0, req);
+
+ if (error || !req->newptr)
+ return (error);
+
+ if (result == 1) {
+ adapter = (struct adapter *)arg1;
+ em_print_hw_stats(adapter);
+ }
+
+ return error;
+}
+
+static int
+em_sysctl_int_delay(SYSCTL_HANDLER_ARGS)
+{
+ struct em_int_delay_info *info;
+ struct adapter *adapter;
+ u_int32_t regval;
+ int error;
+ int usecs;
+ int ticks;
+ int s;
+
+ info = (struct em_int_delay_info *)arg1;
+ adapter = info->adapter;
+ usecs = info->value;
+ error = sysctl_handle_int(oidp, &usecs, 0, req);
+ if (error != 0 || req->newptr == NULL)
+ return error;
+ if (usecs < 0 || usecs > E1000_TICKS_TO_USECS(65535))
+ return EINVAL;
+ info->value = usecs;
+ ticks = E1000_USECS_TO_TICKS(usecs);
+
+ s = splimp();
+ regval = E1000_READ_OFFSET(&adapter->hw, info->offset);
+ regval = (regval & ~0xffff) | (ticks & 0xffff);
+ /* Handle a few special cases. */
+ switch (info->offset) {
+ case E1000_RDTR:
+ case E1000_82542_RDTR:
+ regval |= E1000_RDT_FPDB;
+ break;
+ case E1000_TIDV:
+ case E1000_82542_TIDV:
+ if (ticks == 0) {
+ adapter->txd_cmd &= ~E1000_TXD_CMD_IDE;
+ /* Don't write 0 into the TIDV register. */
+ regval++;
+ } else
+ adapter->txd_cmd |= E1000_TXD_CMD_IDE;
+ break;
+ }
+ E1000_WRITE_OFFSET(&adapter->hw, info->offset, regval);
+ splx(s);
+ return 0;
+}
+
+static void
+em_add_int_delay_sysctl(struct adapter *adapter, const char *name,
+ const char *description, struct em_int_delay_info *info,
+ int offset, int value)
+{
+ info->adapter = adapter;
+ info->offset = offset;
+ info->value = value;
+ SYSCTL_ADD_PROC(device_get_sysctl_ctx(adapter->dev),
+ SYSCTL_CHILDREN(device_get_sysctl_tree(adapter->dev)),
+ OID_AUTO, name, CTLTYPE_INT|CTLFLAG_RW,
+ info, 0, em_sysctl_int_delay, "I", description);
+}
+#endif
+
+#ifdef __rtems__
+/* Initialize bare minimals so we can check the phy link status */
+int
+em_hw_early_init(device_t dev)
+{
+struct adapter *adapter = device_get_softc(dev);
+ adapter->dev = dev;
+ adapter->osdep.dev = dev;
+ em_identify_hardware(adapter);
+ return em_allocate_pci_resources(adapter);
+}
+#endif
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em.h b/bsps/powerpc/beatnik/net/if_em/if_em.h
new file mode 100644
index 0000000..1dc09ce
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em.h
@@ -0,0 +1,493 @@
+/**************************************************************************
+
+Copyright (c) 2001-2005, Intel Corporation
+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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+
+***************************************************************************/
+
+/*$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/if_em.h,v 1.31 2005/05/26 23:32:02 tackerman Exp $*/
+
+#ifndef _EM_H_DEFINED_
+#define _EM_H_DEFINED_
+
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/mbuf.h>
+#include <sys/protosw.h>
+#include <sys/socket.h>
+#include <sys/malloc.h>
+#include <sys/kernel.h>
+#ifndef __rtems__
+#include <sys/module.h>
+#endif
+#include <sys/sockio.h>
+#include <sys/sysctl.h>
+
+#include <net/if.h>
+#include <net/if_arp.h>
+#include <net/ethernet.h>
+#include <net/if_dl.h>
+#include <net/if_media.h>
+#ifndef __rtems__
+
+#include <net/bpf.h>
+#include <net/if_types.h>
+#include <net/if_vlan_var.h>
+#else
+#include <net/if_types.h>
+#endif
+
+#include <netinet/in_systm.h>
+#include <netinet/in.h>
+#include <netinet/ip.h>
+#include <netinet/tcp.h>
+#include <netinet/udp.h>
+
+#ifndef __rtems__
+#include <sys/bus.h>
+#include <machine/bus.h>
+#include <sys/rman.h>
+#include <machine/resource.h>
+#include <vm/vm.h>
+#include <vm/pmap.h>
+#include <machine/clock.h>
+#include <dev/pci/pcivar.h>
+#include <dev/pci/pcireg.h>
+#else
+#include <netinet/if_ether.h>
+#include <bsp/pci.h>
+#endif
+
+#ifndef __rtems__
+#include <sys/endian.h>
+#include <sys/proc.h>
+#include "opt_bdg.h"
+
+
+#include <dev/em/if_em_hw.h>
+#else
+#include "if_em_hw.h"
+#endif
+
+/* Tunables */
+
+/*
+ * EM_MAX_TXD: Maximum number of Transmit Descriptors
+ * Valid Range: 80-256 for 82542 and 82543-based adapters
+ * 80-4096 for others
+ * Default Value: 256
+ * This value is the number of transmit descriptors allocated by the driver.
+ * Increasing this value allows the driver to queue more transmits. Each
+ * descriptor is 16 bytes.
+ */
+#define EM_MAX_TXD 256
+
+/*
+ * EM_MAX_RXD - Maximum number of receive Descriptors
+ * Valid Range: 80-256 for 82542 and 82543-based adapters
+ * 80-4096 for others
+ * Default Value: 256
+ * This value is the number of receive descriptors allocated by the driver.
+ * Increasing this value allows the driver to buffer more incoming packets.
+ * Each descriptor is 16 bytes. A receive buffer is also allocated for each
+ * descriptor. The maximum MTU size is 16110.
+ *
+ */
+#define EM_MAX_RXD 80
+
+/*
+ * EM_TIDV - Transmit Interrupt Delay Value
+ * Valid Range: 0-65535 (0=off)
+ * Default Value: 64
+ * This value delays the generation of transmit interrupts in units of
+ * 1.024 microseconds. Transmit interrupt reduction can improve CPU
+ * efficiency if properly tuned for specific network traffic. If the
+ * system is reporting dropped transmits, this value may be set too high
+ * causing the driver to run out of available transmit descriptors.
+ */
+#define EM_TIDV 64
+
+/*
+ * EM_TADV - Transmit Absolute Interrupt Delay Value (Not valid for 82542/82543/82544)
+ * Valid Range: 0-65535 (0=off)
+ * Default Value: 64
+ * This value, in units of 1.024 microseconds, limits the delay in which a
+ * transmit interrupt is generated. Useful only if EM_TIDV is non-zero,
+ * this value ensures that an interrupt is generated after the initial
+ * packet is sent on the wire within the set amount of time. Proper tuning,
+ * along with EM_TIDV, may improve traffic throughput in specific
+ * network conditions.
+ */
+#define EM_TADV 64
+
+/*
+ * EM_RDTR - Receive Interrupt Delay Timer (Packet Timer)
+ * Valid Range: 0-65535 (0=off)
+ * Default Value: 0
+ * This value delays the generation of receive interrupts in units of 1.024
+ * microseconds. Receive interrupt reduction can improve CPU efficiency if
+ * properly tuned for specific network traffic. Increasing this value adds
+ * extra latency to frame reception and can end up decreasing the throughput
+ * of TCP traffic. If the system is reporting dropped receives, this value
+ * may be set too high, causing the driver to run out of available receive
+ * descriptors.
+ *
+ * CAUTION: When setting EM_RDTR to a value other than 0, adapters
+ * may hang (stop transmitting) under certain network conditions.
+ * If this occurs a WATCHDOG message is logged in the system event log.
+ * In addition, the controller is automatically reset, restoring the
+ * network connection. To eliminate the potential for the hang
+ * ensure that EM_RDTR is set to 0.
+ */
+#define EM_RDTR 0
+
+/*
+ * Receive Interrupt Absolute Delay Timer (Not valid for 82542/82543/82544)
+ * Valid Range: 0-65535 (0=off)
+ * Default Value: 64
+ * This value, in units of 1.024 microseconds, limits the delay in which a
+ * receive interrupt is generated. Useful only if EM_RDTR is non-zero,
+ * this value ensures that an interrupt is generated after the initial
+ * packet is received within the set amount of time. Proper tuning,
+ * along with EM_RDTR, may improve traffic throughput in specific network
+ * conditions.
+ */
+#define EM_RADV 64
+
+
+/*
+ * This parameter controls the maximum no of times the driver will loop
+ * in the isr.
+ * Minimum Value = 1
+ */
+#define EM_MAX_INTR 3
+
+/*
+ * Inform the stack about transmit checksum offload capabilities.
+ */
+#define EM_CHECKSUM_FEATURES (CSUM_TCP | CSUM_UDP)
+
+/*
+ * This parameter controls the duration of transmit watchdog timer.
+ */
+#define EM_TX_TIMEOUT 5 /* set to 5 seconds */
+
+/*
+ * This parameter controls when the driver calls the routine to reclaim
+ * transmit descriptors.
+ */
+#ifndef __rtems__
+#define EM_TX_CLEANUP_THRESHOLD EM_MAX_TXD / 8
+#else
+#define EM_TX_CLEANUP_THRESHOLD (adapter->tx_cleanup_threshold)
+#endif
+
+/*
+ * This parameter controls whether or not autonegotation is enabled.
+ * 0 - Disable autonegotiation
+ * 1 - Enable autonegotiation
+ */
+#define DO_AUTO_NEG 1
+
+/*
+ * This parameter control whether or not the driver will wait for
+ * autonegotiation to complete.
+ * 1 - Wait for autonegotiation to complete
+ * 0 - Don't wait for autonegotiation to complete
+ */
+#define WAIT_FOR_AUTO_NEG_DEFAULT 0
+
+/*
+ * EM_MASTER_SLAVE is only defined to enable a workaround for a known compatibility issue
+ * with 82541/82547 devices and some switches. See the "Known Limitations" section of
+ * the README file for a complete description and a list of affected switches.
+ *
+ * 0 = Hardware default
+ * 1 = Master mode
+ * 2 = Slave mode
+ * 3 = Auto master/slave
+ */
+/* #define EM_MASTER_SLAVE 2 */
+
+/* Tunables -- End */
+
+#define AUTONEG_ADV_DEFAULT (ADVERTISE_10_HALF | ADVERTISE_10_FULL | \
+ ADVERTISE_100_HALF | ADVERTISE_100_FULL | \
+ ADVERTISE_1000_FULL)
+
+#define EM_VENDOR_ID 0x8086
+#define EM_MMBA 0x0010 /* Mem base address */
+#define EM_ROUNDUP(size, unit) (((size) + (unit) - 1) & ~((unit) - 1))
+
+#define EM_JUMBO_PBA 0x00000028
+#define EM_DEFAULT_PBA 0x00000030
+#define EM_SMARTSPEED_DOWNSHIFT 3
+#define EM_SMARTSPEED_MAX 15
+
+
+#define MAX_NUM_MULTICAST_ADDRESSES 128
+#define PCI_ANY_ID (~0U)
+#define ETHER_ALIGN 2
+
+/* Defines for printing debug information */
+#define DEBUG_INIT 0
+#define DEBUG_IOCTL 0
+#define DEBUG_HW 0
+
+#define INIT_DEBUGOUT(S) if (DEBUG_INIT) printf(S "\n")
+#define INIT_DEBUGOUT1(S, A) if (DEBUG_INIT) printf(S "\n", A)
+#define INIT_DEBUGOUT2(S, A, B) if (DEBUG_INIT) printf(S "\n", A, B)
+#define IOCTL_DEBUGOUT(S) if (DEBUG_IOCTL) printf(S "\n")
+#define IOCTL_DEBUGOUT1(S, A) if (DEBUG_IOCTL) printf(S "\n", A)
+#define IOCTL_DEBUGOUT2(S, A, B) if (DEBUG_IOCTL) printf(S "\n", A, B)
+#define HW_DEBUGOUT(S) if (DEBUG_HW) printf(S "\n")
+#define HW_DEBUGOUT1(S, A) if (DEBUG_HW) printf(S "\n", A)
+#define HW_DEBUGOUT2(S, A, B) if (DEBUG_HW) printf(S "\n", A, B)
+
+
+/* Supported RX Buffer Sizes */
+#define EM_RXBUFFER_2048 2048
+#define EM_RXBUFFER_4096 4096
+#define EM_RXBUFFER_8192 8192
+#define EM_RXBUFFER_16384 16384
+
+#define EM_MAX_SCATTER 64
+
+/* ******************************************************************************
+ * vendor_info_array
+ *
+ * This array contains the list of Subvendor/Subdevice IDs on which the driver
+ * should load.
+ *
+ * ******************************************************************************/
+typedef struct _em_vendor_info_t {
+ unsigned int vendor_id;
+ unsigned int device_id;
+ unsigned int subvendor_id;
+ unsigned int subdevice_id;
+ unsigned int index;
+} em_vendor_info_t;
+
+
+struct em_buffer {
+ struct mbuf *m_head;
+#ifndef __rtems__
+ bus_dmamap_t map; /* bus_dma map for packet */
+#endif
+};
+
+/*
+ * Bus dma allocation structure used by
+ * em_dma_malloc and em_dma_free.
+ */
+struct em_dma_alloc {
+ bus_addr_t dma_paddr; /* 64bit in descriptors */
+#ifndef __rtems__
+ caddr_t dma_vaddr;
+ bus_dma_tag_t dma_tag;
+ bus_dmamap_t dma_map;
+ bus_dma_segment_t dma_seg;
+ bus_size_t dma_size;
+ int dma_nseg;
+#else
+ caddr_t dma_vaddr;
+ caddr_t malloc_base;
+#endif
+};
+
+typedef enum _XSUM_CONTEXT_T {
+ OFFLOAD_NONE,
+ OFFLOAD_TCP_IP,
+ OFFLOAD_UDP_IP
+} XSUM_CONTEXT_T;
+
+struct adapter;
+struct em_int_delay_info {
+ struct adapter *adapter; /* Back-pointer to the adapter struct */
+ int offset; /* Register offset to read/write */
+ int value; /* Current value in usecs */
+};
+
+/* For 82544 PCIX Workaround */
+typedef struct _ADDRESS_LENGTH_PAIR
+{
+ u_int64_t address;
+ u_int32_t length;
+} ADDRESS_LENGTH_PAIR, *PADDRESS_LENGTH_PAIR;
+
+typedef struct _DESCRIPTOR_PAIR
+{
+ ADDRESS_LENGTH_PAIR descriptor[4];
+ u_int32_t elements;
+} DESC_ARRAY, *PDESC_ARRAY;
+
+/* Our adapter structure */
+struct adapter {
+ struct arpcom interface_data;
+ struct adapter *next;
+ struct adapter *prev;
+ struct em_hw hw;
+
+ /* FreeBSD operating-system-specific structures */
+ struct em_osdep osdep;
+#ifndef __rtems__
+ struct device *dev;
+ struct resource *res_memory;
+ struct resource *res_ioport;
+ struct resource *res_interrupt;
+ void *int_handler_tag;
+ struct ifmedia media;
+ struct callout timer;
+ struct callout tx_fifo_timer;
+ int io_rid;
+ struct ifmedia media;
+#endif
+ u_int8_t unit;
+#ifndef __rtems__
+ struct mtx mtx;
+ int em_insert_vlan_header;
+#else
+ device_t dev;
+ unsigned char irq_no;
+ unsigned char b,d,f;
+ rtems_id tid;
+#endif
+
+ /* Info about the board itself */
+#ifndef __rtems__
+ u_int32_t part_num;
+#else
+ uint32_t part_num;
+#endif
+ u_int8_t link_active;
+ u_int16_t link_speed;
+ u_int16_t link_duplex;
+ u_int32_t smartspeed;
+ struct em_int_delay_info tx_int_delay;
+ struct em_int_delay_info tx_abs_int_delay;
+ struct em_int_delay_info rx_int_delay;
+ struct em_int_delay_info rx_abs_int_delay;
+
+ XSUM_CONTEXT_T active_checksum_context;
+
+ /*
+ * Transmit definitions
+ *
+ * We have an array of num_tx_desc descriptors (handled
+ * by the controller) paired with an array of tx_buffers
+ * (at tx_buffer_area).
+ * The index of the next available descriptor is next_avail_tx_desc.
+ * The number of remaining tx_desc is num_tx_desc_avail.
+ */
+ struct em_dma_alloc txdma; /* bus_dma glue for tx desc */
+ struct em_tx_desc *tx_desc_base;
+ u_int32_t next_avail_tx_desc;
+ u_int32_t oldest_used_tx_desc;
+ volatile u_int16_t num_tx_desc_avail;
+ u_int16_t num_tx_desc;
+ u_int32_t txd_cmd;
+ struct em_buffer *tx_buffer_area;
+#ifndef __rtems__
+ bus_dma_tag_t txtag; /* dma tag for tx */
+#endif
+#ifdef __rtems__
+ u_int16_t tx_cleanup_threshold;
+#endif
+
+ /*
+ * Receive definitions
+ *
+ * we have an array of num_rx_desc rx_desc (handled by the
+ * controller), and paired with an array of rx_buffers
+ * (at rx_buffer_area).
+ * The next pair to check on receive is at offset next_rx_desc_to_check
+ */
+ struct em_dma_alloc rxdma; /* bus_dma glue for rx desc */
+ struct em_rx_desc *rx_desc_base;
+ u_int32_t next_rx_desc_to_check;
+ u_int16_t num_rx_desc;
+ u_int32_t rx_buffer_len;
+ struct em_buffer *rx_buffer_area;
+#ifndef __rtems__
+ bus_dma_tag_t rxtag;
+#endif
+
+ /* Jumbo frame */
+ struct mbuf *fmp;
+ struct mbuf *lmp;
+
+ /* Misc stats maintained by the driver */
+ unsigned long dropped_pkts;
+ unsigned long mbuf_alloc_failed;
+ unsigned long mbuf_cluster_failed;
+ unsigned long no_tx_desc_avail1;
+ unsigned long no_tx_desc_avail2;
+ unsigned long no_tx_map_avail;
+ unsigned long no_tx_dma_setup;
+
+ /* Used in for 82547 10Mb Half workaround */
+ #define EM_PBA_BYTES_SHIFT 0xA
+ #define EM_TX_HEAD_ADDR_SHIFT 7
+ #define EM_PBA_TX_MASK 0xFFFF0000
+ #define EM_FIFO_HDR 0x10
+
+ #define EM_82547_PKT_THRESH 0x3e0
+
+ u_int32_t tx_fifo_size;
+ u_int32_t tx_fifo_head;
+ u_int32_t tx_fifo_head_addr;
+ u_int64_t tx_fifo_reset_cnt;
+ u_int64_t tx_fifo_wrk_cnt;
+ u_int32_t tx_head_addr;
+
+ /* For 82544 PCIX Workaround */
+ boolean_t pcix_82544;
+ boolean_t in_detach;
+
+ struct em_hw_stats stats;
+};
+
+#define EM_LOCK_INIT(_sc, _name) \
+ mtx_init(&(_sc)->mtx, _name, MTX_NETWORK_LOCK, MTX_DEF)
+#define EM_LOCK_DESTROY(_sc) mtx_destroy(&(_sc)->mtx)
+#define EM_LOCK(_sc) mtx_lock(&(_sc)->mtx)
+#define EM_UNLOCK(_sc) mtx_unlock(&(_sc)->mtx)
+#define EM_LOCK_ASSERT(_sc) mtx_assert(&(_sc)->mtx, MA_OWNED)
+
+#ifdef __rtems__
+/* Initialize bare minimals so we can check the phy link status;
+ * 'rtems_em_pci_setup()' must have been run on the device already!
+ */
+int
+em_hw_early_init(device_t dev);
+#endif
+
+
+#endif /* _EM_H_DEFINED_ */
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em_hw.c b/bsps/powerpc/beatnik/net/if_em/if_em_hw.c
new file mode 100644
index 0000000..e200a6c
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em_hw.c
@@ -0,0 +1,6620 @@
+/*******************************************************************************
+
+ Copyright (c) 2001-2005, Intel Corporation
+ 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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ POSSIBILITY OF SUCH DAMAGE.
+
+*******************************************************************************/
+
+/* if_em_hw.c
+ * Shared functions for accessing and configuring the MAC
+ */
+
+#include <sys/cdefs.h>
+#ifdef __rtems__
+#include "rtemscompat_defs.h"
+#include "../porting/rtemscompat.h"
+#include "if_em_hw.h"
+#else
+__FBSDID("$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/if_em_hw.c,v 1.16 2005/05/26 23:32:02 tackerman Exp $");
+
+#include <dev/em/if_em_hw.h>
+#endif
+
+static int32_t em_set_phy_type(struct em_hw *hw);
+static void em_phy_init_script(struct em_hw *hw);
+static int32_t em_setup_copper_link(struct em_hw *hw);
+static int32_t em_setup_fiber_serdes_link(struct em_hw *hw);
+static int32_t em_adjust_serdes_amplitude(struct em_hw *hw);
+static int32_t em_phy_force_speed_duplex(struct em_hw *hw);
+static int32_t em_config_mac_to_phy(struct em_hw *hw);
+static void em_raise_mdi_clk(struct em_hw *hw, uint32_t *ctrl);
+static void em_lower_mdi_clk(struct em_hw *hw, uint32_t *ctrl);
+static void em_shift_out_mdi_bits(struct em_hw *hw, uint32_t data,
+ uint16_t count);
+static uint16_t em_shift_in_mdi_bits(struct em_hw *hw);
+static int32_t em_phy_reset_dsp(struct em_hw *hw);
+static int32_t em_write_eeprom_spi(struct em_hw *hw, uint16_t offset,
+ uint16_t words, uint16_t *data);
+static int32_t em_write_eeprom_microwire(struct em_hw *hw,
+ uint16_t offset, uint16_t words,
+ uint16_t *data);
+static int32_t em_spi_eeprom_ready(struct em_hw *hw);
+static void em_raise_ee_clk(struct em_hw *hw, uint32_t *eecd);
+static void em_lower_ee_clk(struct em_hw *hw, uint32_t *eecd);
+static void em_shift_out_ee_bits(struct em_hw *hw, uint16_t data,
+ uint16_t count);
+static int32_t em_write_phy_reg_ex(struct em_hw *hw, uint32_t reg_addr,
+ uint16_t phy_data);
+static int32_t em_read_phy_reg_ex(struct em_hw *hw,uint32_t reg_addr,
+ uint16_t *phy_data);
+static uint16_t em_shift_in_ee_bits(struct em_hw *hw, uint16_t count);
+static int32_t em_acquire_eeprom(struct em_hw *hw);
+static void em_release_eeprom(struct em_hw *hw);
+static void em_standby_eeprom(struct em_hw *hw);
+static int32_t em_set_vco_speed(struct em_hw *hw);
+static int32_t em_polarity_reversal_workaround(struct em_hw *hw);
+static int32_t em_set_phy_mode(struct em_hw *hw);
+static int32_t em_host_if_read_cookie(struct em_hw *hw, uint8_t *buffer);
+static uint8_t em_calculate_mng_checksum(char *buffer, uint32_t length);
+
+/* IGP cable length table */
+static const
+uint16_t em_igp_cable_length_table[IGP01E1000_AGC_LENGTH_TABLE_SIZE] =
+ { 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5,
+ 5, 10, 10, 10, 10, 10, 10, 10, 20, 20, 20, 20, 20, 25, 25, 25,
+ 25, 25, 25, 25, 30, 30, 30, 30, 40, 40, 40, 40, 40, 40, 40, 40,
+ 40, 50, 50, 50, 50, 50, 50, 50, 60, 60, 60, 60, 60, 60, 60, 60,
+ 60, 70, 70, 70, 70, 70, 70, 80, 80, 80, 80, 80, 80, 90, 90, 90,
+ 90, 90, 90, 90, 90, 90, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100,
+ 100, 100, 100, 100, 110, 110, 110, 110, 110, 110, 110, 110, 110, 110, 110, 110,
+ 110, 110, 110, 110, 110, 110, 120, 120, 120, 120, 120, 120, 120, 120, 120, 120};
+
+/******************************************************************************
+ * Set the phy type member in the hw struct.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_set_phy_type(struct em_hw *hw)
+{
+ DEBUGFUNC("em_set_phy_type");
+
+ if(hw->mac_type == em_undefined)
+ return -E1000_ERR_PHY_TYPE;
+
+ switch(hw->phy_id) {
+ case M88E1000_E_PHY_ID:
+ case M88E1000_I_PHY_ID:
+ case M88E1011_I_PHY_ID:
+ case M88E1111_I_PHY_ID:
+ hw->phy_type = em_phy_m88;
+ break;
+ case IGP01E1000_I_PHY_ID:
+ if(hw->mac_type == em_82541 ||
+ hw->mac_type == em_82541_rev_2 ||
+ hw->mac_type == em_82547 ||
+ hw->mac_type == em_82547_rev_2) {
+ hw->phy_type = em_phy_igp;
+ break;
+ }
+ /* Fall Through */
+ default:
+ /* Should never have loaded on this device */
+ hw->phy_type = em_phy_undefined;
+ return -E1000_ERR_PHY_TYPE;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * IGP phy init script - initializes the GbE PHY
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+static void
+em_phy_init_script(struct em_hw *hw)
+{
+ uint16_t phy_saved_data;
+
+ DEBUGFUNC("em_phy_init_script");
+
+ if(hw->phy_init_script) {
+ msec_delay(20);
+
+ /* Save off the current value of register 0x2F5B to be restored at
+ * the end of this routine. */
+ em_read_phy_reg(hw, 0x2F5B, &phy_saved_data);
+
+ /* Disabled the PHY transmitter */
+ em_write_phy_reg(hw, 0x2F5B, 0x0003);
+
+ msec_delay(20);
+
+ em_write_phy_reg(hw,0x0000,0x0140);
+
+ msec_delay(5);
+
+ switch(hw->mac_type) {
+ case em_82541:
+ case em_82547:
+ em_write_phy_reg(hw, 0x1F95, 0x0001);
+
+ em_write_phy_reg(hw, 0x1F71, 0xBD21);
+
+ em_write_phy_reg(hw, 0x1F79, 0x0018);
+
+ em_write_phy_reg(hw, 0x1F30, 0x1600);
+
+ em_write_phy_reg(hw, 0x1F31, 0x0014);
+
+ em_write_phy_reg(hw, 0x1F32, 0x161C);
+
+ em_write_phy_reg(hw, 0x1F94, 0x0003);
+
+ em_write_phy_reg(hw, 0x1F96, 0x003F);
+
+ em_write_phy_reg(hw, 0x2010, 0x0008);
+ break;
+
+ case em_82541_rev_2:
+ case em_82547_rev_2:
+ em_write_phy_reg(hw, 0x1F73, 0x0099);
+ break;
+ default:
+ break;
+ }
+
+ em_write_phy_reg(hw, 0x0000, 0x3300);
+
+ msec_delay(20);
+
+ /* Now enable the transmitter */
+ em_write_phy_reg(hw, 0x2F5B, phy_saved_data);
+
+ if(hw->mac_type == em_82547) {
+ uint16_t fused, fine, coarse;
+
+ /* Move to analog registers page */
+ em_read_phy_reg(hw, IGP01E1000_ANALOG_SPARE_FUSE_STATUS, &fused);
+
+ if(!(fused & IGP01E1000_ANALOG_SPARE_FUSE_ENABLED)) {
+ em_read_phy_reg(hw, IGP01E1000_ANALOG_FUSE_STATUS, &fused);
+
+ fine = fused & IGP01E1000_ANALOG_FUSE_FINE_MASK;
+ coarse = fused & IGP01E1000_ANALOG_FUSE_COARSE_MASK;
+
+ if(coarse > IGP01E1000_ANALOG_FUSE_COARSE_THRESH) {
+ coarse -= IGP01E1000_ANALOG_FUSE_COARSE_10;
+ fine -= IGP01E1000_ANALOG_FUSE_FINE_1;
+ } else if(coarse == IGP01E1000_ANALOG_FUSE_COARSE_THRESH)
+ fine -= IGP01E1000_ANALOG_FUSE_FINE_10;
+
+ fused = (fused & IGP01E1000_ANALOG_FUSE_POLY_MASK) |
+ (fine & IGP01E1000_ANALOG_FUSE_FINE_MASK) |
+ (coarse & IGP01E1000_ANALOG_FUSE_COARSE_MASK);
+
+ em_write_phy_reg(hw, IGP01E1000_ANALOG_FUSE_CONTROL, fused);
+ em_write_phy_reg(hw, IGP01E1000_ANALOG_FUSE_BYPASS,
+ IGP01E1000_ANALOG_FUSE_ENABLE_SW_CONTROL);
+ }
+ }
+ }
+}
+
+/******************************************************************************
+ * Set the mac type member in the hw struct.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_set_mac_type(struct em_hw *hw)
+{
+ DEBUGFUNC("em_set_mac_type");
+
+ switch (hw->device_id) {
+ case E1000_DEV_ID_82542:
+ switch (hw->revision_id) {
+ case E1000_82542_2_0_REV_ID:
+ hw->mac_type = em_82542_rev2_0;
+ break;
+ case E1000_82542_2_1_REV_ID:
+ hw->mac_type = em_82542_rev2_1;
+ break;
+ default:
+ /* Invalid 82542 revision ID */
+ return -E1000_ERR_MAC_TYPE;
+ }
+ break;
+ case E1000_DEV_ID_82543GC_FIBER:
+ case E1000_DEV_ID_82543GC_COPPER:
+ hw->mac_type = em_82543;
+ break;
+ case E1000_DEV_ID_82544EI_COPPER:
+ case E1000_DEV_ID_82544EI_FIBER:
+ case E1000_DEV_ID_82544GC_COPPER:
+ case E1000_DEV_ID_82544GC_LOM:
+ hw->mac_type = em_82544;
+ break;
+ case E1000_DEV_ID_82540EM:
+ case E1000_DEV_ID_82540EM_LOM:
+ case E1000_DEV_ID_82540EP:
+ case E1000_DEV_ID_82540EP_LOM:
+ case E1000_DEV_ID_82540EP_LP:
+ hw->mac_type = em_82540;
+ break;
+ case E1000_DEV_ID_82545EM_COPPER:
+ case E1000_DEV_ID_82545EM_FIBER:
+ hw->mac_type = em_82545;
+ break;
+ case E1000_DEV_ID_82545GM_COPPER:
+ case E1000_DEV_ID_82545GM_FIBER:
+ case E1000_DEV_ID_82545GM_SERDES:
+ hw->mac_type = em_82545_rev_3;
+ break;
+ case E1000_DEV_ID_82546EB_COPPER:
+ case E1000_DEV_ID_82546EB_FIBER:
+ case E1000_DEV_ID_82546EB_QUAD_COPPER:
+ hw->mac_type = em_82546;
+ break;
+ case E1000_DEV_ID_82546GB_COPPER:
+ case E1000_DEV_ID_82546GB_FIBER:
+ case E1000_DEV_ID_82546GB_SERDES:
+ case E1000_DEV_ID_82546GB_PCIE:
+ case E1000_DEV_ID_82546GB_QUAD_COPPER:
+ hw->mac_type = em_82546_rev_3;
+ break;
+ case E1000_DEV_ID_82541EI:
+ case E1000_DEV_ID_82541ER_LOM:
+ case E1000_DEV_ID_82541EI_MOBILE:
+ hw->mac_type = em_82541;
+ break;
+ case E1000_DEV_ID_82541ER:
+ case E1000_DEV_ID_82541GI:
+ case E1000_DEV_ID_82541GI_LF:
+ case E1000_DEV_ID_82541GI_MOBILE:
+ hw->mac_type = em_82541_rev_2;
+ break;
+ case E1000_DEV_ID_82547EI:
+ case E1000_DEV_ID_82547EI_MOBILE:
+ hw->mac_type = em_82547;
+ break;
+ case E1000_DEV_ID_82547GI:
+ hw->mac_type = em_82547_rev_2;
+ break;
+ case E1000_DEV_ID_82573E:
+ case E1000_DEV_ID_82573E_IAMT:
+ hw->mac_type = em_82573;
+ break;
+ default:
+ /* Should never have loaded on this device */
+ return -E1000_ERR_MAC_TYPE;
+ }
+
+ switch(hw->mac_type) {
+ case em_82573:
+ hw->eeprom_semaphore_present = TRUE;
+ /* fall through */
+ case em_82541:
+ case em_82547:
+ case em_82541_rev_2:
+ case em_82547_rev_2:
+ hw->asf_firmware_present = TRUE;
+ break;
+ default:
+ break;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ * Set media type and TBI compatibility.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * **************************************************************************/
+void
+em_set_media_type(struct em_hw *hw)
+{
+ uint32_t status;
+
+ DEBUGFUNC("em_set_media_type");
+
+ if(hw->mac_type != em_82543) {
+ /* tbi_compatibility is only valid on 82543 */
+ hw->tbi_compatibility_en = FALSE;
+ }
+
+ switch (hw->device_id) {
+ case E1000_DEV_ID_82545GM_SERDES:
+ case E1000_DEV_ID_82546GB_SERDES:
+ hw->media_type = em_media_type_internal_serdes;
+ break;
+ default:
+ if(hw->mac_type >= em_82543) {
+ status = E1000_READ_REG(hw, STATUS);
+ if(status & E1000_STATUS_TBIMODE) {
+ hw->media_type = em_media_type_fiber;
+ /* tbi_compatibility not valid on fiber */
+ hw->tbi_compatibility_en = FALSE;
+ } else {
+ hw->media_type = em_media_type_copper;
+ }
+ } else {
+ /* This is an 82542 (fiber only) */
+ hw->media_type = em_media_type_fiber;
+ }
+ }
+}
+
+/******************************************************************************
+ * Reset the transmit and receive units; mask and clear all interrupts.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_reset_hw(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ uint32_t ctrl_ext;
+ uint32_t manc;
+ uint32_t led_ctrl;
+ uint32_t timeout;
+ uint32_t extcnf_ctrl;
+ int32_t ret_val;
+
+ DEBUGFUNC("em_reset_hw");
+
+ /* For 82542 (rev 2.0), disable MWI before issuing a device reset */
+ if(hw->mac_type == em_82542_rev2_0) {
+ DEBUGOUT("Disabling MWI on 82542 rev 2.0\n");
+ em_pci_clear_mwi(hw);
+ }
+
+ if(hw->bus_type == em_bus_type_pci_express) {
+ /* Prevent the PCI-E bus from sticking if there is no TLP connection
+ * on the last TLP read/write transaction when MAC is reset.
+ */
+ if(em_disable_pciex_master(hw) != E1000_SUCCESS) {
+ DEBUGOUT("PCI-E Master disable polling has failed.\n");
+ }
+ }
+
+ /* Clear interrupt mask to stop board from generating interrupts */
+ DEBUGOUT("Masking off all interrupts\n");
+ E1000_WRITE_REG(hw, IMC, 0xffffffff);
+
+ /* Disable the Transmit and Receive units. Then delay to allow
+ * any pending transactions to complete before we hit the MAC with
+ * the global reset.
+ */
+ E1000_WRITE_REG(hw, RCTL, 0);
+ E1000_WRITE_REG(hw, TCTL, E1000_TCTL_PSP);
+ E1000_WRITE_FLUSH(hw);
+
+ /* The tbi_compatibility_on Flag must be cleared when Rctl is cleared. */
+ hw->tbi_compatibility_on = FALSE;
+
+ /* Delay to allow any outstanding PCI transactions to complete before
+ * resetting the device
+ */
+ msec_delay(10);
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+
+ /* Must reset the PHY before resetting the MAC */
+ if((hw->mac_type == em_82541) || (hw->mac_type == em_82547)) {
+ E1000_WRITE_REG(hw, CTRL, (ctrl | E1000_CTRL_PHY_RST));
+ msec_delay(5);
+ }
+
+ /* Must acquire the MDIO ownership before MAC reset.
+ * Ownership defaults to firmware after a reset. */
+ if(hw->mac_type == em_82573) {
+ timeout = 10;
+
+ extcnf_ctrl = E1000_READ_REG(hw, EXTCNF_CTRL);
+ extcnf_ctrl |= E1000_EXTCNF_CTRL_MDIO_SW_OWNERSHIP;
+
+ do {
+ E1000_WRITE_REG(hw, EXTCNF_CTRL, extcnf_ctrl);
+ extcnf_ctrl = E1000_READ_REG(hw, EXTCNF_CTRL);
+
+ if(extcnf_ctrl & E1000_EXTCNF_CTRL_MDIO_SW_OWNERSHIP)
+ break;
+ else
+ extcnf_ctrl |= E1000_EXTCNF_CTRL_MDIO_SW_OWNERSHIP;
+
+ msec_delay(2);
+ timeout--;
+ } while(timeout);
+ }
+
+ /* Issue a global reset to the MAC. This will reset the chip's
+ * transmit, receive, DMA, and link units. It will not effect
+ * the current PCI configuration. The global reset bit is self-
+ * clearing, and should clear within a microsecond.
+ */
+ DEBUGOUT("Issuing a global reset to MAC\n");
+
+ switch(hw->mac_type) {
+ case em_82544:
+ case em_82540:
+ case em_82545:
+#ifndef __arm__
+ case em_82546:
+#endif
+ case em_82541:
+ case em_82541_rev_2:
+ /* These controllers can't ack the 64-bit write when issuing the
+ * reset, so use IO-mapping as a workaround to issue the reset */
+ E1000_WRITE_REG_IO(hw, CTRL, (ctrl | E1000_CTRL_RST));
+ break;
+ case em_82545_rev_3:
+ case em_82546_rev_3:
+ /* Reset is performed on a shadow of the control register */
+ E1000_WRITE_REG(hw, CTRL_DUP, (ctrl | E1000_CTRL_RST));
+ break;
+ default:
+ E1000_WRITE_REG(hw, CTRL, (ctrl | E1000_CTRL_RST));
+ break;
+ }
+
+ /* After MAC reset, force reload of EEPROM to restore power-on settings to
+ * device. Later controllers reload the EEPROM automatically, so just wait
+ * for reload to complete.
+ */
+ switch(hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ case em_82544:
+ /* Wait for reset to complete */
+ usec_delay(10);
+ ctrl_ext = E1000_READ_REG(hw, CTRL_EXT);
+ ctrl_ext |= E1000_CTRL_EXT_EE_RST;
+ E1000_WRITE_REG(hw, CTRL_EXT, ctrl_ext);
+ E1000_WRITE_FLUSH(hw);
+ /* Wait for EEPROM reload */
+ msec_delay(2);
+ break;
+ case em_82541:
+ case em_82541_rev_2:
+ case em_82547:
+ case em_82547_rev_2:
+ /* Wait for EEPROM reload */
+ msec_delay(20);
+ break;
+ case em_82573:
+ usec_delay(10);
+ ctrl_ext = E1000_READ_REG(hw, CTRL_EXT);
+ ctrl_ext |= E1000_CTRL_EXT_EE_RST;
+ E1000_WRITE_REG(hw, CTRL_EXT, ctrl_ext);
+ E1000_WRITE_FLUSH(hw);
+ /* fall through */
+ ret_val = em_get_auto_rd_done(hw);
+ if(ret_val)
+ /* We don't want to continue accessing MAC registers. */
+ return ret_val;
+ break;
+ default:
+ /* Wait for EEPROM reload (it happens automatically) */
+ msec_delay(5);
+ break;
+ }
+
+ /* Disable HW ARPs on ASF enabled adapters */
+ if(hw->mac_type >= em_82540 && hw->mac_type <= em_82547_rev_2) {
+ manc = E1000_READ_REG(hw, MANC);
+ manc &= ~(E1000_MANC_ARP_EN);
+ E1000_WRITE_REG(hw, MANC, manc);
+ }
+
+ if((hw->mac_type == em_82541) || (hw->mac_type == em_82547)) {
+ em_phy_init_script(hw);
+
+ /* Configure activity LED after PHY reset */
+ led_ctrl = E1000_READ_REG(hw, LEDCTL);
+ led_ctrl &= IGP_ACTIVITY_LED_MASK;
+ led_ctrl |= (IGP_ACTIVITY_LED_ENABLE | IGP_LED3_MODE);
+ E1000_WRITE_REG(hw, LEDCTL, led_ctrl);
+ }
+
+ /* Clear interrupt mask to stop board from generating interrupts */
+ DEBUGOUT("Masking off all interrupts\n");
+ E1000_WRITE_REG(hw, IMC, 0xffffffff);
+
+ /* Clear any pending interrupt events. */
+ E1000_READ_REG(hw, ICR);
+
+ /* If MWI was previously enabled, reenable it. */
+ if(hw->mac_type == em_82542_rev2_0) {
+ if(hw->pci_cmd_word & CMD_MEM_WRT_INVALIDATE)
+ em_pci_set_mwi(hw);
+ }
+#ifdef __rtems__
+ msec_delay(100);
+#endif
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Performs basic configuration of the adapter.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Assumes that the controller has previously been reset and is in a
+ * post-reset uninitialized state. Initializes the receive address registers,
+ * multicast table, and VLAN filter table. Calls routines to setup link
+ * configuration and flow control settings. Clears all on-chip counters. Leaves
+ * the transmit and receive units disabled and uninitialized.
+ *****************************************************************************/
+int32_t
+em_init_hw(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ uint32_t i;
+ int32_t ret_val;
+ uint16_t pcix_cmd_word;
+ uint16_t pcix_stat_hi_word;
+ uint16_t cmd_mmrbc;
+ uint16_t stat_mmrbc;
+ uint32_t mta_size;
+
+ DEBUGFUNC("em_init_hw");
+
+ /* Initialize Identification LED */
+ ret_val = em_id_led_init(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Initializing Identification LED\n");
+ return ret_val;
+ }
+
+ /* Set the media type and TBI compatibility */
+ em_set_media_type(hw);
+
+ /* Disabling VLAN filtering. */
+ DEBUGOUT("Initializing the IEEE VLAN\n");
+ if (hw->mac_type < em_82545_rev_3)
+ E1000_WRITE_REG(hw, VET, 0);
+ em_clear_vfta(hw);
+
+ /* For 82542 (rev 2.0), disable MWI and put the receiver into reset */
+ if(hw->mac_type == em_82542_rev2_0) {
+ DEBUGOUT("Disabling MWI on 82542 rev 2.0\n");
+ em_pci_clear_mwi(hw);
+ E1000_WRITE_REG(hw, RCTL, E1000_RCTL_RST);
+ E1000_WRITE_FLUSH(hw);
+ msec_delay(5);
+ }
+
+ /* Setup the receive address. This involves initializing all of the Receive
+ * Address Registers (RARs 0 - 15).
+ */
+ em_init_rx_addrs(hw);
+
+ /* For 82542 (rev 2.0), take the receiver out of reset and enable MWI */
+ if(hw->mac_type == em_82542_rev2_0) {
+ E1000_WRITE_REG(hw, RCTL, 0);
+ E1000_WRITE_FLUSH(hw);
+ msec_delay(1);
+ if(hw->pci_cmd_word & CMD_MEM_WRT_INVALIDATE)
+ em_pci_set_mwi(hw);
+ }
+
+ /* Zero out the Multicast HASH table */
+ DEBUGOUT("Zeroing the MTA\n");
+ mta_size = E1000_MC_TBL_SIZE;
+ for(i = 0; i < mta_size; i++)
+ E1000_WRITE_REG_ARRAY(hw, MTA, i, 0);
+
+ /* Set the PCI priority bit correctly in the CTRL register. This
+ * determines if the adapter gives priority to receives, or if it
+ * gives equal priority to transmits and receives. Valid only on
+ * 82542 and 82543 silicon.
+ */
+ if(hw->dma_fairness && hw->mac_type <= em_82543) {
+ ctrl = E1000_READ_REG(hw, CTRL);
+ E1000_WRITE_REG(hw, CTRL, ctrl | E1000_CTRL_PRIOR);
+ }
+
+ switch(hw->mac_type) {
+ case em_82545_rev_3:
+ case em_82546_rev_3:
+ break;
+ default:
+ /* Workaround for PCI-X problem when BIOS sets MMRBC incorrectly. */
+ if(hw->bus_type == em_bus_type_pcix) {
+ em_read_pci_cfg(hw, PCIX_COMMAND_REGISTER, &pcix_cmd_word);
+ em_read_pci_cfg(hw, PCIX_STATUS_REGISTER_HI,
+ &pcix_stat_hi_word);
+ cmd_mmrbc = (pcix_cmd_word & PCIX_COMMAND_MMRBC_MASK) >>
+ PCIX_COMMAND_MMRBC_SHIFT;
+ stat_mmrbc = (pcix_stat_hi_word & PCIX_STATUS_HI_MMRBC_MASK) >>
+ PCIX_STATUS_HI_MMRBC_SHIFT;
+ if(stat_mmrbc == PCIX_STATUS_HI_MMRBC_4K)
+ stat_mmrbc = PCIX_STATUS_HI_MMRBC_2K;
+ if(cmd_mmrbc > stat_mmrbc) {
+ pcix_cmd_word &= ~PCIX_COMMAND_MMRBC_MASK;
+ pcix_cmd_word |= stat_mmrbc << PCIX_COMMAND_MMRBC_SHIFT;
+ em_write_pci_cfg(hw, PCIX_COMMAND_REGISTER,
+ &pcix_cmd_word);
+ }
+ }
+ break;
+ }
+
+ /* Call a subroutine to configure the link and setup flow control. */
+ ret_val = em_setup_link(hw);
+
+ /* Set the transmit descriptor write-back policy */
+ if(hw->mac_type > em_82544) {
+ ctrl = E1000_READ_REG(hw, TXDCTL);
+ ctrl = (ctrl & ~E1000_TXDCTL_WTHRESH) | E1000_TXDCTL_FULL_TX_DESC_WB;
+ switch (hw->mac_type) {
+ default:
+ break;
+ case em_82573:
+ ctrl |= E1000_TXDCTL_COUNT_DESC;
+ break;
+ }
+ E1000_WRITE_REG(hw, TXDCTL, ctrl);
+ }
+
+ if (hw->mac_type == em_82573) {
+ em_enable_tx_pkt_filtering(hw);
+ }
+
+
+ /* Clear all of the statistics registers (clear on read). It is
+ * important that we do this after we have tried to establish link
+ * because the symbol error count will increment wildly if there
+ * is no link.
+ */
+ em_clear_hw_cntrs(hw);
+
+ return ret_val;
+}
+
+/******************************************************************************
+ * Adjust SERDES output amplitude based on EEPROM setting.
+ *
+ * hw - Struct containing variables accessed by shared code.
+ *****************************************************************************/
+static int32_t
+em_adjust_serdes_amplitude(struct em_hw *hw)
+{
+ uint16_t eeprom_data;
+ int32_t ret_val;
+
+ DEBUGFUNC("em_adjust_serdes_amplitude");
+
+ if(hw->media_type != em_media_type_internal_serdes)
+ return E1000_SUCCESS;
+
+ switch(hw->mac_type) {
+ case em_82545_rev_3:
+ case em_82546_rev_3:
+ break;
+ default:
+ return E1000_SUCCESS;
+ }
+
+ ret_val = em_read_eeprom(hw, EEPROM_SERDES_AMPLITUDE, 1, &eeprom_data);
+ if (ret_val) {
+ return ret_val;
+ }
+
+ if(eeprom_data != EEPROM_RESERVED_WORD) {
+ /* Adjust SERDES output amplitude only. */
+ eeprom_data &= EEPROM_SERDES_AMPLITUDE_MASK;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_EXT_CTRL, eeprom_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Configures flow control and link settings.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Determines which flow control settings to use. Calls the apropriate media-
+ * specific link configuration function. Configures the flow control settings.
+ * Assuming the adapter has a valid link partner, a valid link should be
+ * established. Assumes the hardware has previously been reset and the
+ * transmitter and receiver are not enabled.
+ *****************************************************************************/
+int32_t
+em_setup_link(struct em_hw *hw)
+{
+ uint32_t ctrl_ext;
+ int32_t ret_val;
+ uint16_t eeprom_data;
+
+ DEBUGFUNC("em_setup_link");
+
+ /* Read and store word 0x0F of the EEPROM. This word contains bits
+ * that determine the hardware's default PAUSE (flow control) mode,
+ * a bit that determines whether the HW defaults to enabling or
+ * disabling auto-negotiation, and the direction of the
+ * SW defined pins. If there is no SW over-ride of the flow
+ * control setting, then the variable hw->fc will
+ * be initialized based on a value in the EEPROM.
+ */
+ if(em_read_eeprom(hw, EEPROM_INIT_CONTROL2_REG, 1, &eeprom_data)) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ if(hw->fc == em_fc_default) {
+ if((eeprom_data & EEPROM_WORD0F_PAUSE_MASK) == 0)
+ hw->fc = em_fc_none;
+ else if((eeprom_data & EEPROM_WORD0F_PAUSE_MASK) ==
+ EEPROM_WORD0F_ASM_DIR)
+ hw->fc = em_fc_tx_pause;
+ else
+ hw->fc = em_fc_full;
+ }
+
+ /* We want to save off the original Flow Control configuration just
+ * in case we get disconnected and then reconnected into a different
+ * hub or switch with different Flow Control capabilities.
+ */
+ if(hw->mac_type == em_82542_rev2_0)
+ hw->fc &= (~em_fc_tx_pause);
+
+ if((hw->mac_type < em_82543) && (hw->report_tx_early == 1))
+ hw->fc &= (~em_fc_rx_pause);
+
+ hw->original_fc = hw->fc;
+
+ DEBUGOUT1("After fix-ups FlowControl is now = %x\n", hw->fc);
+
+ /* Take the 4 bits from EEPROM word 0x0F that determine the initial
+ * polarity value for the SW controlled pins, and setup the
+ * Extended Device Control reg with that info.
+ * This is needed because one of the SW controlled pins is used for
+ * signal detection. So this should be done before em_setup_pcs_link()
+ * or em_phy_setup() is called.
+ */
+ if(hw->mac_type == em_82543) {
+ ctrl_ext = ((eeprom_data & EEPROM_WORD0F_SWPDIO_EXT) <<
+ SWDPIO__EXT_SHIFT);
+ E1000_WRITE_REG(hw, CTRL_EXT, ctrl_ext);
+ }
+
+ /* Call the necessary subroutine to configure the link. */
+ ret_val = (hw->media_type == em_media_type_copper) ?
+ em_setup_copper_link(hw) :
+ em_setup_fiber_serdes_link(hw);
+
+ /* Initialize the flow control address, type, and PAUSE timer
+ * registers to their default values. This is done even if flow
+ * control is disabled, because it does not hurt anything to
+ * initialize these registers.
+ */
+ DEBUGOUT("Initializing the Flow Control address, type and timer regs\n");
+
+ E1000_WRITE_REG(hw, FCAL, FLOW_CONTROL_ADDRESS_LOW);
+ E1000_WRITE_REG(hw, FCAH, FLOW_CONTROL_ADDRESS_HIGH);
+ E1000_WRITE_REG(hw, FCT, FLOW_CONTROL_TYPE);
+
+ E1000_WRITE_REG(hw, FCTTV, hw->fc_pause_time);
+
+ /* Set the flow control receive threshold registers. Normally,
+ * these registers will be set to a default threshold that may be
+ * adjusted later by the driver's runtime code. However, if the
+ * ability to transmit pause frames in not enabled, then these
+ * registers will be set to 0.
+ */
+ if(!(hw->fc & em_fc_tx_pause)) {
+ E1000_WRITE_REG(hw, FCRTL, 0);
+ E1000_WRITE_REG(hw, FCRTH, 0);
+ } else {
+ /* We need to set up the Receive Threshold high and low water marks
+ * as well as (optionally) enabling the transmission of XON frames.
+ */
+ if(hw->fc_send_xon) {
+ E1000_WRITE_REG(hw, FCRTL, (hw->fc_low_water | E1000_FCRTL_XONE));
+ E1000_WRITE_REG(hw, FCRTH, hw->fc_high_water);
+ } else {
+ E1000_WRITE_REG(hw, FCRTL, hw->fc_low_water);
+ E1000_WRITE_REG(hw, FCRTH, hw->fc_high_water);
+ }
+ }
+ return ret_val;
+}
+
+/******************************************************************************
+ * Sets up link for a fiber based or serdes based adapter
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Manipulates Physical Coding Sublayer functions in order to configure
+ * link. Assumes the hardware has been previously reset and the transmitter
+ * and receiver are not enabled.
+ *****************************************************************************/
+static int32_t
+em_setup_fiber_serdes_link(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ uint32_t status;
+ uint32_t txcw = 0;
+ uint32_t i;
+ uint32_t signal = 0;
+ int32_t ret_val;
+
+ DEBUGFUNC("em_setup_fiber_serdes_link");
+
+ /* On adapters with a MAC newer than 82544, SW Defineable pin 1 will be
+ * set when the optics detect a signal. On older adapters, it will be
+ * cleared when there is a signal. This applies to fiber media only.
+ * If we're on serdes media, adjust the output amplitude to value set in
+ * the EEPROM.
+ */
+ ctrl = E1000_READ_REG(hw, CTRL);
+ if(hw->media_type == em_media_type_fiber)
+ signal = (hw->mac_type > em_82544) ? E1000_CTRL_SWDPIN1 : 0;
+
+ ret_val = em_adjust_serdes_amplitude(hw);
+ if(ret_val)
+ return ret_val;
+
+ /* Take the link out of reset */
+ ctrl &= ~(E1000_CTRL_LRST);
+
+ /* Adjust VCO speed to improve BER performance */
+ ret_val = em_set_vco_speed(hw);
+ if(ret_val)
+ return ret_val;
+
+ em_config_collision_dist(hw);
+
+ /* Check for a software override of the flow control settings, and setup
+ * the device accordingly. If auto-negotiation is enabled, then software
+ * will have to set the "PAUSE" bits to the correct value in the Tranmsit
+ * Config Word Register (TXCW) and re-start auto-negotiation. However, if
+ * auto-negotiation is disabled, then software will have to manually
+ * configure the two flow control enable bits in the CTRL register.
+ *
+ * The possible values of the "fc" parameter are:
+ * 0: Flow control is completely disabled
+ * 1: Rx flow control is enabled (we can receive pause frames, but
+ * not send pause frames).
+ * 2: Tx flow control is enabled (we can send pause frames but we do
+ * not support receiving pause frames).
+ * 3: Both Rx and TX flow control (symmetric) are enabled.
+ */
+ switch (hw->fc) {
+ case em_fc_none:
+ /* Flow control is completely disabled by a software over-ride. */
+ txcw = (E1000_TXCW_ANE | E1000_TXCW_FD);
+ break;
+ case em_fc_rx_pause:
+ /* RX Flow control is enabled and TX Flow control is disabled by a
+ * software over-ride. Since there really isn't a way to advertise
+ * that we are capable of RX Pause ONLY, we will advertise that we
+ * support both symmetric and asymmetric RX PAUSE. Later, we will
+ * disable the adapter's ability to send PAUSE frames.
+ */
+ txcw = (E1000_TXCW_ANE | E1000_TXCW_FD | E1000_TXCW_PAUSE_MASK);
+ break;
+ case em_fc_tx_pause:
+ /* TX Flow control is enabled, and RX Flow control is disabled, by a
+ * software over-ride.
+ */
+ txcw = (E1000_TXCW_ANE | E1000_TXCW_FD | E1000_TXCW_ASM_DIR);
+ break;
+ case em_fc_full:
+ /* Flow control (both RX and TX) is enabled by a software over-ride. */
+ txcw = (E1000_TXCW_ANE | E1000_TXCW_FD | E1000_TXCW_PAUSE_MASK);
+ break;
+ default:
+ DEBUGOUT("Flow control param set incorrectly\n");
+ return -E1000_ERR_CONFIG;
+ break;
+ }
+
+ /* Since auto-negotiation is enabled, take the link out of reset (the link
+ * will be in reset, because we previously reset the chip). This will
+ * restart auto-negotiation. If auto-neogtiation is successful then the
+ * link-up status bit will be set and the flow control enable bits (RFCE
+ * and TFCE) will be set according to their negotiated value.
+ */
+ DEBUGOUT("Auto-negotiation enabled\n");
+
+ E1000_WRITE_REG(hw, TXCW, txcw);
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ E1000_WRITE_FLUSH(hw);
+
+ hw->txcw = txcw;
+ msec_delay(1);
+
+ /* If we have a signal (the cable is plugged in) then poll for a "Link-Up"
+ * indication in the Device Status Register. Time-out if a link isn't
+ * seen in 500 milliseconds seconds (Auto-negotiation should complete in
+ * less than 500 milliseconds even if the other end is doing it in SW).
+ * For internal serdes, we just assume a signal is present, then poll.
+ */
+ if(hw->media_type == em_media_type_internal_serdes ||
+ (E1000_READ_REG(hw, CTRL) & E1000_CTRL_SWDPIN1) == signal) {
+ DEBUGOUT("Looking for Link\n");
+ for(i = 0; i < (LINK_UP_TIMEOUT / 10); i++) {
+ msec_delay(10);
+ status = E1000_READ_REG(hw, STATUS);
+ if(status & E1000_STATUS_LU) break;
+ }
+ if(i == (LINK_UP_TIMEOUT / 10)) {
+ DEBUGOUT("Never got a valid link from auto-neg!!!\n");
+ hw->autoneg_failed = 1;
+ /* AutoNeg failed to achieve a link, so we'll call
+ * em_check_for_link. This routine will force the link up if
+ * we detect a signal. This will allow us to communicate with
+ * non-autonegotiating link partners.
+ */
+ ret_val = em_check_for_link(hw);
+ if(ret_val) {
+ DEBUGOUT("Error while checking for link\n");
+ return ret_val;
+ }
+ hw->autoneg_failed = 0;
+ } else {
+ hw->autoneg_failed = 0;
+ DEBUGOUT("Valid Link Found\n");
+ }
+ } else {
+ DEBUGOUT("No Signal Detected\n");
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Make sure we have a valid PHY and change PHY mode before link setup.
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+static int32_t
+em_copper_link_preconfig(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_copper_link_preconfig");
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+ /* With 82543, we need to force speed and duplex on the MAC equal to what
+ * the PHY speed and duplex configuration is. In addition, we need to
+ * perform a hardware reset on the PHY to take it out of reset.
+ */
+ if(hw->mac_type > em_82543) {
+ ctrl |= E1000_CTRL_SLU;
+ ctrl &= ~(E1000_CTRL_FRCSPD | E1000_CTRL_FRCDPX);
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ } else {
+ ctrl |= (E1000_CTRL_FRCSPD | E1000_CTRL_FRCDPX | E1000_CTRL_SLU);
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ ret_val = em_phy_hw_reset(hw);
+ if(ret_val)
+ return ret_val;
+ }
+
+ /* Make sure we have a valid PHY */
+ ret_val = em_detect_gig_phy(hw);
+ if(ret_val) {
+ DEBUGOUT("Error, did not detect valid phy.\n");
+ return ret_val;
+ }
+ DEBUGOUT1("Phy ID = %x \n", hw->phy_id);
+
+ /* Set PHY to class A mode (if necessary) */
+ ret_val = em_set_phy_mode(hw);
+ if(ret_val)
+ return ret_val;
+
+ if((hw->mac_type == em_82545_rev_3) ||
+ (hw->mac_type == em_82546_rev_3)) {
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, &phy_data);
+ phy_data |= 0x00000008;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, phy_data);
+ }
+
+ if(hw->mac_type <= em_82543 ||
+ hw->mac_type == em_82541 || hw->mac_type == em_82547 ||
+ hw->mac_type == em_82541_rev_2 || hw->mac_type == em_82547_rev_2)
+ hw->phy_reset_disable = FALSE;
+
+ return E1000_SUCCESS;
+}
+
+
+/********************************************************************
+* Copper link setup for em_phy_igp series.
+*
+* hw - Struct containing variables accessed by shared code
+*********************************************************************/
+static int32_t
+em_copper_link_igp_setup(struct em_hw *hw)
+{
+ uint32_t led_ctrl;
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_copper_link_igp_setup");
+
+ if (hw->phy_reset_disable)
+ return E1000_SUCCESS;
+
+ ret_val = em_phy_reset(hw);
+ if (ret_val) {
+ DEBUGOUT("Error Resetting the PHY\n");
+ return ret_val;
+ }
+
+ /* Wait 10ms for MAC to configure PHY from eeprom settings */
+ msec_delay(15);
+
+ /* Configure activity LED after PHY reset */
+ led_ctrl = E1000_READ_REG(hw, LEDCTL);
+ led_ctrl &= IGP_ACTIVITY_LED_MASK;
+ led_ctrl |= (IGP_ACTIVITY_LED_ENABLE | IGP_LED3_MODE);
+ E1000_WRITE_REG(hw, LEDCTL, led_ctrl);
+
+ /* disable lplu d3 during driver init */
+ ret_val = em_set_d3_lplu_state(hw, FALSE);
+ if (ret_val) {
+ DEBUGOUT("Error Disabling LPLU D3\n");
+ return ret_val;
+ }
+
+ /* disable lplu d0 during driver init */
+ ret_val = em_set_d0_lplu_state(hw, FALSE);
+ if (ret_val) {
+ DEBUGOUT("Error Disabling LPLU D0\n");
+ return ret_val;
+ }
+ /* Configure mdi-mdix settings */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CTRL, &phy_data);
+ if (ret_val)
+ return ret_val;
+
+ if ((hw->mac_type == em_82541) || (hw->mac_type == em_82547)) {
+ hw->dsp_config_state = em_dsp_config_disabled;
+ /* Force MDI for earlier revs of the IGP PHY */
+ phy_data &= ~(IGP01E1000_PSCR_AUTO_MDIX | IGP01E1000_PSCR_FORCE_MDI_MDIX);
+ hw->mdix = 1;
+
+ } else {
+ hw->dsp_config_state = em_dsp_config_enabled;
+ phy_data &= ~IGP01E1000_PSCR_AUTO_MDIX;
+
+ switch (hw->mdix) {
+ case 1:
+ phy_data &= ~IGP01E1000_PSCR_FORCE_MDI_MDIX;
+ break;
+ case 2:
+ phy_data |= IGP01E1000_PSCR_FORCE_MDI_MDIX;
+ break;
+ case 0:
+ default:
+ phy_data |= IGP01E1000_PSCR_AUTO_MDIX;
+ break;
+ }
+ }
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* set auto-master slave resolution settings */
+ if(hw->autoneg) {
+ em_ms_type phy_ms_setting = hw->master_slave;
+
+ if(hw->ffe_config_state == em_ffe_config_active)
+ hw->ffe_config_state = em_ffe_config_enabled;
+
+ if(hw->dsp_config_state == em_dsp_config_activated)
+ hw->dsp_config_state = em_dsp_config_enabled;
+
+ /* when autonegotiation advertisment is only 1000Mbps then we
+ * should disable SmartSpeed and enable Auto MasterSlave
+ * resolution as hardware default. */
+ if(hw->autoneg_advertised == ADVERTISE_1000_FULL) {
+ /* Disable SmartSpeed */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG, &phy_data);
+ if(ret_val)
+ return ret_val;
+ phy_data &= ~IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw,
+ IGP01E1000_PHY_PORT_CONFIG,
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ /* Set auto Master/Slave resolution process */
+ ret_val = em_read_phy_reg(hw, PHY_1000T_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+ phy_data &= ~CR_1000T_MS_ENABLE;
+ ret_val = em_write_phy_reg(hw, PHY_1000T_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ ret_val = em_read_phy_reg(hw, PHY_1000T_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* load defaults for future use */
+ hw->original_master_slave = (phy_data & CR_1000T_MS_ENABLE) ?
+ ((phy_data & CR_1000T_MS_VALUE) ?
+ em_ms_force_master :
+ em_ms_force_slave) :
+ em_ms_auto;
+
+ switch (phy_ms_setting) {
+ case em_ms_force_master:
+ phy_data |= (CR_1000T_MS_ENABLE | CR_1000T_MS_VALUE);
+ break;
+ case em_ms_force_slave:
+ phy_data |= CR_1000T_MS_ENABLE;
+ phy_data &= ~(CR_1000T_MS_VALUE);
+ break;
+ case em_ms_auto:
+ phy_data &= ~CR_1000T_MS_ENABLE;
+ default:
+ break;
+ }
+ ret_val = em_write_phy_reg(hw, PHY_1000T_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ return E1000_SUCCESS;
+}
+
+
+/********************************************************************
+* Copper link setup for em_phy_m88 series.
+*
+* hw - Struct containing variables accessed by shared code
+*********************************************************************/
+static int32_t
+em_copper_link_mgp_setup(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_copper_link_mgp_setup");
+
+ if(hw->phy_reset_disable)
+ return E1000_SUCCESS;
+
+ /* Enable CRS on TX. This must be set for half-duplex operation. */
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= M88E1000_PSCR_ASSERT_CRS_ON_TX;
+
+ /* Options:
+ * MDI/MDI-X = 0 (default)
+ * 0 - Auto for all speeds
+ * 1 - MDI mode
+ * 2 - MDI-X mode
+ * 3 - Auto for 1000Base-T only (MDI-X for 10/100Base-T modes)
+ */
+ phy_data &= ~M88E1000_PSCR_AUTO_X_MODE;
+
+ switch (hw->mdix) {
+ case 1:
+ phy_data |= M88E1000_PSCR_MDI_MANUAL_MODE;
+ break;
+ case 2:
+ phy_data |= M88E1000_PSCR_MDIX_MANUAL_MODE;
+ break;
+ case 3:
+ phy_data |= M88E1000_PSCR_AUTO_X_1000T;
+ break;
+ case 0:
+ default:
+ phy_data |= M88E1000_PSCR_AUTO_X_MODE;
+ break;
+ }
+
+ /* Options:
+ * disable_polarity_correction = 0 (default)
+ * Automatic Correction for Reversed Cable Polarity
+ * 0 - Disabled
+ * 1 - Enabled
+ */
+ phy_data &= ~M88E1000_PSCR_POLARITY_REVERSAL;
+ if(hw->disable_polarity_correction == 1)
+ phy_data |= M88E1000_PSCR_POLARITY_REVERSAL;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* Force TX_CLK in the Extended PHY Specific Control Register
+ * to 25MHz clock.
+ */
+ ret_val = em_read_phy_reg(hw, M88E1000_EXT_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= M88E1000_EPSCR_TX_CLK_25;
+
+ if (hw->phy_revision < M88E1011_I_REV_4) {
+ /* Configure Master and Slave downshift values */
+ phy_data &= ~(M88E1000_EPSCR_MASTER_DOWNSHIFT_MASK |
+ M88E1000_EPSCR_SLAVE_DOWNSHIFT_MASK);
+ phy_data |= (M88E1000_EPSCR_MASTER_DOWNSHIFT_1X |
+ M88E1000_EPSCR_SLAVE_DOWNSHIFT_1X);
+ ret_val = em_write_phy_reg(hw, M88E1000_EXT_PHY_SPEC_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ /* SW Reset the PHY so all changes take effect */
+ ret_val = em_phy_reset(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Resetting the PHY\n");
+ return ret_val;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/********************************************************************
+* Setup auto-negotiation and flow control advertisements,
+* and then perform auto-negotiation.
+*
+* hw - Struct containing variables accessed by shared code
+*********************************************************************/
+static int32_t
+em_copper_link_autoneg(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_copper_link_autoneg");
+
+ /* Perform some bounds checking on the hw->autoneg_advertised
+ * parameter. If this variable is zero, then set it to the default.
+ */
+ hw->autoneg_advertised &= AUTONEG_ADVERTISE_SPEED_DEFAULT;
+
+ /* If autoneg_advertised is zero, we assume it was not defaulted
+ * by the calling code so we set to advertise full capability.
+ */
+ if(hw->autoneg_advertised == 0)
+ hw->autoneg_advertised = AUTONEG_ADVERTISE_SPEED_DEFAULT;
+
+ DEBUGOUT("Reconfiguring auto-neg advertisement params\n");
+ ret_val = em_phy_setup_autoneg(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Setting up Auto-Negotiation\n");
+ return ret_val;
+ }
+ DEBUGOUT("Restarting Auto-Neg\n");
+
+ /* Restart auto-negotiation by setting the Auto Neg Enable bit and
+ * the Auto Neg Restart bit in the PHY control register.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= (MII_CR_AUTO_NEG_EN | MII_CR_RESTART_AUTO_NEG);
+ ret_val = em_write_phy_reg(hw, PHY_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* Does the user want to wait for Auto-Neg to complete here, or
+ * check at a later time (for example, callback routine).
+ */
+ if(hw->wait_autoneg_complete) {
+ ret_val = em_wait_autoneg(hw);
+ if(ret_val) {
+ DEBUGOUT("Error while waiting for autoneg to complete\n");
+ return ret_val;
+ }
+ }
+
+ hw->get_link_status = TRUE;
+
+ return E1000_SUCCESS;
+}
+
+
+/******************************************************************************
+* Config the MAC and the PHY after link is up.
+* 1) Set up the MAC to the current PHY speed/duplex
+* if we are on 82543. If we
+* are on newer silicon, we only need to configure
+* collision distance in the Transmit Control Register.
+* 2) Set up flow control on the MAC to that established with
+* the link partner.
+* 3) Config DSP to improve Gigabit link quality for some PHY revisions.
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+static int32_t
+em_copper_link_postconfig(struct em_hw *hw)
+{
+ int32_t ret_val;
+ DEBUGFUNC("em_copper_link_postconfig");
+
+ if(hw->mac_type >= em_82544) {
+ em_config_collision_dist(hw);
+ } else {
+ ret_val = em_config_mac_to_phy(hw);
+ if(ret_val) {
+ DEBUGOUT("Error configuring MAC to PHY settings\n");
+ return ret_val;
+ }
+ }
+ ret_val = em_config_fc_after_link_up(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Configuring Flow Control\n");
+ return ret_val;
+ }
+
+ /* Config DSP to improve Giga link quality */
+ if(hw->phy_type == em_phy_igp) {
+ ret_val = em_config_dsp_after_link_change(hw, TRUE);
+ if(ret_val) {
+ DEBUGOUT("Error Configuring DSP after link up\n");
+ return ret_val;
+ }
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Detects which PHY is present and setup the speed and duplex
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+static int32_t
+em_setup_copper_link(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t i;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_setup_copper_link");
+
+ /* Check if it is a valid PHY and set PHY mode if necessary. */
+ ret_val = em_copper_link_preconfig(hw);
+ if(ret_val)
+ return ret_val;
+
+ if (hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2) {
+ ret_val = em_copper_link_igp_setup(hw);
+ if(ret_val)
+ return ret_val;
+ } else if (hw->phy_type == em_phy_m88) {
+ ret_val = em_copper_link_mgp_setup(hw);
+ if(ret_val)
+ return ret_val;
+ }
+
+ if(hw->autoneg) {
+ /* Setup autoneg and flow control advertisement
+ * and perform autonegotiation */
+ ret_val = em_copper_link_autoneg(hw);
+ if(ret_val)
+ return ret_val;
+ } else {
+ /* PHY will be set to 10H, 10F, 100H,or 100F
+ * depending on value from forced_speed_duplex. */
+ DEBUGOUT("Forcing speed and duplex\n");
+ ret_val = em_phy_force_speed_duplex(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Forcing Speed and Duplex\n");
+ return ret_val;
+ }
+ }
+
+ /* Check link status. Wait up to 100 microseconds for link to become
+ * valid.
+ */
+ for(i = 0; i < 10; i++) {
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if(phy_data & MII_SR_LINK_STATUS) {
+ /* Config the MAC and PHY after link is up */
+ ret_val = em_copper_link_postconfig(hw);
+ if(ret_val)
+ return ret_val;
+
+ DEBUGOUT("Valid link established!!!\n");
+ return E1000_SUCCESS;
+ }
+ usec_delay(10);
+ }
+
+ DEBUGOUT("Unable to establish link!!!\n");
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Configures PHY autoneg and flow control advertisement settings
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+int32_t
+em_phy_setup_autoneg(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t mii_autoneg_adv_reg;
+ uint16_t mii_1000t_ctrl_reg;
+
+ DEBUGFUNC("em_phy_setup_autoneg");
+
+ /* Read the MII Auto-Neg Advertisement Register (Address 4). */
+ ret_val = em_read_phy_reg(hw, PHY_AUTONEG_ADV, &mii_autoneg_adv_reg);
+ if(ret_val)
+ return ret_val;
+
+ /* Read the MII 1000Base-T Control Register (Address 9). */
+ ret_val = em_read_phy_reg(hw, PHY_1000T_CTRL, &mii_1000t_ctrl_reg);
+ if(ret_val)
+ return ret_val;
+
+ /* Need to parse both autoneg_advertised and fc and set up
+ * the appropriate PHY registers. First we will parse for
+ * autoneg_advertised software override. Since we can advertise
+ * a plethora of combinations, we need to check each bit
+ * individually.
+ */
+
+ /* First we clear all the 10/100 mb speed bits in the Auto-Neg
+ * Advertisement Register (Address 4) and the 1000 mb speed bits in
+ * the 1000Base-T Control Register (Address 9).
+ */
+ mii_autoneg_adv_reg &= ~REG4_SPEED_MASK;
+ mii_1000t_ctrl_reg &= ~REG9_SPEED_MASK;
+
+ DEBUGOUT1("autoneg_advertised %x\n", hw->autoneg_advertised);
+
+ /* Do we want to advertise 10 Mb Half Duplex? */
+ if(hw->autoneg_advertised & ADVERTISE_10_HALF) {
+ DEBUGOUT("Advertise 10mb Half duplex\n");
+ mii_autoneg_adv_reg |= NWAY_AR_10T_HD_CAPS;
+ }
+
+ /* Do we want to advertise 10 Mb Full Duplex? */
+ if(hw->autoneg_advertised & ADVERTISE_10_FULL) {
+ DEBUGOUT("Advertise 10mb Full duplex\n");
+ mii_autoneg_adv_reg |= NWAY_AR_10T_FD_CAPS;
+ }
+
+ /* Do we want to advertise 100 Mb Half Duplex? */
+ if(hw->autoneg_advertised & ADVERTISE_100_HALF) {
+ DEBUGOUT("Advertise 100mb Half duplex\n");
+ mii_autoneg_adv_reg |= NWAY_AR_100TX_HD_CAPS;
+ }
+
+ /* Do we want to advertise 100 Mb Full Duplex? */
+ if(hw->autoneg_advertised & ADVERTISE_100_FULL) {
+ DEBUGOUT("Advertise 100mb Full duplex\n");
+ mii_autoneg_adv_reg |= NWAY_AR_100TX_FD_CAPS;
+ }
+
+ /* We do not allow the Phy to advertise 1000 Mb Half Duplex */
+ if(hw->autoneg_advertised & ADVERTISE_1000_HALF) {
+ DEBUGOUT("Advertise 1000mb Half duplex requested, request denied!\n");
+ }
+
+ /* Do we want to advertise 1000 Mb Full Duplex? */
+ if(hw->autoneg_advertised & ADVERTISE_1000_FULL) {
+ DEBUGOUT("Advertise 1000mb Full duplex\n");
+ mii_1000t_ctrl_reg |= CR_1000T_FD_CAPS;
+ }
+
+ /* Check for a software override of the flow control settings, and
+ * setup the PHY advertisement registers accordingly. If
+ * auto-negotiation is enabled, then software will have to set the
+ * "PAUSE" bits to the correct value in the Auto-Negotiation
+ * Advertisement Register (PHY_AUTONEG_ADV) and re-start auto-negotiation.
+ *
+ * The possible values of the "fc" parameter are:
+ * 0: Flow control is completely disabled
+ * 1: Rx flow control is enabled (we can receive pause frames
+ * but not send pause frames).
+ * 2: Tx flow control is enabled (we can send pause frames
+ * but we do not support receiving pause frames).
+ * 3: Both Rx and TX flow control (symmetric) are enabled.
+ * other: No software override. The flow control configuration
+ * in the EEPROM is used.
+ */
+ switch (hw->fc) {
+ case em_fc_none: /* 0 */
+ /* Flow control (RX & TX) is completely disabled by a
+ * software over-ride.
+ */
+ mii_autoneg_adv_reg &= ~(NWAY_AR_ASM_DIR | NWAY_AR_PAUSE);
+ break;
+ case em_fc_rx_pause: /* 1 */
+ /* RX Flow control is enabled, and TX Flow control is
+ * disabled, by a software over-ride.
+ */
+ /* Since there really isn't a way to advertise that we are
+ * capable of RX Pause ONLY, we will advertise that we
+ * support both symmetric and asymmetric RX PAUSE. Later
+ * (in em_config_fc_after_link_up) we will disable the
+ *hw's ability to send PAUSE frames.
+ */
+ mii_autoneg_adv_reg |= (NWAY_AR_ASM_DIR | NWAY_AR_PAUSE);
+ break;
+ case em_fc_tx_pause: /* 2 */
+ /* TX Flow control is enabled, and RX Flow control is
+ * disabled, by a software over-ride.
+ */
+ mii_autoneg_adv_reg |= NWAY_AR_ASM_DIR;
+ mii_autoneg_adv_reg &= ~NWAY_AR_PAUSE;
+ break;
+ case em_fc_full: /* 3 */
+ /* Flow control (both RX and TX) is enabled by a software
+ * over-ride.
+ */
+ mii_autoneg_adv_reg |= (NWAY_AR_ASM_DIR | NWAY_AR_PAUSE);
+ break;
+ default:
+ DEBUGOUT("Flow control param set incorrectly\n");
+ return -E1000_ERR_CONFIG;
+ }
+
+ ret_val = em_write_phy_reg(hw, PHY_AUTONEG_ADV, mii_autoneg_adv_reg);
+ if(ret_val)
+ return ret_val;
+
+ DEBUGOUT1("Auto-Neg Advertising %x\n", mii_autoneg_adv_reg);
+
+ ret_val = em_write_phy_reg(hw, PHY_1000T_CTRL, mii_1000t_ctrl_reg);
+ if(ret_val)
+ return ret_val;
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Force PHY speed and duplex settings to hw->forced_speed_duplex
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+static int32_t
+em_phy_force_speed_duplex(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ int32_t ret_val;
+ uint16_t mii_ctrl_reg;
+ uint16_t mii_status_reg;
+ uint16_t phy_data;
+ uint16_t i;
+
+ DEBUGFUNC("em_phy_force_speed_duplex");
+
+ /* Turn off Flow control if we are forcing speed and duplex. */
+ hw->fc = em_fc_none;
+
+ DEBUGOUT1("hw->fc = %d\n", hw->fc);
+
+ /* Read the Device Control Register. */
+ ctrl = E1000_READ_REG(hw, CTRL);
+
+ /* Set the bits to Force Speed and Duplex in the Device Ctrl Reg. */
+ ctrl |= (E1000_CTRL_FRCSPD | E1000_CTRL_FRCDPX);
+ ctrl &= ~(DEVICE_SPEED_MASK);
+
+ /* Clear the Auto Speed Detect Enable bit. */
+ ctrl &= ~E1000_CTRL_ASDE;
+
+ /* Read the MII Control Register. */
+ ret_val = em_read_phy_reg(hw, PHY_CTRL, &mii_ctrl_reg);
+ if(ret_val)
+ return ret_val;
+
+ /* We need to disable autoneg in order to force link and duplex. */
+
+ mii_ctrl_reg &= ~MII_CR_AUTO_NEG_EN;
+
+ /* Are we forcing Full or Half Duplex? */
+ if(hw->forced_speed_duplex == em_100_full ||
+ hw->forced_speed_duplex == em_10_full) {
+ /* We want to force full duplex so we SET the full duplex bits in the
+ * Device and MII Control Registers.
+ */
+ ctrl |= E1000_CTRL_FD;
+ mii_ctrl_reg |= MII_CR_FULL_DUPLEX;
+ DEBUGOUT("Full Duplex\n");
+ } else {
+ /* We want to force half duplex so we CLEAR the full duplex bits in
+ * the Device and MII Control Registers.
+ */
+ ctrl &= ~E1000_CTRL_FD;
+ mii_ctrl_reg &= ~MII_CR_FULL_DUPLEX;
+ DEBUGOUT("Half Duplex\n");
+ }
+
+ /* Are we forcing 100Mbps??? */
+ if(hw->forced_speed_duplex == em_100_full ||
+ hw->forced_speed_duplex == em_100_half) {
+ /* Set the 100Mb bit and turn off the 1000Mb and 10Mb bits. */
+ ctrl |= E1000_CTRL_SPD_100;
+ mii_ctrl_reg |= MII_CR_SPEED_100;
+ mii_ctrl_reg &= ~(MII_CR_SPEED_1000 | MII_CR_SPEED_10);
+ DEBUGOUT("Forcing 100mb ");
+ } else {
+ /* Set the 10Mb bit and turn off the 1000Mb and 100Mb bits. */
+ ctrl &= ~(E1000_CTRL_SPD_1000 | E1000_CTRL_SPD_100);
+ mii_ctrl_reg |= MII_CR_SPEED_10;
+ mii_ctrl_reg &= ~(MII_CR_SPEED_1000 | MII_CR_SPEED_100);
+ DEBUGOUT("Forcing 10mb ");
+ }
+
+ em_config_collision_dist(hw);
+
+ /* Write the configured values back to the Device Control Reg. */
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+
+ if (hw->phy_type == em_phy_m88) {
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* Clear Auto-Crossover to force MDI manually. M88E1000 requires MDI
+ * forced whenever speed are duplex are forced.
+ */
+ phy_data &= ~M88E1000_PSCR_AUTO_X_MODE;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ DEBUGOUT1("M88E1000 PSCR: %x \n", phy_data);
+
+ /* Need to reset the PHY or these changes will be ignored */
+ mii_ctrl_reg |= MII_CR_RESET;
+ } else {
+ /* Clear Auto-Crossover to force MDI manually. IGP requires MDI
+ * forced whenever speed or duplex are forced.
+ */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PSCR_AUTO_MDIX;
+ phy_data &= ~IGP01E1000_PSCR_FORCE_MDI_MDIX;
+
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ /* Write back the modified PHY MII control register. */
+ ret_val = em_write_phy_reg(hw, PHY_CTRL, mii_ctrl_reg);
+ if(ret_val)
+ return ret_val;
+
+ usec_delay(1);
+
+ /* The wait_autoneg_complete flag may be a little misleading here.
+ * Since we are forcing speed and duplex, Auto-Neg is not enabled.
+ * But we do want to delay for a period while forcing only so we
+ * don't generate false No Link messages. So we will wait here
+ * only if the user has set wait_autoneg_complete to 1, which is
+ * the default.
+ */
+ if(hw->wait_autoneg_complete) {
+ /* We will wait for autoneg to complete. */
+ DEBUGOUT("Waiting for forced speed/duplex link.\n");
+ mii_status_reg = 0;
+
+ /* We will wait for autoneg to complete or 4.5 seconds to expire. */
+ for(i = PHY_FORCE_TIME; i > 0; i--) {
+ /* Read the MII Status Register and wait for Auto-Neg Complete bit
+ * to be set.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ if(mii_status_reg & MII_SR_LINK_STATUS) break;
+ msec_delay(100);
+ }
+ if((i == 0) &&
+ (hw->phy_type == em_phy_m88)) {
+ /* We didn't get link. Reset the DSP and wait again for link. */
+ ret_val = em_phy_reset_dsp(hw);
+ if(ret_val) {
+ DEBUGOUT("Error Resetting PHY DSP\n");
+ return ret_val;
+ }
+ }
+ /* This loop will early-out if the link condition has been met. */
+ for(i = PHY_FORCE_TIME; i > 0; i--) {
+ if(mii_status_reg & MII_SR_LINK_STATUS) break;
+ msec_delay(100);
+ /* Read the MII Status Register and wait for Auto-Neg Complete bit
+ * to be set.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+ }
+ }
+
+ if (hw->phy_type == em_phy_m88) {
+ /* Because we reset the PHY above, we need to re-force TX_CLK in the
+ * Extended PHY Specific Control Register to 25MHz clock. This value
+ * defaults back to a 2.5MHz clock when the PHY is reset.
+ */
+ ret_val = em_read_phy_reg(hw, M88E1000_EXT_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= M88E1000_EPSCR_TX_CLK_25;
+ ret_val = em_write_phy_reg(hw, M88E1000_EXT_PHY_SPEC_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* In addition, because of the s/w reset above, we need to enable CRS on
+ * TX. This must be set for both full and half duplex operation.
+ */
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= M88E1000_PSCR_ASSERT_CRS_ON_TX;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if((hw->mac_type == em_82544 || hw->mac_type == em_82543) &&
+ (!hw->autoneg) &&
+ (hw->forced_speed_duplex == em_10_full ||
+ hw->forced_speed_duplex == em_10_half)) {
+ ret_val = em_polarity_reversal_workaround(hw);
+ if(ret_val)
+ return ret_val;
+ }
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Sets the collision distance in the Transmit Control register
+*
+* hw - Struct containing variables accessed by shared code
+*
+* Link should have been established previously. Reads the speed and duplex
+* information from the Device Status register.
+******************************************************************************/
+void
+em_config_collision_dist(struct em_hw *hw)
+{
+ uint32_t tctl;
+
+ DEBUGFUNC("em_config_collision_dist");
+
+ tctl = E1000_READ_REG(hw, TCTL);
+
+ tctl &= ~E1000_TCTL_COLD;
+ tctl |= E1000_COLLISION_DISTANCE << E1000_COLD_SHIFT;
+
+ E1000_WRITE_REG(hw, TCTL, tctl);
+ E1000_WRITE_FLUSH(hw);
+}
+
+/******************************************************************************
+* Sets MAC speed and duplex settings to reflect the those in the PHY
+*
+* hw - Struct containing variables accessed by shared code
+* mii_reg - data to write to the MII control register
+*
+* The contents of the PHY register containing the needed information need to
+* be passed in.
+******************************************************************************/
+static int32_t
+em_config_mac_to_phy(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_config_mac_to_phy");
+
+ /* 82544 or newer MAC, Auto Speed Detection takes care of
+ * MAC speed/duplex configuration.*/
+ if (hw->mac_type >= em_82544)
+ return E1000_SUCCESS;
+
+ /* Read the Device Control Register and set the bits to Force Speed
+ * and Duplex.
+ */
+ ctrl = E1000_READ_REG(hw, CTRL);
+ ctrl |= (E1000_CTRL_FRCSPD | E1000_CTRL_FRCDPX);
+ ctrl &= ~(E1000_CTRL_SPD_SEL | E1000_CTRL_ILOS);
+
+ /* Set up duplex in the Device Control and Transmit Control
+ * registers depending on negotiated values.
+ */
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if(phy_data & M88E1000_PSSR_DPLX)
+ ctrl |= E1000_CTRL_FD;
+ else
+ ctrl &= ~E1000_CTRL_FD;
+
+ em_config_collision_dist(hw);
+
+ /* Set up speed in the Device Control register depending on
+ * negotiated values.
+ */
+ if((phy_data & M88E1000_PSSR_SPEED) == M88E1000_PSSR_1000MBS)
+ ctrl |= E1000_CTRL_SPD_1000;
+ else if((phy_data & M88E1000_PSSR_SPEED) == M88E1000_PSSR_100MBS)
+ ctrl |= E1000_CTRL_SPD_100;
+
+ /* Write the configured values back to the Device Control Reg. */
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Forces the MAC's flow control settings.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Sets the TFCE and RFCE bits in the device control register to reflect
+ * the adapter settings. TFCE and RFCE need to be explicitly set by
+ * software when a Copper PHY is used because autonegotiation is managed
+ * by the PHY rather than the MAC. Software must also configure these
+ * bits when link is forced on a fiber connection.
+ *****************************************************************************/
+int32_t
+em_force_mac_fc(struct em_hw *hw)
+{
+ uint32_t ctrl;
+
+ DEBUGFUNC("em_force_mac_fc");
+
+ /* Get the current configuration of the Device Control Register */
+ ctrl = E1000_READ_REG(hw, CTRL);
+
+ /* Because we didn't get link via the internal auto-negotiation
+ * mechanism (we either forced link or we got link via PHY
+ * auto-neg), we have to manually enable/disable transmit an
+ * receive flow control.
+ *
+ * The "Case" statement below enables/disable flow control
+ * according to the "hw->fc" parameter.
+ *
+ * The possible values of the "fc" parameter are:
+ * 0: Flow control is completely disabled
+ * 1: Rx flow control is enabled (we can receive pause
+ * frames but not send pause frames).
+ * 2: Tx flow control is enabled (we can send pause frames
+ * frames but we do not receive pause frames).
+ * 3: Both Rx and TX flow control (symmetric) is enabled.
+ * other: No other values should be possible at this point.
+ */
+
+ switch (hw->fc) {
+ case em_fc_none:
+ ctrl &= (~(E1000_CTRL_TFCE | E1000_CTRL_RFCE));
+ break;
+ case em_fc_rx_pause:
+ ctrl &= (~E1000_CTRL_TFCE);
+ ctrl |= E1000_CTRL_RFCE;
+ break;
+ case em_fc_tx_pause:
+ ctrl &= (~E1000_CTRL_RFCE);
+ ctrl |= E1000_CTRL_TFCE;
+ break;
+ case em_fc_full:
+ ctrl |= (E1000_CTRL_TFCE | E1000_CTRL_RFCE);
+ break;
+ default:
+ DEBUGOUT("Flow control param set incorrectly\n");
+ return -E1000_ERR_CONFIG;
+ }
+
+ /* Disable TX Flow Control for 82542 (rev 2.0) */
+ if(hw->mac_type == em_82542_rev2_0)
+ ctrl &= (~E1000_CTRL_TFCE);
+
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Configures flow control settings after link is established
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Should be called immediately after a valid link has been established.
+ * Forces MAC flow control settings if link was forced. When in MII/GMII mode
+ * and autonegotiation is enabled, the MAC flow control settings will be set
+ * based on the flow control negotiated by the PHY. In TBI mode, the TFCE
+ * and RFCE bits will be automaticaly set to the negotiated flow control mode.
+ *****************************************************************************/
+int32_t
+em_config_fc_after_link_up(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t mii_status_reg;
+ uint16_t mii_nway_adv_reg;
+ uint16_t mii_nway_lp_ability_reg;
+ uint16_t speed;
+ uint16_t duplex;
+
+ DEBUGFUNC("em_config_fc_after_link_up");
+
+ /* Check for the case where we have fiber media and auto-neg failed
+ * so we had to force link. In this case, we need to force the
+ * configuration of the MAC to match the "fc" parameter.
+ */
+ if(((hw->media_type == em_media_type_fiber) && (hw->autoneg_failed)) ||
+ ((hw->media_type == em_media_type_internal_serdes) && (hw->autoneg_failed)) ||
+ ((hw->media_type == em_media_type_copper) && (!hw->autoneg))) {
+ ret_val = em_force_mac_fc(hw);
+ if(ret_val) {
+ DEBUGOUT("Error forcing flow control settings\n");
+ return ret_val;
+ }
+ }
+
+ /* Check for the case where we have copper media and auto-neg is
+ * enabled. In this case, we need to check and see if Auto-Neg
+ * has completed, and if so, how the PHY and link partner has
+ * flow control configured.
+ */
+ if((hw->media_type == em_media_type_copper) && hw->autoneg) {
+ /* Read the MII Status Register and check to see if AutoNeg
+ * has completed. We read this twice because this reg has
+ * some "sticky" (latched) bits.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ if(mii_status_reg & MII_SR_AUTONEG_COMPLETE) {
+ /* The AutoNeg process has completed, so we now need to
+ * read both the Auto Negotiation Advertisement Register
+ * (Address 4) and the Auto_Negotiation Base Page Ability
+ * Register (Address 5) to determine how flow control was
+ * negotiated.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_AUTONEG_ADV,
+ &mii_nway_adv_reg);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_read_phy_reg(hw, PHY_LP_ABILITY,
+ &mii_nway_lp_ability_reg);
+ if(ret_val)
+ return ret_val;
+
+ /* Two bits in the Auto Negotiation Advertisement Register
+ * (Address 4) and two bits in the Auto Negotiation Base
+ * Page Ability Register (Address 5) determine flow control
+ * for both the PHY and the link partner. The following
+ * table, taken out of the IEEE 802.3ab/D6.0 dated March 25,
+ * 1999, describes these PAUSE resolution bits and how flow
+ * control is determined based upon these settings.
+ * NOTE: DC = Don't Care
+ *
+ * LOCAL DEVICE | LINK PARTNER
+ * PAUSE | ASM_DIR | PAUSE | ASM_DIR | NIC Resolution
+ *-------|---------|-------|---------|--------------------
+ * 0 | 0 | DC | DC | em_fc_none
+ * 0 | 1 | 0 | DC | em_fc_none
+ * 0 | 1 | 1 | 0 | em_fc_none
+ * 0 | 1 | 1 | 1 | em_fc_tx_pause
+ * 1 | 0 | 0 | DC | em_fc_none
+ * 1 | DC | 1 | DC | em_fc_full
+ * 1 | 1 | 0 | 0 | em_fc_none
+ * 1 | 1 | 0 | 1 | em_fc_rx_pause
+ *
+ */
+ /* Are both PAUSE bits set to 1? If so, this implies
+ * Symmetric Flow Control is enabled at both ends. The
+ * ASM_DIR bits are irrelevant per the spec.
+ *
+ * For Symmetric Flow Control:
+ *
+ * LOCAL DEVICE | LINK PARTNER
+ * PAUSE | ASM_DIR | PAUSE | ASM_DIR | Result
+ *-------|---------|-------|---------|--------------------
+ * 1 | DC | 1 | DC | em_fc_full
+ *
+ */
+ if((mii_nway_adv_reg & NWAY_AR_PAUSE) &&
+ (mii_nway_lp_ability_reg & NWAY_LPAR_PAUSE)) {
+ /* Now we need to check if the user selected RX ONLY
+ * of pause frames. In this case, we had to advertise
+ * FULL flow control because we could not advertise RX
+ * ONLY. Hence, we must now check to see if we need to
+ * turn OFF the TRANSMISSION of PAUSE frames.
+ */
+ if(hw->original_fc == em_fc_full) {
+ hw->fc = em_fc_full;
+ DEBUGOUT("Flow Control = FULL.\r\n");
+ } else {
+ hw->fc = em_fc_rx_pause;
+ DEBUGOUT("Flow Control = RX PAUSE frames only.\r\n");
+ }
+ }
+ /* For receiving PAUSE frames ONLY.
+ *
+ * LOCAL DEVICE | LINK PARTNER
+ * PAUSE | ASM_DIR | PAUSE | ASM_DIR | Result
+ *-------|---------|-------|---------|--------------------
+ * 0 | 1 | 1 | 1 | em_fc_tx_pause
+ *
+ */
+ else if(!(mii_nway_adv_reg & NWAY_AR_PAUSE) &&
+ (mii_nway_adv_reg & NWAY_AR_ASM_DIR) &&
+ (mii_nway_lp_ability_reg & NWAY_LPAR_PAUSE) &&
+ (mii_nway_lp_ability_reg & NWAY_LPAR_ASM_DIR)) {
+ hw->fc = em_fc_tx_pause;
+ DEBUGOUT("Flow Control = TX PAUSE frames only.\r\n");
+ }
+ /* For transmitting PAUSE frames ONLY.
+ *
+ * LOCAL DEVICE | LINK PARTNER
+ * PAUSE | ASM_DIR | PAUSE | ASM_DIR | Result
+ *-------|---------|-------|---------|--------------------
+ * 1 | 1 | 0 | 1 | em_fc_rx_pause
+ *
+ */
+ else if((mii_nway_adv_reg & NWAY_AR_PAUSE) &&
+ (mii_nway_adv_reg & NWAY_AR_ASM_DIR) &&
+ !(mii_nway_lp_ability_reg & NWAY_LPAR_PAUSE) &&
+ (mii_nway_lp_ability_reg & NWAY_LPAR_ASM_DIR)) {
+ hw->fc = em_fc_rx_pause;
+ DEBUGOUT("Flow Control = RX PAUSE frames only.\r\n");
+ }
+ /* Per the IEEE spec, at this point flow control should be
+ * disabled. However, we want to consider that we could
+ * be connected to a legacy switch that doesn't advertise
+ * desired flow control, but can be forced on the link
+ * partner. So if we advertised no flow control, that is
+ * what we will resolve to. If we advertised some kind of
+ * receive capability (Rx Pause Only or Full Flow Control)
+ * and the link partner advertised none, we will configure
+ * ourselves to enable Rx Flow Control only. We can do
+ * this safely for two reasons: If the link partner really
+ * didn't want flow control enabled, and we enable Rx, no
+ * harm done since we won't be receiving any PAUSE frames
+ * anyway. If the intent on the link partner was to have
+ * flow control enabled, then by us enabling RX only, we
+ * can at least receive pause frames and process them.
+ * This is a good idea because in most cases, since we are
+ * predominantly a server NIC, more times than not we will
+ * be asked to delay transmission of packets than asking
+ * our link partner to pause transmission of frames.
+ */
+ else if((hw->original_fc == em_fc_none ||
+ hw->original_fc == em_fc_tx_pause) ||
+ hw->fc_strict_ieee) {
+ hw->fc = em_fc_none;
+ DEBUGOUT("Flow Control = NONE.\r\n");
+ } else {
+ hw->fc = em_fc_rx_pause;
+ DEBUGOUT("Flow Control = RX PAUSE frames only.\r\n");
+ }
+
+ /* Now we need to do one last check... If we auto-
+ * negotiated to HALF DUPLEX, flow control should not be
+ * enabled per IEEE 802.3 spec.
+ */
+ ret_val = em_get_speed_and_duplex(hw, &speed, &duplex);
+ if(ret_val) {
+ DEBUGOUT("Error getting link speed and duplex\n");
+ return ret_val;
+ }
+
+ if(duplex == HALF_DUPLEX)
+ hw->fc = em_fc_none;
+
+ /* Now we call a subroutine to actually force the MAC
+ * controller to use the correct flow control settings.
+ */
+ ret_val = em_force_mac_fc(hw);
+ if(ret_val) {
+ DEBUGOUT("Error forcing flow control settings\n");
+ return ret_val;
+ }
+ } else {
+ DEBUGOUT("Copper PHY and Auto Neg has not completed.\r\n");
+ }
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Checks to see if the link status of the hardware has changed.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Called by any function that needs to check the link status of the adapter.
+ *****************************************************************************/
+int32_t
+em_check_for_link(struct em_hw *hw)
+{
+ uint32_t rxcw = 0;
+ uint32_t ctrl;
+ uint32_t status;
+ uint32_t rctl;
+ uint32_t icr;
+ uint32_t signal = 0;
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_check_for_link");
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+ status = E1000_READ_REG(hw, STATUS);
+
+ /* On adapters with a MAC newer than 82544, SW Defineable pin 1 will be
+ * set when the optics detect a signal. On older adapters, it will be
+ * cleared when there is a signal. This applies to fiber media only.
+ */
+ if((hw->media_type == em_media_type_fiber) ||
+ (hw->media_type == em_media_type_internal_serdes)) {
+ rxcw = E1000_READ_REG(hw, RXCW);
+
+ if(hw->media_type == em_media_type_fiber) {
+ signal = (hw->mac_type > em_82544) ? E1000_CTRL_SWDPIN1 : 0;
+ if(status & E1000_STATUS_LU)
+ hw->get_link_status = FALSE;
+ }
+ }
+
+ /* If we have a copper PHY then we only want to go out to the PHY
+ * registers to see if Auto-Neg has completed and/or if our link
+ * status has changed. The get_link_status flag will be set if we
+ * receive a Link Status Change interrupt or we have Rx Sequence
+ * Errors.
+ */
+ if((hw->media_type == em_media_type_copper) && hw->get_link_status) {
+ /* First we want to see if the MII Status Register reports
+ * link. If so, then we want to get the current speed/duplex
+ * of the PHY.
+ * Read the register twice since the link bit is sticky.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if(phy_data & MII_SR_LINK_STATUS) {
+ hw->get_link_status = FALSE;
+ /* Check if there was DownShift, must be checked immediately after
+ * link-up */
+ em_check_downshift(hw);
+
+ /* If we are on 82544 or 82543 silicon and speed/duplex
+ * are forced to 10H or 10F, then we will implement the polarity
+ * reversal workaround. We disable interrupts first, and upon
+ * returning, place the devices interrupt state to its previous
+ * value except for the link status change interrupt which will
+ * happen due to the execution of this workaround.
+ */
+
+ if((hw->mac_type == em_82544 || hw->mac_type == em_82543) &&
+ (!hw->autoneg) &&
+ (hw->forced_speed_duplex == em_10_full ||
+ hw->forced_speed_duplex == em_10_half)) {
+ E1000_WRITE_REG(hw, IMC, 0xffffffff);
+ ret_val = em_polarity_reversal_workaround(hw);
+ icr = E1000_READ_REG(hw, ICR);
+ E1000_WRITE_REG(hw, ICS, (icr & ~E1000_ICS_LSC));
+ E1000_WRITE_REG(hw, IMS, IMS_ENABLE_MASK);
+ }
+
+ } else {
+ /* No link detected */
+ em_config_dsp_after_link_change(hw, FALSE);
+ return 0;
+ }
+
+ /* If we are forcing speed/duplex, then we simply return since
+ * we have already determined whether we have link or not.
+ */
+ if(!hw->autoneg) return -E1000_ERR_CONFIG;
+
+ /* optimize the dsp settings for the igp phy */
+ em_config_dsp_after_link_change(hw, TRUE);
+
+ /* We have a M88E1000 PHY and Auto-Neg is enabled. If we
+ * have Si on board that is 82544 or newer, Auto
+ * Speed Detection takes care of MAC speed/duplex
+ * configuration. So we only need to configure Collision
+ * Distance in the MAC. Otherwise, we need to force
+ * speed/duplex on the MAC to the current PHY speed/duplex
+ * settings.
+ */
+ if(hw->mac_type >= em_82544)
+ em_config_collision_dist(hw);
+ else {
+ ret_val = em_config_mac_to_phy(hw);
+ if(ret_val) {
+ DEBUGOUT("Error configuring MAC to PHY settings\n");
+ return ret_val;
+ }
+ }
+
+ /* Configure Flow Control now that Auto-Neg has completed. First, we
+ * need to restore the desired flow control settings because we may
+ * have had to re-autoneg with a different link partner.
+ */
+ ret_val = em_config_fc_after_link_up(hw);
+ if(ret_val) {
+ DEBUGOUT("Error configuring flow control\n");
+ return ret_val;
+ }
+
+ /* At this point we know that we are on copper and we have
+ * auto-negotiated link. These are conditions for checking the link
+ * partner capability register. We use the link speed to determine if
+ * TBI compatibility needs to be turned on or off. If the link is not
+ * at gigabit speed, then TBI compatibility is not needed. If we are
+ * at gigabit speed, we turn on TBI compatibility.
+ */
+ if(hw->tbi_compatibility_en) {
+ uint16_t speed, duplex;
+ em_get_speed_and_duplex(hw, &speed, &duplex);
+ if(speed != SPEED_1000) {
+ /* If link speed is not set to gigabit speed, we do not need
+ * to enable TBI compatibility.
+ */
+ if(hw->tbi_compatibility_on) {
+ /* If we previously were in the mode, turn it off. */
+ rctl = E1000_READ_REG(hw, RCTL);
+ rctl &= ~E1000_RCTL_SBP;
+ E1000_WRITE_REG(hw, RCTL, rctl);
+ hw->tbi_compatibility_on = FALSE;
+ }
+ } else {
+ /* If TBI compatibility is was previously off, turn it on. For
+ * compatibility with a TBI link partner, we will store bad
+ * packets. Some frames have an additional byte on the end and
+ * will look like CRC errors to to the hardware.
+ */
+ if(!hw->tbi_compatibility_on) {
+ hw->tbi_compatibility_on = TRUE;
+ rctl = E1000_READ_REG(hw, RCTL);
+ rctl |= E1000_RCTL_SBP;
+ E1000_WRITE_REG(hw, RCTL, rctl);
+ }
+ }
+ }
+ }
+ /* If we don't have link (auto-negotiation failed or link partner cannot
+ * auto-negotiate), the cable is plugged in (we have signal), and our
+ * link partner is not trying to auto-negotiate with us (we are receiving
+ * idles or data), we need to force link up. We also need to give
+ * auto-negotiation time to complete, in case the cable was just plugged
+ * in. The autoneg_failed flag does this.
+ */
+ else if((((hw->media_type == em_media_type_fiber) &&
+ ((ctrl & E1000_CTRL_SWDPIN1) == signal)) ||
+ (hw->media_type == em_media_type_internal_serdes)) &&
+ (!(status & E1000_STATUS_LU)) &&
+ (!(rxcw & E1000_RXCW_C))) {
+ if(hw->autoneg_failed == 0) {
+ hw->autoneg_failed = 1;
+ return 0;
+ }
+ DEBUGOUT("NOT RXing /C/, disable AutoNeg and force link.\r\n");
+
+ /* Disable auto-negotiation in the TXCW register */
+ E1000_WRITE_REG(hw, TXCW, (hw->txcw & ~E1000_TXCW_ANE));
+
+ /* Force link-up and also force full-duplex. */
+ ctrl = E1000_READ_REG(hw, CTRL);
+ ctrl |= (E1000_CTRL_SLU | E1000_CTRL_FD);
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+
+ /* Configure Flow Control after forcing link up. */
+ ret_val = em_config_fc_after_link_up(hw);
+ if(ret_val) {
+ DEBUGOUT("Error configuring flow control\n");
+ return ret_val;
+ }
+ }
+ /* If we are forcing link and we are receiving /C/ ordered sets, re-enable
+ * auto-negotiation in the TXCW register and disable forced link in the
+ * Device Control register in an attempt to auto-negotiate with our link
+ * partner.
+ */
+ else if(((hw->media_type == em_media_type_fiber) ||
+ (hw->media_type == em_media_type_internal_serdes)) &&
+ (ctrl & E1000_CTRL_SLU) && (rxcw & E1000_RXCW_C)) {
+ DEBUGOUT("RXing /C/, enable AutoNeg and stop forcing link.\r\n");
+ E1000_WRITE_REG(hw, TXCW, hw->txcw);
+ E1000_WRITE_REG(hw, CTRL, (ctrl & ~E1000_CTRL_SLU));
+
+ hw->serdes_link_down = FALSE;
+ }
+ /* If we force link for non-auto-negotiation switch, check link status
+ * based on MAC synchronization for internal serdes media type.
+ */
+ else if((hw->media_type == em_media_type_internal_serdes) &&
+ !(E1000_TXCW_ANE & E1000_READ_REG(hw, TXCW))) {
+ /* SYNCH bit and IV bit are sticky. */
+ usec_delay(10);
+ if(E1000_RXCW_SYNCH & E1000_READ_REG(hw, RXCW)) {
+ if(!(rxcw & E1000_RXCW_IV)) {
+ hw->serdes_link_down = FALSE;
+ DEBUGOUT("SERDES: Link is up.\n");
+ }
+ } else {
+ hw->serdes_link_down = TRUE;
+ DEBUGOUT("SERDES: Link is down.\n");
+ }
+ }
+ if((hw->media_type == em_media_type_internal_serdes) &&
+ (E1000_TXCW_ANE & E1000_READ_REG(hw, TXCW))) {
+ hw->serdes_link_down = !(E1000_STATUS_LU & E1000_READ_REG(hw, STATUS));
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Detects the current speed and duplex settings of the hardware.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * speed - Speed of the connection
+ * duplex - Duplex setting of the connection
+ *****************************************************************************/
+int32_t
+em_get_speed_and_duplex(struct em_hw *hw,
+ uint16_t *speed,
+ uint16_t *duplex)
+{
+ uint32_t status;
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_get_speed_and_duplex");
+
+ if(hw->mac_type >= em_82543) {
+ status = E1000_READ_REG(hw, STATUS);
+ if(status & E1000_STATUS_SPEED_1000) {
+ *speed = SPEED_1000;
+ DEBUGOUT("1000 Mbs, ");
+ } else if(status & E1000_STATUS_SPEED_100) {
+ *speed = SPEED_100;
+ DEBUGOUT("100 Mbs, ");
+ } else {
+ *speed = SPEED_10;
+ DEBUGOUT("10 Mbs, ");
+ }
+
+ if(status & E1000_STATUS_FD) {
+ *duplex = FULL_DUPLEX;
+ DEBUGOUT("Full Duplex\r\n");
+ } else {
+ *duplex = HALF_DUPLEX;
+ DEBUGOUT(" Half Duplex\r\n");
+ }
+ } else {
+ DEBUGOUT("1000 Mbs, Full Duplex\r\n");
+ *speed = SPEED_1000;
+ *duplex = FULL_DUPLEX;
+ }
+
+ /* IGP01 PHY may advertise full duplex operation after speed downgrade even
+ * if it is operating at half duplex. Here we set the duplex settings to
+ * match the duplex in the link partner's capabilities.
+ */
+ if(hw->phy_type == em_phy_igp && hw->speed_downgraded) {
+ ret_val = em_read_phy_reg(hw, PHY_AUTONEG_EXP, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if(!(phy_data & NWAY_ER_LP_NWAY_CAPS))
+ *duplex = HALF_DUPLEX;
+ else {
+ ret_val = em_read_phy_reg(hw, PHY_LP_ABILITY, &phy_data);
+ if(ret_val)
+ return ret_val;
+ if((*speed == SPEED_100 && !(phy_data & NWAY_LPAR_100TX_FD_CAPS)) ||
+ (*speed == SPEED_10 && !(phy_data & NWAY_LPAR_10T_FD_CAPS)))
+ *duplex = HALF_DUPLEX;
+ }
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Blocks until autoneg completes or times out (~4.5 seconds)
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+int32_t
+em_wait_autoneg(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t i;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_wait_autoneg");
+ DEBUGOUT("Waiting for Auto-Neg to complete.\n");
+
+ /* We will wait for autoneg to complete or 4.5 seconds to expire. */
+ for(i = PHY_AUTO_NEG_TIME; i > 0; i--) {
+ /* Read the MII Status Register and wait for Auto-Neg
+ * Complete bit to be set.
+ */
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+ if(phy_data & MII_SR_AUTONEG_COMPLETE) {
+ return E1000_SUCCESS;
+ }
+ msec_delay(100);
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Raises the Management Data Clock
+*
+* hw - Struct containing variables accessed by shared code
+* ctrl - Device control register's current value
+******************************************************************************/
+static void
+em_raise_mdi_clk(struct em_hw *hw,
+ uint32_t *ctrl)
+{
+ /* Raise the clock input to the Management Data Clock (by setting the MDC
+ * bit), and then delay 10 microseconds.
+ */
+ E1000_WRITE_REG(hw, CTRL, (*ctrl | E1000_CTRL_MDC));
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(10);
+}
+
+/******************************************************************************
+* Lowers the Management Data Clock
+*
+* hw - Struct containing variables accessed by shared code
+* ctrl - Device control register's current value
+******************************************************************************/
+static void
+em_lower_mdi_clk(struct em_hw *hw,
+ uint32_t *ctrl)
+{
+ /* Lower the clock input to the Management Data Clock (by clearing the MDC
+ * bit), and then delay 10 microseconds.
+ */
+ E1000_WRITE_REG(hw, CTRL, (*ctrl & ~E1000_CTRL_MDC));
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(10);
+}
+
+/******************************************************************************
+* Shifts data bits out to the PHY
+*
+* hw - Struct containing variables accessed by shared code
+* data - Data to send out to the PHY
+* count - Number of bits to shift out
+*
+* Bits are shifted out in MSB to LSB order.
+******************************************************************************/
+static void
+em_shift_out_mdi_bits(struct em_hw *hw,
+ uint32_t data,
+ uint16_t count)
+{
+ uint32_t ctrl;
+ uint32_t mask;
+
+ /* We need to shift "count" number of bits out to the PHY. So, the value
+ * in the "data" parameter will be shifted out to the PHY one bit at a
+ * time. In order to do this, "data" must be broken down into bits.
+ */
+ mask = 0x01;
+ mask <<= (count - 1);
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+
+ /* Set MDIO_DIR and MDC_DIR direction bits to be used as output pins. */
+ ctrl |= (E1000_CTRL_MDIO_DIR | E1000_CTRL_MDC_DIR);
+
+ while(mask) {
+ /* A "1" is shifted out to the PHY by setting the MDIO bit to "1" and
+ * then raising and lowering the Management Data Clock. A "0" is
+ * shifted out to the PHY by setting the MDIO bit to "0" and then
+ * raising and lowering the clock.
+ */
+ if(data & mask) ctrl |= E1000_CTRL_MDIO;
+ else ctrl &= ~E1000_CTRL_MDIO;
+
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ E1000_WRITE_FLUSH(hw);
+
+ usec_delay(10);
+
+ em_raise_mdi_clk(hw, &ctrl);
+ em_lower_mdi_clk(hw, &ctrl);
+
+ mask = mask >> 1;
+ }
+}
+
+/******************************************************************************
+* Shifts data bits in from the PHY
+*
+* hw - Struct containing variables accessed by shared code
+*
+* Bits are shifted in in MSB to LSB order.
+******************************************************************************/
+static uint16_t
+em_shift_in_mdi_bits(struct em_hw *hw)
+{
+ uint32_t ctrl;
+ uint16_t data = 0;
+ uint8_t i;
+
+ /* In order to read a register from the PHY, we need to shift in a total
+ * of 18 bits from the PHY. The first two bit (turnaround) times are used
+ * to avoid contention on the MDIO pin when a read operation is performed.
+ * These two bits are ignored by us and thrown away. Bits are "shifted in"
+ * by raising the input to the Management Data Clock (setting the MDC bit),
+ * and then reading the value of the MDIO bit.
+ */
+ ctrl = E1000_READ_REG(hw, CTRL);
+
+ /* Clear MDIO_DIR (SWDPIO1) to indicate this bit is to be used as input. */
+ ctrl &= ~E1000_CTRL_MDIO_DIR;
+ ctrl &= ~E1000_CTRL_MDIO;
+
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ E1000_WRITE_FLUSH(hw);
+
+ /* Raise and Lower the clock before reading in the data. This accounts for
+ * the turnaround bits. The first clock occurred when we clocked out the
+ * last bit of the Register Address.
+ */
+ em_raise_mdi_clk(hw, &ctrl);
+ em_lower_mdi_clk(hw, &ctrl);
+
+ for(data = 0, i = 0; i < 16; i++) {
+ data = data << 1;
+ em_raise_mdi_clk(hw, &ctrl);
+ ctrl = E1000_READ_REG(hw, CTRL);
+ /* Check to see if we shifted in a "1". */
+ if(ctrl & E1000_CTRL_MDIO) data |= 1;
+ em_lower_mdi_clk(hw, &ctrl);
+ }
+
+ em_raise_mdi_clk(hw, &ctrl);
+ em_lower_mdi_clk(hw, &ctrl);
+
+ return data;
+}
+
+/*****************************************************************************
+* Reads the value from a PHY register, if the value is on a specific non zero
+* page, sets the page first.
+* hw - Struct containing variables accessed by shared code
+* reg_addr - address of the PHY register to read
+******************************************************************************/
+int32_t
+em_read_phy_reg(struct em_hw *hw,
+ uint32_t reg_addr,
+ uint16_t *phy_data)
+{
+ uint32_t ret_val;
+
+ DEBUGFUNC("em_read_phy_reg");
+
+ if((hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2) &&
+ (reg_addr > MAX_PHY_MULTI_PAGE_REG)) {
+ ret_val = em_write_phy_reg_ex(hw, IGP01E1000_PHY_PAGE_SELECT,
+ (uint16_t)reg_addr);
+ if(ret_val) {
+ return ret_val;
+ }
+ }
+
+ ret_val = em_read_phy_reg_ex(hw, MAX_PHY_REG_ADDRESS & reg_addr,
+ phy_data);
+
+ return ret_val;
+}
+
+int32_t
+em_read_phy_reg_ex(struct em_hw *hw,
+ uint32_t reg_addr,
+ uint16_t *phy_data)
+{
+ uint32_t i;
+ uint32_t mdic = 0;
+ const uint32_t phy_addr = 1;
+
+ DEBUGFUNC("em_read_phy_reg_ex");
+
+ if(reg_addr > MAX_PHY_REG_ADDRESS) {
+ DEBUGOUT1("PHY Address %d is out of range\n", reg_addr);
+ return -E1000_ERR_PARAM;
+ }
+
+ if(hw->mac_type > em_82543) {
+ /* Set up Op-code, Phy Address, and register address in the MDI
+ * Control register. The MAC will take care of interfacing with the
+ * PHY to retrieve the desired data.
+ */
+ mdic = ((reg_addr << E1000_MDIC_REG_SHIFT) |
+ (phy_addr << E1000_MDIC_PHY_SHIFT) |
+ (E1000_MDIC_OP_READ));
+
+ E1000_WRITE_REG(hw, MDIC, mdic);
+
+ /* Poll the ready bit to see if the MDI read completed */
+ for(i = 0; i < 64; i++) {
+ usec_delay(50);
+ mdic = E1000_READ_REG(hw, MDIC);
+ if(mdic & E1000_MDIC_READY) break;
+ }
+ if(!(mdic & E1000_MDIC_READY)) {
+ DEBUGOUT("MDI Read did not complete\n");
+ return -E1000_ERR_PHY;
+ }
+ if(mdic & E1000_MDIC_ERROR) {
+ DEBUGOUT("MDI Error\n");
+ return -E1000_ERR_PHY;
+ }
+ *phy_data = (uint16_t) mdic;
+ } else {
+ /* We must first send a preamble through the MDIO pin to signal the
+ * beginning of an MII instruction. This is done by sending 32
+ * consecutive "1" bits.
+ */
+ em_shift_out_mdi_bits(hw, PHY_PREAMBLE, PHY_PREAMBLE_SIZE);
+
+ /* Now combine the next few fields that are required for a read
+ * operation. We use this method instead of calling the
+ * em_shift_out_mdi_bits routine five different times. The format of
+ * a MII read instruction consists of a shift out of 14 bits and is
+ * defined as follows:
+ * <Preamble><SOF><Op Code><Phy Addr><Reg Addr>
+ * followed by a shift in of 18 bits. This first two bits shifted in
+ * are TurnAround bits used to avoid contention on the MDIO pin when a
+ * READ operation is performed. These two bits are thrown away
+ * followed by a shift in of 16 bits which contains the desired data.
+ */
+ mdic = ((reg_addr) | (phy_addr << 5) |
+ (PHY_OP_READ << 10) | (PHY_SOF << 12));
+
+ em_shift_out_mdi_bits(hw, mdic, 14);
+
+ /* Now that we've shifted out the read command to the MII, we need to
+ * "shift in" the 16-bit value (18 total bits) of the requested PHY
+ * register address.
+ */
+ *phy_data = em_shift_in_mdi_bits(hw);
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Writes a value to a PHY register
+*
+* hw - Struct containing variables accessed by shared code
+* reg_addr - address of the PHY register to write
+* data - data to write to the PHY
+******************************************************************************/
+int32_t
+em_write_phy_reg(struct em_hw *hw,
+ uint32_t reg_addr,
+ uint16_t phy_data)
+{
+ uint32_t ret_val;
+
+ DEBUGFUNC("em_write_phy_reg");
+
+ if((hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2) &&
+ (reg_addr > MAX_PHY_MULTI_PAGE_REG)) {
+ ret_val = em_write_phy_reg_ex(hw, IGP01E1000_PHY_PAGE_SELECT,
+ (uint16_t)reg_addr);
+ if(ret_val) {
+ return ret_val;
+ }
+ }
+
+ ret_val = em_write_phy_reg_ex(hw, MAX_PHY_REG_ADDRESS & reg_addr,
+ phy_data);
+
+ return ret_val;
+}
+
+int32_t
+em_write_phy_reg_ex(struct em_hw *hw,
+ uint32_t reg_addr,
+ uint16_t phy_data)
+{
+ uint32_t i;
+ uint32_t mdic = 0;
+ const uint32_t phy_addr = 1;
+
+ DEBUGFUNC("em_write_phy_reg_ex");
+
+ if(reg_addr > MAX_PHY_REG_ADDRESS) {
+ DEBUGOUT1("PHY Address %d is out of range\n", reg_addr);
+ return -E1000_ERR_PARAM;
+ }
+
+ if(hw->mac_type > em_82543) {
+ /* Set up Op-code, Phy Address, register address, and data intended
+ * for the PHY register in the MDI Control register. The MAC will take
+ * care of interfacing with the PHY to send the desired data.
+ */
+ mdic = (((uint32_t) phy_data) |
+ (reg_addr << E1000_MDIC_REG_SHIFT) |
+ (phy_addr << E1000_MDIC_PHY_SHIFT) |
+ (E1000_MDIC_OP_WRITE));
+
+ E1000_WRITE_REG(hw, MDIC, mdic);
+
+ /* Poll the ready bit to see if the MDI read completed */
+ for(i = 0; i < 640; i++) {
+ usec_delay(5);
+ mdic = E1000_READ_REG(hw, MDIC);
+ if(mdic & E1000_MDIC_READY) break;
+ }
+ if(!(mdic & E1000_MDIC_READY)) {
+ DEBUGOUT("MDI Write did not complete\n");
+ return -E1000_ERR_PHY;
+ }
+ } else {
+ /* We'll need to use the SW defined pins to shift the write command
+ * out to the PHY. We first send a preamble to the PHY to signal the
+ * beginning of the MII instruction. This is done by sending 32
+ * consecutive "1" bits.
+ */
+ em_shift_out_mdi_bits(hw, PHY_PREAMBLE, PHY_PREAMBLE_SIZE);
+
+ /* Now combine the remaining required fields that will indicate a
+ * write operation. We use this method instead of calling the
+ * em_shift_out_mdi_bits routine for each field in the command. The
+ * format of a MII write instruction is as follows:
+ * <Preamble><SOF><Op Code><Phy Addr><Reg Addr><Turnaround><Data>.
+ */
+ mdic = ((PHY_TURNAROUND) | (reg_addr << 2) | (phy_addr << 7) |
+ (PHY_OP_WRITE << 12) | (PHY_SOF << 14));
+ mdic <<= 16;
+ mdic |= (uint32_t) phy_data;
+
+ em_shift_out_mdi_bits(hw, mdic, 32);
+ }
+
+ return E1000_SUCCESS;
+}
+
+
+/******************************************************************************
+* Returns the PHY to the power-on reset state
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+int32_t
+em_phy_hw_reset(struct em_hw *hw)
+{
+ uint32_t ctrl, ctrl_ext;
+ uint32_t led_ctrl;
+ int32_t ret_val;
+
+ DEBUGFUNC("em_phy_hw_reset");
+
+ /* In the case of the phy reset being blocked, it's not an error, we
+ * simply return success without performing the reset. */
+ ret_val = em_check_phy_reset_block(hw);
+ if (ret_val)
+ return E1000_SUCCESS;
+
+ DEBUGOUT("Resetting Phy...\n");
+
+ if(hw->mac_type > em_82543) {
+ /* Read the device control register and assert the E1000_CTRL_PHY_RST
+ * bit. Then, take it out of reset.
+ */
+ ctrl = E1000_READ_REG(hw, CTRL);
+ E1000_WRITE_REG(hw, CTRL, ctrl | E1000_CTRL_PHY_RST);
+ E1000_WRITE_FLUSH(hw);
+ msec_delay(10);
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+ E1000_WRITE_FLUSH(hw);
+ } else {
+ /* Read the Extended Device Control Register, assert the PHY_RESET_DIR
+ * bit to put the PHY into reset. Then, take it out of reset.
+ */
+ ctrl_ext = E1000_READ_REG(hw, CTRL_EXT);
+ ctrl_ext |= E1000_CTRL_EXT_SDP4_DIR;
+ ctrl_ext &= ~E1000_CTRL_EXT_SDP4_DATA;
+ E1000_WRITE_REG(hw, CTRL_EXT, ctrl_ext);
+ E1000_WRITE_FLUSH(hw);
+ msec_delay(10);
+ ctrl_ext |= E1000_CTRL_EXT_SDP4_DATA;
+ E1000_WRITE_REG(hw, CTRL_EXT, ctrl_ext);
+ E1000_WRITE_FLUSH(hw);
+ }
+ usec_delay(150);
+
+ if((hw->mac_type == em_82541) || (hw->mac_type == em_82547)) {
+ /* Configure activity LED after PHY reset */
+ led_ctrl = E1000_READ_REG(hw, LEDCTL);
+ led_ctrl &= IGP_ACTIVITY_LED_MASK;
+ led_ctrl |= (IGP_ACTIVITY_LED_ENABLE | IGP_LED3_MODE);
+ E1000_WRITE_REG(hw, LEDCTL, led_ctrl);
+ }
+
+ /* Wait for FW to finish PHY configuration. */
+ ret_val = em_get_phy_cfg_done(hw);
+
+ return ret_val;
+}
+
+/******************************************************************************
+* Resets the PHY
+*
+* hw - Struct containing variables accessed by shared code
+*
+* Sets bit 15 of the MII Control regiser
+******************************************************************************/
+int32_t
+em_phy_reset(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_phy_reset");
+
+ /* In the case of the phy reset being blocked, it's not an error, we
+ * simply return success without performing the reset. */
+ ret_val = em_check_phy_reset_block(hw);
+ if (ret_val)
+ return E1000_SUCCESS;
+
+ switch (hw->mac_type) {
+ case em_82541_rev_2:
+ ret_val = em_phy_hw_reset(hw);
+ if(ret_val)
+ return ret_val;
+ break;
+ default:
+ ret_val = em_read_phy_reg(hw, PHY_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= MII_CR_RESET;
+ ret_val = em_write_phy_reg(hw, PHY_CTRL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ usec_delay(1);
+ break;
+ }
+
+ if(hw->phy_type == em_phy_igp || hw->phy_type == em_phy_igp_2)
+ em_phy_init_script(hw);
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Probes the expected PHY address for known PHY IDs
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+int32_t
+em_detect_gig_phy(struct em_hw *hw)
+{
+ int32_t phy_init_status, ret_val;
+ uint16_t phy_id_high, phy_id_low;
+ boolean_t match = FALSE;
+
+ DEBUGFUNC("em_detect_gig_phy");
+
+ /* Read the PHY ID Registers to identify which PHY is onboard. */
+ ret_val = em_read_phy_reg(hw, PHY_ID1, &phy_id_high);
+ if(ret_val)
+ return ret_val;
+
+ hw->phy_id = (uint32_t) (phy_id_high << 16);
+ usec_delay(20);
+ ret_val = em_read_phy_reg(hw, PHY_ID2, &phy_id_low);
+ if(ret_val)
+ return ret_val;
+
+ hw->phy_id |= (uint32_t) (phy_id_low & PHY_REVISION_MASK);
+ hw->phy_revision = (uint32_t) phy_id_low & ~PHY_REVISION_MASK;
+
+ switch(hw->mac_type) {
+ case em_82543:
+ if(hw->phy_id == M88E1000_E_PHY_ID) match = TRUE;
+ break;
+ case em_82544:
+ if(hw->phy_id == M88E1000_I_PHY_ID) match = TRUE;
+ break;
+ case em_82540:
+ case em_82545:
+ case em_82545_rev_3:
+ case em_82546:
+ case em_82546_rev_3:
+ if(hw->phy_id == M88E1011_I_PHY_ID) match = TRUE;
+ break;
+ case em_82541:
+ case em_82541_rev_2:
+ case em_82547:
+ case em_82547_rev_2:
+ if(hw->phy_id == IGP01E1000_I_PHY_ID) match = TRUE;
+ break;
+ case em_82573:
+ if(hw->phy_id == M88E1111_I_PHY_ID) match = TRUE;
+ break;
+ default:
+ DEBUGOUT1("Invalid MAC type %d\n", hw->mac_type);
+ return -E1000_ERR_CONFIG;
+ }
+ phy_init_status = em_set_phy_type(hw);
+
+ if ((match) && (phy_init_status == E1000_SUCCESS)) {
+ DEBUGOUT1("PHY ID 0x%X detected\n", hw->phy_id);
+ return E1000_SUCCESS;
+ }
+ DEBUGOUT1("Invalid PHY ID 0x%X\n", hw->phy_id);
+ return -E1000_ERR_PHY;
+}
+
+/******************************************************************************
+* Resets the PHY's DSP
+*
+* hw - Struct containing variables accessed by shared code
+******************************************************************************/
+static int32_t
+em_phy_reset_dsp(struct em_hw *hw)
+{
+ int32_t ret_val;
+ DEBUGFUNC("em_phy_reset_dsp");
+
+ do {
+ ret_val = em_write_phy_reg(hw, 29, 0x001d);
+ if(ret_val) break;
+ ret_val = em_write_phy_reg(hw, 30, 0x00c1);
+ if(ret_val) break;
+ ret_val = em_write_phy_reg(hw, 30, 0x0000);
+ if(ret_val) break;
+ ret_val = E1000_SUCCESS;
+ } while(0);
+
+ return ret_val;
+}
+
+/******************************************************************************
+* Get PHY information from various PHY registers for igp PHY only.
+*
+* hw - Struct containing variables accessed by shared code
+* phy_info - PHY information structure
+******************************************************************************/
+int32_t
+em_phy_igp_get_info(struct em_hw *hw,
+ struct em_phy_info *phy_info)
+{
+ int32_t ret_val;
+ uint16_t phy_data, polarity, min_length, max_length, average;
+
+ DEBUGFUNC("em_phy_igp_get_info");
+
+ /* The downshift status is checked only once, after link is established,
+ * and it stored in the hw->speed_downgraded parameter. */
+ phy_info->downshift = (em_downshift)hw->speed_downgraded;
+
+ /* IGP01E1000 does not need to support it. */
+ phy_info->extended_10bt_distance = em_10bt_ext_dist_enable_normal;
+
+ /* IGP01E1000 always correct polarity reversal */
+ phy_info->polarity_correction = em_polarity_reversal_enabled;
+
+ /* Check polarity status */
+ ret_val = em_check_polarity(hw, &polarity);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->cable_polarity = polarity;
+
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->mdix_mode = (phy_data & IGP01E1000_PSSR_MDIX) >>
+ IGP01E1000_PSSR_MDIX_SHIFT;
+
+ if((phy_data & IGP01E1000_PSSR_SPEED_MASK) ==
+ IGP01E1000_PSSR_SPEED_1000MBPS) {
+ /* Local/Remote Receiver Information are only valid at 1000 Mbps */
+ ret_val = em_read_phy_reg(hw, PHY_1000T_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->local_rx = (phy_data & SR_1000T_LOCAL_RX_STATUS) >>
+ SR_1000T_LOCAL_RX_STATUS_SHIFT;
+ phy_info->remote_rx = (phy_data & SR_1000T_REMOTE_RX_STATUS) >>
+ SR_1000T_REMOTE_RX_STATUS_SHIFT;
+
+ /* Get cable length */
+ ret_val = em_get_cable_length(hw, &min_length, &max_length);
+ if(ret_val)
+ return ret_val;
+
+ /* Translate to old method */
+ average = (max_length + min_length) / 2;
+
+ if(average <= em_igp_cable_length_50)
+ phy_info->cable_length = em_cable_length_50;
+ else if(average <= em_igp_cable_length_80)
+ phy_info->cable_length = em_cable_length_50_80;
+ else if(average <= em_igp_cable_length_110)
+ phy_info->cable_length = em_cable_length_80_110;
+ else if(average <= em_igp_cable_length_140)
+ phy_info->cable_length = em_cable_length_110_140;
+ else
+ phy_info->cable_length = em_cable_length_140;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Get PHY information from various PHY registers fot m88 PHY only.
+*
+* hw - Struct containing variables accessed by shared code
+* phy_info - PHY information structure
+******************************************************************************/
+int32_t
+em_phy_m88_get_info(struct em_hw *hw,
+ struct em_phy_info *phy_info)
+{
+ int32_t ret_val;
+ uint16_t phy_data, polarity;
+
+ DEBUGFUNC("em_phy_m88_get_info");
+
+ /* The downshift status is checked only once, after link is established,
+ * and it stored in the hw->speed_downgraded parameter. */
+ phy_info->downshift = (em_downshift)hw->speed_downgraded;
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_CTRL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->extended_10bt_distance =
+ (phy_data & M88E1000_PSCR_10BT_EXT_DIST_ENABLE) >>
+ M88E1000_PSCR_10BT_EXT_DIST_ENABLE_SHIFT;
+ phy_info->polarity_correction =
+ (phy_data & M88E1000_PSCR_POLARITY_REVERSAL) >>
+ M88E1000_PSCR_POLARITY_REVERSAL_SHIFT;
+
+ /* Check polarity status */
+ ret_val = em_check_polarity(hw, &polarity);
+ if(ret_val)
+ return ret_val;
+ phy_info->cable_polarity = polarity;
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->mdix_mode = (phy_data & M88E1000_PSSR_MDIX) >>
+ M88E1000_PSSR_MDIX_SHIFT;
+
+ if ((phy_data & M88E1000_PSSR_SPEED) == M88E1000_PSSR_1000MBS) {
+ /* Cable Length Estimation and Local/Remote Receiver Information
+ * are only valid at 1000 Mbps.
+ */
+ phy_info->cable_length = ((phy_data & M88E1000_PSSR_CABLE_LENGTH) >>
+ M88E1000_PSSR_CABLE_LENGTH_SHIFT);
+
+ ret_val = em_read_phy_reg(hw, PHY_1000T_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_info->local_rx = (phy_data & SR_1000T_LOCAL_RX_STATUS) >>
+ SR_1000T_LOCAL_RX_STATUS_SHIFT;
+
+ phy_info->remote_rx = (phy_data & SR_1000T_REMOTE_RX_STATUS) >>
+ SR_1000T_REMOTE_RX_STATUS_SHIFT;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+* Get PHY information from various PHY registers
+*
+* hw - Struct containing variables accessed by shared code
+* phy_info - PHY information structure
+******************************************************************************/
+int32_t
+em_phy_get_info(struct em_hw *hw,
+ struct em_phy_info *phy_info)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_phy_get_info");
+
+ phy_info->cable_length = em_cable_length_undefined;
+ phy_info->extended_10bt_distance = em_10bt_ext_dist_enable_undefined;
+ phy_info->cable_polarity = em_rev_polarity_undefined;
+ phy_info->downshift = em_downshift_undefined;
+ phy_info->polarity_correction = em_polarity_reversal_undefined;
+ phy_info->mdix_mode = em_auto_x_mode_undefined;
+ phy_info->local_rx = em_1000t_rx_status_undefined;
+ phy_info->remote_rx = em_1000t_rx_status_undefined;
+
+ if(hw->media_type != em_media_type_copper) {
+ DEBUGOUT("PHY info is only valid for copper media\n");
+ return -E1000_ERR_CONFIG;
+ }
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if((phy_data & MII_SR_LINK_STATUS) != MII_SR_LINK_STATUS) {
+ DEBUGOUT("PHY info is only valid if link is up\n");
+ return -E1000_ERR_CONFIG;
+ }
+
+ if(hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2)
+ return em_phy_igp_get_info(hw, phy_info);
+ else
+ return em_phy_m88_get_info(hw, phy_info);
+}
+
+int32_t
+em_validate_mdi_setting(struct em_hw *hw)
+{
+ DEBUGFUNC("em_validate_mdi_settings");
+
+ if(!hw->autoneg && (hw->mdix == 0 || hw->mdix == 3)) {
+ DEBUGOUT("Invalid MDI setting detected\n");
+ hw->mdix = 1;
+ return -E1000_ERR_CONFIG;
+ }
+ return E1000_SUCCESS;
+}
+
+
+/******************************************************************************
+ * Sets up eeprom variables in the hw struct. Must be called after mac_type
+ * is configured.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_init_eeprom_params(struct em_hw *hw)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t eecd = E1000_READ_REG(hw, EECD);
+ int32_t ret_val = E1000_SUCCESS;
+ uint16_t eeprom_size;
+
+ DEBUGFUNC("em_init_eeprom_params");
+
+ switch (hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ case em_82544:
+ eeprom->type = em_eeprom_microwire;
+ eeprom->word_size = 64;
+ eeprom->opcode_bits = 3;
+ eeprom->address_bits = 6;
+ eeprom->delay_usec = 50;
+ eeprom->use_eerd = FALSE;
+ eeprom->use_eewr = FALSE;
+ break;
+ case em_82540:
+ case em_82545:
+ case em_82545_rev_3:
+ case em_82546:
+ case em_82546_rev_3:
+ eeprom->type = em_eeprom_microwire;
+ eeprom->opcode_bits = 3;
+ eeprom->delay_usec = 50;
+ if(eecd & E1000_EECD_SIZE) {
+ eeprom->word_size = 256;
+ eeprom->address_bits = 8;
+ } else {
+ eeprom->word_size = 64;
+ eeprom->address_bits = 6;
+ }
+ eeprom->use_eerd = FALSE;
+ eeprom->use_eewr = FALSE;
+ break;
+ case em_82541:
+ case em_82541_rev_2:
+ case em_82547:
+ case em_82547_rev_2:
+ if (eecd & E1000_EECD_TYPE) {
+ eeprom->type = em_eeprom_spi;
+ eeprom->opcode_bits = 8;
+ eeprom->delay_usec = 1;
+ if (eecd & E1000_EECD_ADDR_BITS) {
+ eeprom->page_size = 32;
+ eeprom->address_bits = 16;
+ } else {
+ eeprom->page_size = 8;
+ eeprom->address_bits = 8;
+ }
+ } else {
+ eeprom->type = em_eeprom_microwire;
+ eeprom->opcode_bits = 3;
+ eeprom->delay_usec = 50;
+ if (eecd & E1000_EECD_ADDR_BITS) {
+ eeprom->word_size = 256;
+ eeprom->address_bits = 8;
+ } else {
+ eeprom->word_size = 64;
+ eeprom->address_bits = 6;
+ }
+ }
+ eeprom->use_eerd = FALSE;
+ eeprom->use_eewr = FALSE;
+ break;
+ case em_82573:
+ eeprom->type = em_eeprom_spi;
+ eeprom->opcode_bits = 8;
+ eeprom->delay_usec = 1;
+ if (eecd & E1000_EECD_ADDR_BITS) {
+ eeprom->page_size = 32;
+ eeprom->address_bits = 16;
+ } else {
+ eeprom->page_size = 8;
+ eeprom->address_bits = 8;
+ }
+ eeprom->use_eerd = TRUE;
+ eeprom->use_eewr = TRUE;
+ if(em_is_onboard_nvm_eeprom(hw) == FALSE) {
+ eeprom->type = em_eeprom_flash;
+ eeprom->word_size = 2048;
+
+ /* Ensure that the Autonomous FLASH update bit is cleared due to
+ * Flash update issue on parts which use a FLASH for NVM. */
+ eecd &= ~E1000_EECD_AUPDEN;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ }
+ break;
+ default:
+ break;
+ }
+
+ if (eeprom->type == em_eeprom_spi) {
+ /* eeprom_size will be an enum [0..8] that maps to eeprom sizes 128B to
+ * 32KB (incremented by powers of 2).
+ */
+ if(hw->mac_type <= em_82547_rev_2) {
+ /* Set to default value for initial eeprom read. */
+ eeprom->word_size = 64;
+ ret_val = em_read_eeprom(hw, EEPROM_CFG, 1, &eeprom_size);
+ if(ret_val)
+ return ret_val;
+ eeprom_size = (eeprom_size & EEPROM_SIZE_MASK) >> EEPROM_SIZE_SHIFT;
+ /* 256B eeprom size was not supported in earlier hardware, so we
+ * bump eeprom_size up one to ensure that "1" (which maps to 256B)
+ * is never the result used in the shifting logic below. */
+ if(eeprom_size)
+ eeprom_size++;
+ } else {
+ eeprom_size = (uint16_t)((eecd & E1000_EECD_SIZE_EX_MASK) >>
+ E1000_EECD_SIZE_EX_SHIFT);
+ }
+
+ eeprom->word_size = 1 << (eeprom_size + EEPROM_WORD_SIZE_SHIFT);
+ }
+ return ret_val;
+}
+
+/******************************************************************************
+ * Raises the EEPROM's clock input.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * eecd - EECD's current value
+ *****************************************************************************/
+static void
+em_raise_ee_clk(struct em_hw *hw,
+ uint32_t *eecd)
+{
+ /* Raise the clock input to the EEPROM (by setting the SK bit), and then
+ * wait <delay> microseconds.
+ */
+ *eecd = *eecd | E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, *eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(hw->eeprom.delay_usec);
+}
+
+/******************************************************************************
+ * Lowers the EEPROM's clock input.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * eecd - EECD's current value
+ *****************************************************************************/
+static void
+em_lower_ee_clk(struct em_hw *hw,
+ uint32_t *eecd)
+{
+ /* Lower the clock input to the EEPROM (by clearing the SK bit), and then
+ * wait 50 microseconds.
+ */
+ *eecd = *eecd & ~E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, *eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(hw->eeprom.delay_usec);
+}
+
+/******************************************************************************
+ * Shift data bits out to the EEPROM.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * data - data to send to the EEPROM
+ * count - number of bits to shift out
+ *****************************************************************************/
+static void
+em_shift_out_ee_bits(struct em_hw *hw,
+ uint16_t data,
+ uint16_t count)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t eecd;
+ uint32_t mask;
+
+ /* We need to shift "count" bits out to the EEPROM. So, value in the
+ * "data" parameter will be shifted out to the EEPROM one bit at a time.
+ * In order to do this, "data" must be broken down into bits.
+ */
+ mask = 0x01 << (count - 1);
+ eecd = E1000_READ_REG(hw, EECD);
+ if (eeprom->type == em_eeprom_microwire) {
+ eecd &= ~E1000_EECD_DO;
+ } else if (eeprom->type == em_eeprom_spi) {
+ eecd |= E1000_EECD_DO;
+ }
+ do {
+ /* A "1" is shifted out to the EEPROM by setting bit "DI" to a "1",
+ * and then raising and then lowering the clock (the SK bit controls
+ * the clock input to the EEPROM). A "0" is shifted out to the EEPROM
+ * by setting "DI" to "0" and then raising and then lowering the clock.
+ */
+ eecd &= ~E1000_EECD_DI;
+
+ if(data & mask)
+ eecd |= E1000_EECD_DI;
+
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+
+ usec_delay(eeprom->delay_usec);
+
+ em_raise_ee_clk(hw, &eecd);
+ em_lower_ee_clk(hw, &eecd);
+
+ mask = mask >> 1;
+
+ } while(mask);
+
+ /* We leave the "DI" bit set to "0" when we leave this routine. */
+ eecd &= ~E1000_EECD_DI;
+ E1000_WRITE_REG(hw, EECD, eecd);
+}
+
+/******************************************************************************
+ * Shift data bits in from the EEPROM
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+static uint16_t
+em_shift_in_ee_bits(struct em_hw *hw,
+ uint16_t count)
+{
+ uint32_t eecd;
+ uint32_t i;
+ uint16_t data;
+
+ /* In order to read a register from the EEPROM, we need to shift 'count'
+ * bits in from the EEPROM. Bits are "shifted in" by raising the clock
+ * input to the EEPROM (setting the SK bit), and then reading the value of
+ * the "DO" bit. During this "shifting in" process the "DI" bit should
+ * always be clear.
+ */
+
+ eecd = E1000_READ_REG(hw, EECD);
+
+ eecd &= ~(E1000_EECD_DO | E1000_EECD_DI);
+ data = 0;
+
+ for(i = 0; i < count; i++) {
+ data = data << 1;
+ em_raise_ee_clk(hw, &eecd);
+
+ eecd = E1000_READ_REG(hw, EECD);
+
+ eecd &= ~(E1000_EECD_DI);
+ if(eecd & E1000_EECD_DO)
+ data |= 1;
+
+ em_lower_ee_clk(hw, &eecd);
+ }
+
+ return data;
+}
+
+/******************************************************************************
+ * Prepares EEPROM for access
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Lowers EEPROM clock. Clears input pin. Sets the chip select pin. This
+ * function should be called before issuing a command to the EEPROM.
+ *****************************************************************************/
+static int32_t
+em_acquire_eeprom(struct em_hw *hw)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t eecd, i=0;
+
+ DEBUGFUNC("em_acquire_eeprom");
+
+ if(em_get_hw_eeprom_semaphore(hw))
+ return -E1000_ERR_EEPROM;
+
+ eecd = E1000_READ_REG(hw, EECD);
+
+ if (hw->mac_type != em_82573) {
+ /* Request EEPROM Access */
+ if(hw->mac_type > em_82544) {
+ eecd |= E1000_EECD_REQ;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ eecd = E1000_READ_REG(hw, EECD);
+ while((!(eecd & E1000_EECD_GNT)) &&
+ (i < E1000_EEPROM_GRANT_ATTEMPTS)) {
+ i++;
+ usec_delay(5);
+ eecd = E1000_READ_REG(hw, EECD);
+ }
+ if(!(eecd & E1000_EECD_GNT)) {
+ eecd &= ~E1000_EECD_REQ;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ DEBUGOUT("Could not acquire EEPROM grant\n");
+ return -E1000_ERR_EEPROM;
+ }
+ }
+ }
+
+ /* Setup EEPROM for Read/Write */
+
+ if (eeprom->type == em_eeprom_microwire) {
+ /* Clear SK and DI */
+ eecd &= ~(E1000_EECD_DI | E1000_EECD_SK);
+ E1000_WRITE_REG(hw, EECD, eecd);
+
+ /* Set CS */
+ eecd |= E1000_EECD_CS;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ } else if (eeprom->type == em_eeprom_spi) {
+ /* Clear SK and CS */
+ eecd &= ~(E1000_EECD_CS | E1000_EECD_SK);
+ E1000_WRITE_REG(hw, EECD, eecd);
+ usec_delay(1);
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Returns EEPROM to a "standby" state
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+static void
+em_standby_eeprom(struct em_hw *hw)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t eecd;
+
+ eecd = E1000_READ_REG(hw, EECD);
+
+ if(eeprom->type == em_eeprom_microwire) {
+ eecd &= ~(E1000_EECD_CS | E1000_EECD_SK);
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+
+ /* Clock high */
+ eecd |= E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+
+ /* Select EEPROM */
+ eecd |= E1000_EECD_CS;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+
+ /* Clock low */
+ eecd &= ~E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+ } else if(eeprom->type == em_eeprom_spi) {
+ /* Toggle CS to flush commands */
+ eecd |= E1000_EECD_CS;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+ eecd &= ~E1000_EECD_CS;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(eeprom->delay_usec);
+ }
+}
+
+/******************************************************************************
+ * Terminates a command by inverting the EEPROM's chip select pin
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+static void
+em_release_eeprom(struct em_hw *hw)
+{
+ uint32_t eecd;
+
+ DEBUGFUNC("em_release_eeprom");
+
+ eecd = E1000_READ_REG(hw, EECD);
+
+ if (hw->eeprom.type == em_eeprom_spi) {
+ eecd |= E1000_EECD_CS; /* Pull CS high */
+ eecd &= ~E1000_EECD_SK; /* Lower SCK */
+
+ E1000_WRITE_REG(hw, EECD, eecd);
+
+ usec_delay(hw->eeprom.delay_usec);
+ } else if(hw->eeprom.type == em_eeprom_microwire) {
+ /* cleanup eeprom */
+
+ /* CS on Microwire is active-high */
+ eecd &= ~(E1000_EECD_CS | E1000_EECD_DI);
+
+ E1000_WRITE_REG(hw, EECD, eecd);
+
+ /* Rising edge of clock */
+ eecd |= E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(hw->eeprom.delay_usec);
+
+ /* Falling edge of clock */
+ eecd &= ~E1000_EECD_SK;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ E1000_WRITE_FLUSH(hw);
+ usec_delay(hw->eeprom.delay_usec);
+ }
+
+ /* Stop requesting EEPROM access */
+ if(hw->mac_type > em_82544) {
+ eecd &= ~E1000_EECD_REQ;
+ E1000_WRITE_REG(hw, EECD, eecd);
+ }
+
+ em_put_hw_eeprom_semaphore(hw);
+}
+
+/******************************************************************************
+ * Reads a 16 bit word from the EEPROM.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_spi_eeprom_ready(struct em_hw *hw)
+{
+ uint16_t retry_count = 0;
+ uint8_t spi_stat_reg;
+
+ DEBUGFUNC("em_spi_eeprom_ready");
+
+ /* Read "Status Register" repeatedly until the LSB is cleared. The
+ * EEPROM will signal that the command has been completed by clearing
+ * bit 0 of the internal status register. If it's not cleared within
+ * 5 milliseconds, then error out.
+ */
+ retry_count = 0;
+ do {
+ em_shift_out_ee_bits(hw, EEPROM_RDSR_OPCODE_SPI,
+ hw->eeprom.opcode_bits);
+ spi_stat_reg = (uint8_t)em_shift_in_ee_bits(hw, 8);
+ if (!(spi_stat_reg & EEPROM_STATUS_RDY_SPI))
+ break;
+
+ usec_delay(5);
+ retry_count += 5;
+
+ em_standby_eeprom(hw);
+ } while(retry_count < EEPROM_MAX_RETRY_SPI);
+
+ /* ATMEL SPI write time could vary from 0-20mSec on 3.3V devices (and
+ * only 0-5mSec on 5V devices)
+ */
+ if(retry_count >= EEPROM_MAX_RETRY_SPI) {
+ DEBUGOUT("SPI EEPROM Status error\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Reads a 16 bit word from the EEPROM.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset of word in the EEPROM to read
+ * data - word read from the EEPROM
+ * words - number of words to read
+ *****************************************************************************/
+int32_t
+em_read_eeprom(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t i = 0;
+ int32_t ret_val;
+
+ DEBUGFUNC("em_read_eeprom");
+
+ /* A check for invalid values: offset too large, too many words, and not
+ * enough words.
+ */
+ if((offset >= eeprom->word_size) || (words > eeprom->word_size - offset) ||
+ (words == 0)) {
+ DEBUGOUT("\"words\" parameter out of bounds\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ /* FLASH reads without acquiring the semaphore are safe in 82573-based
+ * controllers.
+ */
+ if ((em_is_onboard_nvm_eeprom(hw) == TRUE) ||
+ (hw->mac_type != em_82573)) {
+ /* Prepare the EEPROM for reading */
+ if(em_acquire_eeprom(hw) != E1000_SUCCESS)
+ return -E1000_ERR_EEPROM;
+ }
+
+ if(eeprom->use_eerd == TRUE) {
+ ret_val = em_read_eeprom_eerd(hw, offset, words, data);
+ if ((em_is_onboard_nvm_eeprom(hw) == TRUE) ||
+ (hw->mac_type != em_82573))
+ em_release_eeprom(hw);
+ return ret_val;
+ }
+
+ if(eeprom->type == em_eeprom_spi) {
+ uint16_t word_in;
+ uint8_t read_opcode = EEPROM_READ_OPCODE_SPI;
+
+ if(em_spi_eeprom_ready(hw)) {
+ em_release_eeprom(hw);
+ return -E1000_ERR_EEPROM;
+ }
+
+ em_standby_eeprom(hw);
+
+ /* Some SPI eeproms use the 8th address bit embedded in the opcode */
+ if((eeprom->address_bits == 8) && (offset >= 128))
+ read_opcode |= EEPROM_A8_OPCODE_SPI;
+
+ /* Send the READ command (opcode + addr) */
+ em_shift_out_ee_bits(hw, read_opcode, eeprom->opcode_bits);
+ em_shift_out_ee_bits(hw, (uint16_t)(offset*2), eeprom->address_bits);
+
+ /* Read the data. The address of the eeprom internally increments with
+ * each byte (spi) being read, saving on the overhead of eeprom setup
+ * and tear-down. The address counter will roll over if reading beyond
+ * the size of the eeprom, thus allowing the entire memory to be read
+ * starting from any offset. */
+ for (i = 0; i < words; i++) {
+ word_in = em_shift_in_ee_bits(hw, 16);
+ data[i] = (word_in >> 8) | (word_in << 8);
+ }
+ } else if(eeprom->type == em_eeprom_microwire) {
+ for (i = 0; i < words; i++) {
+ /* Send the READ command (opcode + addr) */
+ em_shift_out_ee_bits(hw, EEPROM_READ_OPCODE_MICROWIRE,
+ eeprom->opcode_bits);
+ em_shift_out_ee_bits(hw, (uint16_t)(offset + i),
+ eeprom->address_bits);
+
+ /* Read the data. For microwire, each word requires the overhead
+ * of eeprom setup and tear-down. */
+ data[i] = em_shift_in_ee_bits(hw, 16);
+ em_standby_eeprom(hw);
+ }
+ }
+
+ /* End this read operation */
+ em_release_eeprom(hw);
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Reads a 16 bit word from the EEPROM using the EERD register.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset of word in the EEPROM to read
+ * data - word read from the EEPROM
+ * words - number of words to read
+ *****************************************************************************/
+int32_t
+em_read_eeprom_eerd(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ uint32_t i, eerd = 0;
+ int32_t error = 0;
+
+ for (i = 0; i < words; i++) {
+ eerd = ((offset+i) << E1000_EEPROM_RW_ADDR_SHIFT) +
+ E1000_EEPROM_RW_REG_START;
+
+ E1000_WRITE_REG(hw, EERD, eerd);
+ error = em_poll_eerd_eewr_done(hw, E1000_EEPROM_POLL_READ);
+
+ if(error) {
+ break;
+ }
+ data[i] = (E1000_READ_REG(hw, EERD) >> E1000_EEPROM_RW_REG_DATA);
+
+ }
+
+ return error;
+}
+
+/******************************************************************************
+ * Writes a 16 bit word from the EEPROM using the EEWR register.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset of word in the EEPROM to read
+ * data - word read from the EEPROM
+ * words - number of words to read
+ *****************************************************************************/
+int32_t
+em_write_eeprom_eewr(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ uint32_t register_value = 0;
+ uint32_t i = 0;
+ int32_t error = 0;
+
+ for (i = 0; i < words; i++) {
+ register_value = (data[i] << E1000_EEPROM_RW_REG_DATA) |
+ ((offset+i) << E1000_EEPROM_RW_ADDR_SHIFT) |
+ E1000_EEPROM_RW_REG_START;
+
+ error = em_poll_eerd_eewr_done(hw, E1000_EEPROM_POLL_WRITE);
+ if(error) {
+ break;
+ }
+
+ E1000_WRITE_REG(hw, EEWR, register_value);
+
+ error = em_poll_eerd_eewr_done(hw, E1000_EEPROM_POLL_WRITE);
+
+ if(error) {
+ break;
+ }
+ }
+
+ return error;
+}
+
+/******************************************************************************
+ * Polls the status bit (bit 1) of the EERD to determine when the read is done.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_poll_eerd_eewr_done(struct em_hw *hw, int eerd)
+{
+ uint32_t attempts = 100000;
+ uint32_t i, reg = 0;
+ int32_t done = E1000_ERR_EEPROM;
+
+ for(i = 0; i < attempts; i++) {
+ if(eerd == E1000_EEPROM_POLL_READ)
+ reg = E1000_READ_REG(hw, EERD);
+ else
+ reg = E1000_READ_REG(hw, EEWR);
+
+ if(reg & E1000_EEPROM_RW_REG_DONE) {
+ done = E1000_SUCCESS;
+ break;
+ }
+ usec_delay(5);
+ }
+
+ return done;
+}
+
+/***************************************************************************
+* Description: Determines if the onboard NVM is FLASH or EEPROM.
+*
+* hw - Struct containing variables accessed by shared code
+****************************************************************************/
+boolean_t
+em_is_onboard_nvm_eeprom(struct em_hw *hw)
+{
+ uint32_t eecd = 0;
+
+ if(hw->mac_type == em_82573) {
+ eecd = E1000_READ_REG(hw, EECD);
+
+ /* Isolate bits 15 & 16 */
+ eecd = ((eecd >> 15) & 0x03);
+
+ /* If both bits are set, device is Flash type */
+ if(eecd == 0x03) {
+ return FALSE;
+ }
+ }
+ return TRUE;
+}
+
+/******************************************************************************
+ * Verifies that the EEPROM has a valid checksum
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Reads the first 64 16 bit words of the EEPROM and sums the values read.
+ * If the the sum of the 64 16 bit words is 0xBABA, the EEPROM's checksum is
+ * valid.
+ *****************************************************************************/
+int32_t
+em_validate_eeprom_checksum(struct em_hw *hw)
+{
+ uint16_t checksum = 0;
+ uint16_t i, eeprom_data;
+
+ DEBUGFUNC("em_validate_eeprom_checksum");
+
+ if ((hw->mac_type == em_82573) &&
+ (em_is_onboard_nvm_eeprom(hw) == FALSE)) {
+ /* Check bit 4 of word 10h. If it is 0, firmware is done updating
+ * 10h-12h. Checksum may need to be fixed. */
+ em_read_eeprom(hw, 0x10, 1, &eeprom_data);
+ if ((eeprom_data & 0x10) == 0) {
+ /* Read 0x23 and check bit 15. This bit is a 1 when the checksum
+ * has already been fixed. If the checksum is still wrong and this
+ * bit is a 1, we need to return bad checksum. Otherwise, we need
+ * to set this bit to a 1 and update the checksum. */
+ em_read_eeprom(hw, 0x23, 1, &eeprom_data);
+ if ((eeprom_data & 0x8000) == 0) {
+ eeprom_data |= 0x8000;
+ em_write_eeprom(hw, 0x23, 1, &eeprom_data);
+ em_update_eeprom_checksum(hw);
+ }
+ }
+ }
+
+ for(i = 0; i < (EEPROM_CHECKSUM_REG + 1); i++) {
+ if(em_read_eeprom(hw, i, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ checksum += eeprom_data;
+ }
+
+ if(checksum == (uint16_t) EEPROM_SUM)
+ return E1000_SUCCESS;
+ else {
+ DEBUGOUT("EEPROM Checksum Invalid\n");
+ return -E1000_ERR_EEPROM;
+ }
+}
+
+/******************************************************************************
+ * Calculates the EEPROM checksum and writes it to the EEPROM
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Sums the first 63 16 bit words of the EEPROM. Subtracts the sum from 0xBABA.
+ * Writes the difference to word offset 63 of the EEPROM.
+ *****************************************************************************/
+int32_t
+em_update_eeprom_checksum(struct em_hw *hw)
+{
+ uint16_t checksum = 0;
+ uint16_t i, eeprom_data;
+
+ DEBUGFUNC("em_update_eeprom_checksum");
+
+ for(i = 0; i < EEPROM_CHECKSUM_REG; i++) {
+ if(em_read_eeprom(hw, i, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ checksum += eeprom_data;
+ }
+ checksum = (uint16_t) EEPROM_SUM - checksum;
+ if(em_write_eeprom(hw, EEPROM_CHECKSUM_REG, 1, &checksum) < 0) {
+ DEBUGOUT("EEPROM Write Error\n");
+ return -E1000_ERR_EEPROM;
+ } else if (hw->eeprom.type == em_eeprom_flash) {
+ em_commit_shadow_ram(hw);
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Parent function for writing words to the different EEPROM types.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset within the EEPROM to be written to
+ * words - number of words to write
+ * data - 16 bit word to be written to the EEPROM
+ *
+ * If em_update_eeprom_checksum is not called after this function, the
+ * EEPROM will most likely contain an invalid checksum.
+ *****************************************************************************/
+int32_t
+em_write_eeprom(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ int32_t status = 0;
+
+ DEBUGFUNC("em_write_eeprom");
+
+ /* A check for invalid values: offset too large, too many words, and not
+ * enough words.
+ */
+ if((offset >= eeprom->word_size) || (words > eeprom->word_size - offset) ||
+ (words == 0)) {
+ DEBUGOUT("\"words\" parameter out of bounds\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ /* 82573 reads only through eerd */
+ if(eeprom->use_eewr == TRUE)
+ return em_write_eeprom_eewr(hw, offset, words, data);
+
+ /* Prepare the EEPROM for writing */
+ if (em_acquire_eeprom(hw) != E1000_SUCCESS)
+ return -E1000_ERR_EEPROM;
+
+ if(eeprom->type == em_eeprom_microwire) {
+ status = em_write_eeprom_microwire(hw, offset, words, data);
+ } else {
+ status = em_write_eeprom_spi(hw, offset, words, data);
+ msec_delay(10);
+ }
+
+ /* Done with writing */
+ em_release_eeprom(hw);
+
+ return status;
+}
+
+/******************************************************************************
+ * Writes a 16 bit word to a given offset in an SPI EEPROM.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset within the EEPROM to be written to
+ * words - number of words to write
+ * data - pointer to array of 8 bit words to be written to the EEPROM
+ *
+ *****************************************************************************/
+int32_t
+em_write_eeprom_spi(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint16_t widx = 0;
+
+ DEBUGFUNC("em_write_eeprom_spi");
+
+ while (widx < words) {
+ uint8_t write_opcode = EEPROM_WRITE_OPCODE_SPI;
+
+ if(em_spi_eeprom_ready(hw)) return -E1000_ERR_EEPROM;
+
+ em_standby_eeprom(hw);
+
+ /* Send the WRITE ENABLE command (8 bit opcode ) */
+ em_shift_out_ee_bits(hw, EEPROM_WREN_OPCODE_SPI,
+ eeprom->opcode_bits);
+
+ em_standby_eeprom(hw);
+
+ /* Some SPI eeproms use the 8th address bit embedded in the opcode */
+ if((eeprom->address_bits == 8) && (offset >= 128))
+ write_opcode |= EEPROM_A8_OPCODE_SPI;
+
+ /* Send the Write command (8-bit opcode + addr) */
+ em_shift_out_ee_bits(hw, write_opcode, eeprom->opcode_bits);
+
+ em_shift_out_ee_bits(hw, (uint16_t)((offset + widx)*2),
+ eeprom->address_bits);
+
+ /* Send the data */
+
+ /* Loop to allow for up to whole page write (32 bytes) of eeprom */
+ while (widx < words) {
+ uint16_t word_out = data[widx];
+ word_out = (word_out >> 8) | (word_out << 8);
+ em_shift_out_ee_bits(hw, word_out, 16);
+ widx++;
+
+ /* Some larger eeprom sizes are capable of a 32-byte PAGE WRITE
+ * operation, while the smaller eeproms are capable of an 8-byte
+ * PAGE WRITE operation. Break the inner loop to pass new address
+ */
+ if((((offset + widx)*2) % eeprom->page_size) == 0) {
+ em_standby_eeprom(hw);
+ break;
+ }
+ }
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Writes a 16 bit word to a given offset in a Microwire EEPROM.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset within the EEPROM to be written to
+ * words - number of words to write
+ * data - pointer to array of 16 bit words to be written to the EEPROM
+ *
+ *****************************************************************************/
+int32_t
+em_write_eeprom_microwire(struct em_hw *hw,
+ uint16_t offset,
+ uint16_t words,
+ uint16_t *data)
+{
+ struct em_eeprom_info *eeprom = &hw->eeprom;
+ uint32_t eecd;
+ uint16_t words_written = 0;
+ uint16_t i = 0;
+
+ DEBUGFUNC("em_write_eeprom_microwire");
+
+ /* Send the write enable command to the EEPROM (3-bit opcode plus
+ * 6/8-bit dummy address beginning with 11). It's less work to include
+ * the 11 of the dummy address as part of the opcode than it is to shift
+ * it over the correct number of bits for the address. This puts the
+ * EEPROM into write/erase mode.
+ */
+ em_shift_out_ee_bits(hw, EEPROM_EWEN_OPCODE_MICROWIRE,
+ (uint16_t)(eeprom->opcode_bits + 2));
+
+ em_shift_out_ee_bits(hw, 0, (uint16_t)(eeprom->address_bits - 2));
+
+ /* Prepare the EEPROM */
+ em_standby_eeprom(hw);
+
+ while (words_written < words) {
+ /* Send the Write command (3-bit opcode + addr) */
+ em_shift_out_ee_bits(hw, EEPROM_WRITE_OPCODE_MICROWIRE,
+ eeprom->opcode_bits);
+
+ em_shift_out_ee_bits(hw, (uint16_t)(offset + words_written),
+ eeprom->address_bits);
+
+ /* Send the data */
+ em_shift_out_ee_bits(hw, data[words_written], 16);
+
+ /* Toggle the CS line. This in effect tells the EEPROM to execute
+ * the previous command.
+ */
+ em_standby_eeprom(hw);
+
+ /* Read DO repeatedly until it is high (equal to '1'). The EEPROM will
+ * signal that the command has been completed by raising the DO signal.
+ * If DO does not go high in 10 milliseconds, then error out.
+ */
+ for(i = 0; i < 200; i++) {
+ eecd = E1000_READ_REG(hw, EECD);
+ if(eecd & E1000_EECD_DO) break;
+ usec_delay(50);
+ }
+ if(i == 200) {
+ DEBUGOUT("EEPROM Write did not complete\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ /* Recover from write */
+ em_standby_eeprom(hw);
+
+ words_written++;
+ }
+
+ /* Send the write disable command to the EEPROM (3-bit opcode plus
+ * 6/8-bit dummy address beginning with 10). It's less work to include
+ * the 10 of the dummy address as part of the opcode than it is to shift
+ * it over the correct number of bits for the address. This takes the
+ * EEPROM out of write/erase mode.
+ */
+ em_shift_out_ee_bits(hw, EEPROM_EWDS_OPCODE_MICROWIRE,
+ (uint16_t)(eeprom->opcode_bits + 2));
+
+ em_shift_out_ee_bits(hw, 0, (uint16_t)(eeprom->address_bits - 2));
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Flushes the cached eeprom to NVM. This is done by saving the modified values
+ * in the eeprom cache and the non modified values in the currently active bank
+ * to the new bank.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset of word in the EEPROM to read
+ * data - word read from the EEPROM
+ * words - number of words to read
+ *****************************************************************************/
+int32_t
+em_commit_shadow_ram(struct em_hw *hw)
+{
+ uint32_t attempts = 100000;
+ uint32_t eecd = 0;
+ uint32_t flop = 0;
+ uint32_t i = 0;
+ int32_t error = E1000_SUCCESS;
+
+ /* The flop register will be used to determine if flash type is STM */
+ flop = E1000_READ_REG(hw, FLOP);
+
+ if (hw->mac_type == em_82573) {
+ for (i=0; i < attempts; i++) {
+ eecd = E1000_READ_REG(hw, EECD);
+ if ((eecd & E1000_EECD_FLUPD) == 0) {
+ break;
+ }
+ usec_delay(5);
+ }
+
+ if (i == attempts) {
+ return -E1000_ERR_EEPROM;
+ }
+
+ /* If STM opcode located in bits 15:8 of flop, reset firmware */
+ if ((flop & 0xFF00) == E1000_STM_OPCODE) {
+ E1000_WRITE_REG(hw, HICR, E1000_HICR_FW_RESET);
+ }
+
+ /* Perform the flash update */
+ E1000_WRITE_REG(hw, EECD, eecd | E1000_EECD_FLUPD);
+
+ for (i=0; i < attempts; i++) {
+ eecd = E1000_READ_REG(hw, EECD);
+ if ((eecd & E1000_EECD_FLUPD) == 0) {
+ break;
+ }
+ usec_delay(5);
+ }
+
+ if (i == attempts) {
+ return -E1000_ERR_EEPROM;
+ }
+ }
+
+ return error;
+}
+
+/******************************************************************************
+ * Reads the adapter's part number from the EEPROM
+ *
+ * hw - Struct containing variables accessed by shared code
+ * part_num - Adapter's part number
+ *****************************************************************************/
+int32_t
+em_read_part_num(struct em_hw *hw,
+ uint32_t *part_num)
+{
+ uint16_t offset = EEPROM_PBA_BYTE_1;
+ uint16_t eeprom_data;
+
+ DEBUGFUNC("em_read_part_num");
+
+ /* Get word 0 from EEPROM */
+ if(em_read_eeprom(hw, offset, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ /* Save word 0 in upper half of part_num */
+ *part_num = (uint32_t) (eeprom_data << 16);
+
+ /* Get word 1 from EEPROM */
+ if(em_read_eeprom(hw, ++offset, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ /* Save word 1 in lower half of part_num */
+ *part_num |= eeprom_data;
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Reads the adapter's MAC address from the EEPROM and inverts the LSB for the
+ * second function of dual function devices
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_read_mac_addr(struct em_hw * hw)
+{
+ uint16_t offset;
+ uint16_t eeprom_data, i;
+
+ DEBUGFUNC("em_read_mac_addr");
+
+ for(i = 0; i < NODE_ADDRESS_SIZE; i += 2) {
+ offset = i >> 1;
+ if(em_read_eeprom(hw, offset, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ hw->perm_mac_addr[i] = (uint8_t) (eeprom_data & 0x00FF);
+ hw->perm_mac_addr[i+1] = (uint8_t) (eeprom_data >> 8);
+ }
+ if(((hw->mac_type == em_82546) || (hw->mac_type == em_82546_rev_3)) &&
+ (E1000_READ_REG(hw, STATUS) & E1000_STATUS_FUNC_1))
+ hw->perm_mac_addr[5] ^= 0x01;
+
+ for(i = 0; i < NODE_ADDRESS_SIZE; i++)
+ hw->mac_addr[i] = hw->perm_mac_addr[i];
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Initializes receive address filters.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Places the MAC address in receive address register 0 and clears the rest
+ * of the receive addresss registers. Clears the multicast table. Assumes
+ * the receiver is in reset when the routine is called.
+ *****************************************************************************/
+void
+em_init_rx_addrs(struct em_hw *hw)
+{
+ uint32_t i;
+ uint32_t rar_num;
+
+ DEBUGFUNC("em_init_rx_addrs");
+
+ /* Setup the receive address. */
+ DEBUGOUT("Programming MAC Address into RAR[0]\n");
+
+ em_rar_set(hw, hw->mac_addr, 0);
+
+ rar_num = E1000_RAR_ENTRIES;
+ /* Zero out the other 15 receive addresses. */
+ DEBUGOUT("Clearing RAR[1-15]\n");
+ for(i = 1; i < rar_num; i++) {
+ E1000_WRITE_REG_ARRAY(hw, RA, (i << 1), 0);
+ E1000_WRITE_REG_ARRAY(hw, RA, ((i << 1) + 1), 0);
+ }
+}
+
+/******************************************************************************
+ * Updates the MAC's list of multicast addresses.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * mc_addr_list - the list of new multicast addresses
+ * mc_addr_count - number of addresses
+ * pad - number of bytes between addresses in the list
+ * rar_used_count - offset where to start adding mc addresses into the RAR's
+ *
+ * The given list replaces any existing list. Clears the last 15 receive
+ * address registers and the multicast table. Uses receive address registers
+ * for the first 15 multicast addresses, and hashes the rest into the
+ * multicast table.
+ *****************************************************************************/
+void
+em_mc_addr_list_update(struct em_hw *hw,
+ uint8_t *mc_addr_list,
+ uint32_t mc_addr_count,
+ uint32_t pad,
+ uint32_t rar_used_count)
+{
+ uint32_t hash_value;
+ uint32_t i;
+ uint32_t num_rar_entry;
+ uint32_t num_mta_entry;
+
+ DEBUGFUNC("em_mc_addr_list_update");
+
+ /* Set the new number of MC addresses that we are being requested to use. */
+ hw->num_mc_addrs = mc_addr_count;
+
+ /* Clear RAR[1-15] */
+ DEBUGOUT(" Clearing RAR[1-15]\n");
+ num_rar_entry = E1000_RAR_ENTRIES;
+ for(i = rar_used_count; i < num_rar_entry; i++) {
+ E1000_WRITE_REG_ARRAY(hw, RA, (i << 1), 0);
+ E1000_WRITE_REG_ARRAY(hw, RA, ((i << 1) + 1), 0);
+ }
+
+ /* Clear the MTA */
+ DEBUGOUT(" Clearing MTA\n");
+ num_mta_entry = E1000_NUM_MTA_REGISTERS;
+ for(i = 0; i < num_mta_entry; i++) {
+ E1000_WRITE_REG_ARRAY(hw, MTA, i, 0);
+ }
+
+ /* Add the new addresses */
+ for(i = 0; i < mc_addr_count; i++) {
+ DEBUGOUT(" Adding the multicast addresses:\n");
+ DEBUGOUT7(" MC Addr #%d =%.2X %.2X %.2X %.2X %.2X %.2X\n", i,
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad)],
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad) + 1],
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad) + 2],
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad) + 3],
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad) + 4],
+ mc_addr_list[i * (ETH_LENGTH_OF_ADDRESS + pad) + 5]);
+
+ hash_value = em_hash_mc_addr(hw,
+ mc_addr_list +
+ (i * (ETH_LENGTH_OF_ADDRESS + pad)));
+
+ DEBUGOUT1(" Hash value = 0x%03X\n", hash_value);
+
+ /* Place this multicast address in the RAR if there is room, *
+ * else put it in the MTA
+ */
+ if (rar_used_count < num_rar_entry) {
+ em_rar_set(hw,
+ mc_addr_list + (i * (ETH_LENGTH_OF_ADDRESS + pad)),
+ rar_used_count);
+ rar_used_count++;
+ } else {
+ em_mta_set(hw, hash_value);
+ }
+ }
+ DEBUGOUT("MC Update Complete\n");
+}
+
+/******************************************************************************
+ * Hashes an address to determine its location in the multicast table
+ *
+ * hw - Struct containing variables accessed by shared code
+ * mc_addr - the multicast address to hash
+ *****************************************************************************/
+uint32_t
+em_hash_mc_addr(struct em_hw *hw,
+ uint8_t *mc_addr)
+{
+ uint32_t hash_value = 0;
+
+ /* The portion of the address that is used for the hash table is
+ * determined by the mc_filter_type setting.
+ */
+ switch (hw->mc_filter_type) {
+ /* [0] [1] [2] [3] [4] [5]
+ * 01 AA 00 12 34 56
+ * LSB MSB
+ */
+ case 0:
+ /* [47:36] i.e. 0x563 for above example address */
+ hash_value = ((mc_addr[4] >> 4) | (((uint16_t) mc_addr[5]) << 4));
+ break;
+ case 1:
+ /* [46:35] i.e. 0xAC6 for above example address */
+ hash_value = ((mc_addr[4] >> 3) | (((uint16_t) mc_addr[5]) << 5));
+ break;
+ case 2:
+ /* [45:34] i.e. 0x5D8 for above example address */
+ hash_value = ((mc_addr[4] >> 2) | (((uint16_t) mc_addr[5]) << 6));
+ break;
+ case 3:
+ /* [43:32] i.e. 0x634 for above example address */
+ hash_value = ((mc_addr[4]) | (((uint16_t) mc_addr[5]) << 8));
+ break;
+ }
+
+ hash_value &= 0xFFF;
+
+ return hash_value;
+}
+
+/******************************************************************************
+ * Sets the bit in the multicast table corresponding to the hash value.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * hash_value - Multicast address hash value
+ *****************************************************************************/
+void
+em_mta_set(struct em_hw *hw,
+ uint32_t hash_value)
+{
+ uint32_t hash_bit, hash_reg;
+ uint32_t mta;
+ uint32_t temp;
+
+ /* The MTA is a register array of 128 32-bit registers.
+ * It is treated like an array of 4096 bits. We want to set
+ * bit BitArray[hash_value]. So we figure out what register
+ * the bit is in, read it, OR in the new bit, then write
+ * back the new value. The register is determined by the
+ * upper 7 bits of the hash value and the bit within that
+ * register are determined by the lower 5 bits of the value.
+ */
+ hash_reg = (hash_value >> 5) & 0x7F;
+ hash_bit = hash_value & 0x1F;
+
+ mta = E1000_READ_REG_ARRAY(hw, MTA, hash_reg);
+
+ mta |= (1 << hash_bit);
+
+ /* If we are on an 82544 and we are trying to write an odd offset
+ * in the MTA, save off the previous entry before writing and
+ * restore the old value after writing.
+ */
+ if((hw->mac_type == em_82544) && ((hash_reg & 0x1) == 1)) {
+ temp = E1000_READ_REG_ARRAY(hw, MTA, (hash_reg - 1));
+ E1000_WRITE_REG_ARRAY(hw, MTA, hash_reg, mta);
+ E1000_WRITE_REG_ARRAY(hw, MTA, (hash_reg - 1), temp);
+ } else {
+ E1000_WRITE_REG_ARRAY(hw, MTA, hash_reg, mta);
+ }
+}
+
+/******************************************************************************
+ * Puts an ethernet address into a receive address register.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * addr - Address to put into receive address register
+ * index - Receive address register to write
+ *****************************************************************************/
+void
+em_rar_set(struct em_hw *hw,
+ uint8_t *addr,
+ uint32_t index)
+{
+ uint32_t rar_low, rar_high;
+
+ /* HW expects these in little endian so we reverse the byte order
+ * from network order (big endian) to little endian
+ */
+ rar_low = ((uint32_t) addr[0] |
+ ((uint32_t) addr[1] << 8) |
+ ((uint32_t) addr[2] << 16) | ((uint32_t) addr[3] << 24));
+
+ rar_high = ((uint32_t) addr[4] | ((uint32_t) addr[5] << 8) | E1000_RAH_AV);
+
+ E1000_WRITE_REG_ARRAY(hw, RA, (index << 1), rar_low);
+ E1000_WRITE_REG_ARRAY(hw, RA, ((index << 1) + 1), rar_high);
+}
+
+/******************************************************************************
+ * Writes a value to the specified offset in the VLAN filter table.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - Offset in VLAN filer table to write
+ * value - Value to write into VLAN filter table
+ *****************************************************************************/
+void
+em_write_vfta(struct em_hw *hw,
+ uint32_t offset,
+ uint32_t value)
+{
+ uint32_t temp;
+
+ if((hw->mac_type == em_82544) && ((offset & 0x1) == 1)) {
+ temp = E1000_READ_REG_ARRAY(hw, VFTA, (offset - 1));
+ E1000_WRITE_REG_ARRAY(hw, VFTA, offset, value);
+ E1000_WRITE_REG_ARRAY(hw, VFTA, (offset - 1), temp);
+ } else {
+ E1000_WRITE_REG_ARRAY(hw, VFTA, offset, value);
+ }
+}
+
+/******************************************************************************
+ * Clears the VLAN filer table
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+void
+em_clear_vfta(struct em_hw *hw)
+{
+ uint32_t offset;
+ uint32_t vfta_value = 0;
+ uint32_t vfta_offset = 0;
+ uint32_t vfta_bit_in_reg = 0;
+
+ if (hw->mac_type == em_82573) {
+ if (hw->mng_cookie.vlan_id != 0) {
+ /* The VFTA is a 4096b bit-field, each identifying a single VLAN
+ * ID. The following operations determine which 32b entry
+ * (i.e. offset) into the array we want to set the VLAN ID
+ * (i.e. bit) of the manageability unit. */
+ vfta_offset = (hw->mng_cookie.vlan_id >>
+ E1000_VFTA_ENTRY_SHIFT) &
+ E1000_VFTA_ENTRY_MASK;
+ vfta_bit_in_reg = 1 << (hw->mng_cookie.vlan_id &
+ E1000_VFTA_ENTRY_BIT_SHIFT_MASK);
+ }
+ }
+ for (offset = 0; offset < E1000_VLAN_FILTER_TBL_SIZE; offset++) {
+ /* If the offset we want to clear is the same offset of the
+ * manageability VLAN ID, then clear all bits except that of the
+ * manageability unit */
+ vfta_value = (offset == vfta_offset) ? vfta_bit_in_reg : 0;
+ E1000_WRITE_REG_ARRAY(hw, VFTA, offset, vfta_value);
+ }
+}
+
+int32_t
+em_id_led_init(struct em_hw * hw)
+{
+ uint32_t ledctl;
+ const uint32_t ledctl_mask = 0x000000FF;
+ const uint32_t ledctl_on = E1000_LEDCTL_MODE_LED_ON;
+ const uint32_t ledctl_off = E1000_LEDCTL_MODE_LED_OFF;
+ uint16_t eeprom_data, i, temp;
+ const uint16_t led_mask = 0x0F;
+
+ DEBUGFUNC("em_id_led_init");
+
+ if(hw->mac_type < em_82540) {
+ /* Nothing to do */
+ return E1000_SUCCESS;
+ }
+
+ ledctl = E1000_READ_REG(hw, LEDCTL);
+ hw->ledctl_default = ledctl;
+ hw->ledctl_mode1 = hw->ledctl_default;
+ hw->ledctl_mode2 = hw->ledctl_default;
+
+ if(em_read_eeprom(hw, EEPROM_ID_LED_SETTINGS, 1, &eeprom_data) < 0) {
+ DEBUGOUT("EEPROM Read Error\n");
+ return -E1000_ERR_EEPROM;
+ }
+ if((eeprom_data== ID_LED_RESERVED_0000) ||
+ (eeprom_data == ID_LED_RESERVED_FFFF)) eeprom_data = ID_LED_DEFAULT;
+ for(i = 0; i < 4; i++) {
+ temp = (eeprom_data >> (i << 2)) & led_mask;
+ switch(temp) {
+ case ID_LED_ON1_DEF2:
+ case ID_LED_ON1_ON2:
+ case ID_LED_ON1_OFF2:
+ hw->ledctl_mode1 &= ~(ledctl_mask << (i << 3));
+ hw->ledctl_mode1 |= ledctl_on << (i << 3);
+ break;
+ case ID_LED_OFF1_DEF2:
+ case ID_LED_OFF1_ON2:
+ case ID_LED_OFF1_OFF2:
+ hw->ledctl_mode1 &= ~(ledctl_mask << (i << 3));
+ hw->ledctl_mode1 |= ledctl_off << (i << 3);
+ break;
+ default:
+ /* Do nothing */
+ break;
+ }
+ switch(temp) {
+ case ID_LED_DEF1_ON2:
+ case ID_LED_ON1_ON2:
+ case ID_LED_OFF1_ON2:
+ hw->ledctl_mode2 &= ~(ledctl_mask << (i << 3));
+ hw->ledctl_mode2 |= ledctl_on << (i << 3);
+ break;
+ case ID_LED_DEF1_OFF2:
+ case ID_LED_ON1_OFF2:
+ case ID_LED_OFF1_OFF2:
+ hw->ledctl_mode2 &= ~(ledctl_mask << (i << 3));
+ hw->ledctl_mode2 |= ledctl_off << (i << 3);
+ break;
+ default:
+ /* Do nothing */
+ break;
+ }
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Prepares SW controlable LED for use and saves the current state of the LED.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_setup_led(struct em_hw *hw)
+{
+ uint32_t ledctl;
+ int32_t ret_val = E1000_SUCCESS;
+
+ DEBUGFUNC("em_setup_led");
+
+ switch(hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ case em_82544:
+ /* No setup necessary */
+ break;
+ case em_82541:
+ case em_82547:
+ case em_82541_rev_2:
+ case em_82547_rev_2:
+ /* Turn off PHY Smart Power Down (if enabled) */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_GMII_FIFO,
+ &hw->phy_spd_default);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_GMII_FIFO,
+ (uint16_t)(hw->phy_spd_default &
+ ~IGP01E1000_GMII_SPD));
+ if(ret_val)
+ return ret_val;
+ /* Fall Through */
+ default:
+ if(hw->media_type == em_media_type_fiber) {
+ ledctl = E1000_READ_REG(hw, LEDCTL);
+ /* Save current LEDCTL settings */
+ hw->ledctl_default = ledctl;
+ /* Turn off LED0 */
+ ledctl &= ~(E1000_LEDCTL_LED0_IVRT |
+ E1000_LEDCTL_LED0_BLINK |
+ E1000_LEDCTL_LED0_MODE_MASK);
+ ledctl |= (E1000_LEDCTL_MODE_LED_OFF <<
+ E1000_LEDCTL_LED0_MODE_SHIFT);
+ E1000_WRITE_REG(hw, LEDCTL, ledctl);
+ } else if(hw->media_type == em_media_type_copper)
+ E1000_WRITE_REG(hw, LEDCTL, hw->ledctl_mode1);
+ break;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Restores the saved state of the SW controlable LED.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_cleanup_led(struct em_hw *hw)
+{
+ int32_t ret_val = E1000_SUCCESS;
+
+ DEBUGFUNC("em_cleanup_led");
+
+ switch(hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ case em_82544:
+ /* No cleanup necessary */
+ break;
+ case em_82541:
+ case em_82547:
+ case em_82541_rev_2:
+ case em_82547_rev_2:
+ /* Turn on PHY Smart Power Down (if previously enabled) */
+ ret_val = em_write_phy_reg(hw, IGP01E1000_GMII_FIFO,
+ hw->phy_spd_default);
+ if(ret_val)
+ return ret_val;
+ /* Fall Through */
+ default:
+ /* Restore LEDCTL settings */
+ E1000_WRITE_REG(hw, LEDCTL, hw->ledctl_default);
+ break;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Turns on the software controllable LED
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_led_on(struct em_hw *hw)
+{
+ uint32_t ctrl = E1000_READ_REG(hw, CTRL);
+
+ DEBUGFUNC("em_led_on");
+
+ switch(hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ /* Set SW Defineable Pin 0 to turn on the LED */
+ ctrl |= E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ break;
+ case em_82544:
+ if(hw->media_type == em_media_type_fiber) {
+ /* Set SW Defineable Pin 0 to turn on the LED */
+ ctrl |= E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ } else {
+ /* Clear SW Defineable Pin 0 to turn on the LED */
+ ctrl &= ~E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ }
+ break;
+ default:
+ if(hw->media_type == em_media_type_fiber) {
+ /* Clear SW Defineable Pin 0 to turn on the LED */
+ ctrl &= ~E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ } else if(hw->media_type == em_media_type_copper) {
+ E1000_WRITE_REG(hw, LEDCTL, hw->ledctl_mode2);
+ return E1000_SUCCESS;
+ }
+ break;
+ }
+
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Turns off the software controllable LED
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+int32_t
+em_led_off(struct em_hw *hw)
+{
+ uint32_t ctrl = E1000_READ_REG(hw, CTRL);
+
+ DEBUGFUNC("em_led_off");
+
+ switch(hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ case em_82543:
+ /* Clear SW Defineable Pin 0 to turn off the LED */
+ ctrl &= ~E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ break;
+ case em_82544:
+ if(hw->media_type == em_media_type_fiber) {
+ /* Clear SW Defineable Pin 0 to turn off the LED */
+ ctrl &= ~E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ } else {
+ /* Set SW Defineable Pin 0 to turn off the LED */
+ ctrl |= E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ }
+ break;
+ default:
+ if(hw->media_type == em_media_type_fiber) {
+ /* Set SW Defineable Pin 0 to turn off the LED */
+ ctrl |= E1000_CTRL_SWDPIN0;
+ ctrl |= E1000_CTRL_SWDPIO0;
+ } else if(hw->media_type == em_media_type_copper) {
+ E1000_WRITE_REG(hw, LEDCTL, hw->ledctl_mode1);
+ return E1000_SUCCESS;
+ }
+ break;
+ }
+
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Clears all hardware statistics counters.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+void
+em_clear_hw_cntrs(struct em_hw *hw)
+{
+ E1000_READ_REG(hw, CRCERRS);
+ E1000_READ_REG(hw, SYMERRS);
+ E1000_READ_REG(hw, MPC);
+ E1000_READ_REG(hw, SCC);
+ E1000_READ_REG(hw, ECOL);
+ E1000_READ_REG(hw, MCC);
+ E1000_READ_REG(hw, LATECOL);
+ E1000_READ_REG(hw, COLC);
+ E1000_READ_REG(hw, DC);
+ E1000_READ_REG(hw, SEC);
+ E1000_READ_REG(hw, RLEC);
+ E1000_READ_REG(hw, XONRXC);
+ E1000_READ_REG(hw, XONTXC);
+ E1000_READ_REG(hw, XOFFRXC);
+ E1000_READ_REG(hw, XOFFTXC);
+ E1000_READ_REG(hw, FCRUC);
+ E1000_READ_REG(hw, PRC64);
+ E1000_READ_REG(hw, PRC127);
+ E1000_READ_REG(hw, PRC255);
+ E1000_READ_REG(hw, PRC511);
+ E1000_READ_REG(hw, PRC1023);
+ E1000_READ_REG(hw, PRC1522);
+ E1000_READ_REG(hw, GPRC);
+ E1000_READ_REG(hw, BPRC);
+ E1000_READ_REG(hw, MPRC);
+ E1000_READ_REG(hw, GPTC);
+ E1000_READ_REG(hw, GORCL);
+ E1000_READ_REG(hw, GORCH);
+ E1000_READ_REG(hw, GOTCL);
+ E1000_READ_REG(hw, GOTCH);
+ E1000_READ_REG(hw, RNBC);
+ E1000_READ_REG(hw, RUC);
+ E1000_READ_REG(hw, RFC);
+ E1000_READ_REG(hw, ROC);
+ E1000_READ_REG(hw, RJC);
+ E1000_READ_REG(hw, TORL);
+ E1000_READ_REG(hw, TORH);
+ E1000_READ_REG(hw, TOTL);
+ E1000_READ_REG(hw, TOTH);
+ E1000_READ_REG(hw, TPR);
+ E1000_READ_REG(hw, TPT);
+ E1000_READ_REG(hw, PTC64);
+ E1000_READ_REG(hw, PTC127);
+ E1000_READ_REG(hw, PTC255);
+ E1000_READ_REG(hw, PTC511);
+ E1000_READ_REG(hw, PTC1023);
+ E1000_READ_REG(hw, PTC1522);
+ E1000_READ_REG(hw, MPTC);
+ E1000_READ_REG(hw, BPTC);
+
+ if(hw->mac_type < em_82543) return;
+
+ E1000_READ_REG(hw, ALGNERRC);
+ E1000_READ_REG(hw, RXERRC);
+ E1000_READ_REG(hw, TNCRS);
+ E1000_READ_REG(hw, CEXTERR);
+ E1000_READ_REG(hw, TSCTC);
+ E1000_READ_REG(hw, TSCTFC);
+
+ if(hw->mac_type <= em_82544) return;
+
+ E1000_READ_REG(hw, MGTPRC);
+ E1000_READ_REG(hw, MGTPDC);
+ E1000_READ_REG(hw, MGTPTC);
+
+ if(hw->mac_type <= em_82547_rev_2) return;
+
+ E1000_READ_REG(hw, IAC);
+ E1000_READ_REG(hw, ICRXOC);
+ E1000_READ_REG(hw, ICRXPTC);
+ E1000_READ_REG(hw, ICRXATC);
+ E1000_READ_REG(hw, ICTXPTC);
+ E1000_READ_REG(hw, ICTXATC);
+ E1000_READ_REG(hw, ICTXQEC);
+ E1000_READ_REG(hw, ICTXQMTC);
+ E1000_READ_REG(hw, ICRXDMTC);
+
+}
+
+/******************************************************************************
+ * Resets Adaptive IFS to its default state.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * Call this after em_init_hw. You may override the IFS defaults by setting
+ * hw->ifs_params_forced to TRUE. However, you must initialize hw->
+ * current_ifs_val, ifs_min_val, ifs_max_val, ifs_step_size, and ifs_ratio
+ * before calling this function.
+ *****************************************************************************/
+void
+em_reset_adaptive(struct em_hw *hw)
+{
+ DEBUGFUNC("em_reset_adaptive");
+
+ if(hw->adaptive_ifs) {
+ if(!hw->ifs_params_forced) {
+ hw->current_ifs_val = 0;
+ hw->ifs_min_val = IFS_MIN;
+ hw->ifs_max_val = IFS_MAX;
+ hw->ifs_step_size = IFS_STEP;
+ hw->ifs_ratio = IFS_RATIO;
+ }
+ hw->in_ifs_mode = FALSE;
+ E1000_WRITE_REG(hw, AIT, 0);
+ } else {
+ DEBUGOUT("Not in Adaptive IFS mode!\n");
+ }
+}
+
+/******************************************************************************
+ * Called during the callback/watchdog routine to update IFS value based on
+ * the ratio of transmits to collisions.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * tx_packets - Number of transmits since last callback
+ * total_collisions - Number of collisions since last callback
+ *****************************************************************************/
+void
+em_update_adaptive(struct em_hw *hw)
+{
+ DEBUGFUNC("em_update_adaptive");
+
+ if(hw->adaptive_ifs) {
+ if((hw->collision_delta * hw->ifs_ratio) > hw->tx_packet_delta) {
+ if(hw->tx_packet_delta > MIN_NUM_XMITS) {
+ hw->in_ifs_mode = TRUE;
+ if(hw->current_ifs_val < hw->ifs_max_val) {
+ if(hw->current_ifs_val == 0)
+ hw->current_ifs_val = hw->ifs_min_val;
+ else
+ hw->current_ifs_val += hw->ifs_step_size;
+ E1000_WRITE_REG(hw, AIT, hw->current_ifs_val);
+ }
+ }
+ } else {
+ if(hw->in_ifs_mode && (hw->tx_packet_delta <= MIN_NUM_XMITS)) {
+ hw->current_ifs_val = 0;
+ hw->in_ifs_mode = FALSE;
+ E1000_WRITE_REG(hw, AIT, 0);
+ }
+ }
+ } else {
+ DEBUGOUT("Not in Adaptive IFS mode!\n");
+ }
+}
+
+/******************************************************************************
+ * Adjusts the statistic counters when a frame is accepted by TBI_ACCEPT
+ *
+ * hw - Struct containing variables accessed by shared code
+ * frame_len - The length of the frame in question
+ * mac_addr - The Ethernet destination address of the frame in question
+ *****************************************************************************/
+void
+em_tbi_adjust_stats(struct em_hw *hw,
+ struct em_hw_stats *stats,
+ uint32_t frame_len,
+ uint8_t *mac_addr)
+{
+ uint64_t carry_bit;
+
+ /* First adjust the frame length. */
+ frame_len--;
+ /* We need to adjust the statistics counters, since the hardware
+ * counters overcount this packet as a CRC error and undercount
+ * the packet as a good packet
+ */
+ /* This packet should not be counted as a CRC error. */
+ stats->crcerrs--;
+ /* This packet does count as a Good Packet Received. */
+ stats->gprc++;
+
+ /* Adjust the Good Octets received counters */
+ carry_bit = 0x80000000 & stats->gorcl;
+ stats->gorcl += frame_len;
+ /* If the high bit of Gorcl (the low 32 bits of the Good Octets
+ * Received Count) was one before the addition,
+ * AND it is zero after, then we lost the carry out,
+ * need to add one to Gorch (Good Octets Received Count High).
+ * This could be simplified if all environments supported
+ * 64-bit integers.
+ */
+ if(carry_bit && ((stats->gorcl & 0x80000000) == 0))
+ stats->gorch++;
+ /* Is this a broadcast or multicast? Check broadcast first,
+ * since the test for a multicast frame will test positive on
+ * a broadcast frame.
+ */
+ if((mac_addr[0] == (uint8_t) 0xff) && (mac_addr[1] == (uint8_t) 0xff))
+ /* Broadcast packet */
+ stats->bprc++;
+ else if(*mac_addr & 0x01)
+ /* Multicast packet */
+ stats->mprc++;
+
+ if(frame_len == hw->max_frame_size) {
+ /* In this case, the hardware has overcounted the number of
+ * oversize frames.
+ */
+ if(stats->roc > 0)
+ stats->roc--;
+ }
+
+ /* Adjust the bin counters when the extra byte put the frame in the
+ * wrong bin. Remember that the frame_len was adjusted above.
+ */
+ if(frame_len == 64) {
+ stats->prc64++;
+ stats->prc127--;
+ } else if(frame_len == 127) {
+ stats->prc127++;
+ stats->prc255--;
+ } else if(frame_len == 255) {
+ stats->prc255++;
+ stats->prc511--;
+ } else if(frame_len == 511) {
+ stats->prc511++;
+ stats->prc1023--;
+ } else if(frame_len == 1023) {
+ stats->prc1023++;
+ stats->prc1522--;
+ } else if(frame_len == 1522) {
+ stats->prc1522++;
+ }
+}
+
+/******************************************************************************
+ * Gets the current PCI bus type, speed, and width of the hardware
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+void
+em_get_bus_info(struct em_hw *hw)
+{
+ uint32_t status;
+
+ switch (hw->mac_type) {
+ case em_82542_rev2_0:
+ case em_82542_rev2_1:
+ hw->bus_type = em_bus_type_unknown;
+ hw->bus_speed = em_bus_speed_unknown;
+ hw->bus_width = em_bus_width_unknown;
+ break;
+ case em_82573:
+ hw->bus_type = em_bus_type_pci_express;
+ hw->bus_speed = em_bus_speed_2500;
+ hw->bus_width = em_bus_width_pciex_4;
+ break;
+ default:
+ status = E1000_READ_REG(hw, STATUS);
+ hw->bus_type = (status & E1000_STATUS_PCIX_MODE) ?
+ em_bus_type_pcix : em_bus_type_pci;
+
+ if(hw->device_id == E1000_DEV_ID_82546EB_QUAD_COPPER) {
+ hw->bus_speed = (hw->bus_type == em_bus_type_pci) ?
+ em_bus_speed_66 : em_bus_speed_120;
+ } else if(hw->bus_type == em_bus_type_pci) {
+ hw->bus_speed = (status & E1000_STATUS_PCI66) ?
+ em_bus_speed_66 : em_bus_speed_33;
+ } else {
+ switch (status & E1000_STATUS_PCIX_SPEED) {
+ case E1000_STATUS_PCIX_SPEED_66:
+ hw->bus_speed = em_bus_speed_66;
+ break;
+ case E1000_STATUS_PCIX_SPEED_100:
+ hw->bus_speed = em_bus_speed_100;
+ break;
+ case E1000_STATUS_PCIX_SPEED_133:
+ hw->bus_speed = em_bus_speed_133;
+ break;
+ default:
+ hw->bus_speed = em_bus_speed_reserved;
+ break;
+ }
+ }
+ hw->bus_width = (status & E1000_STATUS_BUS64) ?
+ em_bus_width_64 : em_bus_width_32;
+ break;
+ }
+}
+/******************************************************************************
+ * Reads a value from one of the devices registers using port I/O (as opposed
+ * memory mapped I/O). Only 82544 and newer devices support port I/O.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset to read from
+ *****************************************************************************/
+uint32_t
+em_read_reg_io(struct em_hw *hw,
+ uint32_t offset)
+{
+ unsigned long io_addr = hw->io_base;
+ unsigned long io_data = hw->io_base + 4;
+
+ em_io_write(hw, io_addr, offset);
+ return em_io_read(hw, io_data);
+}
+
+/******************************************************************************
+ * Writes a value to one of the devices registers using port I/O (as opposed to
+ * memory mapped I/O). Only 82544 and newer devices support port I/O.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * offset - offset to write to
+ * value - value to write
+ *****************************************************************************/
+void
+em_write_reg_io(struct em_hw *hw,
+ uint32_t offset,
+ uint32_t value)
+{
+ unsigned long io_addr = hw->io_base;
+ unsigned long io_data = hw->io_base + 4;
+
+ em_io_write(hw, io_addr, offset);
+ em_io_write(hw, io_data, value);
+}
+
+
+/******************************************************************************
+ * Estimates the cable length.
+ *
+ * hw - Struct containing variables accessed by shared code
+ * min_length - The estimated minimum length
+ * max_length - The estimated maximum length
+ *
+ * returns: - E1000_ERR_XXX
+ * E1000_SUCCESS
+ *
+ * This function always returns a ranged length (minimum & maximum).
+ * So for M88 phy's, this function interprets the one value returned from the
+ * register to the minimum and maximum range.
+ * For IGP phy's, the function calculates the range by the AGC registers.
+ *****************************************************************************/
+int32_t
+em_get_cable_length(struct em_hw *hw,
+ uint16_t *min_length,
+ uint16_t *max_length)
+{
+ int32_t ret_val;
+ uint16_t agc_value = 0;
+ uint16_t cur_agc, min_agc = IGP01E1000_AGC_LENGTH_TABLE_SIZE;
+ uint16_t i, phy_data;
+ uint16_t cable_length;
+
+ DEBUGFUNC("em_get_cable_length");
+
+ *min_length = *max_length = 0;
+
+ /* Use old method for Phy older than IGP */
+ if(hw->phy_type == em_phy_m88) {
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+ cable_length = (phy_data & M88E1000_PSSR_CABLE_LENGTH) >>
+ M88E1000_PSSR_CABLE_LENGTH_SHIFT;
+
+ /* Convert the enum value to ranged values */
+ switch (cable_length) {
+ case em_cable_length_50:
+ *min_length = 0;
+ *max_length = em_igp_cable_length_50;
+ break;
+ case em_cable_length_50_80:
+ *min_length = em_igp_cable_length_50;
+ *max_length = em_igp_cable_length_80;
+ break;
+ case em_cable_length_80_110:
+ *min_length = em_igp_cable_length_80;
+ *max_length = em_igp_cable_length_110;
+ break;
+ case em_cable_length_110_140:
+ *min_length = em_igp_cable_length_110;
+ *max_length = em_igp_cable_length_140;
+ break;
+ case em_cable_length_140:
+ *min_length = em_igp_cable_length_140;
+ *max_length = em_igp_cable_length_170;
+ break;
+ default:
+ return -E1000_ERR_PHY;
+ break;
+ }
+ } else if(hw->phy_type == em_phy_igp) { /* For IGP PHY */
+ uint16_t agc_reg_array[IGP01E1000_PHY_CHANNEL_NUM] =
+ {IGP01E1000_PHY_AGC_A,
+ IGP01E1000_PHY_AGC_B,
+ IGP01E1000_PHY_AGC_C,
+ IGP01E1000_PHY_AGC_D};
+ /* Read the AGC registers for all channels */
+ for(i = 0; i < IGP01E1000_PHY_CHANNEL_NUM; i++) {
+
+ ret_val = em_read_phy_reg(hw, agc_reg_array[i], &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ cur_agc = phy_data >> IGP01E1000_AGC_LENGTH_SHIFT;
+
+ /* Array bound check. */
+ if((cur_agc >= IGP01E1000_AGC_LENGTH_TABLE_SIZE - 1) ||
+ (cur_agc == 0))
+ return -E1000_ERR_PHY;
+
+ agc_value += cur_agc;
+
+ /* Update minimal AGC value. */
+ if(min_agc > cur_agc)
+ min_agc = cur_agc;
+ }
+
+ /* Remove the minimal AGC result for length < 50m */
+ if(agc_value < IGP01E1000_PHY_CHANNEL_NUM * em_igp_cable_length_50) {
+ agc_value -= min_agc;
+
+ /* Get the average length of the remaining 3 channels */
+ agc_value /= (IGP01E1000_PHY_CHANNEL_NUM - 1);
+ } else {
+ /* Get the average length of all the 4 channels. */
+ agc_value /= IGP01E1000_PHY_CHANNEL_NUM;
+ }
+
+ /* Set the range of the calculated length. */
+ *min_length = ((em_igp_cable_length_table[agc_value] -
+ IGP01E1000_AGC_RANGE) > 0) ?
+ (em_igp_cable_length_table[agc_value] -
+ IGP01E1000_AGC_RANGE) : 0;
+ *max_length = em_igp_cable_length_table[agc_value] +
+ IGP01E1000_AGC_RANGE;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Check the cable polarity
+ *
+ * hw - Struct containing variables accessed by shared code
+ * polarity - output parameter : 0 - Polarity is not reversed
+ * 1 - Polarity is reversed.
+ *
+ * returns: - E1000_ERR_XXX
+ * E1000_SUCCESS
+ *
+ * For phy's older then IGP, this function simply reads the polarity bit in the
+ * Phy Status register. For IGP phy's, this bit is valid only if link speed is
+ * 10 Mbps. If the link speed is 100 Mbps there is no polarity so this bit will
+ * return 0. If the link speed is 1000 Mbps the polarity status is in the
+ * IGP01E1000_PHY_PCS_INIT_REG.
+ *****************************************************************************/
+int32_t
+em_check_polarity(struct em_hw *hw,
+ uint16_t *polarity)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+#ifdef __rtems__
+ *polarity = 0; /* keep compiler happy */
+#endif
+
+ DEBUGFUNC("em_check_polarity");
+
+ if(hw->phy_type == em_phy_m88) {
+ /* return the Polarity bit in the Status register. */
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+ *polarity = (phy_data & M88E1000_PSSR_REV_POLARITY) >>
+ M88E1000_PSSR_REV_POLARITY_SHIFT;
+ } else if(hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2) {
+ /* Read the Status register to check the speed */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* If speed is 1000 Mbps, must read the IGP01E1000_PHY_PCS_INIT_REG to
+ * find the polarity status */
+ if((phy_data & IGP01E1000_PSSR_SPEED_MASK) ==
+ IGP01E1000_PSSR_SPEED_1000MBPS) {
+
+ /* Read the GIG initialization PCS register (0x00B4) */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PCS_INIT_REG,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* Check the polarity bits */
+ *polarity = (phy_data & IGP01E1000_PHY_POLARITY_MASK) ? 1 : 0;
+ } else {
+ /* For 10 Mbps, read the polarity bit in the status register. (for
+ * 100 Mbps this bit is always 0) */
+ *polarity = phy_data & IGP01E1000_PSSR_POLARITY_REVERSED;
+ }
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Check if Downshift occured
+ *
+ * hw - Struct containing variables accessed by shared code
+ * downshift - output parameter : 0 - No Downshift ocured.
+ * 1 - Downshift ocured.
+ *
+ * returns: - E1000_ERR_XXX
+ * E1000_SUCCESS
+ *
+ * For phy's older then IGP, this function reads the Downshift bit in the Phy
+ * Specific Status register. For IGP phy's, it reads the Downgrade bit in the
+ * Link Health register. In IGP this bit is latched high, so the driver must
+ * read it immediately after link is established.
+ *****************************************************************************/
+int32_t
+em_check_downshift(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_check_downshift");
+
+ if(hw->phy_type == em_phy_igp ||
+ hw->phy_type == em_phy_igp_2) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_LINK_HEALTH,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ hw->speed_downgraded = (phy_data & IGP01E1000_PLHR_SS_DOWNGRADE) ? 1 : 0;
+ } else if(hw->phy_type == em_phy_m88) {
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_SPEC_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ hw->speed_downgraded = (phy_data & M88E1000_PSSR_DOWNSHIFT) >>
+ M88E1000_PSSR_DOWNSHIFT_SHIFT;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ *
+ * 82541_rev_2 & 82547_rev_2 have the capability to configure the DSP when a
+ * gigabit link is achieved to improve link quality.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_ERR_PHY if fail to read/write the PHY
+ * E1000_SUCCESS at any other case.
+ *
+ ****************************************************************************/
+
+int32_t
+em_config_dsp_after_link_change(struct em_hw *hw,
+ boolean_t link_up)
+{
+ int32_t ret_val;
+ uint16_t phy_data, phy_saved_data, speed, duplex, i;
+ uint16_t dsp_reg_array[IGP01E1000_PHY_CHANNEL_NUM] =
+ {IGP01E1000_PHY_AGC_PARAM_A,
+ IGP01E1000_PHY_AGC_PARAM_B,
+ IGP01E1000_PHY_AGC_PARAM_C,
+ IGP01E1000_PHY_AGC_PARAM_D};
+ uint16_t min_length, max_length;
+
+ DEBUGFUNC("em_config_dsp_after_link_change");
+
+ if(hw->phy_type != em_phy_igp)
+ return E1000_SUCCESS;
+
+ if(link_up) {
+ ret_val = em_get_speed_and_duplex(hw, &speed, &duplex);
+ if(ret_val) {
+ DEBUGOUT("Error getting link speed and duplex\n");
+ return ret_val;
+ }
+
+ if(speed == SPEED_1000) {
+
+ em_get_cable_length(hw, &min_length, &max_length);
+
+ if((hw->dsp_config_state == em_dsp_config_enabled) &&
+ min_length >= em_igp_cable_length_50) {
+
+ for(i = 0; i < IGP01E1000_PHY_CHANNEL_NUM; i++) {
+ ret_val = em_read_phy_reg(hw, dsp_reg_array[i],
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PHY_EDAC_MU_INDEX;
+
+ ret_val = em_write_phy_reg(hw, dsp_reg_array[i],
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+ hw->dsp_config_state = em_dsp_config_activated;
+ }
+
+ if((hw->ffe_config_state == em_ffe_config_enabled) &&
+ (min_length < em_igp_cable_length_50)) {
+
+ uint16_t ffe_idle_err_timeout = FFE_IDLE_ERR_COUNT_TIMEOUT_20;
+ uint32_t idle_errs = 0;
+
+ /* clear previous idle error counts */
+ ret_val = em_read_phy_reg(hw, PHY_1000T_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ for(i = 0; i < ffe_idle_err_timeout; i++) {
+ usec_delay(1000);
+ ret_val = em_read_phy_reg(hw, PHY_1000T_STATUS,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ idle_errs += (phy_data & SR_1000T_IDLE_ERROR_CNT);
+ if(idle_errs > SR_1000T_PHY_EXCESSIVE_IDLE_ERR_COUNT) {
+ hw->ffe_config_state = em_ffe_config_active;
+
+ ret_val = em_write_phy_reg(hw,
+ IGP01E1000_PHY_DSP_FFE,
+ IGP01E1000_PHY_DSP_FFE_CM_CP);
+ if(ret_val)
+ return ret_val;
+ break;
+ }
+
+ if(idle_errs)
+ ffe_idle_err_timeout = FFE_IDLE_ERR_COUNT_TIMEOUT_100;
+ }
+ }
+ }
+ } else {
+ if(hw->dsp_config_state == em_dsp_config_activated) {
+ /* Save off the current value of register 0x2F5B to be restored at
+ * the end of the routines. */
+ ret_val = em_read_phy_reg(hw, 0x2F5B, &phy_saved_data);
+
+ if(ret_val)
+ return ret_val;
+
+ /* Disable the PHY transmitter */
+ ret_val = em_write_phy_reg(hw, 0x2F5B, 0x0003);
+
+ if(ret_val)
+ return ret_val;
+
+ msec_delay_irq(20);
+
+ ret_val = em_write_phy_reg(hw, 0x0000,
+ IGP01E1000_IEEE_FORCE_GIGA);
+ if(ret_val)
+ return ret_val;
+ for(i = 0; i < IGP01E1000_PHY_CHANNEL_NUM; i++) {
+ ret_val = em_read_phy_reg(hw, dsp_reg_array[i], &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PHY_EDAC_MU_INDEX;
+ phy_data |= IGP01E1000_PHY_EDAC_SIGN_EXT_9_BITS;
+
+ ret_val = em_write_phy_reg(hw,dsp_reg_array[i], phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ ret_val = em_write_phy_reg(hw, 0x0000,
+ IGP01E1000_IEEE_RESTART_AUTONEG);
+ if(ret_val)
+ return ret_val;
+
+ msec_delay_irq(20);
+
+ /* Now enable the transmitter */
+ ret_val = em_write_phy_reg(hw, 0x2F5B, phy_saved_data);
+
+ if(ret_val)
+ return ret_val;
+
+ hw->dsp_config_state = em_dsp_config_enabled;
+ }
+
+ if(hw->ffe_config_state == em_ffe_config_active) {
+ /* Save off the current value of register 0x2F5B to be restored at
+ * the end of the routines. */
+ ret_val = em_read_phy_reg(hw, 0x2F5B, &phy_saved_data);
+
+ if(ret_val)
+ return ret_val;
+
+ /* Disable the PHY transmitter */
+ ret_val = em_write_phy_reg(hw, 0x2F5B, 0x0003);
+
+ if(ret_val)
+ return ret_val;
+
+ msec_delay_irq(20);
+
+ ret_val = em_write_phy_reg(hw, 0x0000,
+ IGP01E1000_IEEE_FORCE_GIGA);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_DSP_FFE,
+ IGP01E1000_PHY_DSP_FFE_DEFAULT);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_write_phy_reg(hw, 0x0000,
+ IGP01E1000_IEEE_RESTART_AUTONEG);
+ if(ret_val)
+ return ret_val;
+
+ msec_delay_irq(20);
+
+ /* Now enable the transmitter */
+ ret_val = em_write_phy_reg(hw, 0x2F5B, phy_saved_data);
+
+ if(ret_val)
+ return ret_val;
+
+ hw->ffe_config_state = em_ffe_config_enabled;
+ }
+ }
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ * Set PHY to class A mode
+ * Assumes the following operations will follow to enable the new class mode.
+ * 1. Do a PHY soft reset
+ * 2. Restart auto-negotiation or force link.
+ *
+ * hw - Struct containing variables accessed by shared code
+ ****************************************************************************/
+static int32_t
+em_set_phy_mode(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t eeprom_data;
+
+ DEBUGFUNC("em_set_phy_mode");
+
+ if((hw->mac_type == em_82545_rev_3) &&
+ (hw->media_type == em_media_type_copper)) {
+ ret_val = em_read_eeprom(hw, EEPROM_PHY_CLASS_WORD, 1, &eeprom_data);
+ if(ret_val) {
+ return ret_val;
+ }
+
+ if((eeprom_data != EEPROM_RESERVED_WORD) &&
+ (eeprom_data & EEPROM_PHY_CLASS_A)) {
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x000B);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, 0x8104);
+ if(ret_val)
+ return ret_val;
+
+ hw->phy_reset_disable = FALSE;
+ }
+ }
+
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ *
+ * This function sets the lplu state according to the active flag. When
+ * activating lplu this function also disables smart speed and vise versa.
+ * lplu will not be activated unless the device autonegotiation advertisment
+ * meets standards of either 10 or 10/100 or 10/100/1000 at all duplexes.
+ * hw: Struct containing variables accessed by shared code
+ * active - true to enable lplu false to disable lplu.
+ *
+ * returns: - E1000_ERR_PHY if fail to read/write the PHY
+ * E1000_SUCCESS at any other case.
+ *
+ ****************************************************************************/
+
+int32_t
+em_set_d3_lplu_state(struct em_hw *hw,
+ boolean_t active)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+ DEBUGFUNC("em_set_d3_lplu_state");
+
+ if(hw->phy_type != em_phy_igp && hw->phy_type != em_phy_igp_2)
+ return E1000_SUCCESS;
+
+ /* During driver activity LPLU should not be used or it will attain link
+ * from the lowest speeds starting from 10Mbps. The capability is used for
+ * Dx transitions and states */
+ if(hw->mac_type == em_82541_rev_2 || hw->mac_type == em_82547_rev_2) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_GMII_FIFO, &phy_data);
+ if(ret_val)
+ return ret_val;
+ } else {
+ ret_val = em_read_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT, &phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ if(!active) {
+ if(hw->mac_type == em_82541_rev_2 ||
+ hw->mac_type == em_82547_rev_2) {
+ phy_data &= ~IGP01E1000_GMII_FLEX_SPD;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_GMII_FIFO, phy_data);
+ if(ret_val)
+ return ret_val;
+ } else {
+ phy_data &= ~IGP02E1000_PM_D3_LPLU;
+ ret_val = em_write_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT,
+ phy_data);
+ if (ret_val)
+ return ret_val;
+ }
+
+ /* LPLU and SmartSpeed are mutually exclusive. LPLU is used during
+ * Dx states where the power conservation is most important. During
+ * driver activity we should enable SmartSpeed, so performance is
+ * maintained. */
+ if (hw->smart_speed == em_smart_speed_on) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ } else if (hw->smart_speed == em_smart_speed_off) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ &phy_data);
+ if (ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+ } else if((hw->autoneg_advertised == AUTONEG_ADVERTISE_SPEED_DEFAULT) ||
+ (hw->autoneg_advertised == AUTONEG_ADVERTISE_10_ALL ) ||
+ (hw->autoneg_advertised == AUTONEG_ADVERTISE_10_100_ALL)) {
+
+ if(hw->mac_type == em_82541_rev_2 ||
+ hw->mac_type == em_82547_rev_2) {
+ phy_data |= IGP01E1000_GMII_FLEX_SPD;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_GMII_FIFO, phy_data);
+ if(ret_val)
+ return ret_val;
+ } else {
+ phy_data |= IGP02E1000_PM_D3_LPLU;
+ ret_val = em_write_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT,
+ phy_data);
+ if (ret_val)
+ return ret_val;
+ }
+
+ /* When LPLU is enabled we should disable SmartSpeed */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ }
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ *
+ * This function sets the lplu d0 state according to the active flag. When
+ * activating lplu this function also disables smart speed and vise versa.
+ * lplu will not be activated unless the device autonegotiation advertisment
+ * meets standards of either 10 or 10/100 or 10/100/1000 at all duplexes.
+ * hw: Struct containing variables accessed by shared code
+ * active - true to enable lplu false to disable lplu.
+ *
+ * returns: - E1000_ERR_PHY if fail to read/write the PHY
+ * E1000_SUCCESS at any other case.
+ *
+ ****************************************************************************/
+
+int32_t
+em_set_d0_lplu_state(struct em_hw *hw,
+ boolean_t active)
+{
+ int32_t ret_val;
+ uint16_t phy_data;
+ DEBUGFUNC("em_set_d0_lplu_state");
+
+ if(hw->mac_type <= em_82547_rev_2)
+ return E1000_SUCCESS;
+
+ ret_val = em_read_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ if (!active) {
+ phy_data &= ~IGP02E1000_PM_D0_LPLU;
+ ret_val = em_write_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT, phy_data);
+ if (ret_val)
+ return ret_val;
+
+ /* LPLU and SmartSpeed are mutually exclusive. LPLU is used during
+ * Dx states where the power conservation is most important. During
+ * driver activity we should enable SmartSpeed, so performance is
+ * maintained. */
+ if (hw->smart_speed == em_smart_speed_on) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ } else if (hw->smart_speed == em_smart_speed_off) {
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ &phy_data);
+ if (ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG,
+ phy_data);
+ if(ret_val)
+ return ret_val;
+ }
+
+
+ } else {
+
+ phy_data |= IGP02E1000_PM_D0_LPLU;
+ ret_val = em_write_phy_reg(hw, IGP02E1000_PHY_POWER_MGMT, phy_data);
+ if (ret_val)
+ return ret_val;
+
+ /* When LPLU is enabled we should disable SmartSpeed */
+ ret_val = em_read_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~IGP01E1000_PSCFR_SMART_SPEED;
+ ret_val = em_write_phy_reg(hw, IGP01E1000_PHY_PORT_CONFIG, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ }
+ return E1000_SUCCESS;
+}
+
+/******************************************************************************
+ * Change VCO speed register to improve Bit Error Rate performance of SERDES.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *****************************************************************************/
+static int32_t
+em_set_vco_speed(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t default_page = 0;
+ uint16_t phy_data;
+
+ DEBUGFUNC("em_set_vco_speed");
+
+ switch(hw->mac_type) {
+ case em_82545_rev_3:
+ case em_82546_rev_3:
+ break;
+ default:
+ return E1000_SUCCESS;
+ }
+
+ /* Set PHY register 30, page 5, bit 8 to 0 */
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, &default_page);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0005);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data &= ~M88E1000_PHY_VCO_REG_BIT8;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ /* Set PHY register 30, page 4, bit 11 to 1 */
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0004);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, &phy_data);
+ if(ret_val)
+ return ret_val;
+
+ phy_data |= M88E1000_PHY_VCO_REG_BIT11;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, phy_data);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, default_page);
+ if(ret_val)
+ return ret_val;
+
+ return E1000_SUCCESS;
+}
+
+
+/*****************************************************************************
+ * This function reads the cookie from ARC ram.
+ *
+ * returns: - E1000_SUCCESS .
+ ****************************************************************************/
+int32_t
+em_host_if_read_cookie(struct em_hw * hw, uint8_t *buffer)
+{
+ uint8_t i;
+ uint32_t offset = E1000_MNG_DHCP_COOKIE_OFFSET;
+ uint8_t length = E1000_MNG_DHCP_COOKIE_LENGTH;
+
+ length = (length >> 2);
+ offset = (offset >> 2);
+
+ for (i = 0; i < length; i++) {
+ *((uint32_t *) buffer + i) =
+ E1000_READ_REG_ARRAY_DWORD(hw, HOST_IF, offset + i);
+ }
+ return E1000_SUCCESS;
+}
+
+
+/*****************************************************************************
+ * This function checks whether the HOST IF is enabled for command operaton
+ * and also checks whether the previous command is completed.
+ * It busy waits in case of previous command is not completed.
+ *
+ * returns: - E1000_ERR_HOST_INTERFACE_COMMAND in case if is not ready or
+ * timeout
+ * - E1000_SUCCESS for success.
+ ****************************************************************************/
+int32_t
+em_mng_enable_host_if(struct em_hw * hw)
+{
+ uint32_t hicr;
+ uint8_t i;
+
+ /* Check that the host interface is enabled. */
+ hicr = E1000_READ_REG(hw, HICR);
+ if ((hicr & E1000_HICR_EN) == 0) {
+ DEBUGOUT("E1000_HOST_EN bit disabled.\n");
+ return -E1000_ERR_HOST_INTERFACE_COMMAND;
+ }
+ /* check the previous command is completed */
+ for (i = 0; i < E1000_MNG_DHCP_COMMAND_TIMEOUT; i++) {
+ hicr = E1000_READ_REG(hw, HICR);
+ if (!(hicr & E1000_HICR_C))
+ break;
+ msec_delay_irq(1);
+ }
+
+ if (i == E1000_MNG_DHCP_COMMAND_TIMEOUT) {
+ DEBUGOUT("Previous command timeout failed .\n");
+ return -E1000_ERR_HOST_INTERFACE_COMMAND;
+ }
+ return E1000_SUCCESS;
+}
+
+/*****************************************************************************
+ * This function writes the buffer content at the offset given on the host if.
+ * It also does alignment considerations to do the writes in most efficient way.
+ * Also fills up the sum of the buffer in *buffer parameter.
+ *
+ * returns - E1000_SUCCESS for success.
+ ****************************************************************************/
+int32_t
+em_mng_host_if_write(struct em_hw * hw, uint8_t *buffer,
+ uint16_t length, uint16_t offset, uint8_t *sum)
+{
+ uint8_t *tmp;
+ uint8_t *bufptr = buffer;
+ uint32_t data;
+ uint16_t remaining, i, j, prev_bytes;
+
+ /* sum = only sum of the data and it is not checksum */
+
+ if (length == 0 || offset + length > E1000_HI_MAX_MNG_DATA_LENGTH) {
+ return -E1000_ERR_PARAM;
+ }
+
+ tmp = (uint8_t *)&data;
+ prev_bytes = offset & 0x3;
+ offset &= 0xFFFC;
+ offset >>= 2;
+
+ if (prev_bytes) {
+ data = E1000_READ_REG_ARRAY_DWORD(hw, HOST_IF, offset);
+ for (j = prev_bytes; j < sizeof(uint32_t); j++) {
+ *(tmp + j) = *bufptr++;
+ *sum += *(tmp + j);
+ }
+ E1000_WRITE_REG_ARRAY_DWORD(hw, HOST_IF, offset, data);
+ length -= j - prev_bytes;
+ offset++;
+ }
+
+ remaining = length & 0x3;
+ length -= remaining;
+
+ /* Calculate length in DWORDs */
+ length >>= 2;
+
+ /* The device driver writes the relevant command block into the
+ * ram area. */
+ for (i = 0; i < length; i++) {
+ for (j = 0; j < sizeof(uint32_t); j++) {
+ *(tmp + j) = *bufptr++;
+ *sum += *(tmp + j);
+ }
+
+ E1000_WRITE_REG_ARRAY_DWORD(hw, HOST_IF, offset + i, data);
+ }
+ if (remaining) {
+ for (j = 0; j < sizeof(uint32_t); j++) {
+ if (j < remaining)
+ *(tmp + j) = *bufptr++;
+ else
+ *(tmp + j) = 0;
+
+ *sum += *(tmp + j);
+ }
+ E1000_WRITE_REG_ARRAY_DWORD(hw, HOST_IF, offset + i, data);
+ }
+
+ return E1000_SUCCESS;
+}
+
+
+/*****************************************************************************
+ * This function writes the command header after does the checksum calculation.
+ *
+ * returns - E1000_SUCCESS for success.
+ ****************************************************************************/
+int32_t
+em_mng_write_cmd_header(struct em_hw * hw,
+ struct em_host_mng_command_header * hdr)
+{
+ uint16_t i;
+ uint8_t sum;
+ uint8_t *buffer;
+
+ /* Write the whole command header structure which includes sum of
+ * the buffer */
+
+ uint16_t length = sizeof(struct em_host_mng_command_header);
+
+ sum = hdr->checksum;
+ hdr->checksum = 0;
+
+ buffer = (uint8_t *) hdr;
+ i = length;
+ while(i--)
+ sum += buffer[i];
+
+ hdr->checksum = 0 - sum;
+
+ length >>= 2;
+ /* The device driver writes the relevant command block into the ram area. */
+ for (i = 0; i < length; i++)
+ E1000_WRITE_REG_ARRAY_DWORD(hw, HOST_IF, i, *((uint32_t *) hdr + i));
+
+ return E1000_SUCCESS;
+}
+
+
+/*****************************************************************************
+ * This function indicates to ARC that a new command is pending which completes
+ * one write operation by the driver.
+ *
+ * returns - E1000_SUCCESS for success.
+ ****************************************************************************/
+int32_t
+em_mng_write_commit(
+ struct em_hw * hw)
+{
+ uint32_t hicr;
+
+ hicr = E1000_READ_REG(hw, HICR);
+ /* Setting this bit tells the ARC that a new command is pending. */
+ E1000_WRITE_REG(hw, HICR, hicr | E1000_HICR_C);
+
+ return E1000_SUCCESS;
+}
+
+
+/*****************************************************************************
+ * This function checks the mode of the firmware.
+ *
+ * returns - TRUE when the mode is IAMT or FALSE.
+ ****************************************************************************/
+boolean_t
+em_check_mng_mode(
+ struct em_hw *hw)
+{
+ uint32_t fwsm;
+
+ fwsm = E1000_READ_REG(hw, FWSM);
+
+ if((fwsm & E1000_FWSM_MODE_MASK) ==
+ (E1000_MNG_IAMT_MODE << E1000_FWSM_MODE_SHIFT))
+ return TRUE;
+
+ return FALSE;
+}
+
+
+/*****************************************************************************
+ * This function writes the dhcp info .
+ ****************************************************************************/
+int32_t
+em_mng_write_dhcp_info(struct em_hw * hw, uint8_t *buffer,
+ uint16_t length)
+{
+ int32_t ret_val;
+ struct em_host_mng_command_header hdr;
+
+ hdr.command_id = E1000_MNG_DHCP_TX_PAYLOAD_CMD;
+ hdr.command_length = length;
+ hdr.reserved1 = 0;
+ hdr.reserved2 = 0;
+ hdr.checksum = 0;
+
+ ret_val = em_mng_enable_host_if(hw);
+ if (ret_val == E1000_SUCCESS) {
+ ret_val = em_mng_host_if_write(hw, buffer, length, sizeof(hdr),
+ &(hdr.checksum));
+ if (ret_val == E1000_SUCCESS) {
+ ret_val = em_mng_write_cmd_header(hw, &hdr);
+ if (ret_val == E1000_SUCCESS)
+ ret_val = em_mng_write_commit(hw);
+ }
+ }
+ return ret_val;
+}
+
+
+/*****************************************************************************
+ * This function calculates the checksum.
+ *
+ * returns - checksum of buffer contents.
+ ****************************************************************************/
+uint8_t
+em_calculate_mng_checksum(char *buffer, uint32_t length)
+{
+ uint8_t sum = 0;
+ uint32_t i;
+
+ if (!buffer)
+ return 0;
+
+ for (i=0; i < length; i++)
+ sum += buffer[i];
+
+ return (uint8_t) (0 - sum);
+}
+
+/*****************************************************************************
+ * This function checks whether tx pkt filtering needs to be enabled or not.
+ *
+ * returns - TRUE for packet filtering or FALSE.
+ ****************************************************************************/
+boolean_t
+em_enable_tx_pkt_filtering(struct em_hw *hw)
+{
+ /* called in init as well as watchdog timer functions */
+
+ int32_t ret_val, checksum;
+ boolean_t tx_filter = FALSE;
+ struct em_host_mng_dhcp_cookie *hdr = &(hw->mng_cookie);
+ uint8_t *buffer = (uint8_t *) &(hw->mng_cookie);
+
+ if (em_check_mng_mode(hw)) {
+ ret_val = em_mng_enable_host_if(hw);
+ if (ret_val == E1000_SUCCESS) {
+ ret_val = em_host_if_read_cookie(hw, buffer);
+ if (ret_val == E1000_SUCCESS) {
+ checksum = hdr->checksum;
+ hdr->checksum = 0;
+ if ((hdr->signature == E1000_IAMT_SIGNATURE) &&
+ checksum == em_calculate_mng_checksum((char *)buffer,
+ E1000_MNG_DHCP_COOKIE_LENGTH)) {
+ if (hdr->status &
+ E1000_MNG_DHCP_COOKIE_STATUS_PARSING_SUPPORT)
+ tx_filter = TRUE;
+ } else
+ tx_filter = TRUE;
+ } else
+ tx_filter = TRUE;
+ }
+ }
+
+ hw->tx_pkt_filtering = tx_filter;
+ return tx_filter;
+}
+
+/******************************************************************************
+ * Verifies the hardware needs to allow ARPs to be processed by the host
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * returns: - TRUE/FALSE
+ *
+ *****************************************************************************/
+uint32_t
+em_enable_mng_pass_thru(struct em_hw *hw)
+{
+ uint32_t manc;
+ uint32_t fwsm, factps;
+
+ if (hw->asf_firmware_present) {
+ manc = E1000_READ_REG(hw, MANC);
+
+ if (!(manc & E1000_MANC_RCV_TCO_EN) ||
+ !(manc & E1000_MANC_EN_MAC_ADDR_FILTER))
+ return FALSE;
+ if (em_arc_subsystem_valid(hw) == TRUE) {
+ fwsm = E1000_READ_REG(hw, FWSM);
+ factps = E1000_READ_REG(hw, FACTPS);
+
+ if (((fwsm & E1000_FWSM_MODE_MASK) ==
+ (em_mng_mode_pt << E1000_FWSM_MODE_SHIFT)) &&
+ (factps & E1000_FACTPS_MNGCG))
+ return TRUE;
+ } else
+ if ((manc & E1000_MANC_SMBUS_EN) && !(manc & E1000_MANC_ASF_EN))
+ return TRUE;
+ }
+ return FALSE;
+}
+
+static int32_t
+em_polarity_reversal_workaround(struct em_hw *hw)
+{
+ int32_t ret_val;
+ uint16_t mii_status_reg;
+ uint16_t i;
+
+ /* Polarity reversal workaround for forced 10F/10H links. */
+
+ /* Disable the transmitter on the PHY */
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0019);
+ if(ret_val)
+ return ret_val;
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, 0xFFFF);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0000);
+ if(ret_val)
+ return ret_val;
+
+ /* This loop will early-out if the NO link condition has been met. */
+ for(i = PHY_FORCE_TIME; i > 0; i--) {
+ /* Read the MII Status Register and wait for Link Status bit
+ * to be clear.
+ */
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ if((mii_status_reg & ~MII_SR_LINK_STATUS) == 0) break;
+ msec_delay_irq(100);
+ }
+
+ /* Recommended delay time after link has been lost */
+ msec_delay_irq(1000);
+
+ /* Now we will re-enable th transmitter on the PHY */
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0019);
+ if(ret_val)
+ return ret_val;
+ msec_delay_irq(50);
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, 0xFFF0);
+ if(ret_val)
+ return ret_val;
+ msec_delay_irq(50);
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, 0xFF00);
+ if(ret_val)
+ return ret_val;
+ msec_delay_irq(50);
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_GEN_CONTROL, 0x0000);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_write_phy_reg(hw, M88E1000_PHY_PAGE_SELECT, 0x0000);
+ if(ret_val)
+ return ret_val;
+
+ /* This loop will early-out if the link condition has been met. */
+ for(i = PHY_FORCE_TIME; i > 0; i--) {
+ /* Read the MII Status Register and wait for Link Status bit
+ * to be set.
+ */
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ ret_val = em_read_phy_reg(hw, PHY_STATUS, &mii_status_reg);
+ if(ret_val)
+ return ret_val;
+
+ if(mii_status_reg & MII_SR_LINK_STATUS) break;
+ msec_delay_irq(100);
+ }
+ return E1000_SUCCESS;
+}
+
+/***************************************************************************
+ *
+ * Disables PCI-Express master access.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - none.
+ *
+ ***************************************************************************/
+void
+em_set_pci_express_master_disable(struct em_hw *hw)
+{
+ uint32_t ctrl;
+
+ DEBUGFUNC("em_set_pci_express_master_disable");
+
+ if (hw->bus_type != em_bus_type_pci_express)
+ return;
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+ ctrl |= E1000_CTRL_GIO_MASTER_DISABLE;
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+}
+
+/***************************************************************************
+ *
+ * Enables PCI-Express master access.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - none.
+ *
+ ***************************************************************************/
+void
+em_enable_pciex_master(struct em_hw *hw)
+{
+ uint32_t ctrl;
+
+ DEBUGFUNC("em_enable_pciex_master");
+
+ if (hw->bus_type != em_bus_type_pci_express)
+ return;
+
+ ctrl = E1000_READ_REG(hw, CTRL);
+ ctrl &= ~E1000_CTRL_GIO_MASTER_DISABLE;
+ E1000_WRITE_REG(hw, CTRL, ctrl);
+}
+
+/*******************************************************************************
+ *
+ * Disables PCI-Express master access and verifies there are no pending requests
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_ERR_MASTER_REQUESTS_PENDING if master disable bit hasn't
+ * caused the master requests to be disabled.
+ * E1000_SUCCESS master requests disabled.
+ *
+ ******************************************************************************/
+int32_t
+em_disable_pciex_master(struct em_hw *hw)
+{
+ int32_t timeout = MASTER_DISABLE_TIMEOUT; /* 80ms */
+
+ DEBUGFUNC("em_disable_pciex_master");
+
+ if (hw->bus_type != em_bus_type_pci_express)
+ return E1000_SUCCESS;
+
+ em_set_pci_express_master_disable(hw);
+
+ while(timeout) {
+ if(!(E1000_READ_REG(hw, STATUS) & E1000_STATUS_GIO_MASTER_ENABLE))
+ break;
+ else
+ usec_delay(100);
+ timeout--;
+ }
+
+ if(!timeout) {
+ DEBUGOUT("Master requests are pending.\n");
+ return -E1000_ERR_MASTER_REQUESTS_PENDING;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/*******************************************************************************
+ *
+ * Check for EEPROM Auto Read bit done.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_ERR_RESET if fail to reset MAC
+ * E1000_SUCCESS at any other case.
+ *
+ ******************************************************************************/
+int32_t
+em_get_auto_rd_done(struct em_hw *hw)
+{
+ int32_t timeout = AUTO_READ_DONE_TIMEOUT;
+
+ DEBUGFUNC("em_get_auto_rd_done");
+
+ switch (hw->mac_type) {
+ default:
+ msec_delay(5);
+ break;
+ case em_82573:
+ while(timeout) {
+ if (E1000_READ_REG(hw, EECD) & E1000_EECD_AUTO_RD) break;
+ else msec_delay(1);
+ timeout--;
+ }
+
+ if(!timeout) {
+ DEBUGOUT("Auto read by HW from EEPROM has not completed.\n");
+ return -E1000_ERR_RESET;
+ }
+ break;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/***************************************************************************
+ * Checks if the PHY configuration is done
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_ERR_RESET if fail to reset MAC
+ * E1000_SUCCESS at any other case.
+ *
+ ***************************************************************************/
+int32_t
+em_get_phy_cfg_done(struct em_hw *hw)
+{
+ DEBUGFUNC("em_get_phy_cfg_done");
+
+ /* Simply wait for 10ms */
+ msec_delay(10);
+
+ return E1000_SUCCESS;
+}
+
+/***************************************************************************
+ *
+ * Using the combination of SMBI and SWESMBI semaphore bits when resetting
+ * adapter or Eeprom access.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_ERR_EEPROM if fail to access EEPROM.
+ * E1000_SUCCESS at any other case.
+ *
+ ***************************************************************************/
+int32_t
+em_get_hw_eeprom_semaphore(struct em_hw *hw)
+{
+ int32_t timeout;
+ uint32_t swsm;
+
+ DEBUGFUNC("em_get_hw_eeprom_semaphore");
+
+ if(!hw->eeprom_semaphore_present)
+ return E1000_SUCCESS;
+
+
+ /* Get the FW semaphore. */
+ timeout = hw->eeprom.word_size + 1;
+ while(timeout) {
+ swsm = E1000_READ_REG(hw, SWSM);
+ swsm |= E1000_SWSM_SWESMBI;
+ E1000_WRITE_REG(hw, SWSM, swsm);
+ /* if we managed to set the bit we got the semaphore. */
+ swsm = E1000_READ_REG(hw, SWSM);
+ if(swsm & E1000_SWSM_SWESMBI)
+ break;
+
+ usec_delay(50);
+ timeout--;
+ }
+
+ if(!timeout) {
+ /* Release semaphores */
+ em_put_hw_eeprom_semaphore(hw);
+ DEBUGOUT("Driver can't access the Eeprom - SWESMBI bit is set.\n");
+ return -E1000_ERR_EEPROM;
+ }
+
+ return E1000_SUCCESS;
+}
+
+/***************************************************************************
+ * This function clears HW semaphore bits.
+ *
+ * hw: Struct containing variables accessed by shared code
+ *
+ * returns: - None.
+ *
+ ***************************************************************************/
+void
+em_put_hw_eeprom_semaphore(struct em_hw *hw)
+{
+ uint32_t swsm;
+
+ DEBUGFUNC("em_put_hw_eeprom_semaphore");
+
+ if(!hw->eeprom_semaphore_present)
+ return;
+
+ swsm = E1000_READ_REG(hw, SWSM);
+ /* Release both semaphores. */
+ swsm &= ~(E1000_SWSM_SMBI | E1000_SWSM_SWESMBI);
+ E1000_WRITE_REG(hw, SWSM, swsm);
+}
+
+/******************************************************************************
+ * Checks if PHY reset is blocked due to SOL/IDER session, for example.
+ * Returning E1000_BLK_PHY_RESET isn't necessarily an error. But it's up to
+ * the caller to figure out how to deal with it.
+ *
+ * hw - Struct containing variables accessed by shared code
+ *
+ * returns: - E1000_BLK_PHY_RESET
+ * E1000_SUCCESS
+ *
+ *****************************************************************************/
+int32_t
+em_check_phy_reset_block(struct em_hw *hw)
+{
+ uint32_t manc = 0;
+ if(hw->mac_type > em_82547_rev_2)
+ manc = E1000_READ_REG(hw, MANC);
+ return (manc & E1000_MANC_BLK_PHY_RST_ON_IDE) ?
+ E1000_BLK_PHY_RESET : E1000_SUCCESS;
+}
+
+uint8_t
+em_arc_subsystem_valid(struct em_hw *hw)
+{
+ uint32_t fwsm;
+
+ /* On 8257x silicon, registers in the range of 0x8800 - 0x8FFC
+ * may not be provided a DMA clock when no manageability features are
+ * enabled. We do not want to perform any reads/writes to these registers
+ * if this is the case. We read FWSM to determine the manageability mode.
+ */
+ switch (hw->mac_type) {
+ case em_82573:
+ fwsm = E1000_READ_REG(hw, FWSM);
+ if((fwsm & E1000_FWSM_MODE_MASK) != 0)
+ return TRUE;
+ break;
+ default:
+ break;
+ }
+ return FALSE;
+}
+
+
+
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em_hw.h b/bsps/powerpc/beatnik/net/if_em/if_em_hw.h
new file mode 100644
index 0000000..98f4c5e
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em_hw.h
@@ -0,0 +1,2678 @@
+/*******************************************************************************
+
+ Copyright (c) 2001-2005, Intel Corporation
+ 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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ POSSIBILITY OF SUCH DAMAGE.
+
+*******************************************************************************/
+
+/*$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/if_em_hw.h,v 1.15 2005/05/26 23:32:02 tackerman Exp $*/
+/* if_em_hw.h
+ * Structures, enums, and macros for the MAC
+ */
+
+#ifndef _EM_HW_H_
+#define _EM_HW_H_
+
+#ifndef __rtems__
+#include <dev/em/if_em_osdep.h>
+#else
+#include "if_em_osdep.h"
+#endif
+
+
+/* Forward declarations of structures used by the shared code */
+struct em_hw;
+struct em_hw_stats;
+
+/* Enumerated types specific to the e1000 hardware */
+/* Media Access Controlers */
+typedef enum {
+ em_undefined = 0,
+ em_82542_rev2_0,
+ em_82542_rev2_1,
+ em_82543,
+ em_82544,
+ em_82540,
+ em_82545,
+ em_82545_rev_3,
+ em_82546,
+ em_82546_rev_3,
+ em_82541,
+ em_82541_rev_2,
+ em_82547,
+ em_82547_rev_2,
+ em_82573,
+ em_num_macs
+} em_mac_type;
+
+typedef enum {
+ em_eeprom_uninitialized = 0,
+ em_eeprom_spi,
+ em_eeprom_microwire,
+ em_eeprom_flash,
+ em_num_eeprom_types
+} em_eeprom_type;
+
+/* Media Types */
+typedef enum {
+ em_media_type_copper = 0,
+ em_media_type_fiber = 1,
+ em_media_type_internal_serdes = 2,
+ em_num_media_types
+} em_media_type;
+
+typedef enum {
+ em_10_half = 0,
+ em_10_full = 1,
+ em_100_half = 2,
+ em_100_full = 3
+} em_speed_duplex_type;
+
+/* Flow Control Settings */
+typedef enum {
+ em_fc_none = 0,
+ em_fc_rx_pause = 1,
+ em_fc_tx_pause = 2,
+ em_fc_full = 3,
+ em_fc_default = 0xFF
+} em_fc_type;
+
+/* PCI bus types */
+typedef enum {
+ em_bus_type_unknown = 0,
+ em_bus_type_pci,
+ em_bus_type_pcix,
+ em_bus_type_pci_express,
+ em_bus_type_reserved
+} em_bus_type;
+
+/* PCI bus speeds */
+typedef enum {
+ em_bus_speed_unknown = 0,
+ em_bus_speed_33,
+ em_bus_speed_66,
+ em_bus_speed_100,
+ em_bus_speed_120,
+ em_bus_speed_133,
+ em_bus_speed_2500,
+ em_bus_speed_reserved
+} em_bus_speed;
+
+/* PCI bus widths */
+typedef enum {
+ em_bus_width_unknown = 0,
+ em_bus_width_32,
+ em_bus_width_64,
+ em_bus_width_pciex_1,
+ em_bus_width_pciex_4,
+ em_bus_width_reserved
+} em_bus_width;
+
+/* PHY status info structure and supporting enums */
+typedef enum {
+ em_cable_length_50 = 0,
+ em_cable_length_50_80,
+ em_cable_length_80_110,
+ em_cable_length_110_140,
+ em_cable_length_140,
+ em_cable_length_undefined = 0xFF
+} em_cable_length;
+
+typedef enum {
+ em_igp_cable_length_10 = 10,
+ em_igp_cable_length_20 = 20,
+ em_igp_cable_length_30 = 30,
+ em_igp_cable_length_40 = 40,
+ em_igp_cable_length_50 = 50,
+ em_igp_cable_length_60 = 60,
+ em_igp_cable_length_70 = 70,
+ em_igp_cable_length_80 = 80,
+ em_igp_cable_length_90 = 90,
+ em_igp_cable_length_100 = 100,
+ em_igp_cable_length_110 = 110,
+ em_igp_cable_length_120 = 120,
+ em_igp_cable_length_130 = 130,
+ em_igp_cable_length_140 = 140,
+ em_igp_cable_length_150 = 150,
+ em_igp_cable_length_160 = 160,
+ em_igp_cable_length_170 = 170,
+ em_igp_cable_length_180 = 180
+} em_igp_cable_length;
+
+typedef enum {
+ em_10bt_ext_dist_enable_normal = 0,
+ em_10bt_ext_dist_enable_lower,
+ em_10bt_ext_dist_enable_undefined = 0xFF
+} em_10bt_ext_dist_enable;
+
+typedef enum {
+ em_rev_polarity_normal = 0,
+ em_rev_polarity_reversed,
+ em_rev_polarity_undefined = 0xFF
+} em_rev_polarity;
+
+typedef enum {
+ em_downshift_normal = 0,
+ em_downshift_activated,
+ em_downshift_undefined = 0xFF
+} em_downshift;
+
+typedef enum {
+ em_smart_speed_default = 0,
+ em_smart_speed_on,
+ em_smart_speed_off
+} em_smart_speed;
+
+typedef enum {
+ em_polarity_reversal_enabled = 0,
+ em_polarity_reversal_disabled,
+ em_polarity_reversal_undefined = 0xFF
+} em_polarity_reversal;
+
+typedef enum {
+ em_auto_x_mode_manual_mdi = 0,
+ em_auto_x_mode_manual_mdix,
+ em_auto_x_mode_auto1,
+ em_auto_x_mode_auto2,
+ em_auto_x_mode_undefined = 0xFF
+} em_auto_x_mode;
+
+typedef enum {
+ em_1000t_rx_status_not_ok = 0,
+ em_1000t_rx_status_ok,
+ em_1000t_rx_status_undefined = 0xFF
+} em_1000t_rx_status;
+
+typedef enum {
+ em_phy_m88 = 0,
+ em_phy_igp,
+ em_phy_igp_2,
+ em_phy_undefined = 0xFF
+} em_phy_type;
+
+typedef enum {
+ em_ms_hw_default = 0,
+ em_ms_force_master,
+ em_ms_force_slave,
+ em_ms_auto
+} em_ms_type;
+
+typedef enum {
+ em_ffe_config_enabled = 0,
+ em_ffe_config_active,
+ em_ffe_config_blocked
+} em_ffe_config;
+
+typedef enum {
+ em_dsp_config_disabled = 0,
+ em_dsp_config_enabled,
+ em_dsp_config_activated,
+ em_dsp_config_undefined = 0xFF
+} em_dsp_config;
+
+struct em_phy_info {
+ em_cable_length cable_length;
+ em_10bt_ext_dist_enable extended_10bt_distance;
+ em_rev_polarity cable_polarity;
+ em_downshift downshift;
+ em_polarity_reversal polarity_correction;
+ em_auto_x_mode mdix_mode;
+ em_1000t_rx_status local_rx;
+ em_1000t_rx_status remote_rx;
+};
+
+struct em_phy_stats {
+ uint32_t idle_errors;
+ uint32_t receive_errors;
+};
+
+struct em_eeprom_info {
+ em_eeprom_type type;
+ uint16_t word_size;
+ uint16_t opcode_bits;
+ uint16_t address_bits;
+ uint16_t delay_usec;
+ uint16_t page_size;
+ boolean_t use_eerd;
+ boolean_t use_eewr;
+};
+
+/* Flex ASF Information */
+#define E1000_HOST_IF_MAX_SIZE 2048
+
+typedef enum {
+ em_byte_align = 0,
+ em_word_align = 1,
+ em_dword_align = 2
+} em_align_type;
+
+
+
+/* Error Codes */
+#define E1000_SUCCESS 0
+#define E1000_ERR_EEPROM 1
+#define E1000_ERR_PHY 2
+#define E1000_ERR_CONFIG 3
+#define E1000_ERR_PARAM 4
+#define E1000_ERR_MAC_TYPE 5
+#define E1000_ERR_PHY_TYPE 6
+#define E1000_ERR_RESET 9
+#define E1000_ERR_MASTER_REQUESTS_PENDING 10
+#define E1000_ERR_HOST_INTERFACE_COMMAND 11
+#define E1000_BLK_PHY_RESET 12
+
+/* Function prototypes */
+/* Initialization */
+int32_t em_reset_hw(struct em_hw *hw);
+int32_t em_init_hw(struct em_hw *hw);
+int32_t em_id_led_init(struct em_hw * hw);
+int32_t em_set_mac_type(struct em_hw *hw);
+void em_set_media_type(struct em_hw *hw);
+
+/* Link Configuration */
+int32_t em_setup_link(struct em_hw *hw);
+int32_t em_phy_setup_autoneg(struct em_hw *hw);
+void em_config_collision_dist(struct em_hw *hw);
+int32_t em_config_fc_after_link_up(struct em_hw *hw);
+int32_t em_check_for_link(struct em_hw *hw);
+int32_t em_get_speed_and_duplex(struct em_hw *hw, uint16_t * speed, uint16_t * duplex);
+int32_t em_wait_autoneg(struct em_hw *hw);
+int32_t em_force_mac_fc(struct em_hw *hw);
+
+/* PHY */
+int32_t em_read_phy_reg(struct em_hw *hw, uint32_t reg_addr, uint16_t *phy_data);
+int32_t em_write_phy_reg(struct em_hw *hw, uint32_t reg_addr, uint16_t data);
+int32_t em_phy_hw_reset(struct em_hw *hw);
+int32_t em_phy_reset(struct em_hw *hw);
+int32_t em_detect_gig_phy(struct em_hw *hw);
+int32_t em_phy_get_info(struct em_hw *hw, struct em_phy_info *phy_info);
+int32_t em_phy_m88_get_info(struct em_hw *hw, struct em_phy_info *phy_info);
+int32_t em_phy_igp_get_info(struct em_hw *hw, struct em_phy_info *phy_info);
+int32_t em_get_cable_length(struct em_hw *hw, uint16_t *min_length, uint16_t *max_length);
+int32_t em_check_polarity(struct em_hw *hw, uint16_t *polarity);
+int32_t em_check_downshift(struct em_hw *hw);
+int32_t em_validate_mdi_setting(struct em_hw *hw);
+
+/* EEPROM Functions */
+int32_t em_init_eeprom_params(struct em_hw *hw);
+boolean_t em_is_onboard_nvm_eeprom(struct em_hw *hw);
+int32_t em_read_eeprom_eerd(struct em_hw *hw, uint16_t offset, uint16_t words, uint16_t *data);
+int32_t em_write_eeprom_eewr(struct em_hw *hw, uint16_t offset, uint16_t words, uint16_t *data);
+int32_t em_poll_eerd_eewr_done(struct em_hw *hw, int eerd);
+
+/* MNG HOST IF functions */
+uint32_t em_enable_mng_pass_thru(struct em_hw *hw);
+
+#define E1000_MNG_DHCP_TX_PAYLOAD_CMD 64
+#define E1000_HI_MAX_MNG_DATA_LENGTH 0x6F8 /* Host Interface data length */
+
+#define E1000_MNG_DHCP_COMMAND_TIMEOUT 10 /* Time in ms to process MNG command */
+#define E1000_MNG_DHCP_COOKIE_OFFSET 0x6F0 /* Cookie offset */
+#define E1000_MNG_DHCP_COOKIE_LENGTH 0x10 /* Cookie length */
+#define E1000_MNG_IAMT_MODE 0x3
+#define E1000_IAMT_SIGNATURE 0x544D4149 /* Intel(R) Active Management Technology signature */
+
+#define E1000_MNG_DHCP_COOKIE_STATUS_PARSING_SUPPORT 0x1 /* DHCP parsing enabled */
+#define E1000_MNG_DHCP_COOKIE_STATUS_VLAN_SUPPORT 0x2 /* DHCP parsing enabled */
+#define E1000_VFTA_ENTRY_SHIFT 0x5
+#define E1000_VFTA_ENTRY_MASK 0x7F
+#define E1000_VFTA_ENTRY_BIT_SHIFT_MASK 0x1F
+
+struct em_host_mng_command_header {
+ uint8_t command_id;
+ uint8_t checksum;
+ uint16_t reserved1;
+ uint16_t reserved2;
+ uint16_t command_length;
+};
+
+struct em_host_mng_command_info {
+ struct em_host_mng_command_header command_header; /* Command Head/Command Result Head has 4 bytes */
+ uint8_t command_data[E1000_HI_MAX_MNG_DATA_LENGTH]; /* Command data can length 0..0x658*/
+};
+#ifdef __BIG_ENDIAN
+struct em_host_mng_dhcp_cookie{
+ uint32_t signature;
+ uint16_t vlan_id;
+ uint8_t reserved0;
+ uint8_t status;
+ uint32_t reserved1;
+ uint8_t checksum;
+ uint8_t reserved3;
+ uint16_t reserved2;
+};
+#else
+struct em_host_mng_dhcp_cookie{
+ uint32_t signature;
+ uint8_t status;
+ uint8_t reserved0;
+ uint16_t vlan_id;
+ uint32_t reserved1;
+ uint16_t reserved2;
+ uint8_t reserved3;
+ uint8_t checksum;
+};
+#endif
+
+int32_t em_mng_write_dhcp_info(struct em_hw *hw, uint8_t *buffer,
+ uint16_t length);
+boolean_t em_check_mng_mode(struct em_hw *hw);
+boolean_t em_enable_tx_pkt_filtering(struct em_hw *hw);
+int32_t em_mng_enable_host_if(struct em_hw *hw);
+int32_t em_mng_host_if_write(struct em_hw *hw, uint8_t *buffer,
+ uint16_t length, uint16_t offset, uint8_t *sum);
+int32_t em_mng_write_cmd_header(struct em_hw* hw,
+ struct em_host_mng_command_header* hdr);
+
+int32_t em_mng_write_commit(struct em_hw *hw);
+
+int32_t em_read_eeprom(struct em_hw *hw, uint16_t reg, uint16_t words, uint16_t *data);
+int32_t em_validate_eeprom_checksum(struct em_hw *hw);
+int32_t em_update_eeprom_checksum(struct em_hw *hw);
+int32_t em_write_eeprom(struct em_hw *hw, uint16_t reg, uint16_t words, uint16_t *data);
+int32_t em_read_part_num(struct em_hw *hw, uint32_t * part_num);
+int32_t em_read_mac_addr(struct em_hw * hw);
+int32_t em_swfw_sync_acquire(struct em_hw *hw, uint16_t mask);
+void em_swfw_sync_release(struct em_hw *hw, uint16_t mask);
+
+/* Filters (multicast, vlan, receive) */
+void em_init_rx_addrs(struct em_hw *hw);
+void em_mc_addr_list_update(struct em_hw *hw, uint8_t * mc_addr_list, uint32_t mc_addr_count, uint32_t pad, uint32_t rar_used_count);
+uint32_t em_hash_mc_addr(struct em_hw *hw, uint8_t * mc_addr);
+void em_mta_set(struct em_hw *hw, uint32_t hash_value);
+void em_rar_set(struct em_hw *hw, uint8_t * mc_addr, uint32_t rar_index);
+void em_write_vfta(struct em_hw *hw, uint32_t offset, uint32_t value);
+void em_clear_vfta(struct em_hw *hw);
+
+/* LED functions */
+int32_t em_setup_led(struct em_hw *hw);
+int32_t em_cleanup_led(struct em_hw *hw);
+int32_t em_led_on(struct em_hw *hw);
+int32_t em_led_off(struct em_hw *hw);
+
+/* Adaptive IFS Functions */
+
+/* Everything else */
+void em_clear_hw_cntrs(struct em_hw *hw);
+void em_reset_adaptive(struct em_hw *hw);
+void em_update_adaptive(struct em_hw *hw);
+void em_tbi_adjust_stats(struct em_hw *hw, struct em_hw_stats *stats, uint32_t frame_len, uint8_t * mac_addr);
+void em_get_bus_info(struct em_hw *hw);
+void em_pci_set_mwi(struct em_hw *hw);
+void em_pci_clear_mwi(struct em_hw *hw);
+void em_read_pci_cfg(struct em_hw *hw, uint32_t reg, uint16_t * value);
+void em_write_pci_cfg(struct em_hw *hw, uint32_t reg, uint16_t * value);
+/* Port I/O is only supported on 82544 and newer */
+uint32_t em_io_read(struct em_hw *hw, unsigned long port);
+uint32_t em_read_reg_io(struct em_hw *hw, uint32_t offset);
+void em_io_write(struct em_hw *hw, unsigned long port, uint32_t value);
+void em_write_reg_io(struct em_hw *hw, uint32_t offset, uint32_t value);
+int32_t em_config_dsp_after_link_change(struct em_hw *hw, boolean_t link_up);
+int32_t em_set_d3_lplu_state(struct em_hw *hw, boolean_t active);
+int32_t em_set_d0_lplu_state(struct em_hw *hw, boolean_t active);
+void em_set_pci_express_master_disable(struct em_hw *hw);
+void em_enable_pciex_master(struct em_hw *hw);
+int32_t em_disable_pciex_master(struct em_hw *hw);
+int32_t em_get_auto_rd_done(struct em_hw *hw);
+int32_t em_get_phy_cfg_done(struct em_hw *hw);
+int32_t em_get_software_semaphore(struct em_hw *hw);
+void em_release_software_semaphore(struct em_hw *hw);
+int32_t em_check_phy_reset_block(struct em_hw *hw);
+int32_t em_get_hw_eeprom_semaphore(struct em_hw *hw);
+void em_put_hw_eeprom_semaphore(struct em_hw *hw);
+int32_t em_commit_shadow_ram(struct em_hw *hw);
+uint8_t em_arc_subsystem_valid(struct em_hw *hw);
+
+#define E1000_READ_REG_IO(a, reg) \
+ em_read_reg_io((a), E1000_##reg)
+#define E1000_WRITE_REG_IO(a, reg, val) \
+ em_write_reg_io((a), E1000_##reg, val)
+
+/* PCI Device IDs */
+#define E1000_DEV_ID_82542 0x1000
+#define E1000_DEV_ID_82543GC_FIBER 0x1001
+#define E1000_DEV_ID_82543GC_COPPER 0x1004
+#define E1000_DEV_ID_82544EI_COPPER 0x1008
+#define E1000_DEV_ID_82544EI_FIBER 0x1009
+#define E1000_DEV_ID_82544GC_COPPER 0x100C
+#define E1000_DEV_ID_82544GC_LOM 0x100D
+#define E1000_DEV_ID_82540EM 0x100E
+#define E1000_DEV_ID_82541ER_LOM 0x1014
+#define E1000_DEV_ID_82540EM_LOM 0x1015
+#define E1000_DEV_ID_82540EP_LOM 0x1016
+#define E1000_DEV_ID_82540EP 0x1017
+#define E1000_DEV_ID_82540EP_LP 0x101E
+#define E1000_DEV_ID_82545EM_COPPER 0x100F
+#define E1000_DEV_ID_82545EM_FIBER 0x1011
+#define E1000_DEV_ID_82545GM_COPPER 0x1026
+#define E1000_DEV_ID_82545GM_FIBER 0x1027
+#define E1000_DEV_ID_82545GM_SERDES 0x1028
+#define E1000_DEV_ID_82546EB_COPPER 0x1010
+#define E1000_DEV_ID_82546EB_FIBER 0x1012
+#define E1000_DEV_ID_82546EB_QUAD_COPPER 0x101D
+#define E1000_DEV_ID_82541EI 0x1013
+#define E1000_DEV_ID_82541EI_MOBILE 0x1018
+#define E1000_DEV_ID_82541ER 0x1078
+#define E1000_DEV_ID_82547GI 0x1075
+#define E1000_DEV_ID_82541GI 0x1076
+#define E1000_DEV_ID_82541GI_MOBILE 0x1077
+#define E1000_DEV_ID_82541GI_LF 0x107C
+#define E1000_DEV_ID_82546GB_COPPER 0x1079
+#define E1000_DEV_ID_82546GB_FIBER 0x107A
+#define E1000_DEV_ID_82546GB_SERDES 0x107B
+#define E1000_DEV_ID_82546GB_PCIE 0x108A
+#define E1000_DEV_ID_82547EI 0x1019
+#define E1000_DEV_ID_82547EI_MOBILE 0x101A
+#define E1000_DEV_ID_82573E 0x108B
+#define E1000_DEV_ID_82573E_IAMT 0x108C
+
+#define E1000_DEV_ID_82546GB_QUAD_COPPER 0x1099
+
+#define NODE_ADDRESS_SIZE 6
+#define ETH_LENGTH_OF_ADDRESS 6
+
+/* MAC decode size is 128K - This is the size of BAR0 */
+#define MAC_DECODE_SIZE (128 * 1024)
+
+#define E1000_82542_2_0_REV_ID 2
+#define E1000_82542_2_1_REV_ID 3
+#define E1000_REVISION_0 0
+#define E1000_REVISION_1 1
+#define E1000_REVISION_2 2
+#define E1000_REVISION_3 3
+
+#define SPEED_10 10
+#define SPEED_100 100
+#define SPEED_1000 1000
+#define HALF_DUPLEX 1
+#define FULL_DUPLEX 2
+
+/* The sizes (in bytes) of a ethernet packet */
+#define ENET_HEADER_SIZE 14
+#define MAXIMUM_ETHERNET_FRAME_SIZE 1518 /* With FCS */
+#define MINIMUM_ETHERNET_FRAME_SIZE 64 /* With FCS */
+#define ETHERNET_FCS_SIZE 4
+#define MAXIMUM_ETHERNET_PACKET_SIZE \
+ (MAXIMUM_ETHERNET_FRAME_SIZE - ETHERNET_FCS_SIZE)
+#define MINIMUM_ETHERNET_PACKET_SIZE \
+ (MINIMUM_ETHERNET_FRAME_SIZE - ETHERNET_FCS_SIZE)
+#define CRC_LENGTH ETHERNET_FCS_SIZE
+#define MAX_JUMBO_FRAME_SIZE 0x3F00
+
+
+/* 802.1q VLAN Packet Sizes */
+#define VLAN_TAG_SIZE 4 /* 802.3ac tag (not DMAed) */
+
+/* Ethertype field values */
+#define ETHERNET_IEEE_VLAN_TYPE 0x8100 /* 802.3ac packet */
+#define ETHERNET_IP_TYPE 0x0800 /* IP packets */
+#define ETHERNET_ARP_TYPE 0x0806 /* Address Resolution Protocol (ARP) */
+
+/* Packet Header defines */
+#define IP_PROTOCOL_TCP 6
+#define IP_PROTOCOL_UDP 0x11
+
+/* This defines the bits that are set in the Interrupt Mask
+ * Set/Read Register. Each bit is documented below:
+ * o RXDMT0 = Receive Descriptor Minimum Threshold hit (ring 0)
+ * o RXSEQ = Receive Sequence Error
+ */
+#define POLL_IMS_ENABLE_MASK ( \
+ E1000_IMS_RXDMT0 | \
+ E1000_IMS_RXSEQ)
+
+/* This defines the bits that are set in the Interrupt Mask
+ * Set/Read Register. Each bit is documented below:
+ * o RXT0 = Receiver Timer Interrupt (ring 0)
+ * o TXDW = Transmit Descriptor Written Back
+ * o RXDMT0 = Receive Descriptor Minimum Threshold hit (ring 0)
+ * o RXSEQ = Receive Sequence Error
+ * o LSC = Link Status Change
+ */
+#define IMS_ENABLE_MASK ( \
+ E1000_IMS_RXT0 | \
+ E1000_IMS_TXDW | \
+ E1000_IMS_RXDMT0 | \
+ E1000_IMS_RXSEQ | \
+ E1000_IMS_LSC)
+
+
+/* Number of high/low register pairs in the RAR. The RAR (Receive Address
+ * Registers) holds the directed and multicast addresses that we monitor. We
+ * reserve one of these spots for our directed address, allowing us room for
+ * E1000_RAR_ENTRIES - 1 multicast addresses.
+ */
+#define E1000_RAR_ENTRIES 15
+
+#define MIN_NUMBER_OF_DESCRIPTORS 8
+#define MAX_NUMBER_OF_DESCRIPTORS 0xFFF8
+
+/* Receive Descriptor */
+struct em_rx_desc {
+ uint64_t buffer_addr; /* Address of the descriptor's data buffer */
+ uint16_t length; /* Length of data DMAed into data buffer */
+ uint16_t csum; /* Packet checksum */
+ uint8_t status; /* Descriptor status */
+ uint8_t errors; /* Descriptor Errors */
+ uint16_t special;
+};
+
+/* Receive Descriptor - Extended */
+union em_rx_desc_extended {
+ struct {
+ uint64_t buffer_addr;
+ uint64_t reserved;
+ } read;
+ struct {
+ struct {
+ uint32_t mrq; /* Multiple Rx Queues */
+ union {
+ uint32_t rss; /* RSS Hash */
+ struct {
+ uint16_t ip_id; /* IP id */
+ uint16_t csum; /* Packet Checksum */
+ } csum_ip;
+ } hi_dword;
+ } lower;
+ struct {
+ uint32_t status_error; /* ext status/error */
+ uint16_t length;
+ uint16_t vlan; /* VLAN tag */
+ } upper;
+ } wb; /* writeback */
+};
+
+#define MAX_PS_BUFFERS 4
+/* Receive Descriptor - Packet Split */
+union em_rx_desc_packet_split {
+ struct {
+ /* one buffer for protocol header(s), three data buffers */
+ uint64_t buffer_addr[MAX_PS_BUFFERS];
+ } read;
+ struct {
+ struct {
+ uint32_t mrq; /* Multiple Rx Queues */
+ union {
+ uint32_t rss; /* RSS Hash */
+ struct {
+ uint16_t ip_id; /* IP id */
+ uint16_t csum; /* Packet Checksum */
+ } csum_ip;
+ } hi_dword;
+ } lower;
+ struct {
+ uint32_t status_error; /* ext status/error */
+ uint16_t length0; /* length of buffer 0 */
+ uint16_t vlan; /* VLAN tag */
+ } middle;
+ struct {
+ uint16_t header_status;
+ uint16_t length[3]; /* length of buffers 1-3 */
+ } upper;
+ uint64_t reserved;
+ } wb; /* writeback */
+};
+
+/* Receive Decriptor bit definitions */
+#define E1000_RXD_STAT_DD 0x01 /* Descriptor Done */
+#define E1000_RXD_STAT_EOP 0x02 /* End of Packet */
+#define E1000_RXD_STAT_IXSM 0x04 /* Ignore checksum */
+#define E1000_RXD_STAT_VP 0x08 /* IEEE VLAN Packet */
+#define E1000_RXD_STAT_UDPCS 0x10 /* UDP xsum caculated */
+#define E1000_RXD_STAT_TCPCS 0x20 /* TCP xsum calculated */
+#define E1000_RXD_STAT_IPCS 0x40 /* IP xsum calculated */
+#define E1000_RXD_STAT_PIF 0x80 /* passed in-exact filter */
+#define E1000_RXD_STAT_IPIDV 0x200 /* IP identification valid */
+#define E1000_RXD_STAT_UDPV 0x400 /* Valid UDP checksum */
+#define E1000_RXD_STAT_ACK 0x8000 /* ACK Packet indication */
+#define E1000_RXD_ERR_CE 0x01 /* CRC Error */
+#define E1000_RXD_ERR_SE 0x02 /* Symbol Error */
+#define E1000_RXD_ERR_SEQ 0x04 /* Sequence Error */
+#define E1000_RXD_ERR_CXE 0x10 /* Carrier Extension Error */
+#define E1000_RXD_ERR_TCPE 0x20 /* TCP/UDP Checksum Error */
+#define E1000_RXD_ERR_IPE 0x40 /* IP Checksum Error */
+#define E1000_RXD_ERR_RXE 0x80 /* Rx Data Error */
+#define E1000_RXD_SPC_VLAN_MASK 0x0FFF /* VLAN ID is in lower 12 bits */
+#define E1000_RXD_SPC_PRI_MASK 0xE000 /* Priority is in upper 3 bits */
+#define E1000_RXD_SPC_PRI_SHIFT 13
+#define E1000_RXD_SPC_CFI_MASK 0x1000 /* CFI is bit 12 */
+#define E1000_RXD_SPC_CFI_SHIFT 12
+
+#define E1000_RXDEXT_STATERR_CE 0x01000000
+#define E1000_RXDEXT_STATERR_SE 0x02000000
+#define E1000_RXDEXT_STATERR_SEQ 0x04000000
+#define E1000_RXDEXT_STATERR_CXE 0x10000000
+#define E1000_RXDEXT_STATERR_TCPE 0x20000000
+#define E1000_RXDEXT_STATERR_IPE 0x40000000
+#define E1000_RXDEXT_STATERR_RXE 0x80000000
+
+#define E1000_RXDPS_HDRSTAT_HDRSP 0x00008000
+#define E1000_RXDPS_HDRSTAT_HDRLEN_MASK 0x000003FF
+
+/* mask to determine if packets should be dropped due to frame errors */
+#define E1000_RXD_ERR_FRAME_ERR_MASK ( \
+ E1000_RXD_ERR_CE | \
+ E1000_RXD_ERR_SE | \
+ E1000_RXD_ERR_SEQ | \
+ E1000_RXD_ERR_CXE | \
+ E1000_RXD_ERR_RXE)
+
+
+/* Same mask, but for extended and packet split descriptors */
+#define E1000_RXDEXT_ERR_FRAME_ERR_MASK ( \
+ E1000_RXDEXT_STATERR_CE | \
+ E1000_RXDEXT_STATERR_SE | \
+ E1000_RXDEXT_STATERR_SEQ | \
+ E1000_RXDEXT_STATERR_CXE | \
+ E1000_RXDEXT_STATERR_RXE)
+
+/* Transmit Descriptor */
+struct em_tx_desc {
+ uint64_t buffer_addr; /* Address of the descriptor's data buffer */
+ union {
+ uint32_t data;
+ struct {
+ uint16_t length; /* Data buffer length */
+ uint8_t cso; /* Checksum offset */
+ uint8_t cmd; /* Descriptor control */
+ } flags;
+ } lower;
+ union {
+ uint32_t data;
+ struct {
+ uint8_t status; /* Descriptor status */
+ uint8_t css; /* Checksum start */
+ uint16_t special;
+ } fields;
+ } upper;
+};
+
+/* Transmit Descriptor bit definitions */
+#define E1000_TXD_DTYP_D 0x00100000 /* Data Descriptor */
+#define E1000_TXD_DTYP_C 0x00000000 /* Context Descriptor */
+#define E1000_TXD_POPTS_IXSM 0x01 /* Insert IP checksum */
+#define E1000_TXD_POPTS_TXSM 0x02 /* Insert TCP/UDP checksum */
+#define E1000_TXD_CMD_EOP 0x01000000 /* End of Packet */
+#define E1000_TXD_CMD_IFCS 0x02000000 /* Insert FCS (Ethernet CRC) */
+#define E1000_TXD_CMD_IC 0x04000000 /* Insert Checksum */
+#define E1000_TXD_CMD_RS 0x08000000 /* Report Status */
+#define E1000_TXD_CMD_RPS 0x10000000 /* Report Packet Sent */
+#define E1000_TXD_CMD_DEXT 0x20000000 /* Descriptor extension (0 = legacy) */
+#define E1000_TXD_CMD_VLE 0x40000000 /* Add VLAN tag */
+#define E1000_TXD_CMD_IDE 0x80000000 /* Enable Tidv register */
+#define E1000_TXD_STAT_DD 0x00000001 /* Descriptor Done */
+#define E1000_TXD_STAT_EC 0x00000002 /* Excess Collisions */
+#define E1000_TXD_STAT_LC 0x00000004 /* Late Collisions */
+#define E1000_TXD_STAT_TU 0x00000008 /* Transmit underrun */
+#define E1000_TXD_CMD_TCP 0x01000000 /* TCP packet */
+#define E1000_TXD_CMD_IP 0x02000000 /* IP packet */
+#define E1000_TXD_CMD_TSE 0x04000000 /* TCP Seg enable */
+#define E1000_TXD_STAT_TC 0x00000004 /* Tx Underrun */
+
+/* Offload Context Descriptor */
+struct em_context_desc {
+ union {
+ uint32_t ip_config;
+ struct {
+ uint8_t ipcss; /* IP checksum start */
+ uint8_t ipcso; /* IP checksum offset */
+ uint16_t ipcse; /* IP checksum end */
+ } ip_fields;
+ } lower_setup;
+ union {
+ uint32_t tcp_config;
+ struct {
+ uint8_t tucss; /* TCP checksum start */
+ uint8_t tucso; /* TCP checksum offset */
+ uint16_t tucse; /* TCP checksum end */
+ } tcp_fields;
+ } upper_setup;
+ uint32_t cmd_and_length; /* */
+ union {
+ uint32_t data;
+ struct {
+ uint8_t status; /* Descriptor status */
+ uint8_t hdr_len; /* Header length */
+ uint16_t mss; /* Maximum segment size */
+ } fields;
+ } tcp_seg_setup;
+};
+
+/* Offload data descriptor */
+struct em_data_desc {
+ uint64_t buffer_addr; /* Address of the descriptor's buffer address */
+ union {
+ uint32_t data;
+ struct {
+ uint16_t length; /* Data buffer length */
+ uint8_t typ_len_ext; /* */
+ uint8_t cmd; /* */
+ } flags;
+ } lower;
+ union {
+ uint32_t data;
+ struct {
+ uint8_t status; /* Descriptor status */
+ uint8_t popts; /* Packet Options */
+ uint16_t special; /* */
+ } fields;
+ } upper;
+};
+
+/* Filters */
+#define E1000_NUM_UNICAST 16 /* Unicast filter entries */
+#define E1000_MC_TBL_SIZE 128 /* Multicast Filter Table (4096 bits) */
+#define E1000_VLAN_FILTER_TBL_SIZE 128 /* VLAN Filter Table (4096 bits) */
+
+
+/* Receive Address Register */
+struct em_rar {
+ volatile uint32_t low; /* receive address low */
+ volatile uint32_t high; /* receive address high */
+};
+
+/* Number of entries in the Multicast Table Array (MTA). */
+#define E1000_NUM_MTA_REGISTERS 128
+
+/* IPv4 Address Table Entry */
+struct em_ipv4_at_entry {
+ volatile uint32_t ipv4_addr; /* IP Address (RW) */
+ volatile uint32_t reserved;
+};
+
+/* Four wakeup IP addresses are supported */
+#define E1000_WAKEUP_IP_ADDRESS_COUNT_MAX 4
+#define E1000_IP4AT_SIZE E1000_WAKEUP_IP_ADDRESS_COUNT_MAX
+#define E1000_IP6AT_SIZE 1
+
+/* IPv6 Address Table Entry */
+struct em_ipv6_at_entry {
+ volatile uint8_t ipv6_addr[16];
+};
+
+/* Flexible Filter Length Table Entry */
+struct em_fflt_entry {
+ volatile uint32_t length; /* Flexible Filter Length (RW) */
+ volatile uint32_t reserved;
+};
+
+/* Flexible Filter Mask Table Entry */
+struct em_ffmt_entry {
+ volatile uint32_t mask; /* Flexible Filter Mask (RW) */
+ volatile uint32_t reserved;
+};
+
+/* Flexible Filter Value Table Entry */
+struct em_ffvt_entry {
+ volatile uint32_t value; /* Flexible Filter Value (RW) */
+ volatile uint32_t reserved;
+};
+
+/* Four Flexible Filters are supported */
+#define E1000_FLEXIBLE_FILTER_COUNT_MAX 4
+
+/* Each Flexible Filter is at most 128 (0x80) bytes in length */
+#define E1000_FLEXIBLE_FILTER_SIZE_MAX 128
+
+#define E1000_FFLT_SIZE E1000_FLEXIBLE_FILTER_COUNT_MAX
+#define E1000_FFMT_SIZE E1000_FLEXIBLE_FILTER_SIZE_MAX
+#define E1000_FFVT_SIZE E1000_FLEXIBLE_FILTER_SIZE_MAX
+
+/* Register Set. (82543, 82544)
+ *
+ * Registers are defined to be 32 bits and should be accessed as 32 bit values.
+ * These registers are physically located on the NIC, but are mapped into the
+ * host memory address space.
+ *
+ * RW - register is both readable and writable
+ * RO - register is read only
+ * WO - register is write only
+ * R/clr - register is read only and is cleared when read
+ * A - register array
+ */
+#define E1000_CTRL 0x00000 /* Device Control - RW */
+#define E1000_CTRL_DUP 0x00004 /* Device Control Duplicate (Shadow) - RW */
+#define E1000_STATUS 0x00008 /* Device Status - RO */
+#define E1000_EECD 0x00010 /* EEPROM/Flash Control - RW */
+#define E1000_EERD 0x00014 /* EEPROM Read - RW */
+#define E1000_CTRL_EXT 0x00018 /* Extended Device Control - RW */
+#define E1000_FLA 0x0001C /* Flash Access - RW */
+#define E1000_MDIC 0x00020 /* MDI Control - RW */
+#define E1000_FCAL 0x00028 /* Flow Control Address Low - RW */
+#define E1000_FCAH 0x0002C /* Flow Control Address High -RW */
+#define E1000_FCT 0x00030 /* Flow Control Type - RW */
+#define E1000_VET 0x00038 /* VLAN Ether Type - RW */
+#define E1000_ICR 0x000C0 /* Interrupt Cause Read - R/clr */
+#define E1000_ITR 0x000C4 /* Interrupt Throttling Rate - RW */
+#define E1000_ICS 0x000C8 /* Interrupt Cause Set - WO */
+#define E1000_IMS 0x000D0 /* Interrupt Mask Set - RW */
+#define E1000_IMC 0x000D8 /* Interrupt Mask Clear - WO */
+#define E1000_IAM 0x000E0 /* Interrupt Acknowledge Auto Mask */
+#define E1000_RCTL 0x00100 /* RX Control - RW */
+#define E1000_FCTTV 0x00170 /* Flow Control Transmit Timer Value - RW */
+#define E1000_TXCW 0x00178 /* TX Configuration Word - RW */
+#define E1000_RXCW 0x00180 /* RX Configuration Word - RO */
+#define E1000_TCTL 0x00400 /* TX Control - RW */
+#define E1000_TIPG 0x00410 /* TX Inter-packet gap -RW */
+#define E1000_TBT 0x00448 /* TX Burst Timer - RW */
+#define E1000_AIT 0x00458 /* Adaptive Interframe Spacing Throttle - RW */
+#define E1000_LEDCTL 0x00E00 /* LED Control - RW */
+#define E1000_EXTCNF_CTRL 0x00F00 /* Extended Configuration Control */
+#define E1000_EXTCNF_SIZE 0x00F08 /* Extended Configuration Size */
+#define E1000_PBA 0x01000 /* Packet Buffer Allocation - RW */
+#define E1000_PBS 0x01008 /* Packet Buffer Size */
+#define E1000_EEMNGCTL 0x01010 /* MNG EEprom Control */
+#define E1000_FLASH_UPDATES 1000
+#define E1000_EEARBC 0x01024 /* EEPROM Auto Read Bus Control */
+#define E1000_FLASHT 0x01028 /* FLASH Timer Register */
+#define E1000_EEWR 0x0102C /* EEPROM Write Register - RW */
+#define E1000_FLSWCTL 0x01030 /* FLASH control register */
+#define E1000_FLSWDATA 0x01034 /* FLASH data register */
+#define E1000_FLSWCNT 0x01038 /* FLASH Access Counter */
+#define E1000_FLOP 0x0103C /* FLASH Opcode Register */
+#define E1000_ERT 0x02008 /* Early Rx Threshold - RW */
+#define E1000_FCRTL 0x02160 /* Flow Control Receive Threshold Low - RW */
+#define E1000_FCRTH 0x02168 /* Flow Control Receive Threshold High - RW */
+#define E1000_PSRCTL 0x02170 /* Packet Split Receive Control - RW */
+#define E1000_RDBAL 0x02800 /* RX Descriptor Base Address Low - RW */
+#define E1000_RDBAH 0x02804 /* RX Descriptor Base Address High - RW */
+#define E1000_RDLEN 0x02808 /* RX Descriptor Length - RW */
+#define E1000_RDH 0x02810 /* RX Descriptor Head - RW */
+#define E1000_RDT 0x02818 /* RX Descriptor Tail - RW */
+#define E1000_RDTR 0x02820 /* RX Delay Timer - RW */
+#define E1000_RXDCTL 0x02828 /* RX Descriptor Control - RW */
+#define E1000_RADV 0x0282C /* RX Interrupt Absolute Delay Timer - RW */
+#define E1000_RSRPD 0x02C00 /* RX Small Packet Detect - RW */
+#define E1000_RAID 0x02C08 /* Receive Ack Interrupt Delay - RW */
+#define E1000_TXDMAC 0x03000 /* TX DMA Control - RW */
+#define E1000_TDFH 0x03410 /* TX Data FIFO Head - RW */
+#define E1000_TDFT 0x03418 /* TX Data FIFO Tail - RW */
+#define E1000_TDFHS 0x03420 /* TX Data FIFO Head Saved - RW */
+#define E1000_TDFTS 0x03428 /* TX Data FIFO Tail Saved - RW */
+#define E1000_TDFPC 0x03430 /* TX Data FIFO Packet Count - RW */
+#define E1000_TDBAL 0x03800 /* TX Descriptor Base Address Low - RW */
+#define E1000_TDBAH 0x03804 /* TX Descriptor Base Address High - RW */
+#define E1000_TDLEN 0x03808 /* TX Descriptor Length - RW */
+#define E1000_TDH 0x03810 /* TX Descriptor Head - RW */
+#define E1000_TDT 0x03818 /* TX Descripotr Tail - RW */
+#define E1000_TIDV 0x03820 /* TX Interrupt Delay Value - RW */
+#define E1000_TXDCTL 0x03828 /* TX Descriptor Control - RW */
+#define E1000_TADV 0x0382C /* TX Interrupt Absolute Delay Val - RW */
+#define E1000_TSPMT 0x03830 /* TCP Segmentation PAD & Min Threshold - RW */
+#define E1000_TARC0 0x03840 /* TX Arbitration Count (0) */
+#define E1000_TDBAL1 0x03900 /* TX Desc Base Address Low (1) - RW */
+#define E1000_TDBAH1 0x03904 /* TX Desc Base Address High (1) - RW */
+#define E1000_TDLEN1 0x03908 /* TX Desc Length (1) - RW */
+#define E1000_TDH1 0x03910 /* TX Desc Head (1) - RW */
+#define E1000_TDT1 0x03918 /* TX Desc Tail (1) - RW */
+#define E1000_TXDCTL1 0x03928 /* TX Descriptor Control (1) - RW */
+#define E1000_TARC1 0x03940 /* TX Arbitration Count (1) */
+#define E1000_CRCERRS 0x04000 /* CRC Error Count - R/clr */
+#define E1000_ALGNERRC 0x04004 /* Alignment Error Count - R/clr */
+#define E1000_SYMERRS 0x04008 /* Symbol Error Count - R/clr */
+#define E1000_RXERRC 0x0400C /* Receive Error Count - R/clr */
+#define E1000_MPC 0x04010 /* Missed Packet Count - R/clr */
+#define E1000_SCC 0x04014 /* Single Collision Count - R/clr */
+#define E1000_ECOL 0x04018 /* Excessive Collision Count - R/clr */
+#define E1000_MCC 0x0401C /* Multiple Collision Count - R/clr */
+#define E1000_LATECOL 0x04020 /* Late Collision Count - R/clr */
+#define E1000_COLC 0x04028 /* Collision Count - R/clr */
+#define E1000_DC 0x04030 /* Defer Count - R/clr */
+#define E1000_TNCRS 0x04034 /* TX-No CRS - R/clr */
+#define E1000_SEC 0x04038 /* Sequence Error Count - R/clr */
+#define E1000_CEXTERR 0x0403C /* Carrier Extension Error Count - R/clr */
+#define E1000_RLEC 0x04040 /* Receive Length Error Count - R/clr */
+#define E1000_XONRXC 0x04048 /* XON RX Count - R/clr */
+#define E1000_XONTXC 0x0404C /* XON TX Count - R/clr */
+#define E1000_XOFFRXC 0x04050 /* XOFF RX Count - R/clr */
+#define E1000_XOFFTXC 0x04054 /* XOFF TX Count - R/clr */
+#define E1000_FCRUC 0x04058 /* Flow Control RX Unsupported Count- R/clr */
+#define E1000_PRC64 0x0405C /* Packets RX (64 bytes) - R/clr */
+#define E1000_PRC127 0x04060 /* Packets RX (65-127 bytes) - R/clr */
+#define E1000_PRC255 0x04064 /* Packets RX (128-255 bytes) - R/clr */
+#define E1000_PRC511 0x04068 /* Packets RX (255-511 bytes) - R/clr */
+#define E1000_PRC1023 0x0406C /* Packets RX (512-1023 bytes) - R/clr */
+#define E1000_PRC1522 0x04070 /* Packets RX (1024-1522 bytes) - R/clr */
+#define E1000_GPRC 0x04074 /* Good Packets RX Count - R/clr */
+#define E1000_BPRC 0x04078 /* Broadcast Packets RX Count - R/clr */
+#define E1000_MPRC 0x0407C /* Multicast Packets RX Count - R/clr */
+#define E1000_GPTC 0x04080 /* Good Packets TX Count - R/clr */
+#define E1000_GORCL 0x04088 /* Good Octets RX Count Low - R/clr */
+#define E1000_GORCH 0x0408C /* Good Octets RX Count High - R/clr */
+#define E1000_GOTCL 0x04090 /* Good Octets TX Count Low - R/clr */
+#define E1000_GOTCH 0x04094 /* Good Octets TX Count High - R/clr */
+#define E1000_RNBC 0x040A0 /* RX No Buffers Count - R/clr */
+#define E1000_RUC 0x040A4 /* RX Undersize Count - R/clr */
+#define E1000_RFC 0x040A8 /* RX Fragment Count - R/clr */
+#define E1000_ROC 0x040AC /* RX Oversize Count - R/clr */
+#define E1000_RJC 0x040B0 /* RX Jabber Count - R/clr */
+#define E1000_MGTPRC 0x040B4 /* Management Packets RX Count - R/clr */
+#define E1000_MGTPDC 0x040B8 /* Management Packets Dropped Count - R/clr */
+#define E1000_MGTPTC 0x040BC /* Management Packets TX Count - R/clr */
+#define E1000_TORL 0x040C0 /* Total Octets RX Low - R/clr */
+#define E1000_TORH 0x040C4 /* Total Octets RX High - R/clr */
+#define E1000_TOTL 0x040C8 /* Total Octets TX Low - R/clr */
+#define E1000_TOTH 0x040CC /* Total Octets TX High - R/clr */
+#define E1000_TPR 0x040D0 /* Total Packets RX - R/clr */
+#define E1000_TPT 0x040D4 /* Total Packets TX - R/clr */
+#define E1000_PTC64 0x040D8 /* Packets TX (64 bytes) - R/clr */
+#define E1000_PTC127 0x040DC /* Packets TX (65-127 bytes) - R/clr */
+#define E1000_PTC255 0x040E0 /* Packets TX (128-255 bytes) - R/clr */
+#define E1000_PTC511 0x040E4 /* Packets TX (256-511 bytes) - R/clr */
+#define E1000_PTC1023 0x040E8 /* Packets TX (512-1023 bytes) - R/clr */
+#define E1000_PTC1522 0x040EC /* Packets TX (1024-1522 Bytes) - R/clr */
+#define E1000_MPTC 0x040F0 /* Multicast Packets TX Count - R/clr */
+#define E1000_BPTC 0x040F4 /* Broadcast Packets TX Count - R/clr */
+#define E1000_TSCTC 0x040F8 /* TCP Segmentation Context TX - R/clr */
+#define E1000_TSCTFC 0x040FC /* TCP Segmentation Context TX Fail - R/clr */
+#define E1000_IAC 0x4100 /* Interrupt Assertion Count */
+#define E1000_ICRXPTC 0x4104 /* Interrupt Cause Rx Packet Timer Expire Count */
+#define E1000_ICRXATC 0x4108 /* Interrupt Cause Rx Absolute Timer Expire Count */
+#define E1000_ICTXPTC 0x410C /* Interrupt Cause Tx Packet Timer Expire Count */
+#define E1000_ICTXATC 0x4110 /* Interrupt Cause Tx Absolute Timer Expire Count */
+#define E1000_ICTXQEC 0x4118 /* Interrupt Cause Tx Queue Empty Count */
+#define E1000_ICTXQMTC 0x411C /* Interrupt Cause Tx Queue Minimum Threshold Count */
+#define E1000_ICRXDMTC 0x4120 /* Interrupt Cause Rx Descriptor Minimum Threshold Count */
+#define E1000_ICRXOC 0x4124 /* Interrupt Cause Receiver Overrun Count */
+#define E1000_RXCSUM 0x05000 /* RX Checksum Control - RW */
+#define E1000_RFCTL 0x05008 /* Receive Filter Control*/
+#define E1000_MTA 0x05200 /* Multicast Table Array - RW Array */
+#define E1000_RA 0x05400 /* Receive Address - RW Array */
+#define E1000_VFTA 0x05600 /* VLAN Filter Table Array - RW Array */
+#define E1000_WUC 0x05800 /* Wakeup Control - RW */
+#define E1000_WUFC 0x05808 /* Wakeup Filter Control - RW */
+#define E1000_WUS 0x05810 /* Wakeup Status - RO */
+#define E1000_MANC 0x05820 /* Management Control - RW */
+#define E1000_IPAV 0x05838 /* IP Address Valid - RW */
+#define E1000_IP4AT 0x05840 /* IPv4 Address Table - RW Array */
+#define E1000_IP6AT 0x05880 /* IPv6 Address Table - RW Array */
+#define E1000_WUPL 0x05900 /* Wakeup Packet Length - RW */
+#define E1000_WUPM 0x05A00 /* Wakeup Packet Memory - RO A */
+#define E1000_FFLT 0x05F00 /* Flexible Filter Length Table - RW Array */
+#define E1000_HOST_IF 0x08800 /* Host Interface */
+#define E1000_FFMT 0x09000 /* Flexible Filter Mask Table - RW Array */
+#define E1000_FFVT 0x09800 /* Flexible Filter Value Table - RW Array */
+
+#define E1000_GCR 0x05B00 /* PCI-Ex Control */
+#define E1000_GSCL_1 0x05B10 /* PCI-Ex Statistic Control #1 */
+#define E1000_GSCL_2 0x05B14 /* PCI-Ex Statistic Control #2 */
+#define E1000_GSCL_3 0x05B18 /* PCI-Ex Statistic Control #3 */
+#define E1000_GSCL_4 0x05B1C /* PCI-Ex Statistic Control #4 */
+#define E1000_FACTPS 0x05B30 /* Function Active and Power State to MNG */
+#define E1000_SWSM 0x05B50 /* SW Semaphore */
+#define E1000_FWSM 0x05B54 /* FW Semaphore */
+#define E1000_FFLT_DBG 0x05F04 /* Debug Register */
+#define E1000_HICR 0x08F00 /* Host Inteface Control */
+/* Register Set (82542)
+ *
+ * Some of the 82542 registers are located at different offsets than they are
+ * in more current versions of the 8254x. Despite the difference in location,
+ * the registers function in the same manner.
+ */
+#define E1000_82542_CTRL E1000_CTRL
+#define E1000_82542_CTRL_DUP E1000_CTRL_DUP
+#define E1000_82542_STATUS E1000_STATUS
+#define E1000_82542_EECD E1000_EECD
+#define E1000_82542_EERD E1000_EERD
+#define E1000_82542_CTRL_EXT E1000_CTRL_EXT
+#define E1000_82542_FLA E1000_FLA
+#define E1000_82542_MDIC E1000_MDIC
+#define E1000_82542_FCAL E1000_FCAL
+#define E1000_82542_FCAH E1000_FCAH
+#define E1000_82542_FCT E1000_FCT
+#define E1000_82542_VET E1000_VET
+#define E1000_82542_RA 0x00040
+#define E1000_82542_ICR E1000_ICR
+#define E1000_82542_ITR E1000_ITR
+#define E1000_82542_ICS E1000_ICS
+#define E1000_82542_IMS E1000_IMS
+#define E1000_82542_IMC E1000_IMC
+#define E1000_82542_RCTL E1000_RCTL
+#define E1000_82542_RDTR 0x00108
+#define E1000_82542_RDBAL 0x00110
+#define E1000_82542_RDBAH 0x00114
+#define E1000_82542_RDLEN 0x00118
+#define E1000_82542_RDH 0x00120
+#define E1000_82542_RDT 0x00128
+#define E1000_82542_FCRTH 0x00160
+#define E1000_82542_FCRTL 0x00168
+#define E1000_82542_FCTTV E1000_FCTTV
+#define E1000_82542_TXCW E1000_TXCW
+#define E1000_82542_RXCW E1000_RXCW
+#define E1000_82542_MTA 0x00200
+#define E1000_82542_TCTL E1000_TCTL
+#define E1000_82542_TIPG E1000_TIPG
+#define E1000_82542_TDBAL 0x00420
+#define E1000_82542_TDBAH 0x00424
+#define E1000_82542_TDLEN 0x00428
+#define E1000_82542_TDH 0x00430
+#define E1000_82542_TDT 0x00438
+#define E1000_82542_TIDV 0x00440
+#define E1000_82542_TBT E1000_TBT
+#define E1000_82542_AIT E1000_AIT
+#define E1000_82542_VFTA 0x00600
+#define E1000_82542_LEDCTL E1000_LEDCTL
+#define E1000_82542_PBA E1000_PBA
+#define E1000_82542_PBS E1000_PBS
+#define E1000_82542_EEMNGCTL E1000_EEMNGCTL
+#define E1000_82542_EEARBC E1000_EEARBC
+#define E1000_82542_FLASHT E1000_FLASHT
+#define E1000_82542_EEWR E1000_EEWR
+#define E1000_82542_FLSWCTL E1000_FLSWCTL
+#define E1000_82542_FLSWDATA E1000_FLSWDATA
+#define E1000_82542_FLSWCNT E1000_FLSWCNT
+#define E1000_82542_FLOP E1000_FLOP
+#define E1000_82542_EXTCNF_CTRL E1000_EXTCNF_CTRL
+#define E1000_82542_EXTCNF_SIZE E1000_EXTCNF_SIZE
+#define E1000_82542_ERT E1000_ERT
+#define E1000_82542_RXDCTL E1000_RXDCTL
+#define E1000_82542_RADV E1000_RADV
+#define E1000_82542_RSRPD E1000_RSRPD
+#define E1000_82542_TXDMAC E1000_TXDMAC
+#define E1000_82542_TDFHS E1000_TDFHS
+#define E1000_82542_TDFTS E1000_TDFTS
+#define E1000_82542_TDFPC E1000_TDFPC
+#define E1000_82542_TXDCTL E1000_TXDCTL
+#define E1000_82542_TADV E1000_TADV
+#define E1000_82542_TSPMT E1000_TSPMT
+#define E1000_82542_CRCERRS E1000_CRCERRS
+#define E1000_82542_ALGNERRC E1000_ALGNERRC
+#define E1000_82542_SYMERRS E1000_SYMERRS
+#define E1000_82542_RXERRC E1000_RXERRC
+#define E1000_82542_MPC E1000_MPC
+#define E1000_82542_SCC E1000_SCC
+#define E1000_82542_ECOL E1000_ECOL
+#define E1000_82542_MCC E1000_MCC
+#define E1000_82542_LATECOL E1000_LATECOL
+#define E1000_82542_COLC E1000_COLC
+#define E1000_82542_DC E1000_DC
+#define E1000_82542_TNCRS E1000_TNCRS
+#define E1000_82542_SEC E1000_SEC
+#define E1000_82542_CEXTERR E1000_CEXTERR
+#define E1000_82542_RLEC E1000_RLEC
+#define E1000_82542_XONRXC E1000_XONRXC
+#define E1000_82542_XONTXC E1000_XONTXC
+#define E1000_82542_XOFFRXC E1000_XOFFRXC
+#define E1000_82542_XOFFTXC E1000_XOFFTXC
+#define E1000_82542_FCRUC E1000_FCRUC
+#define E1000_82542_PRC64 E1000_PRC64
+#define E1000_82542_PRC127 E1000_PRC127
+#define E1000_82542_PRC255 E1000_PRC255
+#define E1000_82542_PRC511 E1000_PRC511
+#define E1000_82542_PRC1023 E1000_PRC1023
+#define E1000_82542_PRC1522 E1000_PRC1522
+#define E1000_82542_GPRC E1000_GPRC
+#define E1000_82542_BPRC E1000_BPRC
+#define E1000_82542_MPRC E1000_MPRC
+#define E1000_82542_GPTC E1000_GPTC
+#define E1000_82542_GORCL E1000_GORCL
+#define E1000_82542_GORCH E1000_GORCH
+#define E1000_82542_GOTCL E1000_GOTCL
+#define E1000_82542_GOTCH E1000_GOTCH
+#define E1000_82542_RNBC E1000_RNBC
+#define E1000_82542_RUC E1000_RUC
+#define E1000_82542_RFC E1000_RFC
+#define E1000_82542_ROC E1000_ROC
+#define E1000_82542_RJC E1000_RJC
+#define E1000_82542_MGTPRC E1000_MGTPRC
+#define E1000_82542_MGTPDC E1000_MGTPDC
+#define E1000_82542_MGTPTC E1000_MGTPTC
+#define E1000_82542_TORL E1000_TORL
+#define E1000_82542_TORH E1000_TORH
+#define E1000_82542_TOTL E1000_TOTL
+#define E1000_82542_TOTH E1000_TOTH
+#define E1000_82542_TPR E1000_TPR
+#define E1000_82542_TPT E1000_TPT
+#define E1000_82542_PTC64 E1000_PTC64
+#define E1000_82542_PTC127 E1000_PTC127
+#define E1000_82542_PTC255 E1000_PTC255
+#define E1000_82542_PTC511 E1000_PTC511
+#define E1000_82542_PTC1023 E1000_PTC1023
+#define E1000_82542_PTC1522 E1000_PTC1522
+#define E1000_82542_MPTC E1000_MPTC
+#define E1000_82542_BPTC E1000_BPTC
+#define E1000_82542_TSCTC E1000_TSCTC
+#define E1000_82542_TSCTFC E1000_TSCTFC
+#define E1000_82542_RXCSUM E1000_RXCSUM
+#define E1000_82542_WUC E1000_WUC
+#define E1000_82542_WUFC E1000_WUFC
+#define E1000_82542_WUS E1000_WUS
+#define E1000_82542_MANC E1000_MANC
+#define E1000_82542_IPAV E1000_IPAV
+#define E1000_82542_IP4AT E1000_IP4AT
+#define E1000_82542_IP6AT E1000_IP6AT
+#define E1000_82542_WUPL E1000_WUPL
+#define E1000_82542_WUPM E1000_WUPM
+#define E1000_82542_FFLT E1000_FFLT
+#define E1000_82542_TDFH 0x08010
+#define E1000_82542_TDFT 0x08018
+#define E1000_82542_FFMT E1000_FFMT
+#define E1000_82542_FFVT E1000_FFVT
+#define E1000_82542_HOST_IF E1000_HOST_IF
+#define E1000_82542_IAM E1000_IAM
+#define E1000_82542_EEMNGCTL E1000_EEMNGCTL
+#define E1000_82542_PSRCTL E1000_PSRCTL
+#define E1000_82542_RAID E1000_RAID
+#define E1000_82542_TARC0 E1000_TARC0
+#define E1000_82542_TDBAL1 E1000_TDBAL1
+#define E1000_82542_TDBAH1 E1000_TDBAH1
+#define E1000_82542_TDLEN1 E1000_TDLEN1
+#define E1000_82542_TDH1 E1000_TDH1
+#define E1000_82542_TDT1 E1000_TDT1
+#define E1000_82542_TXDCTL1 E1000_TXDCTL1
+#define E1000_82542_TARC1 E1000_TARC1
+#define E1000_82542_RFCTL E1000_RFCTL
+#define E1000_82542_GCR E1000_GCR
+#define E1000_82542_GSCL_1 E1000_GSCL_1
+#define E1000_82542_GSCL_2 E1000_GSCL_2
+#define E1000_82542_GSCL_3 E1000_GSCL_3
+#define E1000_82542_GSCL_4 E1000_GSCL_4
+#define E1000_82542_FACTPS E1000_FACTPS
+#define E1000_82542_SWSM E1000_SWSM
+#define E1000_82542_FWSM E1000_FWSM
+#define E1000_82542_FFLT_DBG E1000_FFLT_DBG
+#define E1000_82542_IAC E1000_IAC
+#define E1000_82542_ICRXPTC E1000_ICRXPTC
+#define E1000_82542_ICRXATC E1000_ICRXATC
+#define E1000_82542_ICTXPTC E1000_ICTXPTC
+#define E1000_82542_ICTXATC E1000_ICTXATC
+#define E1000_82542_ICTXQEC E1000_ICTXQEC
+#define E1000_82542_ICTXQMTC E1000_ICTXQMTC
+#define E1000_82542_ICRXDMTC E1000_ICRXDMTC
+#define E1000_82542_ICRXOC E1000_ICRXOC
+#define E1000_82542_HICR E1000_HICR
+
+/* Statistics counters collected by the MAC */
+struct em_hw_stats {
+ uint64_t crcerrs;
+ uint64_t algnerrc;
+ uint64_t symerrs;
+ uint64_t rxerrc;
+ uint64_t mpc;
+ uint64_t scc;
+ uint64_t ecol;
+ uint64_t mcc;
+ uint64_t latecol;
+ uint64_t colc;
+ uint64_t dc;
+ uint64_t tncrs;
+ uint64_t sec;
+ uint64_t cexterr;
+ uint64_t rlec;
+ uint64_t xonrxc;
+ uint64_t xontxc;
+ uint64_t xoffrxc;
+ uint64_t xofftxc;
+ uint64_t fcruc;
+ uint64_t prc64;
+ uint64_t prc127;
+ uint64_t prc255;
+ uint64_t prc511;
+ uint64_t prc1023;
+ uint64_t prc1522;
+ uint64_t gprc;
+ uint64_t bprc;
+ uint64_t mprc;
+ uint64_t gptc;
+ uint64_t gorcl;
+ uint64_t gorch;
+ uint64_t gotcl;
+ uint64_t gotch;
+ uint64_t rnbc;
+ uint64_t ruc;
+ uint64_t rfc;
+ uint64_t roc;
+ uint64_t rjc;
+ uint64_t mgprc;
+ uint64_t mgpdc;
+ uint64_t mgptc;
+ uint64_t torl;
+ uint64_t torh;
+ uint64_t totl;
+ uint64_t toth;
+ uint64_t tpr;
+ uint64_t tpt;
+ uint64_t ptc64;
+ uint64_t ptc127;
+ uint64_t ptc255;
+ uint64_t ptc511;
+ uint64_t ptc1023;
+ uint64_t ptc1522;
+ uint64_t mptc;
+ uint64_t bptc;
+ uint64_t tsctc;
+ uint64_t tsctfc;
+ uint64_t iac;
+ uint64_t icrxptc;
+ uint64_t icrxatc;
+ uint64_t ictxptc;
+ uint64_t ictxatc;
+ uint64_t ictxqec;
+ uint64_t ictxqmtc;
+ uint64_t icrxdmtc;
+ uint64_t icrxoc;
+};
+
+/* Structure containing variables used by the shared code (em_hw.c) */
+struct em_hw {
+ uint8_t *hw_addr;
+ uint8_t *flash_address;
+ em_mac_type mac_type;
+ em_phy_type phy_type;
+ uint32_t phy_init_script;
+ em_media_type media_type;
+ void *back;
+ em_fc_type fc;
+ em_bus_speed bus_speed;
+ em_bus_width bus_width;
+ em_bus_type bus_type;
+ struct em_eeprom_info eeprom;
+ em_ms_type master_slave;
+ em_ms_type original_master_slave;
+ em_ffe_config ffe_config_state;
+ uint32_t asf_firmware_present;
+ uint32_t eeprom_semaphore_present;
+ unsigned long io_base;
+ uint32_t phy_id;
+ uint32_t phy_revision;
+ uint32_t phy_addr;
+ uint32_t original_fc;
+ uint32_t txcw;
+ uint32_t autoneg_failed;
+ uint32_t max_frame_size;
+ uint32_t min_frame_size;
+ uint32_t mc_filter_type;
+ uint32_t num_mc_addrs;
+ uint32_t collision_delta;
+ uint32_t tx_packet_delta;
+ uint32_t ledctl_default;
+ uint32_t ledctl_mode1;
+ uint32_t ledctl_mode2;
+ boolean_t tx_pkt_filtering;
+ struct em_host_mng_dhcp_cookie mng_cookie;
+ uint16_t phy_spd_default;
+ uint16_t autoneg_advertised;
+ uint16_t pci_cmd_word;
+ uint16_t fc_high_water;
+ uint16_t fc_low_water;
+ uint16_t fc_pause_time;
+ uint16_t current_ifs_val;
+ uint16_t ifs_min_val;
+ uint16_t ifs_max_val;
+ uint16_t ifs_step_size;
+ uint16_t ifs_ratio;
+ uint16_t device_id;
+ uint16_t vendor_id;
+ uint16_t subsystem_id;
+ uint16_t subsystem_vendor_id;
+ uint8_t revision_id;
+ uint8_t autoneg;
+ uint8_t mdix;
+ uint8_t forced_speed_duplex;
+ uint8_t wait_autoneg_complete;
+ uint8_t dma_fairness;
+ uint8_t mac_addr[NODE_ADDRESS_SIZE];
+ uint8_t perm_mac_addr[NODE_ADDRESS_SIZE];
+ boolean_t disable_polarity_correction;
+ boolean_t speed_downgraded;
+ em_smart_speed smart_speed;
+ em_dsp_config dsp_config_state;
+ boolean_t get_link_status;
+ boolean_t serdes_link_down;
+ boolean_t tbi_compatibility_en;
+ boolean_t tbi_compatibility_on;
+ boolean_t phy_reset_disable;
+ boolean_t fc_send_xon;
+ boolean_t fc_strict_ieee;
+ boolean_t report_tx_early;
+ boolean_t adaptive_ifs;
+ boolean_t ifs_params_forced;
+ boolean_t in_ifs_mode;
+ boolean_t mng_reg_access_disabled;
+};
+
+
+#define E1000_EEPROM_SWDPIN0 0x0001 /* SWDPIN 0 EEPROM Value */
+#define E1000_EEPROM_LED_LOGIC 0x0020 /* Led Logic Word */
+#define E1000_EEPROM_RW_REG_DATA 16 /* Offset to data in EEPROM read/write registers */
+#define E1000_EEPROM_RW_REG_DONE 2 /* Offset to READ/WRITE done bit */
+#define E1000_EEPROM_RW_REG_START 1 /* First bit for telling part to start operation */
+#define E1000_EEPROM_RW_ADDR_SHIFT 2 /* Shift to the address bits */
+#define E1000_EEPROM_POLL_WRITE 1 /* Flag for polling for write complete */
+#define E1000_EEPROM_POLL_READ 0 /* Flag for polling for read complete */
+/* Register Bit Masks */
+/* Device Control */
+#define E1000_CTRL_FD 0x00000001 /* Full duplex.0=half; 1=full */
+#define E1000_CTRL_BEM 0x00000002 /* Endian Mode.0=little,1=big */
+#define E1000_CTRL_PRIOR 0x00000004 /* Priority on PCI. 0=rx,1=fair */
+#define E1000_CTRL_GIO_MASTER_DISABLE 0x00000004 /*Blocks new Master requests */
+#define E1000_CTRL_LRST 0x00000008 /* Link reset. 0=normal,1=reset */
+#define E1000_CTRL_TME 0x00000010 /* Test mode. 0=normal,1=test */
+#define E1000_CTRL_SLE 0x00000020 /* Serial Link on 0=dis,1=en */
+#define E1000_CTRL_ASDE 0x00000020 /* Auto-speed detect enable */
+#define E1000_CTRL_SLU 0x00000040 /* Set link up (Force Link) */
+#define E1000_CTRL_ILOS 0x00000080 /* Invert Loss-Of Signal */
+#define E1000_CTRL_SPD_SEL 0x00000300 /* Speed Select Mask */
+#define E1000_CTRL_SPD_10 0x00000000 /* Force 10Mb */
+#define E1000_CTRL_SPD_100 0x00000100 /* Force 100Mb */
+#define E1000_CTRL_SPD_1000 0x00000200 /* Force 1Gb */
+#define E1000_CTRL_BEM32 0x00000400 /* Big Endian 32 mode */
+#define E1000_CTRL_FRCSPD 0x00000800 /* Force Speed */
+#define E1000_CTRL_FRCDPX 0x00001000 /* Force Duplex */
+#define E1000_CTRL_D_UD_POLARITY 0x00004000 /* Defined polarity of Dock/Undock indication in SDP[0] */
+#define E1000_CTRL_SWDPIN0 0x00040000 /* SWDPIN 0 value */
+#define E1000_CTRL_SWDPIN1 0x00080000 /* SWDPIN 1 value */
+#define E1000_CTRL_SWDPIN2 0x00100000 /* SWDPIN 2 value */
+#define E1000_CTRL_SWDPIN3 0x00200000 /* SWDPIN 3 value */
+#define E1000_CTRL_SWDPIO0 0x00400000 /* SWDPIN 0 Input or output */
+#define E1000_CTRL_SWDPIO1 0x00800000 /* SWDPIN 1 input or output */
+#define E1000_CTRL_SWDPIO2 0x01000000 /* SWDPIN 2 input or output */
+#define E1000_CTRL_SWDPIO3 0x02000000 /* SWDPIN 3 input or output */
+#define E1000_CTRL_RST 0x04000000 /* Global reset */
+#define E1000_CTRL_RFCE 0x08000000 /* Receive Flow Control enable */
+#define E1000_CTRL_TFCE 0x10000000 /* Transmit flow control enable */
+#define E1000_CTRL_RTE 0x20000000 /* Routing tag enable */
+#define E1000_CTRL_VME 0x40000000 /* IEEE VLAN mode enable */
+#define E1000_CTRL_PHY_RST 0x80000000 /* PHY Reset */
+
+/* Device Status */
+#define E1000_STATUS_FD 0x00000001 /* Full duplex.0=half,1=full */
+#define E1000_STATUS_LU 0x00000002 /* Link up.0=no,1=link */
+#define E1000_STATUS_FUNC_MASK 0x0000000C /* PCI Function Mask */
+#define E1000_STATUS_FUNC_SHIFT 2
+#define E1000_STATUS_FUNC_0 0x00000000 /* Function 0 */
+#define E1000_STATUS_FUNC_1 0x00000004 /* Function 1 */
+#define E1000_STATUS_TXOFF 0x00000010 /* transmission paused */
+#define E1000_STATUS_TBIMODE 0x00000020 /* TBI mode */
+#define E1000_STATUS_SPEED_MASK 0x000000C0
+#define E1000_STATUS_SPEED_10 0x00000000 /* Speed 10Mb/s */
+#define E1000_STATUS_SPEED_100 0x00000040 /* Speed 100Mb/s */
+#define E1000_STATUS_SPEED_1000 0x00000080 /* Speed 1000Mb/s */
+#define E1000_STATUS_ASDV 0x00000300 /* Auto speed detect value */
+#define E1000_STATUS_DOCK_CI 0x00000800 /* Change in Dock/Undock state. Clear on write '0'. */
+#define E1000_STATUS_GIO_MASTER_ENABLE 0x00080000 /* Status of Master requests. */
+#define E1000_STATUS_MTXCKOK 0x00000400 /* MTX clock running OK */
+#define E1000_STATUS_PCI66 0x00000800 /* In 66Mhz slot */
+#define E1000_STATUS_BUS64 0x00001000 /* In 64 bit slot */
+#define E1000_STATUS_PCIX_MODE 0x00002000 /* PCI-X mode */
+#define E1000_STATUS_PCIX_SPEED 0x0000C000 /* PCI-X bus speed */
+
+/* Constants used to intrepret the masked PCI-X bus speed. */
+#define E1000_STATUS_PCIX_SPEED_66 0x00000000 /* PCI-X bus speed 50-66 MHz */
+#define E1000_STATUS_PCIX_SPEED_100 0x00004000 /* PCI-X bus speed 66-100 MHz */
+#define E1000_STATUS_PCIX_SPEED_133 0x00008000 /* PCI-X bus speed 100-133 MHz */
+
+/* EEPROM/Flash Control */
+#define E1000_EECD_SK 0x00000001 /* EEPROM Clock */
+#define E1000_EECD_CS 0x00000002 /* EEPROM Chip Select */
+#define E1000_EECD_DI 0x00000004 /* EEPROM Data In */
+#define E1000_EECD_DO 0x00000008 /* EEPROM Data Out */
+#define E1000_EECD_FWE_MASK 0x00000030
+#define E1000_EECD_FWE_DIS 0x00000010 /* Disable FLASH writes */
+#define E1000_EECD_FWE_EN 0x00000020 /* Enable FLASH writes */
+#define E1000_EECD_FWE_SHIFT 4
+#define E1000_EECD_REQ 0x00000040 /* EEPROM Access Request */
+#define E1000_EECD_GNT 0x00000080 /* EEPROM Access Grant */
+#define E1000_EECD_PRES 0x00000100 /* EEPROM Present */
+#define E1000_EECD_SIZE 0x00000200 /* EEPROM Size (0=64 word 1=256 word) */
+#define E1000_EECD_ADDR_BITS 0x00000400 /* EEPROM Addressing bits based on type
+ * (0-small, 1-large) */
+#define E1000_EECD_TYPE 0x00002000 /* EEPROM Type (1-SPI, 0-Microwire) */
+#ifndef E1000_EEPROM_GRANT_ATTEMPTS
+#define E1000_EEPROM_GRANT_ATTEMPTS 1000 /* EEPROM # attempts to gain grant */
+#endif
+#define E1000_EECD_AUTO_RD 0x00000200 /* EEPROM Auto Read done */
+#define E1000_EECD_SIZE_EX_MASK 0x00007800 /* EEprom Size */
+#define E1000_EECD_SIZE_EX_SHIFT 11
+#define E1000_EECD_NVADDS 0x00018000 /* NVM Address Size */
+#define E1000_EECD_SELSHAD 0x00020000 /* Select Shadow RAM */
+#define E1000_EECD_INITSRAM 0x00040000 /* Initialize Shadow RAM */
+#define E1000_EECD_FLUPD 0x00080000 /* Update FLASH */
+#define E1000_EECD_AUPDEN 0x00100000 /* Enable Autonomous FLASH update */
+#define E1000_EECD_SHADV 0x00200000 /* Shadow RAM Data Valid */
+#define E1000_EECD_SEC1VAL 0x00400000 /* Sector One Valid */
+#define E1000_STM_OPCODE 0xDB00
+#define E1000_HICR_FW_RESET 0xC0
+
+/* EEPROM Read */
+#define E1000_EERD_START 0x00000001 /* Start Read */
+#define E1000_EERD_DONE 0x00000010 /* Read Done */
+#define E1000_EERD_ADDR_SHIFT 8
+#define E1000_EERD_ADDR_MASK 0x0000FF00 /* Read Address */
+#define E1000_EERD_DATA_SHIFT 16
+#define E1000_EERD_DATA_MASK 0xFFFF0000 /* Read Data */
+
+/* SPI EEPROM Status Register */
+#define EEPROM_STATUS_RDY_SPI 0x01
+#define EEPROM_STATUS_WEN_SPI 0x02
+#define EEPROM_STATUS_BP0_SPI 0x04
+#define EEPROM_STATUS_BP1_SPI 0x08
+#define EEPROM_STATUS_WPEN_SPI 0x80
+
+/* Extended Device Control */
+#define E1000_CTRL_EXT_GPI0_EN 0x00000001 /* Maps SDP4 to GPI0 */
+#define E1000_CTRL_EXT_GPI1_EN 0x00000002 /* Maps SDP5 to GPI1 */
+#define E1000_CTRL_EXT_PHYINT_EN E1000_CTRL_EXT_GPI1_EN
+#define E1000_CTRL_EXT_GPI2_EN 0x00000004 /* Maps SDP6 to GPI2 */
+#define E1000_CTRL_EXT_GPI3_EN 0x00000008 /* Maps SDP7 to GPI3 */
+#define E1000_CTRL_EXT_SDP4_DATA 0x00000010 /* Value of SW Defineable Pin 4 */
+#define E1000_CTRL_EXT_SDP5_DATA 0x00000020 /* Value of SW Defineable Pin 5 */
+#define E1000_CTRL_EXT_PHY_INT E1000_CTRL_EXT_SDP5_DATA
+#define E1000_CTRL_EXT_SDP6_DATA 0x00000040 /* Value of SW Defineable Pin 6 */
+#define E1000_CTRL_EXT_SDP7_DATA 0x00000080 /* Value of SW Defineable Pin 7 */
+#define E1000_CTRL_EXT_SDP4_DIR 0x00000100 /* Direction of SDP4 0=in 1=out */
+#define E1000_CTRL_EXT_SDP5_DIR 0x00000200 /* Direction of SDP5 0=in 1=out */
+#define E1000_CTRL_EXT_SDP6_DIR 0x00000400 /* Direction of SDP6 0=in 1=out */
+#define E1000_CTRL_EXT_SDP7_DIR 0x00000800 /* Direction of SDP7 0=in 1=out */
+#define E1000_CTRL_EXT_ASDCHK 0x00001000 /* Initiate an ASD sequence */
+#define E1000_CTRL_EXT_EE_RST 0x00002000 /* Reinitialize from EEPROM */
+#define E1000_CTRL_EXT_IPS 0x00004000 /* Invert Power State */
+#define E1000_CTRL_EXT_SPD_BYPS 0x00008000 /* Speed Select Bypass */
+#define E1000_CTRL_EXT_LINK_MODE_MASK 0x00C00000
+#define E1000_CTRL_EXT_LINK_MODE_GMII 0x00000000
+#define E1000_CTRL_EXT_LINK_MODE_TBI 0x00C00000
+#define E1000_CTRL_EXT_WR_WMARK_MASK 0x03000000
+#define E1000_CTRL_EXT_WR_WMARK_256 0x00000000
+#define E1000_CTRL_EXT_WR_WMARK_320 0x01000000
+#define E1000_CTRL_EXT_WR_WMARK_384 0x02000000
+#define E1000_CTRL_EXT_WR_WMARK_448 0x03000000
+#define E1000_CTRL_EXT_IAME 0x08000000 /* Interrupt acknowledge Auto-mask */
+#define E1000_CTRL_EXT_INT_TIMER_CLR 0x20000000 /* Clear Interrupt timers after IMS clear */
+
+/* MDI Control */
+#define E1000_MDIC_DATA_MASK 0x0000FFFF
+#define E1000_MDIC_REG_MASK 0x001F0000
+#define E1000_MDIC_REG_SHIFT 16
+#define E1000_MDIC_PHY_MASK 0x03E00000
+#define E1000_MDIC_PHY_SHIFT 21
+#define E1000_MDIC_OP_WRITE 0x04000000
+#define E1000_MDIC_OP_READ 0x08000000
+#define E1000_MDIC_READY 0x10000000
+#define E1000_MDIC_INT_EN 0x20000000
+#define E1000_MDIC_ERROR 0x40000000
+
+/* LED Control */
+#define E1000_LEDCTL_LED0_MODE_MASK 0x0000000F
+#define E1000_LEDCTL_LED0_MODE_SHIFT 0
+#define E1000_LEDCTL_LED0_BLINK_RATE 0x0000020
+#define E1000_LEDCTL_LED0_IVRT 0x00000040
+#define E1000_LEDCTL_LED0_BLINK 0x00000080
+#define E1000_LEDCTL_LED1_MODE_MASK 0x00000F00
+#define E1000_LEDCTL_LED1_MODE_SHIFT 8
+#define E1000_LEDCTL_LED1_BLINK_RATE 0x0002000
+#define E1000_LEDCTL_LED1_IVRT 0x00004000
+#define E1000_LEDCTL_LED1_BLINK 0x00008000
+#define E1000_LEDCTL_LED2_MODE_MASK 0x000F0000
+#define E1000_LEDCTL_LED2_MODE_SHIFT 16
+#define E1000_LEDCTL_LED2_BLINK_RATE 0x00200000
+#define E1000_LEDCTL_LED2_IVRT 0x00400000
+#define E1000_LEDCTL_LED2_BLINK 0x00800000
+#define E1000_LEDCTL_LED3_MODE_MASK 0x0F000000
+#define E1000_LEDCTL_LED3_MODE_SHIFT 24
+#define E1000_LEDCTL_LED3_IVRT 0x40000000
+#define E1000_LEDCTL_LED3_BLINK 0x80000000
+
+#define E1000_LEDCTL_MODE_LINK_10_1000 0x0
+#define E1000_LEDCTL_MODE_LINK_100_1000 0x1
+#define E1000_LEDCTL_MODE_LINK_UP 0x2
+#define E1000_LEDCTL_MODE_ACTIVITY 0x3
+#define E1000_LEDCTL_MODE_LINK_ACTIVITY 0x4
+#define E1000_LEDCTL_MODE_LINK_10 0x5
+#define E1000_LEDCTL_MODE_LINK_100 0x6
+#define E1000_LEDCTL_MODE_LINK_1000 0x7
+#define E1000_LEDCTL_MODE_PCIX_MODE 0x8
+#define E1000_LEDCTL_MODE_FULL_DUPLEX 0x9
+#define E1000_LEDCTL_MODE_COLLISION 0xA
+#define E1000_LEDCTL_MODE_BUS_SPEED 0xB
+#define E1000_LEDCTL_MODE_BUS_SIZE 0xC
+#define E1000_LEDCTL_MODE_PAUSED 0xD
+#define E1000_LEDCTL_MODE_LED_ON 0xE
+#define E1000_LEDCTL_MODE_LED_OFF 0xF
+
+/* Receive Address */
+#define E1000_RAH_AV 0x80000000 /* Receive descriptor valid */
+
+/* Interrupt Cause Read */
+#define E1000_ICR_TXDW 0x00000001 /* Transmit desc written back */
+#define E1000_ICR_TXQE 0x00000002 /* Transmit Queue empty */
+#define E1000_ICR_LSC 0x00000004 /* Link Status Change */
+#define E1000_ICR_RXSEQ 0x00000008 /* rx sequence error */
+#define E1000_ICR_RXDMT0 0x00000010 /* rx desc min. threshold (0) */
+#define E1000_ICR_RXO 0x00000040 /* rx overrun */
+#define E1000_ICR_RXT0 0x00000080 /* rx timer intr (ring 0) */
+#define E1000_ICR_MDAC 0x00000200 /* MDIO access complete */
+#define E1000_ICR_RXCFG 0x00000400 /* RX /c/ ordered set */
+#define E1000_ICR_GPI_EN0 0x00000800 /* GP Int 0 */
+#define E1000_ICR_GPI_EN1 0x00001000 /* GP Int 1 */
+#define E1000_ICR_GPI_EN2 0x00002000 /* GP Int 2 */
+#define E1000_ICR_GPI_EN3 0x00004000 /* GP Int 3 */
+#define E1000_ICR_TXD_LOW 0x00008000
+#define E1000_ICR_SRPD 0x00010000
+#define E1000_ICR_ACK 0x00020000 /* Receive Ack frame */
+#define E1000_ICR_MNG 0x00040000 /* Manageability event */
+#define E1000_ICR_DOCK 0x00080000 /* Dock/Undock */
+#define E1000_ICR_INT_ASSERTED 0x80000000 /* If this bit asserted, the driver should claim the interrupt */
+
+/* Interrupt Cause Set */
+#define E1000_ICS_TXDW E1000_ICR_TXDW /* Transmit desc written back */
+#define E1000_ICS_TXQE E1000_ICR_TXQE /* Transmit Queue empty */
+#define E1000_ICS_LSC E1000_ICR_LSC /* Link Status Change */
+#define E1000_ICS_RXSEQ E1000_ICR_RXSEQ /* rx sequence error */
+#define E1000_ICS_RXDMT0 E1000_ICR_RXDMT0 /* rx desc min. threshold */
+#define E1000_ICS_RXO E1000_ICR_RXO /* rx overrun */
+#define E1000_ICS_RXT0 E1000_ICR_RXT0 /* rx timer intr */
+#define E1000_ICS_MDAC E1000_ICR_MDAC /* MDIO access complete */
+#define E1000_ICS_RXCFG E1000_ICR_RXCFG /* RX /c/ ordered set */
+#define E1000_ICS_GPI_EN0 E1000_ICR_GPI_EN0 /* GP Int 0 */
+#define E1000_ICS_GPI_EN1 E1000_ICR_GPI_EN1 /* GP Int 1 */
+#define E1000_ICS_GPI_EN2 E1000_ICR_GPI_EN2 /* GP Int 2 */
+#define E1000_ICS_GPI_EN3 E1000_ICR_GPI_EN3 /* GP Int 3 */
+#define E1000_ICS_TXD_LOW E1000_ICR_TXD_LOW
+#define E1000_ICS_SRPD E1000_ICR_SRPD
+#define E1000_ICS_ACK E1000_ICR_ACK /* Receive Ack frame */
+#define E1000_ICS_MNG E1000_ICR_MNG /* Manageability event */
+#define E1000_ICS_DOCK E1000_ICR_DOCK /* Dock/Undock */
+
+/* Interrupt Mask Set */
+#define E1000_IMS_TXDW E1000_ICR_TXDW /* Transmit desc written back */
+#define E1000_IMS_TXQE E1000_ICR_TXQE /* Transmit Queue empty */
+#define E1000_IMS_LSC E1000_ICR_LSC /* Link Status Change */
+#define E1000_IMS_RXSEQ E1000_ICR_RXSEQ /* rx sequence error */
+#define E1000_IMS_RXDMT0 E1000_ICR_RXDMT0 /* rx desc min. threshold */
+#define E1000_IMS_RXO E1000_ICR_RXO /* rx overrun */
+#define E1000_IMS_RXT0 E1000_ICR_RXT0 /* rx timer intr */
+#define E1000_IMS_MDAC E1000_ICR_MDAC /* MDIO access complete */
+#define E1000_IMS_RXCFG E1000_ICR_RXCFG /* RX /c/ ordered set */
+#define E1000_IMS_GPI_EN0 E1000_ICR_GPI_EN0 /* GP Int 0 */
+#define E1000_IMS_GPI_EN1 E1000_ICR_GPI_EN1 /* GP Int 1 */
+#define E1000_IMS_GPI_EN2 E1000_ICR_GPI_EN2 /* GP Int 2 */
+#define E1000_IMS_GPI_EN3 E1000_ICR_GPI_EN3 /* GP Int 3 */
+#define E1000_IMS_TXD_LOW E1000_ICR_TXD_LOW
+#define E1000_IMS_SRPD E1000_ICR_SRPD
+#define E1000_IMS_ACK E1000_ICR_ACK /* Receive Ack frame */
+#define E1000_IMS_MNG E1000_ICR_MNG /* Manageability event */
+#define E1000_IMS_DOCK E1000_ICR_DOCK /* Dock/Undock */
+
+/* Interrupt Mask Clear */
+#define E1000_IMC_TXDW E1000_ICR_TXDW /* Transmit desc written back */
+#define E1000_IMC_TXQE E1000_ICR_TXQE /* Transmit Queue empty */
+#define E1000_IMC_LSC E1000_ICR_LSC /* Link Status Change */
+#define E1000_IMC_RXSEQ E1000_ICR_RXSEQ /* rx sequence error */
+#define E1000_IMC_RXDMT0 E1000_ICR_RXDMT0 /* rx desc min. threshold */
+#define E1000_IMC_RXO E1000_ICR_RXO /* rx overrun */
+#define E1000_IMC_RXT0 E1000_ICR_RXT0 /* rx timer intr */
+#define E1000_IMC_MDAC E1000_ICR_MDAC /* MDIO access complete */
+#define E1000_IMC_RXCFG E1000_ICR_RXCFG /* RX /c/ ordered set */
+#define E1000_IMC_GPI_EN0 E1000_ICR_GPI_EN0 /* GP Int 0 */
+#define E1000_IMC_GPI_EN1 E1000_ICR_GPI_EN1 /* GP Int 1 */
+#define E1000_IMC_GPI_EN2 E1000_ICR_GPI_EN2 /* GP Int 2 */
+#define E1000_IMC_GPI_EN3 E1000_ICR_GPI_EN3 /* GP Int 3 */
+#define E1000_IMC_TXD_LOW E1000_ICR_TXD_LOW
+#define E1000_IMC_SRPD E1000_ICR_SRPD
+#define E1000_IMC_ACK E1000_ICR_ACK /* Receive Ack frame */
+#define E1000_IMC_MNG E1000_ICR_MNG /* Manageability event */
+#define E1000_IMC_DOCK E1000_ICR_DOCK /* Dock/Undock */
+
+/* Receive Control */
+#define E1000_RCTL_RST 0x00000001 /* Software reset */
+#define E1000_RCTL_EN 0x00000002 /* enable */
+#define E1000_RCTL_SBP 0x00000004 /* store bad packet */
+#define E1000_RCTL_UPE 0x00000008 /* unicast promiscuous enable */
+#define E1000_RCTL_MPE 0x00000010 /* multicast promiscuous enab */
+#define E1000_RCTL_LPE 0x00000020 /* long packet enable */
+#define E1000_RCTL_LBM_NO 0x00000000 /* no loopback mode */
+#define E1000_RCTL_LBM_MAC 0x00000040 /* MAC loopback mode */
+#define E1000_RCTL_LBM_SLP 0x00000080 /* serial link loopback mode */
+#define E1000_RCTL_LBM_TCVR 0x000000C0 /* tcvr loopback mode */
+#define E1000_RCTL_DTYP_MASK 0x00000C00 /* Descriptor type mask */
+#define E1000_RCTL_DTYP_PS 0x00000400 /* Packet Split descriptor */
+#define E1000_RCTL_RDMTS_HALF 0x00000000 /* rx desc min threshold size */
+#define E1000_RCTL_RDMTS_QUAT 0x00000100 /* rx desc min threshold size */
+#define E1000_RCTL_RDMTS_EIGTH 0x00000200 /* rx desc min threshold size */
+#define E1000_RCTL_MO_SHIFT 12 /* multicast offset shift */
+#define E1000_RCTL_MO_0 0x00000000 /* multicast offset 11:0 */
+#define E1000_RCTL_MO_1 0x00001000 /* multicast offset 12:1 */
+#define E1000_RCTL_MO_2 0x00002000 /* multicast offset 13:2 */
+#define E1000_RCTL_MO_3 0x00003000 /* multicast offset 15:4 */
+#define E1000_RCTL_MDR 0x00004000 /* multicast desc ring 0 */
+#define E1000_RCTL_BAM 0x00008000 /* broadcast enable */
+/* these buffer sizes are valid if E1000_RCTL_BSEX is 0 */
+#define E1000_RCTL_SZ_2048 0x00000000 /* rx buffer size 2048 */
+#define E1000_RCTL_SZ_1024 0x00010000 /* rx buffer size 1024 */
+#define E1000_RCTL_SZ_512 0x00020000 /* rx buffer size 512 */
+#define E1000_RCTL_SZ_256 0x00030000 /* rx buffer size 256 */
+/* these buffer sizes are valid if E1000_RCTL_BSEX is 1 */
+#define E1000_RCTL_SZ_16384 0x00010000 /* rx buffer size 16384 */
+#define E1000_RCTL_SZ_8192 0x00020000 /* rx buffer size 8192 */
+#define E1000_RCTL_SZ_4096 0x00030000 /* rx buffer size 4096 */
+#define E1000_RCTL_VFE 0x00040000 /* vlan filter enable */
+#define E1000_RCTL_CFIEN 0x00080000 /* canonical form enable */
+#define E1000_RCTL_CFI 0x00100000 /* canonical form indicator */
+#define E1000_RCTL_DPF 0x00400000 /* discard pause frames */
+#define E1000_RCTL_PMCF 0x00800000 /* pass MAC control frames */
+#define E1000_RCTL_BSEX 0x02000000 /* Buffer size extension */
+#define E1000_RCTL_SECRC 0x04000000 /* Strip Ethernet CRC */
+#define E1000_RCTL_FLXBUF_MASK 0x78000000 /* Flexible buffer size */
+#define E1000_RCTL_FLXBUF_SHIFT 27 /* Flexible buffer shift */
+
+/* Use byte values for the following shift parameters
+ * Usage:
+ * psrctl |= (((ROUNDUP(value0, 128) >> E1000_PSRCTL_BSIZE0_SHIFT) &
+ * E1000_PSRCTL_BSIZE0_MASK) |
+ * ((ROUNDUP(value1, 1024) >> E1000_PSRCTL_BSIZE1_SHIFT) &
+ * E1000_PSRCTL_BSIZE1_MASK) |
+ * ((ROUNDUP(value2, 1024) << E1000_PSRCTL_BSIZE2_SHIFT) &
+ * E1000_PSRCTL_BSIZE2_MASK) |
+ * ((ROUNDUP(value3, 1024) << E1000_PSRCTL_BSIZE3_SHIFT) |;
+ * E1000_PSRCTL_BSIZE3_MASK))
+ * where value0 = [128..16256], default=256
+ * value1 = [1024..64512], default=4096
+ * value2 = [0..64512], default=4096
+ * value3 = [0..64512], default=0
+ */
+
+#define E1000_PSRCTL_BSIZE0_MASK 0x0000007F
+#define E1000_PSRCTL_BSIZE1_MASK 0x00003F00
+#define E1000_PSRCTL_BSIZE2_MASK 0x003F0000
+#define E1000_PSRCTL_BSIZE3_MASK 0x3F000000
+
+#define E1000_PSRCTL_BSIZE0_SHIFT 7 /* Shift _right_ 7 */
+#define E1000_PSRCTL_BSIZE1_SHIFT 2 /* Shift _right_ 2 */
+#define E1000_PSRCTL_BSIZE2_SHIFT 6 /* Shift _left_ 6 */
+#define E1000_PSRCTL_BSIZE3_SHIFT 14 /* Shift _left_ 14 */
+
+/* Receive Descriptor */
+#define E1000_RDT_DELAY 0x0000ffff /* Delay timer (1=1024us) */
+#define E1000_RDT_FPDB 0x80000000 /* Flush descriptor block */
+#define E1000_RDLEN_LEN 0x0007ff80 /* descriptor length */
+#define E1000_RDH_RDH 0x0000ffff /* receive descriptor head */
+#define E1000_RDT_RDT 0x0000ffff /* receive descriptor tail */
+
+/* Flow Control */
+#define E1000_FCRTH_RTH 0x0000FFF8 /* Mask Bits[15:3] for RTH */
+#define E1000_FCRTH_XFCE 0x80000000 /* External Flow Control Enable */
+#define E1000_FCRTL_RTL 0x0000FFF8 /* Mask Bits[15:3] for RTL */
+#define E1000_FCRTL_XONE 0x80000000 /* Enable XON frame transmission */
+
+/* Header split receive */
+#define E1000_RFCTL_ISCSI_DIS 0x00000001
+#define E1000_RFCTL_ISCSI_DWC_MASK 0x0000003E
+#define E1000_RFCTL_ISCSI_DWC_SHIFT 1
+#define E1000_RFCTL_NFSW_DIS 0x00000040
+#define E1000_RFCTL_NFSR_DIS 0x00000080
+#define E1000_RFCTL_NFS_VER_MASK 0x00000300
+#define E1000_RFCTL_NFS_VER_SHIFT 8
+#define E1000_RFCTL_IPV6_DIS 0x00000400
+#define E1000_RFCTL_IPV6_XSUM_DIS 0x00000800
+#define E1000_RFCTL_ACK_DIS 0x00001000
+#define E1000_RFCTL_ACKD_DIS 0x00002000
+#define E1000_RFCTL_IPFRSP_DIS 0x00004000
+#define E1000_RFCTL_EXTEN 0x00008000
+#define E1000_RFCTL_IPV6_EX_DIS 0x00010000
+#define E1000_RFCTL_NEW_IPV6_EXT_DIS 0x00020000
+
+/* Receive Descriptor Control */
+#define E1000_RXDCTL_PTHRESH 0x0000003F /* RXDCTL Prefetch Threshold */
+#define E1000_RXDCTL_HTHRESH 0x00003F00 /* RXDCTL Host Threshold */
+#define E1000_RXDCTL_WTHRESH 0x003F0000 /* RXDCTL Writeback Threshold */
+#define E1000_RXDCTL_GRAN 0x01000000 /* RXDCTL Granularity */
+
+/* Transmit Descriptor Control */
+#define E1000_TXDCTL_PTHRESH 0x000000FF /* TXDCTL Prefetch Threshold */
+#define E1000_TXDCTL_HTHRESH 0x0000FF00 /* TXDCTL Host Threshold */
+#define E1000_TXDCTL_WTHRESH 0x00FF0000 /* TXDCTL Writeback Threshold */
+#define E1000_TXDCTL_GRAN 0x01000000 /* TXDCTL Granularity */
+#define E1000_TXDCTL_LWTHRESH 0xFE000000 /* TXDCTL Low Threshold */
+#define E1000_TXDCTL_FULL_TX_DESC_WB 0x01010000 /* GRAN=1, WTHRESH=1 */
+#define E1000_TXDCTL_COUNT_DESC 0x00400000 /* Enable the counting of desc.
+ still to be processed. */
+
+/* Transmit Configuration Word */
+#define E1000_TXCW_FD 0x00000020 /* TXCW full duplex */
+#define E1000_TXCW_HD 0x00000040 /* TXCW half duplex */
+#define E1000_TXCW_PAUSE 0x00000080 /* TXCW sym pause request */
+#define E1000_TXCW_ASM_DIR 0x00000100 /* TXCW astm pause direction */
+#define E1000_TXCW_PAUSE_MASK 0x00000180 /* TXCW pause request mask */
+#define E1000_TXCW_RF 0x00003000 /* TXCW remote fault */
+#define E1000_TXCW_NP 0x00008000 /* TXCW next page */
+#define E1000_TXCW_CW 0x0000ffff /* TxConfigWord mask */
+#define E1000_TXCW_TXC 0x40000000 /* Transmit Config control */
+#define E1000_TXCW_ANE 0x80000000 /* Auto-neg enable */
+
+/* Receive Configuration Word */
+#define E1000_RXCW_CW 0x0000ffff /* RxConfigWord mask */
+#define E1000_RXCW_NC 0x04000000 /* Receive config no carrier */
+#define E1000_RXCW_IV 0x08000000 /* Receive config invalid */
+#define E1000_RXCW_CC 0x10000000 /* Receive config change */
+#define E1000_RXCW_C 0x20000000 /* Receive config */
+#define E1000_RXCW_SYNCH 0x40000000 /* Receive config synch */
+#define E1000_RXCW_ANC 0x80000000 /* Auto-neg complete */
+
+/* Transmit Control */
+#define E1000_TCTL_RST 0x00000001 /* software reset */
+#define E1000_TCTL_EN 0x00000002 /* enable tx */
+#define E1000_TCTL_BCE 0x00000004 /* busy check enable */
+#define E1000_TCTL_PSP 0x00000008 /* pad short packets */
+#define E1000_TCTL_CT 0x00000ff0 /* collision threshold */
+#define E1000_TCTL_COLD 0x003ff000 /* collision distance */
+#define E1000_TCTL_SWXOFF 0x00400000 /* SW Xoff transmission */
+#define E1000_TCTL_PBE 0x00800000 /* Packet Burst Enable */
+#define E1000_TCTL_RTLC 0x01000000 /* Re-transmit on late collision */
+#define E1000_TCTL_NRTU 0x02000000 /* No Re-transmit on underrun */
+#define E1000_TCTL_MULR 0x10000000 /* Multiple request support */
+
+/* Receive Checksum Control */
+#define E1000_RXCSUM_PCSS_MASK 0x000000FF /* Packet Checksum Start */
+#define E1000_RXCSUM_IPOFL 0x00000100 /* IPv4 checksum offload */
+#define E1000_RXCSUM_TUOFL 0x00000200 /* TCP / UDP checksum offload */
+#define E1000_RXCSUM_IPV6OFL 0x00000400 /* IPv6 checksum offload */
+#define E1000_RXCSUM_IPPCSE 0x00001000 /* IP payload checksum enable */
+#define E1000_RXCSUM_PCSD 0x00002000 /* packet checksum disabled */
+
+
+/* Definitions for power management and wakeup registers */
+/* Wake Up Control */
+#define E1000_WUC_APME 0x00000001 /* APM Enable */
+#define E1000_WUC_PME_EN 0x00000002 /* PME Enable */
+#define E1000_WUC_PME_STATUS 0x00000004 /* PME Status */
+#define E1000_WUC_APMPME 0x00000008 /* Assert PME on APM Wakeup */
+#define E1000_WUC_SPM 0x80000000 /* Enable SPM */
+
+/* Wake Up Filter Control */
+#define E1000_WUFC_LNKC 0x00000001 /* Link Status Change Wakeup Enable */
+#define E1000_WUFC_MAG 0x00000002 /* Magic Packet Wakeup Enable */
+#define E1000_WUFC_EX 0x00000004 /* Directed Exact Wakeup Enable */
+#define E1000_WUFC_MC 0x00000008 /* Directed Multicast Wakeup Enable */
+#define E1000_WUFC_BC 0x00000010 /* Broadcast Wakeup Enable */
+#define E1000_WUFC_ARP 0x00000020 /* ARP Request Packet Wakeup Enable */
+#define E1000_WUFC_IPV4 0x00000040 /* Directed IPv4 Packet Wakeup Enable */
+#define E1000_WUFC_IPV6 0x00000080 /* Directed IPv6 Packet Wakeup Enable */
+#define E1000_WUFC_IGNORE_TCO 0x00008000 /* Ignore WakeOn TCO packets */
+#define E1000_WUFC_FLX0 0x00010000 /* Flexible Filter 0 Enable */
+#define E1000_WUFC_FLX1 0x00020000 /* Flexible Filter 1 Enable */
+#define E1000_WUFC_FLX2 0x00040000 /* Flexible Filter 2 Enable */
+#define E1000_WUFC_FLX3 0x00080000 /* Flexible Filter 3 Enable */
+#define E1000_WUFC_ALL_FILTERS 0x000F00FF /* Mask for all wakeup filters */
+#define E1000_WUFC_FLX_OFFSET 16 /* Offset to the Flexible Filters bits */
+#define E1000_WUFC_FLX_FILTERS 0x000F0000 /* Mask for the 4 flexible filters */
+
+/* Wake Up Status */
+#define E1000_WUS_LNKC 0x00000001 /* Link Status Changed */
+#define E1000_WUS_MAG 0x00000002 /* Magic Packet Received */
+#define E1000_WUS_EX 0x00000004 /* Directed Exact Received */
+#define E1000_WUS_MC 0x00000008 /* Directed Multicast Received */
+#define E1000_WUS_BC 0x00000010 /* Broadcast Received */
+#define E1000_WUS_ARP 0x00000020 /* ARP Request Packet Received */
+#define E1000_WUS_IPV4 0x00000040 /* Directed IPv4 Packet Wakeup Received */
+#define E1000_WUS_IPV6 0x00000080 /* Directed IPv6 Packet Wakeup Received */
+#define E1000_WUS_FLX0 0x00010000 /* Flexible Filter 0 Match */
+#define E1000_WUS_FLX1 0x00020000 /* Flexible Filter 1 Match */
+#define E1000_WUS_FLX2 0x00040000 /* Flexible Filter 2 Match */
+#define E1000_WUS_FLX3 0x00080000 /* Flexible Filter 3 Match */
+#define E1000_WUS_FLX_FILTERS 0x000F0000 /* Mask for the 4 flexible filters */
+
+/* Management Control */
+#define E1000_MANC_SMBUS_EN 0x00000001 /* SMBus Enabled - RO */
+#define E1000_MANC_ASF_EN 0x00000002 /* ASF Enabled - RO */
+#define E1000_MANC_R_ON_FORCE 0x00000004 /* Reset on Force TCO - RO */
+#define E1000_MANC_RMCP_EN 0x00000100 /* Enable RCMP 026Fh Filtering */
+#define E1000_MANC_0298_EN 0x00000200 /* Enable RCMP 0298h Filtering */
+#define E1000_MANC_IPV4_EN 0x00000400 /* Enable IPv4 */
+#define E1000_MANC_IPV6_EN 0x00000800 /* Enable IPv6 */
+#define E1000_MANC_SNAP_EN 0x00001000 /* Accept LLC/SNAP */
+#define E1000_MANC_ARP_EN 0x00002000 /* Enable ARP Request Filtering */
+#define E1000_MANC_NEIGHBOR_EN 0x00004000 /* Enable Neighbor Discovery
+ * Filtering */
+#define E1000_MANC_ARP_RES_EN 0x00008000 /* Enable ARP response Filtering */
+#define E1000_MANC_TCO_RESET 0x00010000 /* TCO Reset Occurred */
+#define E1000_MANC_RCV_TCO_EN 0x00020000 /* Receive TCO Packets Enabled */
+#define E1000_MANC_REPORT_STATUS 0x00040000 /* Status Reporting Enabled */
+#define E1000_MANC_BLK_PHY_RST_ON_IDE 0x00040000 /* Block phy resets */
+#define E1000_MANC_EN_MAC_ADDR_FILTER 0x00100000 /* Enable MAC address
+ * filtering */
+#define E1000_MANC_EN_MNG2HOST 0x00200000 /* Enable MNG packets to host
+ * memory */
+#define E1000_MANC_EN_IP_ADDR_FILTER 0x00400000 /* Enable IP address
+ * filtering */
+#define E1000_MANC_EN_XSUM_FILTER 0x00800000 /* Enable checksum filtering */
+#define E1000_MANC_BR_EN 0x01000000 /* Enable broadcast filtering */
+#define E1000_MANC_SMB_REQ 0x01000000 /* SMBus Request */
+#define E1000_MANC_SMB_GNT 0x02000000 /* SMBus Grant */
+#define E1000_MANC_SMB_CLK_IN 0x04000000 /* SMBus Clock In */
+#define E1000_MANC_SMB_DATA_IN 0x08000000 /* SMBus Data In */
+#define E1000_MANC_SMB_DATA_OUT 0x10000000 /* SMBus Data Out */
+#define E1000_MANC_SMB_CLK_OUT 0x20000000 /* SMBus Clock Out */
+
+#define E1000_MANC_SMB_DATA_OUT_SHIFT 28 /* SMBus Data Out Shift */
+#define E1000_MANC_SMB_CLK_OUT_SHIFT 29 /* SMBus Clock Out Shift */
+
+/* SW Semaphore Register */
+#define E1000_SWSM_SMBI 0x00000001 /* Driver Semaphore bit */
+#define E1000_SWSM_SWESMBI 0x00000002 /* FW Semaphore bit */
+#define E1000_SWSM_WMNG 0x00000004 /* Wake MNG Clock */
+#define E1000_SWSM_DRV_LOAD 0x00000008 /* Driver Loaded Bit */
+
+/* FW Semaphore Register */
+#define E1000_FWSM_MODE_MASK 0x0000000E /* FW mode */
+#define E1000_FWSM_MODE_SHIFT 1
+#define E1000_FWSM_FW_VALID 0x00008000 /* FW established a valid mode */
+
+/* FFLT Debug Register */
+#define E1000_FFLT_DBG_INVC 0x00100000 /* Invalid /C/ code handling */
+
+typedef enum {
+ em_mng_mode_none = 0,
+ em_mng_mode_asf,
+ em_mng_mode_pt,
+ em_mng_mode_ipmi,
+ em_mng_mode_host_interface_only
+} em_mng_mode;
+
+/* Host Inteface Control Register */
+#define E1000_HICR_EN 0x00000001 /* Enable Bit - RO */
+#define E1000_HICR_C 0x00000002 /* Driver sets this bit when done
+ * to put command in RAM */
+#define E1000_HICR_SV 0x00000004 /* Status Validity */
+#define E1000_HICR_FWR 0x00000080 /* FW reset. Set by the Host */
+
+/* Host Interface Command Interface - Address range 0x8800-0x8EFF */
+#define E1000_HI_MAX_DATA_LENGTH 252 /* Host Interface data length */
+#define E1000_HI_MAX_BLOCK_BYTE_LENGTH 1792 /* Number of bytes in range */
+#define E1000_HI_MAX_BLOCK_DWORD_LENGTH 448 /* Number of dwords in range */
+#define E1000_HI_COMMAND_TIMEOUT 500 /* Time in ms to process HI command */
+
+struct em_host_command_header {
+ uint8_t command_id;
+ uint8_t command_length;
+ uint8_t command_options; /* I/F bits for command, status for return */
+ uint8_t checksum;
+};
+struct em_host_command_info {
+ struct em_host_command_header command_header; /* Command Head/Command Result Head has 4 bytes */
+ uint8_t command_data[E1000_HI_MAX_DATA_LENGTH]; /* Command data can length 0..252 */
+};
+
+/* Host SMB register #0 */
+#define E1000_HSMC0R_CLKIN 0x00000001 /* SMB Clock in */
+#define E1000_HSMC0R_DATAIN 0x00000002 /* SMB Data in */
+#define E1000_HSMC0R_DATAOUT 0x00000004 /* SMB Data out */
+#define E1000_HSMC0R_CLKOUT 0x00000008 /* SMB Clock out */
+
+/* Host SMB register #1 */
+#define E1000_HSMC1R_CLKIN E1000_HSMC0R_CLKIN
+#define E1000_HSMC1R_DATAIN E1000_HSMC0R_DATAIN
+#define E1000_HSMC1R_DATAOUT E1000_HSMC0R_DATAOUT
+#define E1000_HSMC1R_CLKOUT E1000_HSMC0R_CLKOUT
+
+/* FW Status Register */
+#define E1000_FWSTS_FWS_MASK 0x000000FF /* FW Status */
+
+/* Wake Up Packet Length */
+#define E1000_WUPL_LENGTH_MASK 0x0FFF /* Only the lower 12 bits are valid */
+
+#define E1000_MDALIGN 4096
+
+#define E1000_GCR_BEM32 0x00400000
+/* Function Active and Power State to MNG */
+#define E1000_FACTPS_FUNC0_POWER_STATE_MASK 0x00000003
+#define E1000_FACTPS_LAN0_VALID 0x00000004
+#define E1000_FACTPS_FUNC0_AUX_EN 0x00000008
+#define E1000_FACTPS_FUNC1_POWER_STATE_MASK 0x000000C0
+#define E1000_FACTPS_FUNC1_POWER_STATE_SHIFT 6
+#define E1000_FACTPS_LAN1_VALID 0x00000100
+#define E1000_FACTPS_FUNC1_AUX_EN 0x00000200
+#define E1000_FACTPS_FUNC2_POWER_STATE_MASK 0x00003000
+#define E1000_FACTPS_FUNC2_POWER_STATE_SHIFT 12
+#define E1000_FACTPS_IDE_ENABLE 0x00004000
+#define E1000_FACTPS_FUNC2_AUX_EN 0x00008000
+#define E1000_FACTPS_FUNC3_POWER_STATE_MASK 0x000C0000
+#define E1000_FACTPS_FUNC3_POWER_STATE_SHIFT 18
+#define E1000_FACTPS_SP_ENABLE 0x00100000
+#define E1000_FACTPS_FUNC3_AUX_EN 0x00200000
+#define E1000_FACTPS_FUNC4_POWER_STATE_MASK 0x03000000
+#define E1000_FACTPS_FUNC4_POWER_STATE_SHIFT 24
+#define E1000_FACTPS_IPMI_ENABLE 0x04000000
+#define E1000_FACTPS_FUNC4_AUX_EN 0x08000000
+#define E1000_FACTPS_MNGCG 0x20000000
+#define E1000_FACTPS_LAN_FUNC_SEL 0x40000000
+#define E1000_FACTPS_PM_STATE_CHANGED 0x80000000
+
+/* EEPROM Commands - Microwire */
+#define EEPROM_READ_OPCODE_MICROWIRE 0x6 /* EEPROM read opcode */
+#define EEPROM_WRITE_OPCODE_MICROWIRE 0x5 /* EEPROM write opcode */
+#define EEPROM_ERASE_OPCODE_MICROWIRE 0x7 /* EEPROM erase opcode */
+#define EEPROM_EWEN_OPCODE_MICROWIRE 0x13 /* EEPROM erase/write enable */
+#define EEPROM_EWDS_OPCODE_MICROWIRE 0x10 /* EEPROM erast/write disable */
+
+/* EEPROM Commands - SPI */
+#define EEPROM_MAX_RETRY_SPI 5000 /* Max wait of 5ms, for RDY signal */
+#define EEPROM_READ_OPCODE_SPI 0x03 /* EEPROM read opcode */
+#define EEPROM_WRITE_OPCODE_SPI 0x02 /* EEPROM write opcode */
+#define EEPROM_A8_OPCODE_SPI 0x08 /* opcode bit-3 = address bit-8 */
+#define EEPROM_WREN_OPCODE_SPI 0x06 /* EEPROM set Write Enable latch */
+#define EEPROM_WRDI_OPCODE_SPI 0x04 /* EEPROM reset Write Enable latch */
+#define EEPROM_RDSR_OPCODE_SPI 0x05 /* EEPROM read Status register */
+#define EEPROM_WRSR_OPCODE_SPI 0x01 /* EEPROM write Status register */
+#define EEPROM_ERASE4K_OPCODE_SPI 0x20 /* EEPROM ERASE 4KB */
+#define EEPROM_ERASE64K_OPCODE_SPI 0xD8 /* EEPROM ERASE 64KB */
+#define EEPROM_ERASE256_OPCODE_SPI 0xDB /* EEPROM ERASE 256B */
+
+/* EEPROM Size definitions */
+#define EEPROM_WORD_SIZE_SHIFT 6
+#define EEPROM_SIZE_SHIFT 10
+#define EEPROM_SIZE_MASK 0x1C00
+
+/* EEPROM Word Offsets */
+#define EEPROM_COMPAT 0x0003
+#define EEPROM_ID_LED_SETTINGS 0x0004
+#define EEPROM_SERDES_AMPLITUDE 0x0006 /* For SERDES output amplitude adjustment. */
+#define EEPROM_PHY_CLASS_WORD 0x0007
+#define EEPROM_INIT_CONTROL1_REG 0x000A
+#define EEPROM_INIT_CONTROL2_REG 0x000F
+#define EEPROM_INIT_CONTROL3_PORT_B 0x0014
+#define EEPROM_INIT_CONTROL3_PORT_A 0x0024
+#define EEPROM_CFG 0x0012
+#define EEPROM_FLASH_VERSION 0x0032
+#define EEPROM_CHECKSUM_REG 0x003F
+
+/* Word definitions for ID LED Settings */
+#define ID_LED_RESERVED_0000 0x0000
+#define ID_LED_RESERVED_FFFF 0xFFFF
+#define ID_LED_DEFAULT ((ID_LED_OFF1_ON2 << 12) | \
+ (ID_LED_OFF1_OFF2 << 8) | \
+ (ID_LED_DEF1_DEF2 << 4) | \
+ (ID_LED_DEF1_DEF2))
+#define ID_LED_DEF1_DEF2 0x1
+#define ID_LED_DEF1_ON2 0x2
+#define ID_LED_DEF1_OFF2 0x3
+#define ID_LED_ON1_DEF2 0x4
+#define ID_LED_ON1_ON2 0x5
+#define ID_LED_ON1_OFF2 0x6
+#define ID_LED_OFF1_DEF2 0x7
+#define ID_LED_OFF1_ON2 0x8
+#define ID_LED_OFF1_OFF2 0x9
+
+#define IGP_ACTIVITY_LED_MASK 0xFFFFF0FF
+#define IGP_ACTIVITY_LED_ENABLE 0x0300
+#define IGP_LED3_MODE 0x07000000
+
+
+/* Mask bits for SERDES amplitude adjustment in Word 6 of the EEPROM */
+#define EEPROM_SERDES_AMPLITUDE_MASK 0x000F
+
+/* Mask bit for PHY class in Word 7 of the EEPROM */
+#define EEPROM_PHY_CLASS_A 0x8000
+
+/* Mask bits for fields in Word 0x0a of the EEPROM */
+#define EEPROM_WORD0A_ILOS 0x0010
+#define EEPROM_WORD0A_SWDPIO 0x01E0
+#define EEPROM_WORD0A_LRST 0x0200
+#define EEPROM_WORD0A_FD 0x0400
+#define EEPROM_WORD0A_66MHZ 0x0800
+
+/* Mask bits for fields in Word 0x0f of the EEPROM */
+#define EEPROM_WORD0F_PAUSE_MASK 0x3000
+#define EEPROM_WORD0F_PAUSE 0x1000
+#define EEPROM_WORD0F_ASM_DIR 0x2000
+#define EEPROM_WORD0F_ANE 0x0800
+#define EEPROM_WORD0F_SWPDIO_EXT 0x00F0
+
+/* For checksumming, the sum of all words in the EEPROM should equal 0xBABA. */
+#define EEPROM_SUM 0xBABA
+
+/* EEPROM Map defines (WORD OFFSETS)*/
+#define EEPROM_NODE_ADDRESS_BYTE_0 0
+#define EEPROM_PBA_BYTE_1 8
+
+#define EEPROM_RESERVED_WORD 0xFFFF
+
+/* EEPROM Map Sizes (Byte Counts) */
+#define PBA_SIZE 4
+
+/* Collision related configuration parameters */
+#define E1000_COLLISION_THRESHOLD 15
+#define E1000_CT_SHIFT 4
+#define E1000_COLLISION_DISTANCE 64
+#define E1000_FDX_COLLISION_DISTANCE E1000_COLLISION_DISTANCE
+#define E1000_HDX_COLLISION_DISTANCE E1000_COLLISION_DISTANCE
+#define E1000_COLD_SHIFT 12
+
+/* Number of Transmit and Receive Descriptors must be a multiple of 8 */
+#define REQ_TX_DESCRIPTOR_MULTIPLE 8
+#define REQ_RX_DESCRIPTOR_MULTIPLE 8
+
+/* Default values for the transmit IPG register */
+#define DEFAULT_82542_TIPG_IPGT 10
+#define DEFAULT_82543_TIPG_IPGT_FIBER 9
+#define DEFAULT_82543_TIPG_IPGT_COPPER 8
+
+#define E1000_TIPG_IPGT_MASK 0x000003FF
+#define E1000_TIPG_IPGR1_MASK 0x000FFC00
+#define E1000_TIPG_IPGR2_MASK 0x3FF00000
+
+#define DEFAULT_82542_TIPG_IPGR1 2
+#define DEFAULT_82543_TIPG_IPGR1 8
+#define E1000_TIPG_IPGR1_SHIFT 10
+
+#define DEFAULT_82542_TIPG_IPGR2 10
+#define DEFAULT_82543_TIPG_IPGR2 6
+#define E1000_TIPG_IPGR2_SHIFT 20
+
+#define E1000_TXDMAC_DPP 0x00000001
+
+/* Adaptive IFS defines */
+#define TX_THRESHOLD_START 8
+#define TX_THRESHOLD_INCREMENT 10
+#define TX_THRESHOLD_DECREMENT 1
+#define TX_THRESHOLD_STOP 190
+#define TX_THRESHOLD_DISABLE 0
+#define TX_THRESHOLD_TIMER_MS 10000
+#define MIN_NUM_XMITS 1000
+#define IFS_MAX 80
+#define IFS_STEP 10
+#define IFS_MIN 40
+#define IFS_RATIO 4
+
+/* Extended Configuration Control and Size */
+#define E1000_EXTCNF_CTRL_PCIE_WRITE_ENABLE 0x00000001
+#define E1000_EXTCNF_CTRL_PHY_WRITE_ENABLE 0x00000002
+#define E1000_EXTCNF_CTRL_D_UD_ENABLE 0x00000004
+#define E1000_EXTCNF_CTRL_D_UD_LATENCY 0x00000008
+#define E1000_EXTCNF_CTRL_D_UD_OWNER 0x00000010
+#define E1000_EXTCNF_CTRL_MDIO_SW_OWNERSHIP 0x00000020
+#define E1000_EXTCNF_CTRL_MDIO_HW_OWNERSHIP 0x00000040
+#define E1000_EXTCNF_CTRL_EXT_CNF_POINTER 0x1FFF0000
+
+#define E1000_EXTCNF_SIZE_EXT_PHY_LENGTH 0x000000FF
+#define E1000_EXTCNF_SIZE_EXT_DOCK_LENGTH 0x0000FF00
+#define E1000_EXTCNF_SIZE_EXT_PCIE_LENGTH 0x00FF0000
+
+/* PBA constants */
+#define E1000_PBA_12K 0x000C /* 12KB, default Rx allocation */
+#define E1000_PBA_16K 0x0010 /* 16KB, default TX allocation */
+#define E1000_PBA_22K 0x0016
+#define E1000_PBA_24K 0x0018
+#define E1000_PBA_30K 0x001E
+#define E1000_PBA_40K 0x0028
+#define E1000_PBA_48K 0x0030 /* 48KB, default RX allocation */
+
+/* Flow Control Constants */
+#define FLOW_CONTROL_ADDRESS_LOW 0x00C28001
+#define FLOW_CONTROL_ADDRESS_HIGH 0x00000100
+#define FLOW_CONTROL_TYPE 0x8808
+
+/* The historical defaults for the flow control values are given below. */
+#define FC_DEFAULT_HI_THRESH (0x8000) /* 32KB */
+#define FC_DEFAULT_LO_THRESH (0x4000) /* 16KB */
+#define FC_DEFAULT_TX_TIMER (0x100) /* ~130 us */
+
+/* PCIX Config space */
+#define PCIX_COMMAND_REGISTER 0xE6
+#define PCIX_STATUS_REGISTER_LO 0xE8
+#define PCIX_STATUS_REGISTER_HI 0xEA
+
+#define PCIX_COMMAND_MMRBC_MASK 0x000C
+#define PCIX_COMMAND_MMRBC_SHIFT 0x2
+#define PCIX_STATUS_HI_MMRBC_MASK 0x0060
+#define PCIX_STATUS_HI_MMRBC_SHIFT 0x5
+#define PCIX_STATUS_HI_MMRBC_4K 0x3
+#define PCIX_STATUS_HI_MMRBC_2K 0x2
+
+
+/* Number of bits required to shift right the "pause" bits from the
+ * EEPROM (bits 13:12) to the "pause" (bits 8:7) field in the TXCW register.
+ */
+#define PAUSE_SHIFT 5
+
+/* Number of bits required to shift left the "SWDPIO" bits from the
+ * EEPROM (bits 8:5) to the "SWDPIO" (bits 25:22) field in the CTRL register.
+ */
+#define SWDPIO_SHIFT 17
+
+/* Number of bits required to shift left the "SWDPIO_EXT" bits from the
+ * EEPROM word F (bits 7:4) to the bits 11:8 of The Extended CTRL register.
+ */
+#define SWDPIO__EXT_SHIFT 4
+
+/* Number of bits required to shift left the "ILOS" bit from the EEPROM
+ * (bit 4) to the "ILOS" (bit 7) field in the CTRL register.
+ */
+#define ILOS_SHIFT 3
+
+
+#define RECEIVE_BUFFER_ALIGN_SIZE (256)
+
+/* Number of milliseconds we wait for auto-negotiation to complete */
+#define LINK_UP_TIMEOUT 500
+
+/* Number of 100 microseconds we wait for PCI Express master disable */
+#define MASTER_DISABLE_TIMEOUT 800
+/* Number of milliseconds we wait for Eeprom auto read bit done after MAC reset */
+#define AUTO_READ_DONE_TIMEOUT 10
+/* Number of milliseconds we wait for PHY configuration done after MAC reset */
+#define PHY_CFG_TIMEOUT 40
+
+#define E1000_TX_BUFFER_SIZE ((uint32_t)1514)
+
+/* The carrier extension symbol, as received by the NIC. */
+#define CARRIER_EXTENSION 0x0F
+
+/* TBI_ACCEPT macro definition:
+ *
+ * This macro requires:
+ * adapter = a pointer to struct em_hw
+ * status = the 8 bit status field of the RX descriptor with EOP set
+ * error = the 8 bit error field of the RX descriptor with EOP set
+ * length = the sum of all the length fields of the RX descriptors that
+ * make up the current frame
+ * last_byte = the last byte of the frame DMAed by the hardware
+ * max_frame_length = the maximum frame length we want to accept.
+ * min_frame_length = the minimum frame length we want to accept.
+ *
+ * This macro is a conditional that should be used in the interrupt
+ * handler's Rx processing routine when RxErrors have been detected.
+ *
+ * Typical use:
+ * ...
+ * if (TBI_ACCEPT) {
+ * accept_frame = TRUE;
+ * em_tbi_adjust_stats(adapter, MacAddress);
+ * frame_length--;
+ * } else {
+ * accept_frame = FALSE;
+ * }
+ * ...
+ */
+
+#define TBI_ACCEPT(adapter, status, errors, length, last_byte) \
+ ((adapter)->tbi_compatibility_on && \
+ (((errors) & E1000_RXD_ERR_FRAME_ERR_MASK) == E1000_RXD_ERR_CE) && \
+ ((last_byte) == CARRIER_EXTENSION) && \
+ (((status) & E1000_RXD_STAT_VP) ? \
+ (((length) > ((adapter)->min_frame_size - VLAN_TAG_SIZE)) && \
+ ((length) <= ((adapter)->max_frame_size + 1))) : \
+ (((length) > (adapter)->min_frame_size) && \
+ ((length) <= ((adapter)->max_frame_size + VLAN_TAG_SIZE + 1)))))
+
+
+/* Structures, enums, and macros for the PHY */
+
+/* Bit definitions for the Management Data IO (MDIO) and Management Data
+ * Clock (MDC) pins in the Device Control Register.
+ */
+#define E1000_CTRL_PHY_RESET_DIR E1000_CTRL_SWDPIO0
+#define E1000_CTRL_PHY_RESET E1000_CTRL_SWDPIN0
+#define E1000_CTRL_MDIO_DIR E1000_CTRL_SWDPIO2
+#define E1000_CTRL_MDIO E1000_CTRL_SWDPIN2
+#define E1000_CTRL_MDC_DIR E1000_CTRL_SWDPIO3
+#define E1000_CTRL_MDC E1000_CTRL_SWDPIN3
+#define E1000_CTRL_PHY_RESET_DIR4 E1000_CTRL_EXT_SDP4_DIR
+#define E1000_CTRL_PHY_RESET4 E1000_CTRL_EXT_SDP4_DATA
+
+/* PHY 1000 MII Register/Bit Definitions */
+/* PHY Registers defined by IEEE */
+#define PHY_CTRL 0x00 /* Control Register */
+#define PHY_STATUS 0x01 /* Status Regiser */
+#define PHY_ID1 0x02 /* Phy Id Reg (word 1) */
+#define PHY_ID2 0x03 /* Phy Id Reg (word 2) */
+#define PHY_AUTONEG_ADV 0x04 /* Autoneg Advertisement */
+#define PHY_LP_ABILITY 0x05 /* Link Partner Ability (Base Page) */
+#define PHY_AUTONEG_EXP 0x06 /* Autoneg Expansion Reg */
+#define PHY_NEXT_PAGE_TX 0x07 /* Next Page TX */
+#define PHY_LP_NEXT_PAGE 0x08 /* Link Partner Next Page */
+#define PHY_1000T_CTRL 0x09 /* 1000Base-T Control Reg */
+#define PHY_1000T_STATUS 0x0A /* 1000Base-T Status Reg */
+#define PHY_EXT_STATUS 0x0F /* Extended Status Reg */
+
+/* M88E1000 Specific Registers */
+#define M88E1000_PHY_SPEC_CTRL 0x10 /* PHY Specific Control Register */
+#define M88E1000_PHY_SPEC_STATUS 0x11 /* PHY Specific Status Register */
+#define M88E1000_INT_ENABLE 0x12 /* Interrupt Enable Register */
+#define M88E1000_INT_STATUS 0x13 /* Interrupt Status Register */
+#define M88E1000_EXT_PHY_SPEC_CTRL 0x14 /* Extended PHY Specific Control */
+#define M88E1000_RX_ERR_CNTR 0x15 /* Receive Error Counter */
+
+#define M88E1000_PHY_EXT_CTRL 0x1A /* PHY extend control register */
+#define M88E1000_PHY_PAGE_SELECT 0x1D /* Reg 29 for page number setting */
+#define M88E1000_PHY_GEN_CONTROL 0x1E /* Its meaning depends on reg 29 */
+#define M88E1000_PHY_VCO_REG_BIT8 0x100 /* Bits 8 & 11 are adjusted for */
+#define M88E1000_PHY_VCO_REG_BIT11 0x800 /* improved BER performance */
+
+#define IGP01E1000_IEEE_REGS_PAGE 0x0000
+#define IGP01E1000_IEEE_RESTART_AUTONEG 0x3300
+#define IGP01E1000_IEEE_FORCE_GIGA 0x0140
+
+/* IGP01E1000 Specific Registers */
+#define IGP01E1000_PHY_PORT_CONFIG 0x10 /* PHY Specific Port Config Register */
+#define IGP01E1000_PHY_PORT_STATUS 0x11 /* PHY Specific Status Register */
+#define IGP01E1000_PHY_PORT_CTRL 0x12 /* PHY Specific Control Register */
+#define IGP01E1000_PHY_LINK_HEALTH 0x13 /* PHY Link Health Register */
+#define IGP01E1000_GMII_FIFO 0x14 /* GMII FIFO Register */
+#define IGP01E1000_PHY_CHANNEL_QUALITY 0x15 /* PHY Channel Quality Register */
+#define IGP02E1000_PHY_POWER_MGMT 0x19
+#define IGP01E1000_PHY_PAGE_SELECT 0x1F /* PHY Page Select Core Register */
+
+/* IGP01E1000 AGC Registers - stores the cable length values*/
+#define IGP01E1000_PHY_AGC_A 0x1172
+#define IGP01E1000_PHY_AGC_B 0x1272
+#define IGP01E1000_PHY_AGC_C 0x1472
+#define IGP01E1000_PHY_AGC_D 0x1872
+
+/* IGP02E1000 AGC Registers for cable length values */
+#define IGP02E1000_PHY_AGC_A 0x11B1
+#define IGP02E1000_PHY_AGC_B 0x12B1
+#define IGP02E1000_PHY_AGC_C 0x14B1
+#define IGP02E1000_PHY_AGC_D 0x18B1
+
+/* IGP01E1000 DSP Reset Register */
+#define IGP01E1000_PHY_DSP_RESET 0x1F33
+#define IGP01E1000_PHY_DSP_SET 0x1F71
+#define IGP01E1000_PHY_DSP_FFE 0x1F35
+
+#define IGP01E1000_PHY_CHANNEL_NUM 4
+#define IGP02E1000_PHY_CHANNEL_NUM 4
+
+#define IGP01E1000_PHY_AGC_PARAM_A 0x1171
+#define IGP01E1000_PHY_AGC_PARAM_B 0x1271
+#define IGP01E1000_PHY_AGC_PARAM_C 0x1471
+#define IGP01E1000_PHY_AGC_PARAM_D 0x1871
+
+#define IGP01E1000_PHY_EDAC_MU_INDEX 0xC000
+#define IGP01E1000_PHY_EDAC_SIGN_EXT_9_BITS 0x8000
+
+#define IGP01E1000_PHY_ANALOG_TX_STATE 0x2890
+#define IGP01E1000_PHY_ANALOG_CLASS_A 0x2000
+#define IGP01E1000_PHY_FORCE_ANALOG_ENABLE 0x0004
+#define IGP01E1000_PHY_DSP_FFE_CM_CP 0x0069
+
+#define IGP01E1000_PHY_DSP_FFE_DEFAULT 0x002A
+/* IGP01E1000 PCS Initialization register - stores the polarity status when
+ * speed = 1000 Mbps. */
+#define IGP01E1000_PHY_PCS_INIT_REG 0x00B4
+#define IGP01E1000_PHY_PCS_CTRL_REG 0x00B5
+
+#define IGP01E1000_ANALOG_REGS_PAGE 0x20C0
+
+#define MAX_PHY_REG_ADDRESS 0x1F /* 5 bit address bus (0-0x1F) */
+#define MAX_PHY_MULTI_PAGE_REG 0xF /*Registers that are equal on all pages*/
+/* PHY Control Register */
+#define MII_CR_SPEED_SELECT_MSB 0x0040 /* bits 6,13: 10=1000, 01=100, 00=10 */
+#define MII_CR_COLL_TEST_ENABLE 0x0080 /* Collision test enable */
+#define MII_CR_FULL_DUPLEX 0x0100 /* FDX =1, half duplex =0 */
+#define MII_CR_RESTART_AUTO_NEG 0x0200 /* Restart auto negotiation */
+#define MII_CR_ISOLATE 0x0400 /* Isolate PHY from MII */
+#define MII_CR_POWER_DOWN 0x0800 /* Power down */
+#define MII_CR_AUTO_NEG_EN 0x1000 /* Auto Neg Enable */
+#define MII_CR_SPEED_SELECT_LSB 0x2000 /* bits 6,13: 10=1000, 01=100, 00=10 */
+#define MII_CR_LOOPBACK 0x4000 /* 0 = normal, 1 = loopback */
+#define MII_CR_RESET 0x8000 /* 0 = normal, 1 = PHY reset */
+
+/* PHY Status Register */
+#define MII_SR_EXTENDED_CAPS 0x0001 /* Extended register capabilities */
+#define MII_SR_JABBER_DETECT 0x0002 /* Jabber Detected */
+#define MII_SR_LINK_STATUS 0x0004 /* Link Status 1 = link */
+#define MII_SR_AUTONEG_CAPS 0x0008 /* Auto Neg Capable */
+#define MII_SR_REMOTE_FAULT 0x0010 /* Remote Fault Detect */
+#define MII_SR_AUTONEG_COMPLETE 0x0020 /* Auto Neg Complete */
+#define MII_SR_PREAMBLE_SUPPRESS 0x0040 /* Preamble may be suppressed */
+#define MII_SR_EXTENDED_STATUS 0x0100 /* Ext. status info in Reg 0x0F */
+#define MII_SR_100T2_HD_CAPS 0x0200 /* 100T2 Half Duplex Capable */
+#define MII_SR_100T2_FD_CAPS 0x0400 /* 100T2 Full Duplex Capable */
+#define MII_SR_10T_HD_CAPS 0x0800 /* 10T Half Duplex Capable */
+#define MII_SR_10T_FD_CAPS 0x1000 /* 10T Full Duplex Capable */
+#define MII_SR_100X_HD_CAPS 0x2000 /* 100X Half Duplex Capable */
+#define MII_SR_100X_FD_CAPS 0x4000 /* 100X Full Duplex Capable */
+#define MII_SR_100T4_CAPS 0x8000 /* 100T4 Capable */
+
+/* Autoneg Advertisement Register */
+#define NWAY_AR_SELECTOR_FIELD 0x0001 /* indicates IEEE 802.3 CSMA/CD */
+#define NWAY_AR_10T_HD_CAPS 0x0020 /* 10T Half Duplex Capable */
+#define NWAY_AR_10T_FD_CAPS 0x0040 /* 10T Full Duplex Capable */
+#define NWAY_AR_100TX_HD_CAPS 0x0080 /* 100TX Half Duplex Capable */
+#define NWAY_AR_100TX_FD_CAPS 0x0100 /* 100TX Full Duplex Capable */
+#define NWAY_AR_100T4_CAPS 0x0200 /* 100T4 Capable */
+#define NWAY_AR_PAUSE 0x0400 /* Pause operation desired */
+#define NWAY_AR_ASM_DIR 0x0800 /* Asymmetric Pause Direction bit */
+#define NWAY_AR_REMOTE_FAULT 0x2000 /* Remote Fault detected */
+#define NWAY_AR_NEXT_PAGE 0x8000 /* Next Page ability supported */
+
+/* Link Partner Ability Register (Base Page) */
+#define NWAY_LPAR_SELECTOR_FIELD 0x0000 /* LP protocol selector field */
+#define NWAY_LPAR_10T_HD_CAPS 0x0020 /* LP is 10T Half Duplex Capable */
+#define NWAY_LPAR_10T_FD_CAPS 0x0040 /* LP is 10T Full Duplex Capable */
+#define NWAY_LPAR_100TX_HD_CAPS 0x0080 /* LP is 100TX Half Duplex Capable */
+#define NWAY_LPAR_100TX_FD_CAPS 0x0100 /* LP is 100TX Full Duplex Capable */
+#define NWAY_LPAR_100T4_CAPS 0x0200 /* LP is 100T4 Capable */
+#define NWAY_LPAR_PAUSE 0x0400 /* LP Pause operation desired */
+#define NWAY_LPAR_ASM_DIR 0x0800 /* LP Asymmetric Pause Direction bit */
+#define NWAY_LPAR_REMOTE_FAULT 0x2000 /* LP has detected Remote Fault */
+#define NWAY_LPAR_ACKNOWLEDGE 0x4000 /* LP has rx'd link code word */
+#define NWAY_LPAR_NEXT_PAGE 0x8000 /* Next Page ability supported */
+
+/* Autoneg Expansion Register */
+#define NWAY_ER_LP_NWAY_CAPS 0x0001 /* LP has Auto Neg Capability */
+#define NWAY_ER_PAGE_RXD 0x0002 /* LP is 10T Half Duplex Capable */
+#define NWAY_ER_NEXT_PAGE_CAPS 0x0004 /* LP is 10T Full Duplex Capable */
+#define NWAY_ER_LP_NEXT_PAGE_CAPS 0x0008 /* LP is 100TX Half Duplex Capable */
+#define NWAY_ER_PAR_DETECT_FAULT 0x0010 /* LP is 100TX Full Duplex Capable */
+
+/* Next Page TX Register */
+#define NPTX_MSG_CODE_FIELD 0x0001 /* NP msg code or unformatted data */
+#define NPTX_TOGGLE 0x0800 /* Toggles between exchanges
+ * of different NP
+ */
+#define NPTX_ACKNOWLDGE2 0x1000 /* 1 = will comply with msg
+ * 0 = cannot comply with msg
+ */
+#define NPTX_MSG_PAGE 0x2000 /* formatted(1)/unformatted(0) pg */
+#define NPTX_NEXT_PAGE 0x8000 /* 1 = addition NP will follow
+ * 0 = sending last NP
+ */
+
+/* Link Partner Next Page Register */
+#define LP_RNPR_MSG_CODE_FIELD 0x0001 /* NP msg code or unformatted data */
+#define LP_RNPR_TOGGLE 0x0800 /* Toggles between exchanges
+ * of different NP
+ */
+#define LP_RNPR_ACKNOWLDGE2 0x1000 /* 1 = will comply with msg
+ * 0 = cannot comply with msg
+ */
+#define LP_RNPR_MSG_PAGE 0x2000 /* formatted(1)/unformatted(0) pg */
+#define LP_RNPR_ACKNOWLDGE 0x4000 /* 1 = ACK / 0 = NO ACK */
+#define LP_RNPR_NEXT_PAGE 0x8000 /* 1 = addition NP will follow
+ * 0 = sending last NP
+ */
+
+/* 1000BASE-T Control Register */
+#define CR_1000T_ASYM_PAUSE 0x0080 /* Advertise asymmetric pause bit */
+#define CR_1000T_HD_CAPS 0x0100 /* Advertise 1000T HD capability */
+#define CR_1000T_FD_CAPS 0x0200 /* Advertise 1000T FD capability */
+#define CR_1000T_REPEATER_DTE 0x0400 /* 1=Repeater/switch device port */
+ /* 0=DTE device */
+#define CR_1000T_MS_VALUE 0x0800 /* 1=Configure PHY as Master */
+ /* 0=Configure PHY as Slave */
+#define CR_1000T_MS_ENABLE 0x1000 /* 1=Master/Slave manual config value */
+ /* 0=Automatic Master/Slave config */
+#define CR_1000T_TEST_MODE_NORMAL 0x0000 /* Normal Operation */
+#define CR_1000T_TEST_MODE_1 0x2000 /* Transmit Waveform test */
+#define CR_1000T_TEST_MODE_2 0x4000 /* Master Transmit Jitter test */
+#define CR_1000T_TEST_MODE_3 0x6000 /* Slave Transmit Jitter test */
+#define CR_1000T_TEST_MODE_4 0x8000 /* Transmitter Distortion test */
+
+/* 1000BASE-T Status Register */
+#define SR_1000T_IDLE_ERROR_CNT 0x00FF /* Num idle errors since last read */
+#define SR_1000T_ASYM_PAUSE_DIR 0x0100 /* LP asymmetric pause direction bit */
+#define SR_1000T_LP_HD_CAPS 0x0400 /* LP is 1000T HD capable */
+#define SR_1000T_LP_FD_CAPS 0x0800 /* LP is 1000T FD capable */
+#define SR_1000T_REMOTE_RX_STATUS 0x1000 /* Remote receiver OK */
+#define SR_1000T_LOCAL_RX_STATUS 0x2000 /* Local receiver OK */
+#define SR_1000T_MS_CONFIG_RES 0x4000 /* 1=Local TX is Master, 0=Slave */
+#define SR_1000T_MS_CONFIG_FAULT 0x8000 /* Master/Slave config fault */
+#define SR_1000T_REMOTE_RX_STATUS_SHIFT 12
+#define SR_1000T_LOCAL_RX_STATUS_SHIFT 13
+#define SR_1000T_PHY_EXCESSIVE_IDLE_ERR_COUNT 5
+#define FFE_IDLE_ERR_COUNT_TIMEOUT_20 20
+#define FFE_IDLE_ERR_COUNT_TIMEOUT_100 100
+
+/* Extended Status Register */
+#define IEEE_ESR_1000T_HD_CAPS 0x1000 /* 1000T HD capable */
+#define IEEE_ESR_1000T_FD_CAPS 0x2000 /* 1000T FD capable */
+#define IEEE_ESR_1000X_HD_CAPS 0x4000 /* 1000X HD capable */
+#define IEEE_ESR_1000X_FD_CAPS 0x8000 /* 1000X FD capable */
+
+#define PHY_TX_POLARITY_MASK 0x0100 /* register 10h bit 8 (polarity bit) */
+#define PHY_TX_NORMAL_POLARITY 0 /* register 10h bit 8 (normal polarity) */
+
+#define AUTO_POLARITY_DISABLE 0x0010 /* register 11h bit 4 */
+ /* (0=enable, 1=disable) */
+
+/* M88E1000 PHY Specific Control Register */
+#define M88E1000_PSCR_JABBER_DISABLE 0x0001 /* 1=Jabber Function disabled */
+#define M88E1000_PSCR_POLARITY_REVERSAL 0x0002 /* 1=Polarity Reversal enabled */
+#define M88E1000_PSCR_SQE_TEST 0x0004 /* 1=SQE Test enabled */
+#define M88E1000_PSCR_CLK125_DISABLE 0x0010 /* 1=CLK125 low,
+ * 0=CLK125 toggling
+ */
+#define M88E1000_PSCR_MDI_MANUAL_MODE 0x0000 /* MDI Crossover Mode bits 6:5 */
+ /* Manual MDI configuration */
+#define M88E1000_PSCR_MDIX_MANUAL_MODE 0x0020 /* Manual MDIX configuration */
+#define M88E1000_PSCR_AUTO_X_1000T 0x0040 /* 1000BASE-T: Auto crossover,
+ * 100BASE-TX/10BASE-T:
+ * MDI Mode
+ */
+#define M88E1000_PSCR_AUTO_X_MODE 0x0060 /* Auto crossover enabled
+ * all speeds.
+ */
+#define M88E1000_PSCR_10BT_EXT_DIST_ENABLE 0x0080
+ /* 1=Enable Extended 10BASE-T distance
+ * (Lower 10BASE-T RX Threshold)
+ * 0=Normal 10BASE-T RX Threshold */
+#define M88E1000_PSCR_MII_5BIT_ENABLE 0x0100
+ /* 1=5-Bit interface in 100BASE-TX
+ * 0=MII interface in 100BASE-TX */
+#define M88E1000_PSCR_SCRAMBLER_DISABLE 0x0200 /* 1=Scrambler disable */
+#define M88E1000_PSCR_FORCE_LINK_GOOD 0x0400 /* 1=Force link good */
+#define M88E1000_PSCR_ASSERT_CRS_ON_TX 0x0800 /* 1=Assert CRS on Transmit */
+
+#define M88E1000_PSCR_POLARITY_REVERSAL_SHIFT 1
+#define M88E1000_PSCR_AUTO_X_MODE_SHIFT 5
+#define M88E1000_PSCR_10BT_EXT_DIST_ENABLE_SHIFT 7
+
+/* M88E1000 PHY Specific Status Register */
+#define M88E1000_PSSR_JABBER 0x0001 /* 1=Jabber */
+#define M88E1000_PSSR_REV_POLARITY 0x0002 /* 1=Polarity reversed */
+#define M88E1000_PSSR_DOWNSHIFT 0x0020 /* 1=Downshifted */
+#define M88E1000_PSSR_MDIX 0x0040 /* 1=MDIX; 0=MDI */
+#define M88E1000_PSSR_CABLE_LENGTH 0x0380 /* 0=<50M;1=50-80M;2=80-110M;
+ * 3=110-140M;4=>140M */
+#define M88E1000_PSSR_LINK 0x0400 /* 1=Link up, 0=Link down */
+#define M88E1000_PSSR_SPD_DPLX_RESOLVED 0x0800 /* 1=Speed & Duplex resolved */
+#define M88E1000_PSSR_PAGE_RCVD 0x1000 /* 1=Page received */
+#define M88E1000_PSSR_DPLX 0x2000 /* 1=Duplex 0=Half Duplex */
+#define M88E1000_PSSR_SPEED 0xC000 /* Speed, bits 14:15 */
+#define M88E1000_PSSR_10MBS 0x0000 /* 00=10Mbs */
+#define M88E1000_PSSR_100MBS 0x4000 /* 01=100Mbs */
+#define M88E1000_PSSR_1000MBS 0x8000 /* 10=1000Mbs */
+
+#define M88E1000_PSSR_REV_POLARITY_SHIFT 1
+#define M88E1000_PSSR_DOWNSHIFT_SHIFT 5
+#define M88E1000_PSSR_MDIX_SHIFT 6
+#define M88E1000_PSSR_CABLE_LENGTH_SHIFT 7
+
+/* M88E1000 Extended PHY Specific Control Register */
+#define M88E1000_EPSCR_FIBER_LOOPBACK 0x4000 /* 1=Fiber loopback */
+#define M88E1000_EPSCR_DOWN_NO_IDLE 0x8000 /* 1=Lost lock detect enabled.
+ * Will assert lost lock and bring
+ * link down if idle not seen
+ * within 1ms in 1000BASE-T
+ */
+/* Number of times we will attempt to autonegotiate before downshifting if we
+ * are the master */
+#define M88E1000_EPSCR_MASTER_DOWNSHIFT_MASK 0x0C00
+#define M88E1000_EPSCR_MASTER_DOWNSHIFT_1X 0x0000
+#define M88E1000_EPSCR_MASTER_DOWNSHIFT_2X 0x0400
+#define M88E1000_EPSCR_MASTER_DOWNSHIFT_3X 0x0800
+#define M88E1000_EPSCR_MASTER_DOWNSHIFT_4X 0x0C00
+/* Number of times we will attempt to autonegotiate before downshifting if we
+ * are the slave */
+#define M88E1000_EPSCR_SLAVE_DOWNSHIFT_MASK 0x0300
+#define M88E1000_EPSCR_SLAVE_DOWNSHIFT_DIS 0x0000
+#define M88E1000_EPSCR_SLAVE_DOWNSHIFT_1X 0x0100
+#define M88E1000_EPSCR_SLAVE_DOWNSHIFT_2X 0x0200
+#define M88E1000_EPSCR_SLAVE_DOWNSHIFT_3X 0x0300
+#define M88E1000_EPSCR_TX_CLK_2_5 0x0060 /* 2.5 MHz TX_CLK */
+#define M88E1000_EPSCR_TX_CLK_25 0x0070 /* 25 MHz TX_CLK */
+#define M88E1000_EPSCR_TX_CLK_0 0x0000 /* NO TX_CLK */
+
+/* IGP01E1000 Specific Port Config Register - R/W */
+#define IGP01E1000_PSCFR_AUTO_MDIX_PAR_DETECT 0x0010
+#define IGP01E1000_PSCFR_PRE_EN 0x0020
+#define IGP01E1000_PSCFR_SMART_SPEED 0x0080
+#define IGP01E1000_PSCFR_DISABLE_TPLOOPBACK 0x0100
+#define IGP01E1000_PSCFR_DISABLE_JABBER 0x0400
+#define IGP01E1000_PSCFR_DISABLE_TRANSMIT 0x2000
+
+/* IGP01E1000 Specific Port Status Register - R/O */
+#define IGP01E1000_PSSR_AUTONEG_FAILED 0x0001 /* RO LH SC */
+#define IGP01E1000_PSSR_POLARITY_REVERSED 0x0002
+#define IGP01E1000_PSSR_CABLE_LENGTH 0x007C
+#define IGP01E1000_PSSR_FULL_DUPLEX 0x0200
+#define IGP01E1000_PSSR_LINK_UP 0x0400
+#define IGP01E1000_PSSR_MDIX 0x0800
+#define IGP01E1000_PSSR_SPEED_MASK 0xC000 /* speed bits mask */
+#define IGP01E1000_PSSR_SPEED_10MBPS 0x4000
+#define IGP01E1000_PSSR_SPEED_100MBPS 0x8000
+#define IGP01E1000_PSSR_SPEED_1000MBPS 0xC000
+#define IGP01E1000_PSSR_CABLE_LENGTH_SHIFT 0x0002 /* shift right 2 */
+#define IGP01E1000_PSSR_MDIX_SHIFT 0x000B /* shift right 11 */
+
+/* IGP01E1000 Specific Port Control Register - R/W */
+#define IGP01E1000_PSCR_TP_LOOPBACK 0x0010
+#define IGP01E1000_PSCR_CORRECT_NC_SCMBLR 0x0200
+#define IGP01E1000_PSCR_TEN_CRS_SELECT 0x0400
+#define IGP01E1000_PSCR_FLIP_CHIP 0x0800
+#define IGP01E1000_PSCR_AUTO_MDIX 0x1000
+#define IGP01E1000_PSCR_FORCE_MDI_MDIX 0x2000 /* 0-MDI, 1-MDIX */
+
+/* IGP01E1000 Specific Port Link Health Register */
+#define IGP01E1000_PLHR_SS_DOWNGRADE 0x8000
+#define IGP01E1000_PLHR_GIG_SCRAMBLER_ERROR 0x4000
+#define IGP01E1000_PLHR_MASTER_FAULT 0x2000
+#define IGP01E1000_PLHR_MASTER_RESOLUTION 0x1000
+#define IGP01E1000_PLHR_GIG_REM_RCVR_NOK 0x0800 /* LH */
+#define IGP01E1000_PLHR_IDLE_ERROR_CNT_OFLOW 0x0400 /* LH */
+#define IGP01E1000_PLHR_DATA_ERR_1 0x0200 /* LH */
+#define IGP01E1000_PLHR_DATA_ERR_0 0x0100
+#define IGP01E1000_PLHR_AUTONEG_FAULT 0x0040
+#define IGP01E1000_PLHR_AUTONEG_ACTIVE 0x0010
+#define IGP01E1000_PLHR_VALID_CHANNEL_D 0x0008
+#define IGP01E1000_PLHR_VALID_CHANNEL_C 0x0004
+#define IGP01E1000_PLHR_VALID_CHANNEL_B 0x0002
+#define IGP01E1000_PLHR_VALID_CHANNEL_A 0x0001
+
+/* IGP01E1000 Channel Quality Register */
+#define IGP01E1000_MSE_CHANNEL_D 0x000F
+#define IGP01E1000_MSE_CHANNEL_C 0x00F0
+#define IGP01E1000_MSE_CHANNEL_B 0x0F00
+#define IGP01E1000_MSE_CHANNEL_A 0xF000
+
+#define IGP02E1000_PM_SPD 0x0001 /* Smart Power Down */
+#define IGP02E1000_PM_D3_LPLU 0x0004 /* Enable LPLU in non-D0a modes */
+#define IGP02E1000_PM_D0_LPLU 0x0002 /* Enable LPLU in D0a mode */
+
+/* IGP01E1000 DSP reset macros */
+#define DSP_RESET_ENABLE 0x0
+#define DSP_RESET_DISABLE 0x2
+#define E1000_MAX_DSP_RESETS 10
+
+/* IGP01E1000 & IGP02E1000 AGC Registers */
+
+#define IGP01E1000_AGC_LENGTH_SHIFT 7 /* Coarse - 13:11, Fine - 10:7 */
+#define IGP02E1000_AGC_LENGTH_SHIFT 9 /* Coarse - 15:13, Fine - 12:9 */
+
+/* IGP02E1000 AGC Register Length 9-bit mask */
+#define IGP02E1000_AGC_LENGTH_MASK 0x7F
+
+/* 7 bits (3 Coarse + 4 Fine) --> 128 optional values */
+#define IGP01E1000_AGC_LENGTH_TABLE_SIZE 128
+#define IGP02E1000_AGC_LENGTH_TABLE_SIZE 128
+
+/* The precision error of the cable length is +/- 10 meters */
+#define IGP01E1000_AGC_RANGE 10
+#define IGP02E1000_AGC_RANGE 10
+
+/* IGP01E1000 PCS Initialization register */
+/* bits 3:6 in the PCS registers stores the channels polarity */
+#define IGP01E1000_PHY_POLARITY_MASK 0x0078
+
+/* IGP01E1000 GMII FIFO Register */
+#define IGP01E1000_GMII_FLEX_SPD 0x10 /* Enable flexible speed
+ * on Link-Up */
+#define IGP01E1000_GMII_SPD 0x20 /* Enable SPD */
+
+/* IGP01E1000 Analog Register */
+#define IGP01E1000_ANALOG_SPARE_FUSE_STATUS 0x20D1
+#define IGP01E1000_ANALOG_FUSE_STATUS 0x20D0
+#define IGP01E1000_ANALOG_FUSE_CONTROL 0x20DC
+#define IGP01E1000_ANALOG_FUSE_BYPASS 0x20DE
+
+#define IGP01E1000_ANALOG_FUSE_POLY_MASK 0xF000
+#define IGP01E1000_ANALOG_FUSE_FINE_MASK 0x0F80
+#define IGP01E1000_ANALOG_FUSE_COARSE_MASK 0x0070
+#define IGP01E1000_ANALOG_SPARE_FUSE_ENABLED 0x0100
+#define IGP01E1000_ANALOG_FUSE_ENABLE_SW_CONTROL 0x0002
+
+#define IGP01E1000_ANALOG_FUSE_COARSE_THRESH 0x0040
+#define IGP01E1000_ANALOG_FUSE_COARSE_10 0x0010
+#define IGP01E1000_ANALOG_FUSE_FINE_1 0x0080
+#define IGP01E1000_ANALOG_FUSE_FINE_10 0x0500
+
+
+/* Bit definitions for valid PHY IDs. */
+/* I = Integrated
+ * E = External
+ */
+#define M88E1000_E_PHY_ID 0x01410C50
+#define M88E1000_I_PHY_ID 0x01410C30
+#define M88E1011_I_PHY_ID 0x01410C20
+#define IGP01E1000_I_PHY_ID 0x02A80380
+#define M88E1000_12_PHY_ID M88E1000_E_PHY_ID
+#define M88E1000_14_PHY_ID M88E1000_E_PHY_ID
+#define M88E1011_I_REV_4 0x04
+#define M88E1111_I_PHY_ID 0x01410CC0
+#define L1LXT971A_PHY_ID 0x001378E0
+
+/* Miscellaneous PHY bit definitions. */
+#define PHY_PREAMBLE 0xFFFFFFFF
+#define PHY_SOF 0x01
+#define PHY_OP_READ 0x02
+#define PHY_OP_WRITE 0x01
+#define PHY_TURNAROUND 0x02
+#define PHY_PREAMBLE_SIZE 32
+#define MII_CR_SPEED_1000 0x0040
+#define MII_CR_SPEED_100 0x2000
+#define MII_CR_SPEED_10 0x0000
+#define E1000_PHY_ADDRESS 0x01
+#define PHY_AUTO_NEG_TIME 45 /* 4.5 Seconds */
+#define PHY_FORCE_TIME 20 /* 2.0 Seconds */
+#define PHY_REVISION_MASK 0xFFFFFFF0
+#define DEVICE_SPEED_MASK 0x00000300 /* Device Ctrl Reg Speed Mask */
+#define REG4_SPEED_MASK 0x01E0
+#define REG9_SPEED_MASK 0x0300
+#define ADVERTISE_10_HALF 0x0001
+#define ADVERTISE_10_FULL 0x0002
+#define ADVERTISE_100_HALF 0x0004
+#define ADVERTISE_100_FULL 0x0008
+#define ADVERTISE_1000_HALF 0x0010
+#define ADVERTISE_1000_FULL 0x0020
+#define AUTONEG_ADVERTISE_SPEED_DEFAULT 0x002F /* Everything but 1000-Half */
+#define AUTONEG_ADVERTISE_10_100_ALL 0x000F /* All 10/100 speeds*/
+#define AUTONEG_ADVERTISE_10_ALL 0x0003 /* 10Mbps Full & Half speeds*/
+
+#endif /* _EM_HW_H_ */
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em_osdep.h b/bsps/powerpc/beatnik/net/if_em/if_em_osdep.h
new file mode 100644
index 0000000..4bc5843
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em_osdep.h
@@ -0,0 +1,146 @@
+/**************************************************************************
+
+Copyright (c) 2001-2005, Intel Corporation
+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 Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+
+***************************************************************************/
+
+/*$FreeBSD: /repoman/r/ncvs/src/sys/dev/em/if_em_osdep.h,v 1.14 2005/05/26 23:32:02 tackerman Exp $*/
+
+#ifndef _RTEMS_OS_H_
+#define _RTEMS_OS_H_
+
+#include <rtems.h>
+#include "../porting/rtemscompat.h"
+
+#include <sys/types.h>
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/mbuf.h>
+#include <sys/protosw.h>
+#include <sys/socket.h>
+#include <sys/malloc.h>
+#include <sys/kernel.h>
+#include <bsp/pci.h>
+
+/* Eventually, we should include this
+#include <rtems/rtems-mii-ioctl.h>
+*/
+#define IFM_LINK_OK IFM_FLAG0
+#define IFM_ANEG_DIS IFM_FLAG1
+
+#define ASSERT(x) if(!(x)) panic("EM: x")
+
+/* The happy-fun DELAY macro is defined in /usr/src/sys/i386/include/clock.h */
+#define usec_delay(x) DELAY(x)
+#define msec_delay(x) DELAY(1000*(x))
+/* TODO: Should we be paranoid about delaying in interrupt context? */
+#define msec_delay_irq(x) DELAY(1000*(x))
+
+#define MSGOUT(S, A, B) printf(S "\n", A, B)
+#define DEBUGFUNC(F) DEBUGOUT(F);
+#if DBG
+ #define DEBUGOUT(S) printf(S "\n")
+ #define DEBUGOUT1(S,A) printf(S "\n",A)
+ #define DEBUGOUT2(S,A,B) printf(S "\n",A,B)
+ #define DEBUGOUT3(S,A,B,C) printf(S "\n",A,B,C)
+ #define bootverbose (1)
+ #define DEBUGOUT7(S,A,B,C,D,E,F,G) printf(S "\n",A,B,C,D,E,F,G)
+#else
+ #define DEBUGOUT(S)
+ #define DEBUGOUT1(S,A)
+ #define DEBUGOUT2(S,A,B)
+ #define DEBUGOUT3(S,A,B,C)
+ #define bootverbose (0)
+ #define DEBUGOUT7(S,A,B,C,D,E,F,G)
+#endif
+
+#define CMD_MEM_WRT_INVALIDATE 0x0010 /* BIT_4 */
+#define PCI_COMMAND_REGISTER PCIR_COMMAND
+
+struct em_osdep
+{
+ unsigned mem_bus_space_handle;
+ device_t dev;
+};
+
+struct rtems_ifmedia {
+ int ifm_media;
+};
+
+#define E1000_WRITE_FLUSH(hw) E1000_READ_REG(hw, STATUS)
+
+/* Read from an absolute offset in the adapter's memory space */
+#define E1000_READ_OFFSET(hw, offset) \
+ bus_space_read_4( ((struct em_osdep *)(hw)->back)->mem_bus_space_tag, \
+ ((struct em_osdep *)(hw)->back)->mem_bus_space_handle, \
+ offset)
+
+/* Write to an absolute offset in the adapter's memory space */
+#define E1000_WRITE_OFFSET(hw, offset, value) \
+ bus_space_write_4( ((struct em_osdep *)(hw)->back)->mem_bus_space_tag, \
+ ((struct em_osdep *)(hw)->back)->mem_bus_space_handle, \
+ offset, \
+ value)
+
+/* Convert a register name to its offset in the adapter's memory space */
+#define E1000_REG_OFFSET(hw, reg) \
+ ((hw)->mac_type >= em_82543 ? E1000_##reg : E1000_82542_##reg)
+
+#define E1000_READ_REG(hw, reg) \
+ E1000_READ_OFFSET(hw, E1000_REG_OFFSET(hw, reg))
+
+#define E1000_WRITE_REG(hw, reg, value) \
+ E1000_WRITE_OFFSET(hw, E1000_REG_OFFSET(hw, reg), value)
+
+#define E1000_READ_REG_ARRAY(hw, reg, index) \
+ E1000_READ_OFFSET(hw, E1000_REG_OFFSET(hw, reg) + ((index) << 2))
+
+#define E1000_READ_REG_ARRAY_DWORD E1000_READ_REG_ARRAY
+
+#define E1000_WRITE_REG_ARRAY(hw, reg, index, value) \
+ E1000_WRITE_OFFSET(hw, E1000_REG_OFFSET(hw, reg) + ((index) << 2), value)
+
+#define E1000_WRITE_REG_ARRAY_BYTE(hw, reg, index, value) \
+ bus_space_write_1( ((struct em_osdep *)(hw)->back)->mem_bus_space_tag, \
+ ((struct em_osdep *)(hw)->back)->mem_bus_space_handle, \
+ E1000_REG_OFFSET(hw, reg) + (index), \
+ value)
+
+#define E1000_WRITE_REG_ARRAY_WORD(hw, reg, index, value) \
+ bus_space_write_2( ((struct em_osdep *)(hw)->back)->mem_bus_space_tag, \
+ ((struct em_osdep *)(hw)->back)->mem_bus_space_handle, \
+ E1000_REG_OFFSET(hw, reg) + (index), \
+ value)
+
+#define E1000_WRITE_REG_ARRAY_DWORD(hw, reg, index, value) \
+ E1000_WRITE_OFFSET(hw, E1000_REG_OFFSET(hw, reg) + ((index) << 2), value)
+
+#endif /* _FREEBSD_OS_H_ */
+
diff --git a/bsps/powerpc/beatnik/net/if_em/if_em_rtems.c b/bsps/powerpc/beatnik/net/if_em/if_em_rtems.c
new file mode 100644
index 0000000..fde1de7
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/if_em_rtems.c
@@ -0,0 +1,106 @@
+#include "rtemscompat_defs.h"
+#include "../porting/if_xxx_rtems.c"
+#include <bsp/early_enet_link_status.h>
+#include <bsp/if_em_pub.h>
+
+/* Provide a routine to check link status early,
+ * i.e., before the network is really running.
+ * In case someone wants to decide whether to use/configure
+ * this interface at all :-)
+ *
+ * NOTE: this routine tries to enable autonegotiation!
+ *
+ * unit: unit number starting with 1 (usual BSDNET convention)
+ *
+ * RETURNS: Phy status register contents (1<<2 means link up).
+ * or -1 on error.
+ */
+
+/*
+ * Authorship
+ * ----------
+ * This software ('beatnik' RTEMS BSP for MVME6100 and MVME5500) was
+ * created by Till Straumann <strauman@slac.stanford.edu>, 2005-2007,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * The 'beatnik' BSP was produced by
+ * the Stanford Linear Accelerator Center, Stanford University,
+ * under Contract DE-AC03-76SFO0515 with the Department of Energy.
+ *
+ * Government disclaimer of liability
+ * ----------------------------------
+ * Neither the United States nor the United States Department of Energy,
+ * nor any of their employees, makes any warranty, express or implied, or
+ * assumes any legal liability or responsibility for the accuracy,
+ * completeness, or usefulness of any data, apparatus, product, or process
+ * disclosed, or represents that its use would not infringe privately owned
+ * rights.
+ *
+ * Stanford disclaimer of liability
+ * --------------------------------
+ * Stanford University makes no representations or warranties, express or
+ * implied, nor assumes any liability for the use of this software.
+ *
+ * Stanford disclaimer of copyright
+ * --------------------------------
+ * Stanford University, owner of the copyright, hereby disclaims its
+ * copyright and all other rights in this software. Hence, anyone may
+ * freely use it for any purpose without restriction.
+ *
+ * Maintenance of notices
+ * ----------------------
+ * In the interest of clarity regarding the origin and status of this
+ * SLAC software, this and all the preceding Stanford University notices
+ * are to remain affixed to any copy or derivative of this software made
+ * or distributed by the recipient and are to be affixed to any copy of
+ * software made or distributed by the recipient that contains a copy or
+ * derivative of this software.
+ *
+ * ------------------ SLAC Software Notices, Set 4 OTT.002a, 2004 FEB 03
+ */
+
+static int
+em_early_init(int idx)
+{
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+ return em_hw_early_init(&the_em_devs[idx]);
+}
+
+static int
+em_early_read_phy(int idx, unsigned reg)
+{
+unsigned short data;
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+ /* Bizarre - I always have to read PHY_STATUS twice until a good link
+ * status is read
+ */
+ if ( em_read_phy_reg(&the_em_devs[idx].d_softc.hw, reg, &data) )
+ return -1;
+ if ( PHY_STATUS == reg ) {
+ /* read again */
+ if ( em_read_phy_reg(&the_em_devs[idx].d_softc.hw, PHY_STATUS, &data) )
+ return -1;
+ }
+ return data;
+}
+
+static int
+em_early_write_phy(int idx, unsigned reg, unsigned val)
+{
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+ return em_write_phy_reg(&the_em_devs[idx].d_softc.hw, reg, val);
+}
+
+rtems_bsdnet_early_link_check_ops
+rtems_em_early_link_check_ops = {
+ init: em_early_init,
+ read_phy: em_early_read_phy,
+ write_phy: em_early_write_phy,
+ name: NETDRIVER,
+ num_slots: NETDRIVER_SLOTS
+};
diff --git a/bsps/powerpc/beatnik/net/if_em/rtemscompat_defs.h b/bsps/powerpc/beatnik/net/if_em/rtemscompat_defs.h
new file mode 100644
index 0000000..6a132a1
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_em/rtemscompat_defs.h
@@ -0,0 +1,198 @@
+#ifndef RTEMS_COMPAT_DEFS_H
+#define RTEMS_COMPAT_DEFS_H
+
+/* Number of device instances the driver should support
+ * - may be limited to 1 depending on IRQ API
+ * (braindamaged PC586 and powerpc)
+ */
+#define NETDRIVER_SLOTS 1
+
+/* String name to print with error messages */
+#define NETDRIVER "em"
+/* Name snippet used to make global symbols unique to this driver */
+#define NETDRIVER_PREFIX em
+
+#define adapter em_softc
+#define interface_data arpcom
+
+/* Define according to endianness of the *ethernet*chip*
+ * (not the CPU - most probably are LE)
+ * This must be either NET_CHIP_LE or NET_CHIP_BE
+ */
+
+#define NET_CHIP_LE
+#undef NET_CHIP_BE
+
+/* Define either NET_CHIP_MEM_IO or NET_CHIP_PORT_IO,
+ * depending whether the CPU sees it in memory address space
+ * or (e.g. x86) uses special I/O instructions.
+ */
+#define NET_CHIP_MEM_IO
+#undef NET_CHIP_PORT_IO
+
+/* The name of the hijacked 'bus handle' field in the softc
+ * structure. We use this field to store the chip's base address.
+ */
+#define NET_SOFTC_BHANDLE_FIELD osdep.mem_bus_space_handle
+
+/* define the names of the 'if_XXXreg.h' and 'if_XXXvar.h' headers
+ * (only if present, i.e., if the BSDNET driver has no respective
+ * header, leave this undefined).
+ *
+ */
+#define IF_REG_HEADER "../if_em/if_em.h"
+#undef IF_VAR_HEADER
+
+/* define if a pci device */
+#define NETDRIVER_PCI <bsp/pci.h>
+
+/* Macros to disable and enable interrupts, respectively.
+ * The 'disable' macro is expanded in the ISR, the 'enable'
+ * macro is expanded in the driver task.
+ * The global network semaphore usually provides mutex
+ * protection of the device registers.
+ * Special care must be taken when coding the 'disable' macro,
+ * however to MAKE SURE THERE ARE NO OTHER SIDE EFFECTS such
+ * as:
+ * - macro must not clear any status flags
+ * - macro must save/restore any context information
+ * (e.g., a address register pointer or a bank switch register)
+ *
+ * ARGUMENT: the macro arg is a pointer to the driver's 'softc' structure
+ */
+
+#define NET_ENABLE_IRQS(sc) do { \
+ E1000_WRITE_REG(&sc->hw, IMS, (IMS_ENABLE_MASK)); \
+ } while (0)
+
+#define NET_DISABLE_IRQS(sc) do { \
+ E1000_WRITE_REG(&sc->hw, IMC, 0xffffffff); \
+ } while (0)
+
+#define KASSERT(a...) do {} while (0)
+
+/* dmamap stuff; these are defined just to work with the current version
+ * of this driver and the implementation must be carefully checked if
+ * a newer version is merged.!
+ *
+ * The more cumbersome routines have been commented in the source, the
+ * simpler ones are defined to be NOOPs here so the source gets less
+ * cluttered...
+ *
+ * ASSUMPTIONS:
+ *
+ * -> dmamap_sync cannot sync caches; assume we have HW snooping
+ *
+ */
+
+typedef unsigned bus_size_t;
+typedef unsigned bus_addr_t;
+
+typedef struct {
+ unsigned ds_addr;
+ unsigned ds_len;
+} bus_dma_segment_t;
+
+#define bus_dma_tag_destroy(args...) do {} while(0)
+
+#define bus_dmamap_destroy(args...) do {} while(0)
+
+#define bus_dmamap_unload(args...) do {} while (0)
+
+#ifdef __PPC__
+#define bus_dmamap_sync(args...) do { __asm__ volatile("sync":::"memory"); } while (0)
+#else
+#define bus_dmamap_sync(args...) do {} while (0)
+#endif
+
+#define BUS_DMA_NOWAIT 0xdeadbeef /* unused */
+
+#define em_adapter_list _bsd_em_adapter_list
+#define em_arc_subsystem_valid _bsd_em_arc_subsystem_valid
+#define em_check_downshift _bsd_em_check_downshift
+#define em_check_for_link _bsd_em_check_for_link
+#define em_check_mng_mode _bsd_em_check_mng_mode
+#define em_check_phy_reset_block _bsd_em_check_phy_reset_block
+#define em_check_polarity _bsd_em_check_polarity
+#define em_cleanup_led _bsd_em_cleanup_led
+#define em_clear_hw_cntrs _bsd_em_clear_hw_cntrs
+#define em_clear_vfta _bsd_em_clear_vfta
+#define em_commit_shadow_ram _bsd_em_commit_shadow_ram
+#define em_config_collision_dist _bsd_em_config_collision_dist
+#define em_config_dsp_after_link_change _bsd_em_config_dsp_after_link_change
+#define em_config_fc_after_link_up _bsd_em_config_fc_after_link_up
+#define em_dbg_config _bsd_em_dbg_config
+#define em_detect_gig_phy _bsd_em_detect_gig_phy
+#define em_disable_pciex_master _bsd_em_disable_pciex_master
+#define em_display_debug_stats _bsd_em_display_debug_stats
+#define em_driver_version _bsd_em_driver_version
+#define em_enable_mng_pass_thru _bsd_em_enable_mng_pass_thru
+#define em_enable_pciex_master _bsd_em_enable_pciex_master
+#define em_enable_tx_pkt_filtering _bsd_em_enable_tx_pkt_filtering
+#define em_force_mac_fc _bsd_em_force_mac_fc
+#define em_get_auto_rd_done _bsd_em_get_auto_rd_done
+#define em_get_bus_info _bsd_em_get_bus_info
+#define em_get_cable_length _bsd_em_get_cable_length
+#define em_get_hw_eeprom_semaphore _bsd_em_get_hw_eeprom_semaphore
+#define em_get_phy_cfg_done _bsd_em_get_phy_cfg_done
+#define em_get_speed_and_duplex _bsd_em_get_speed_and_duplex
+#define em_hash_mc_addr _bsd_em_hash_mc_addr
+#define em_hw_early_init _bsd_em_hw_early_init
+#define em_id_led_init _bsd_em_id_led_init
+#define em_init_eeprom_params _bsd_em_init_eeprom_params
+#define em_init_hw _bsd_em_init_hw
+#define em_init_rx_addrs _bsd_em_init_rx_addrs
+#define em_io_read _bsd_em_io_read
+#define em_io_write _bsd_em_io_write
+#define em_is_onboard_nvm_eeprom _bsd_em_is_onboard_nvm_eeprom
+#define em_led_off _bsd_em_led_off
+#define em_led_on _bsd_em_led_on
+#define em_mc_addr_list_update _bsd_em_mc_addr_list_update
+#define em_mng_enable_host_if _bsd_em_mng_enable_host_if
+#define em_mng_host_if_write _bsd_em_mng_host_if_write
+#define em_mng_write_cmd_header _bsd_em_mng_write_cmd_header
+#define em_mng_write_commit _bsd_em_mng_write_commit
+#define em_mng_write_dhcp_info _bsd_em_mng_write_dhcp_info
+#define em_mta_set _bsd_em_mta_set
+#define em_pci_clear_mwi _bsd_em_pci_clear_mwi
+#define em_pci_set_mwi _bsd_em_pci_set_mwi
+#define em_phy_get_info _bsd_em_phy_get_info
+#define em_phy_hw_reset _bsd_em_phy_hw_reset
+#define em_phy_igp_get_info _bsd_em_phy_igp_get_info
+#define em_phy_m88_get_info _bsd_em_phy_m88_get_info
+#define em_phy_reset _bsd_em_phy_reset
+#define em_phy_setup_autoneg _bsd_em_phy_setup_autoneg
+#define em_poll_eerd_eewr_done _bsd_em_poll_eerd_eewr_done
+#define em_put_hw_eeprom_semaphore _bsd_em_put_hw_eeprom_semaphore
+#define em_rar_set _bsd_em_rar_set
+#define em_read_eeprom _bsd_em_read_eeprom
+#define em_read_eeprom_eerd _bsd_em_read_eeprom_eerd
+#define em_read_mac_addr _bsd_em_read_mac_addr
+#define em_read_part_num _bsd_em_read_part_num
+#define em_read_pci_cfg _bsd_em_read_pci_cfg
+#define em_read_phy_reg _bsd_em_read_phy_reg
+#define em_read_reg_io _bsd_em_read_reg_io
+#define em_reset_adaptive _bsd_em_reset_adaptive
+#define em_reset_hw _bsd_em_reset_hw
+#define em_set_d0_lplu_state _bsd_em_set_d0_lplu_state
+#define em_set_d3_lplu_state _bsd_em_set_d3_lplu_state
+#define em_set_mac_type _bsd_em_set_mac_type
+#define em_set_media_type _bsd_em_set_media_type
+#define em_set_pci_express_master_disable _bsd_em_set_pci_express_master_disable
+#define em_setup_led _bsd_em_setup_led
+#define em_setup_link _bsd_em_setup_link
+#define em_tbi_adjust_stats _bsd_em_tbi_adjust_stats
+#define em_update_adaptive _bsd_em_update_adaptive
+#define em_update_eeprom_checksum _bsd_em_update_eeprom_checksum
+#define em_validate_eeprom_checksum _bsd_em_validate_eeprom_checksum
+#define em_validate_mdi_setting _bsd_em_validate_mdi_setting
+#define em_wait_autoneg _bsd_em_wait_autoneg
+#define em_write_eeprom _bsd_em_write_eeprom
+#define em_write_eeprom_eewr _bsd_em_write_eeprom_eewr
+#define em_write_pci_cfg _bsd_em_write_pci_cfg
+#define em_write_phy_reg _bsd_em_write_phy_reg
+#define em_write_reg_io _bsd_em_write_reg_io
+#define em_write_vfta _bsd_em_write_vfta
+#define the_em_devs _bsd_the_em_devs
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/if_gfe/gtethreg.h b/bsps/powerpc/beatnik/net/if_gfe/gtethreg.h
new file mode 100644
index 0000000..d571eec
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/gtethreg.h
@@ -0,0 +1,854 @@
+/* $NetBSD: gtethreg.h,v 1.2.10.1 2005/04/29 11:28:55 kent Exp $ */
+
+/*
+ * Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed for the NetBSD Project by
+ * Allegro Networks, Inc., and Wasabi Systems, Inc.
+ * 4. The name of Allegro Networks, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ * 5. The name of Wasabi Systems, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ALLEGRO NETWORKS, INC. AND
+ * WASABI SYSTEMS, INC. ``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 EITHER ALLEGRO NETWORKS, INC. OR WASABI SYSTEMS, INC.
+ * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _DEV_GTETHREG_H_
+#define _DEV_GTETHREG_H_
+
+#define ETH__BIT(bit) (1U << (bit))
+#define ETH__LLBIT(bit) (1LLU << (bit))
+#define ETH__MASK(bit) (ETH__BIT(bit) - 1)
+#define ETH__LLMASK(bit) (ETH__LLBIT(bit) - 1)
+#define ETH__GEN(n, off) (0x2400+((n) << 10)+(ETH__ ## off))
+#define ETH__EXT(data, bit, len) (((data) >> (bit)) & ETH__MASK(len))
+#define ETH__LLEXT(data, bit, len) (((data) >> (bit)) & ETH__LLMASK(len))
+#define ETH__CLR(data, bit, len) ((data) &= ~(ETH__MASK(len) << (bit)))
+#define ETH__INS(new, bit) ((new) << (bit))
+#define ETH__LLINS(new, bit) ((uint64_t)(new) << (bit))
+
+/*
+ * Descriptors used for both receive & transmit data. Note that the descriptor
+ * must start on a 4LW boundary. Since the GT accesses the descriptor as
+ * two 64-bit quantities, we must present them 32bit quantities in the right
+ * order based on endianess.
+ */
+
+struct gt_eth_desc {
+#if defined(BYTE_ORDER) && BYTE_ORDER == BIG_ENDIAN
+ u_int32_t ed_lencnt; /* length is hi 16 bits; count (rx) is lo 16 */
+ u_int32_t ed_cmdsts; /* command (hi16)/status (lo16) bits */
+ u_int32_t ed_nxtptr; /* next descriptor (must be 4LW aligned) */
+ u_int32_t ed_bufptr; /* pointer to packet buffer */
+#endif
+#if defined(BYTE_ORDER) && BYTE_ORDER == LITTLE_ENDIAN
+ u_int32_t ed_cmdsts; /* command (hi16)/status (lo16) bits */
+ u_int32_t ed_lencnt; /* length is hi 16 bits; count (rx) is lo 16 */
+ u_int32_t ed_bufptr; /* pointer to packet buffer */
+ u_int32_t ed_nxtptr; /* next descriptor (must be 4LW aligned) */
+#endif
+};
+
+/* Table 578: Ethernet TX Descriptor - Command/Status word
+ * All bits except F, EI, AM, O are only valid if TX_CMD_L is also set,
+ * otherwise should be 0 (tx).
+ */
+#define TX_STS_LC ETH__BIT(5) /* Late Collision */
+#define TX_STS_UR ETH__BIT(6) /* Underrun error */
+#define TX_STS_RL ETH__BIT(8) /* Retransmit Limit (excession coll) */
+#define TX_STS_COL ETH__BIT(9) /* Collision Occurred */
+#define TX_STS_RC(v) ETH__GETBITS(v, 10, 4) /* Retransmit Count */
+#define TX_STS_ES ETH__BIT(15) /* Error Summary (LC|UR|RL) */
+#define TX_CMD_L ETH__BIT(16) /* Last - End Of Packet */
+#define TX_CMD_F ETH__BIT(17) /* First - Start Of Packet */
+#define TX_CMD_P ETH__BIT(18) /* Pad Packet */
+#define TX_CMD_GC ETH__BIT(22) /* Generate CRC */
+#define TX_CMD_EI ETH__BIT(23) /* Enable Interrupt */
+#define TX_CMD_AM ETH__BIT(30) /* Auto Mode */
+#define TX_CMD_O ETH__BIT(31) /* Ownership (1=GT 0=CPU) */
+
+#define TX_CMD_FIRST (TX_CMD_F|TX_CMD_O)
+#define TX_CMD_LAST (TX_CMD_L|TX_CMD_GC|TX_CMD_P|TX_CMD_O)
+
+/* Table 582: Ethernet RX Descriptor - Command/Status Word
+ * All bits except F, EI, AM, O are only valid if RX_CMD_L is also set,
+ * otherwise should be ignored (rx).
+ */
+#define RX_STS_CE ETH__BIT(0) /* CRC Error */
+#define RX_STS_COL ETH__BIT(1) /* Collision sensed during reception */
+#define RX_STS_LC ETH__BIT(5) /* Late Collision (Reserved) */
+#define RX_STS_OR ETH__BIT(6) /* Overrun Error */
+#define RX_STS_MFL ETH__BIT(7) /* Max Frame Len Error */
+#define RX_STS_SF ETH__BIT(8) /* Short Frame Error (< 64 bytes) */
+#define RX_STS_FT ETH__BIT(11) /* Frame Type (1 = 802.3) */
+#define RX_STS_M ETH__BIT(12) /* Missed Frame */
+#define RX_STS_HE ETH__BIT(13) /* Hash Expired (manual match) */
+#define RX_STS_IGMP ETH__BIT(14) /* IGMP Packet */
+#define RX_STS_ES ETH__BIT(15) /* Error Summary (CE|COL|LC|OR|MFL|SF) */
+#define RX_CMD_L ETH__BIT(16) /* Last - End Of Packet */
+#define RX_CMD_F ETH__BIT(17) /* First - Start Of Packet */
+#define RX_CMD_EI ETH__BIT(23) /* Enable Interrupt */
+#define RX_CMD_AM ETH__BIT(30) /* Auto Mode */
+#define RX_CMD_O ETH__BIT(31) /* Ownership (1=GT 0=CPU) */
+
+/* Table 586: Hash Table Entry Fields
+ */
+#define HSH_V ETH__LLBIT(0) /* Entry is valid */
+#define HSH_S ETH__LLBIT(1) /* Skip this entry */
+#define HSH_RD ETH__LLBIT(2) /* Receive(1) / Discard (0) */
+#define HSH_R ETH__LLBIT(2) /* Receive(1) */
+#define HSH_PRIO_GET(v) ETH__LLEXT(v, 51, 2)
+#define HSH_PRIO_INS(v) ETH__LLINS(v, 51)
+#define HSH_ADDR_MASK 0x7fffff8LLU
+#define HSH_LIMIT 12
+
+
+#define ETH_EPAR 0x2000 /* PHY Address Register */
+#define ETH_ESMIR 0x2010 /* SMI Register */
+
+#define ETH_BASE_ETH0 0x2400 /* Ethernet0 Register Base */
+#define ETH_BASE_ETH1 0x2800 /* Ethernet1 Register Base */
+#define ETH_BASE_ETH2 0x2c00 /* Ethernet2 Register Base */
+#define ETH_SIZE 0x0400 /* Register Space */
+
+#define ETH__EBASE 0x0000 /* Base of Registers */
+#define ETH__EPCR 0x0000 /* Port Config. Register */
+#define ETH__EPCXR 0x0008 /* Port Config. Extend Reg */
+#define ETH__EPCMR 0x0010 /* Port Command Register */
+#define ETH__EPSR 0x0018 /* Port Status Register */
+#define ETH__ESPR 0x0020 /* Port Serial Parameters Reg */
+#define ETH__EHTPR 0x0028 /* Port Hash Table Pointer Reg*/
+#define ETH__EFCSAL 0x0030 /* Flow Control Src Addr Low */
+#define ETH__EFCSAH 0x0038 /* Flow Control Src Addr High */
+#define ETH__ESDCR 0x0040 /* SDMA Configuration Reg */
+#define ETH__ESDCMR 0x0048 /* SDMA Command Register */
+#define ETH__EICR 0x0050 /* Interrupt Cause Register */
+#define ETH__EIMR 0x0058 /* Interrupt Mask Register */
+#define ETH__EFRDP0 0x0080 /* First Rx Desc Pointer 0 */
+#define ETH__EFRDP1 0x0084 /* First Rx Desc Pointer 1 */
+#define ETH__EFRDP2 0x0088 /* First Rx Desc Pointer 2 */
+#define ETH__EFRDP3 0x008c /* First Rx Desc Pointer 3 */
+#define ETH__ECRDP0 0x00a0 /* Current Rx Desc Pointer 0 */
+#define ETH__ECRDP1 0x00a4 /* Current Rx Desc Pointer 1 */
+#define ETH__ECRDP2 0x00a8 /* Current Rx Desc Pointer 2 */
+#define ETH__ECRDP3 0x00ac /* Current Rx Desc Pointer 3 */
+#define ETH__ECTDP0 0x00e0 /* Current Tx Desc Pointer 0 */
+#define ETH__ECTDP1 0x00e4 /* Current Tx Desc Pointer 1 */
+#define ETH__EDSCP2P0L 0x0060 /* IP Differentiated Services
+ CodePoint to Priority0 low */
+#define ETH__EDSCP2P0H 0x0064 /* IP Differentiated Services
+ CodePoint to Priority0 high*/
+#define ETH__EDSCP2P1L 0x0068 /* IP Differentiated Services
+ CodePoint to Priority1 low */
+#define ETH__EDSCP2P1H 0x006c /* IP Differentiated Services
+ CodePoint to Priority1 high*/
+#define ETH__EVPT2P 0x0068 /* VLAN Prio. Tag to Priority */
+#define ETH__EMIBCTRS 0x0100 /* MIB Counters */
+
+#define ETH_BASE(n) ETH__GEN(n, EBASE)
+#define ETH_EPCR(n) ETH__GEN(n, EPCR) /* Port Config. Register */
+#define ETH_EPCXR(n) ETH__GEN(n, EPCXR) /* Port Config. Extend Reg */
+#define ETH_EPCMR(n) ETH__GEN(n, EPCMR) /* Port Command Register */
+#define ETH_EPSR(n) ETH__GEN(n, EPSR) /* Port Status Register */
+#define ETH_ESPR(n) ETH__GEN(n, ESPR) /* Port Serial Parameters Reg */
+#define ETH_EHTPR(n) ETH__GEN(n, EHPTR) /* Port Hash Table Pointer Reg*/
+#define ETH_EFCSAL(n) ETH__GEN(n, EFCSAL) /* Flow Control Src Addr Low */
+#define ETH_EFCSAH(n) ETH__GEN(n, EFCSAH) /* Flow Control Src Addr High */
+#define ETH_ESDCR(n) ETH__GEN(n, ESDCR) /* SDMA Configuration Reg */
+#define ETH_ESDCMR(n) ETH__GEN(n, ESDCMR) /* SDMA Command Register */
+#define ETH_EICR(n) ETH__GEN(n, EICR) /* Interrupt Cause Register */
+#define ETH_EIMR(n) ETH__GEN(n, EIMR) /* Interrupt Mask Register */
+#define ETH_EFRDP0(n) ETH__GEN(n, EFRDP0) /* First Rx Desc Pointer 0 */
+#define ETH_EFRDP1(n) ETH__GEN(n, EFRDP1) /* First Rx Desc Pointer 1 */
+#define ETH_EFRDP2(n) ETH__GEN(n, EFRDP2) /* First Rx Desc Pointer 2 */
+#define ETH_EFRDP3(n) ETH__GEN(n, EFRDP3) /* First Rx Desc Pointer 3 */
+#define ETH_ECRDP0(n) ETH__GEN(n, ECRDP0) /* Current Rx Desc Pointer 0 */
+#define ETH_ECRDP1(n) ETH__GEN(n, ECRDP1) /* Current Rx Desc Pointer 1 */
+#define ETH_ECRDP2(n) ETH__GEN(n, ECRDP2) /* Current Rx Desc Pointer 2 */
+#define ETH_ECRDP3(n) ETH__GEN(n, ECRDP3) /* Current Rx Desc Pointer 3 */
+#define ETH_ECTDP0(n) ETH__GEN(n, ECTDP0) /* Current Tx Desc Pointer 0 */
+#define ETH_ECTDP1(n) ETH__GEN(n, ECTDP1) /* Current Tx Desc Pointer 1 */
+#define ETH_EDSCP2P0L(n) ETH__GEN(n, EDSCP2P0L) /* IP Differentiated Services
+ CodePoint to Priority0 low */
+#define ETH_EDSCP2P0H(n) ETH__GEN(n, EDSCP2P0H) /* IP Differentiated Services
+ CodePoint to Priority0 high*/
+#define ETH_EDSCP2P1L(n) ETH__GEN(n, EDSCP2P1L) /* IP Differentiated Services
+ CodePoint to Priority1 low */
+#define ETH_EDSCP2P1H(n) ETH__GEN(n, EDSCP1P1H) /* IP Differentiated Services
+ CodePoint to Priority1 high*/
+#define ETH_EVPT2P(n) ETH__GEN(n, EVPT2P) /* VLAN Prio. Tag to Priority */
+#define ETH_EMIBCTRS(n) ETH__GEN(n, EMIBCTRS) /* MIB Counters */
+
+#define ETH_EPAR_PhyAD_GET(v, n) (((v) >> ((n) * 5)) & 0x1f)
+
+#define ETH_ESMIR_READ(phy, reg) (ETH__INS(phy, 16)|\
+ ETH__INS(reg, 21)|\
+ ETH_ESMIR_ReadOpcode)
+#define ETH_ESMIR_WRITE(phy, reg, val) (ETH__INS(phy, 16)|\
+ ETH__INS(reg, 21)|\
+ ETH__INS(val, 0)|\
+ ETH_ESMIR_WriteOpcode)
+#define ETH_ESMIR_Value_GET(v) ETH__EXT(v, 0, 16)
+#define ETH_ESMIR_WriteOpcode 0
+#define ETH_ESMIR_ReadOpcode ETH__BIT(26)
+#define ETH_ESMIR_ReadValid ETH__BIT(27)
+#define ETH_ESMIR_Busy ETH__BIT(28)
+
+/*
+ * Table 597: Port Configuration Register (PCR)
+ * 00:00 PM Promiscuous mode
+ * 0: Normal mode (Frames are only received if the
+ * destination address is found in the hash
+ * table)
+ * 1: Promiscuous mode (Frames are received
+ * regardless of their destination address.
+ * Errored frames are discarded unless the Port
+ * Configuration register's PBF bit is set)
+ * 01:01 RBM Reject Broadcast Mode
+ * 0: Receive broadcast address
+ * 1: Reject frames with broadcast address
+ * Overridden by the promiscuous mode.
+ * 02:02 PBF Pass Bad Frames
+ * (0: Normal mode, 1: Pass bad Frames)
+ * The Ethernet receiver passes to the CPU errored
+ * frames (like fragments and collided packets)
+ * that are normally rejected.
+ * NOTE: Frames are only passed if they
+ * successfully pass address filtering.
+ * 06:03 Reserved
+ * 07:07 EN Enable (0: Disabled, 1: Enable)
+ * When enabled, the ethernet port is ready to
+ * transmit/receive.
+ * 09:08 LPBK Loop Back Mode
+ * 00: Normal mode
+ * 01: Internal loop back mode (TX data is looped
+ * back to the RX lines. No transition is seen
+ * on the interface pins)
+ * 10: External loop back mode (TX data is looped
+ * back to the RX lines and also transmitted
+ * out to the MII interface pins)
+ * 11: Reserved
+ * 10:10 FC Force Collision
+ * 0: Normal mode.
+ * 1: Force Collision on any TX frame.
+ * For RXM test (in Loopback mode).
+ * 11:11 Reserved.
+ * 12:12 HS Hash Size
+ * 0: 8K address filtering
+ * (256KB of memory space required).
+ * 1: 512 address filtering
+ * ( 16KB of memory space required).
+ * 13:13 HM Hash Mode (0: Hash Func. 0; 1: Hash Func. 1)
+ * 14:14 HDM Hash Default Mode
+ * 0: Discard addresses not found in address table
+ * 1: Pass addresses not found in address table
+ * 15:15 HD Duplex Mode (0: Half Duplex, 1: Full Duplex)
+ * NOTE: Valid only when auto-negotiation for
+ * duplex mode is disabled.
+ * 30:16 Reserved
+ * 31:31 ACCS Accelerate Slot Time
+ * (0: Normal mode, 1: Reserved)
+ */
+#define ETH_EPCR_PM ETH__BIT(0)
+#define ETH_EPCR_RBM ETH__BIT(1)
+#define ETH_EPCR_PBF ETH__BIT(2)
+#define ETH_EPCR_EN ETH__BIT(7)
+#define ETH_EPCR_LPBK_GET(v) ETH__BIT(v, 8, 2)
+#define ETH_EPCR_LPBK_Normal 0
+#define ETH_EPCR_LPBK_Internal 1
+#define ETH_EPCR_LPBK_External 2
+#define ETH_EPCR_FC ETH__BIT(10)
+
+#define ETH_EPCR_HS ETH__BIT(12)
+#define ETH_EPCR_HS_8K 0
+#define ETH_EPCR_HS_512 ETH_EPCR_HS
+
+#define ETH_EPCR_HM ETH__BIT(13)
+#define ETH_EPCR_HM_0 0
+#define ETH_EPCR_HM_1 ETH_EPCR_HM
+
+#define ETH_EPCR_HDM ETH__BIT(14)
+#define ETH_EPCR_HDM_Discard 0
+#define ETH_EPCR_HDM_Pass ETH_EPCR_HDM
+
+#define ETH_EPCR_HD_Half 0
+#define ETH_EPCR_HD_Full ETH_EPCR_HD_Full
+
+#define ETH_EPCR_ACCS ETH__BIT(31)
+
+
+
+/*
+ * Table 598: Port Configuration Extend Register (PCXR)
+ * 00:00 IGMP IGMP Packets Capture Enable
+ * 0: IGMP packets are treated as normal Multicast
+ * packets.
+ * 1: IGMP packets on IPv4/Ipv6 over Ethernet/802.3
+ * are trapped and sent to high priority RX
+ * queue.
+ * 01:01 SPAN Spanning Tree Packets Capture Enable
+ * 0: BPDU (Bridge Protocol Data Unit) packets are
+ * treated as normal Multicast packets.
+ * 1: BPDU packets are trapped and sent to high
+ * priority RX queue.
+ * 02:02 PAR Partition Enable (0: Normal, 1: Partition)
+ * When more than 61 collisions occur while
+ * transmitting, the port enters Partition mode.
+ * It waits for the first good packet from the
+ * wire and then goes back to Normal mode. Under
+ * Partition mode it continues transmitting, but
+ * it does not receive.
+ * 05:03 PRIOtx Priority weight in the round-robin between high
+ * and low priority TX queues.
+ * 000: 1 pkt from HIGH, 1 pkt from LOW.
+ * 001: 2 pkt from HIGH, 1 pkt from LOW.
+ * 010: 4 pkt from HIGH, 1 pkt from LOW.
+ * 011: 6 pkt from HIGH, 1 pkt from LOW.
+ * 100: 8 pkt from HIGH, 1 pkt from LOW.
+ * 101: 10 pkt from HIGH, 1 pkt from LOW.
+ * 110: 12 pkt from HIGH, 1 pkt from LOW.
+ * 111: All pkt from HIGH, 0 pkt from LOW. LOW is
+ * served only if HIGH is empty.
+ * NOTE: If the HIGH queue is emptied before
+ * finishing the count, the count is reset
+ * until the next first HIGH comes in.
+ * 07:06 PRIOrx Default Priority for Packets Received on this
+ * Port (00: Lowest priority, 11: Highest priority)
+ * 08:08 PRIOrx_Override Override Priority for Packets Received on this
+ * Port (0: Do not override, 1: Override with
+ * <PRIOrx> field)
+ * 09:09 DPLXen Enable Auto-negotiation for Duplex Mode
+ * (0: Enable, 1: Disable)
+ * 11:10 FCTLen Enable Auto-negotiation for 802.3x Flow-control
+ * 0: Enable; When enabled, 1 is written (through
+ * SMI access) to the PHY's register 4 bit 10
+ * to advertise flow-control capability.
+ * 1: Disable; Only enables flow control after the
+ * PHY address is set by the CPU. When changing
+ * the PHY address the flow control
+ * auto-negotiation must be disabled.
+ * 11:11 FLP Force Link Pass
+ * (0: Force Link Pass, 1: Do NOT Force Link pass)
+ * 12:12 FCTL 802.3x Flow-Control Mode (0: Enable, 1: Disable)
+ * NOTE: Only valid when auto negotiation for flow
+ * control is disabled.
+ * 13:13 Reserved
+ * 15:14 MFL Max Frame Length
+ * Maximum packet allowed for reception (including
+ * CRC): 00: 1518 bytes, 01: 1536 bytes,
+ * 10: 2048 bytes, 11: 64K bytes
+ * 16:16 MIBclrMode MIB Counters Clear Mode (0: Clear, 1: No effect)
+ * 17:17 MIBctrMode Reserved. (MBZ)
+ * 18:18 Speed Port Speed (0: 10Mbit/Sec, 1: 100Mbit/Sec)
+ * NOTE: Only valid if SpeedEn bit is set.
+ * 19:19 SpeedEn Enable Auto-negotiation for Speed
+ * (0: Enable, 1: Disable)
+ * 20:20 RMIIen RMII enable
+ * 0: Port functions as MII port
+ * 1: Port functions as RMII port
+ * 21:21 DSCPen DSCP enable
+ * 0: IP DSCP field decoding is disabled.
+ * 1: IP DSCP field decoding is enabled.
+ * 31:22 Reserved
+ */
+#define ETH_EPCXR_IGMP ETH__BIT(0)
+#define ETH_EPCXR_SPAN ETH__BIT(1)
+#define ETH_EPCXR_PAR ETH__BIT(2)
+#define ETH_EPCXR_PRIOtx_GET(v) ETH__EXT(v, 3, 3)
+#define ETH_EPCXR_PRIOrx_GET(v) ETH__EXT(v, 3, 3)
+#define ETH_EPCXR_PRIOrx_Override ETH__BIT(8)
+#define ETH_EPCXR_DLPXen ETH__BIT(9)
+#define ETH_EPCXR_FCTLen ETH__BIT(10)
+#define ETH_EPCXR_FLP ETH__BIT(11)
+#define ETH_EPCXR_FCTL ETH__BIT(12)
+#define ETH_EPCXR_MFL_GET(v) ETH__EXT(v, 14, 2)
+#define ETH_EPCXR_MFL_1518 0
+#define ETH_EPCXR_MFL_1536 1
+#define ETH_EPCXR_MFL_2084 2
+#define ETH_EPCXR_MFL_64K 3
+#define ETH_EPCXR_MIBclrMode ETH__BIT(16)
+#define ETH_EPCXR_MIBctrMode ETH__BIT(17)
+#define ETH_EPCXR_Speed ETH__BIT(18)
+#define ETH_EPCXR_SpeedEn ETH__BIT(19)
+#define ETH_EPCXR_RMIIEn ETH__BIT(20)
+#define ETH_EPCXR_DSCPEn ETH__BIT(21)
+
+
+
+/*
+ * Table 599: Port Command Register (PCMR)
+ * 14:00 Reserved
+ * 15:15 FJ Force Jam / Flow Control
+ * When in half-duplex mode, the CPU uses this bit
+ * to force collisions on the Ethernet segment.
+ * When the CPU recognizes that it is going to run
+ * out of receive buffers, it can force the
+ * transmitter to send jam frames, forcing
+ * collisions on the wire. To allow transmission
+ * on the Ethernet segment, the CPU must clear the
+ * FJ bit when more resources are available. When
+ * in full-duplex and flow-control is enabled, this
+ * bit causes the port's transmitter to send
+ * flow-control PAUSE packets. The CPU must reset
+ * this bit when more resources are available.
+ * 31:16 Reserved
+ */
+
+#define ETH_EPCMR_FJ ETH__BIT(15)
+
+
+/*
+ * Table 600: Port Status Register (PSR) -- Read Only
+ * 00:00 Speed Indicates Port Speed (0: 10Mbs, 1: 100Mbs)
+ * 01:01 Duplex Indicates Port Duplex Mode (0: Half, 1: Full)
+ * 02:02 Fctl Indicates Flow-control Mode
+ * (0: enabled, 1: disabled)
+ * 03:03 Link Indicates Link Status (0: down, 1: up)
+ * 04:04 Pause Indicates that the port is in flow-control
+ * disabled state. This bit is set when an IEEE
+ * 802.3x flow-control PAUSE (XOFF) packet is
+ * received (assuming that flow-control is
+ * enabled and the port is in full-duplex mode).
+ * Reset when XON is received, or when the XOFF
+ * timer has expired.
+ * 05:05 TxLow Tx Low Priority Status
+ * Indicates the status of the low priority
+ * transmit queue: (0: Stopped, 1: Running)
+ * 06:06 TxHigh Tx High Priority Status
+ * Indicates the status of the high priority
+ * transmit queue: (0: Stopped, 1: Running)
+ * 07:07 TXinProg TX in Progress
+ * Indicates that the port's transmitter is in an
+ * active transmission state.
+ * 31:08 Reserved
+ */
+#define ETH_EPSR_Speed ETH__BIT(0)
+#define ETH_EPSR_Duplex ETH__BIT(1)
+#define ETH_EPSR_Fctl ETH__BIT(2)
+#define ETH_EPSR_Link ETH__BIT(3)
+#define ETH_EPSR_Pause ETH__BIT(4)
+#define ETH_EPSR_TxLow ETH__BIT(5)
+#define ETH_EPSR_TxHigh ETH__BIT(6)
+#define ETH_EPSR_TXinProg ETH__BIT(7)
+
+
+/*
+ * Table 601: Serial Parameters Register (SPR)
+ * 01:00 JAM_LENGTH Two bits to determine the JAM Length
+ * (in Backpressure) as follows:
+ * 00 = 12K bit-times
+ * 01 = 24K bit-times
+ * 10 = 32K bit-times
+ * 11 = 48K bit-times
+ * 06:02 JAM_IPG Five bits to determine the JAM IPG.
+ * The step is four bit-times. The value may vary
+ * between 4 bit time to 124.
+ * 11:07 IPG_JAM_TO_DATA Five bits to determine the IPG JAM to DATA.
+ * The step is four bit-times. The value may vary
+ * between 4 bit time to 124.
+ * 16:12 IPG_DATA Inter-Packet Gap (IPG)
+ * The step is four bit-times. The value may vary
+ * between 12 bit time to 124.
+ * NOTE: These bits may be changed only when the
+ * Ethernet ports is disabled.
+ * 21:17 Data_Blind Data Blinder
+ * The number of nibbles from the beginning of the
+ * IPG, in which the IPG counter is restarted when
+ * detecting a carrier activity. Following this
+ * value, the port enters the Data Blinder zone and
+ * does not reset the IPG counter. This ensures
+ * fair access to the medium.
+ * The default is 10 hex (64 bit times - 2/3 of the
+ * default IPG). The step is 4 bit-times. Valid
+ * range is 3 to 1F hex nibbles.
+ * NOTE: These bits may be only changed when the
+ * Ethernet port is disabled.
+ * 22:22 Limit4 The number of consecutive packet collisions that
+ * occur before the collision counter is reset.
+ * 0: The port resets its collision counter after
+ * 16 consecutive retransmit trials and
+ * restarts the Backoff algorithm.
+ * 1: The port resets its collision counter and
+ * restarts the Backoff algorithm after 4
+ * consecutive transmit trials.
+ * 31:23 Reserved
+ */
+#define ETH_ESPR_JAM_LENGTH_GET(v) ETH__EXT(v, 0, 2)
+#define ETH_ESPR_JAM_IPG_GET(v) ETH__EXT(v, 2, 5)
+#define ETH_ESPR_IPG_JAM_TO_DATA_GET(v) ETH__EXT(v, 7, 5)
+#define ETH_ESPR_IPG_DATA_GET(v) ETH__EXT(v, 12, 5)
+#define ETH_ESPR_Data_Bilnd_GET(v) ETH__EXT(v, 17, 5)
+#define ETH_ESPR_Limit4(v) ETH__BIT(22)
+
+/*
+ * Table 602: Hash Table Pointer Register (HTPR)
+ * 31:00 HTP 32-bit pointer to the address table.
+ * Bits [2:0] must be set to zero.
+ */
+
+/*
+ * Table 603: Flow Control Source Address Low (FCSAL)
+ * 15:0 SA[15:0] Source Address
+ * The least significant bits of the source
+ * address for the port. This address is used for
+ * Flow Control.
+ * 31:16 Reserved
+ */
+
+/*
+ * Table 604: Flow Control Source Address High (FCSAH)
+ * 31:0 SA[47:16] Source Address
+ * The most significant bits of the source address
+ * for the port. This address is used for Flow
+ * Control.
+ */
+
+
+/*
+ * Table 605: SDMA Configuration Register (SDCR)
+ * 01:00 Reserved
+ * 05:02 RC Retransmit Count
+ * Sets the maximum number of retransmits per
+ * packet. After executing retransmit for RC
+ * times, the TX SDMA closes the descriptor with a
+ * Retransmit Limit error indication and processes
+ * the next packet. When RC is set to 0, the
+ * number of retransmits is unlimited. In this
+ * case, the retransmit process is only terminated
+ * if CPU issues an Abort command.
+ * 06:06 BLMR Big/Little Endian Receive Mode
+ * The DMA supports Big or Little Endian
+ * configurations on a per channel basis. The BLMR
+ * bit only affects data transfer to memory.
+ * 0: Big Endian
+ * 1: Little Endian
+ * 07:07 BLMT Big/Little Endian Transmit Mode
+ * The DMA supports Big or Little Endian
+ * configurations on a per channel basis. The BLMT
+ * bit only affects data transfer from memory.
+ * 0: Big Endian
+ * 1: Little Endian
+ * 08:08 POVR PCI Override
+ * When set, causes the SDMA to direct all its
+ * accesses in PCI_0 direction and overrides
+ * normal address decoding process.
+ * 09:09 RIFB Receive Interrupt on Frame Boundaries
+ * When set, the SDMA Rx generates interrupts only
+ * on frame boundaries (i.e. after writing the
+ * frame status to the descriptor).
+ * 11:10 Reserved
+ * 13:12 BSZ Burst Size
+ * Sets the maximum burst size for SDMA
+ * transactions:
+ * 00: Burst is limited to 1 64bit words.
+ * 01: Burst is limited to 2 64bit words.
+ * 10: Burst is limited to 4 64bit words.
+ * 11: Burst is limited to 8 64bit words.
+ * 31:14 Reserved
+ */
+#define ETH_ESDCR_RC_GET(v) ETH__EXT(v, 2, 4)
+#define ETH_ESDCR_BLMR ETH__BIT(6)
+#define ETH_ESDCR_BLMT ETH__BIT(7)
+#define ETH_ESDCR_POVR ETH__BIT(8)
+#define ETH_ESDCR_RIFB ETH__BIT(9)
+#define ETH_ESDCR_BSZ_GET(v) ETH__EXT(v, 12, 2)
+#define ETH_ESDCR_BSZ_SET(v, n) (ETH__CLR(v, 12, 2),\
+ (v) |= ETH__INS(n, 12))
+#define ETH_ESDCR_BSZ_1 0
+#define ETH_ESDCR_BSZ_2 1
+#define ETH_ESDCR_BSZ_4 2
+#define ETH_ESDCR_BSZ_8 3
+
+#define ETH_ESDCR_BSZ_Strings { "1 64-bit word", "2 64-bit words", \
+ "4 64-bit words", "8 64-bit words" }
+
+/*
+ * Table 606: SDMA Command Register (SDCMR)
+ * 06:00 Reserved
+ * 07:07 ERD Enable RX DMA.
+ * Set to 1 by the CPU to cause the SDMA to start
+ * a receive process. Cleared when the CPU issues
+ * an Abort Receive command.
+ * 14:08 Reserved
+ * 15:15 AR Abort Receive
+ * Set to 1 by the CPU to abort a receive SDMA
+ * operation. When the AR bit is set, the SDMA
+ * aborts its current operation and moves to IDLE.
+ * No descriptor is closed. The AR bit is cleared
+ * upon entering IDLE. After setting the AR bit,
+ * the CPU must poll the bit to verify that the
+ * abort sequence is completed.
+ * 16:16 STDH Stop TX High
+ * Set to 1 by the CPU to stop the transmission
+ * process from the high priority queue at the end
+ * of the current frame. An interrupt is generated
+ * when the stop command has been executed.
+ * Writing 1 to STDH resets TXDH bit.
+ * Writing 0 to this bit has no effect.
+ * 17:17 STDL Stop TX Low
+ * Set to 1 by the CPU to stop the transmission
+ * process from the low priority queue at the end
+ * of the current frame. An interrupt is generated
+ * when the stop command has been executed.
+ * Writing 1 to STDL resets TXDL bit.
+ * Writing 0 to this bit has no effect.
+ * 22:18 Reserved
+ * 23:23 TXDH Start Tx High
+ * Set to 1 by the CPU to cause the SDMA to fetch
+ * the first descriptor and start a transmit
+ * process from the high priority Tx queue.
+ * Writing 1 to TXDH resets STDH bit.
+ * Writing 0 to this bit has no effect.
+ * 24:24 TXDL Start Tx Low
+ * Set to 1 by the CPU to cause the SDMA to fetch
+ * the first descriptor and start a transmit
+ * process from the low priority Tx queue.
+ * Writing 1 to TXDL resets STDL bit.
+ * Writing 0 to this bit has no effect.
+ * 30:25 Reserved
+ * 31:31 AT Abort Transmit
+ * Set to 1 by the CPU to abort a transmit DMA
+ * operation. When the AT bit is set, the SDMA
+ * aborts its current operation and moves to IDLE.
+ * No descriptor is closed. Cleared upon entering
+ * IDLE. After setting AT bit, the CPU must poll
+ * it in order to verify that the abort sequence
+ * is completed.
+ */
+#define ETH_ESDCMR_ERD ETH__BIT(7)
+#define ETH_ESDCMR_AR ETH__BIT(15)
+#define ETH_ESDCMR_STDH ETH__BIT(16)
+#define ETH_ESDCMR_STDL ETH__BIT(17)
+#define ETH_ESDCMR_TXDH ETH__BIT(23)
+#define ETH_ESDCMR_TXDL ETH__BIT(24)
+#define ETH_ESDCMR_AT ETH__BIT(31)
+
+/*
+ * Table 607: Interrupt Cause Register (ICR)
+ * 00:00 RxBuffer Rx Buffer Return
+ * Indicates an Rx buffer returned to CPU ownership
+ * or that the port finished reception of a Rx
+ * frame in either priority queues.
+ * NOTE: In order to get a Rx Buffer return per
+ * priority queue, use bit 19:16. This bit is
+ * set upon closing any Rx descriptor which
+ * has its EI bit set. To limit the
+ * interrupts to frame (rather than buffer)
+ * boundaries, the user must set SDMA
+ * Configuration register's RIFB bit. When
+ * the RIFB bit is set, an interrupt
+ * generates only upon closing the first
+ * descriptor of a received packet, if this
+ * descriptor has it EI bit set.
+ * 01:01 Reserved
+ * 02:02 TxBufferHigh Tx Buffer for High priority Queue
+ * Indicates a Tx buffer returned to CPU ownership
+ * or that the port finished transmission of a Tx
+ * frame.
+ * NOTE: This bit is set upon closing any Tx
+ * descriptor which has its EI bit set. To
+ * limit the interrupts to frame (rather than
+ * buffer) boundaries, the user must set EI
+ * only in the last descriptor.
+ * 03:03 TxBufferLow Tx Buffer for Low Priority Queue
+ * Indicates a Tx buffer returned to CPU ownership
+ * or that the port finished transmission of a Tx
+ * frame.
+ * NOTE: This bit is set upon closing any Tx
+ * descriptor which has its EI bit set. To
+ * limit the interrupts to frame (rather than
+ * buffer) boundaries, the user must set EI
+ * only in the last descriptor.
+ * 05:04 Reserved
+ * 06:06 TxEndHigh Tx End for High Priority Queue
+ * Indicates that the Tx DMA stopped processing the
+ * high priority queue after stop command, or that
+ * it reached the end of the high priority
+ * descriptor chain.
+ * 07:07 TxEndLow Tx End for Low Priority Queue
+ * Indicates that the Tx DMA stopped processing the
+ * low priority queue after stop command, or that
+ * it reached the end of the low priority
+ * descriptor chain.
+ * 08:08 RxError Rx Resource Error
+ * Indicates a Rx resource error event in one of
+ * the priority queues.
+ * NOTE: To get a Rx Resource Error Indication per
+ * priority queue, use bit 23:20.
+ * 09:09 Reserved
+ * 10:10 TxErrorHigh Tx Resource Error for High Priority Queue
+ * Indicates a Tx resource error event during
+ * packet transmission from the high priority queue
+ * 11:11 TxErrorLow Tx Resource Error for Low Priority Queue
+ * Indicates a Tx resource error event during
+ * packet transmission from the low priority queue
+ * 12:12 RxOVR Rx Overrun
+ * Indicates an overrun event that occurred during
+ * reception of a packet.
+ * 13:13 TxUdr Tx Underrun
+ * Indicates an underrun event that occurred during
+ * transmission of packet from either queue.
+ * 15:14 Reserved
+ * 16:16 RxBuffer-Queue[0] Rx Buffer Return in Priority Queue[0]
+ * Indicates a Rx buffer returned to CPU ownership
+ * or that the port completed reception of a Rx
+ * frame in a receive priority queue[0]
+ * 17:17 RxBuffer-Queue[1] Rx Buffer Return in Priority Queue[1]
+ * Indicates a Rx buffer returned to CPU ownership
+ * or that the port completed reception of a Rx
+ * frame in a receive priority queue[1].
+ * 18:18 RxBuffer-Queue[2] Rx Buffer Return in Priority Queue[2]
+ * Indicates a Rx buffer returned to CPU ownership
+ * or that the port completed reception of a Rx
+ * frame in a receive priority queue[2].
+ * 19:19 RxBuffer-Queue[3] Rx Buffer Return in Priority Queue[3]
+ * Indicates a Rx buffer returned to CPU ownership
+ * or that the port completed reception of a Rx
+ * frame in a receive priority queue[3].
+ * 20:20 RxError-Queue[0] Rx Resource Error in Priority Queue[0]
+ * Indicates a Rx resource error event in receive
+ * priority queue[0].
+ * 21:21 RxError-Queue[1] Rx Resource Error in Priority Queue[1]
+ * Indicates a Rx resource error event in receive
+ * priority queue[1].
+ * 22:22 RxError-Queue[2] Rx Resource Error in Priority Queue[2]
+ * Indicates a Rx resource error event in receive
+ * priority queue[2].
+ * 23:23 RxError-Queue[3] Rx Resource Error in Priority Queue[3]
+ * Indicates a Rx resource error event in receive
+ * priority queue[3].
+ * 27:24 Reserved
+ * 28:29 MIIPhySTC MII PHY Status Change
+ * Indicates a status change reported by the PHY
+ * connected to this port. Set when the MII
+ * management interface block identifies a change
+ * in PHY's register 1.
+ * 29:29 SMIdone SMI Command Done
+ * Indicates that the SMI completed a MII
+ * management command (either read or write) that
+ * was initiated by the CPU writing to the SMI
+ * register.
+ * 30:30 Reserved
+ * 31:31 EtherIntSum Ethernet Interrupt Summary
+ * This bit is a logical OR of the (unmasked) bits
+ * [30:04] in the Interrupt Cause register.
+ */
+
+#define ETH_IR_RxBuffer ETH__BIT(0)
+#define ETH_IR_TxBufferHigh ETH__BIT(2)
+#define ETH_IR_TxBufferLow ETH__BIT(3)
+#define ETH_IR_TxEndHigh ETH__BIT(6)
+#define ETH_IR_TxEndLow ETH__BIT(7)
+#define ETH_IR_RxError ETH__BIT(8)
+#define ETH_IR_TxErrorHigh ETH__BIT(10)
+#define ETH_IR_TxErrorLow ETH__BIT(11)
+#define ETH_IR_RxOVR ETH__BIT(12)
+#define ETH_IR_TxUdr ETH__BIT(13)
+#define ETH_IR_RxBuffer_0 ETH__BIT(16)
+#define ETH_IR_RxBuffer_1 ETH__BIT(17)
+#define ETH_IR_RxBuffer_2 ETH__BIT(18)
+#define ETH_IR_RxBuffer_3 ETH__BIT(19)
+#define ETH_IR_RxBuffer_GET(v) ETH__EXT(v, 16, 4)
+#define ETH_IR_RxError_0 ETH__BIT(20)
+#define ETH_IR_RxError_1 ETH__BIT(21)
+#define ETH_IR_RxError_2 ETH__BIT(22)
+#define ETH_IR_RxError_3 ETH__BIT(23)
+#define ETH_IR_RxError_GET(v) ETH__EXT(v, 20, 4)
+#define ETH_IR_RxBits (ETH_IR_RxBuffer_0|\
+ ETH_IR_RxBuffer_1|\
+ ETH_IR_RxBuffer_2|\
+ ETH_IR_RxBuffer_3|\
+ ETH_IR_RxError_0|\
+ ETH_IR_RxError_1|\
+ ETH_IR_RxError_2|\
+ ETH_IR_RxError_3)
+#define ETH_IR_MIIPhySTC ETH__BIT(28)
+#define ETH_IR_SMIdone ETH__BIT(29)
+#define ETH_IR_EtherIntSum ETH__BIT(31)
+#define ETH_IR_Summary ETH__BIT(31)
+
+/*
+ * Table 608: Interrupt Mask Register (IMR)
+ * 31:00 Various Mask bits for the Interrupt Cause register.
+ */
+
+/*
+ * Table 609: IP Differentiated Services CodePoint to Priority0 low (DSCP2P0L),
+ * 31:00 Priority0_low The LSB priority bits for DSCP[31:0] entries.
+ */
+
+/*
+ * Table 610: IP Differentiated Services CodePoint to Priority0 high (DSCP2P0H)
+ * 31:00 Priority0_high The LSB priority bits for DSCP[63:32] entries.
+ */
+
+/*
+ * Table 611: IP Differentiated Services CodePoint to Priority1 low (DSCP2P1L)
+ * 31:00 Priority1_low The MSB priority bits for DSCP[31:0] entries.
+ */
+
+/*
+ * Table 612: IP Differentiated Services CodePoint to Priority1 high (DSCP2P1H)
+ * 31:00 Priority1_high The MSB priority bit for DSCP[63:32] entries.
+ */
+
+/*
+ * Table 613: VLAN Priority Tag to Priority (VPT2P)
+ * 07:00 Priority0 The LSB priority bits for VLAN Priority[7:0]
+ * entries.
+ * 15:08 Priority1 The MSB priority bits for VLAN Priority[7:0]
+ * entries.
+ * 31:16 Reserved
+ */
+
+/* Address control registers -- these are offsets from the GT base
+ * and NOT from the ethernet port base. <tss>
+ */
+#define ETH_ACTL_0_LO 0xf200
+
+/* Enable hardware cache snooping;
+ * Copyright Shuchen K. Feng <feng1@bnl.gov>, 2004
+ */
+
+/* Ethernet address control (Low) snoop bits */
+#define RxBSnoopEn ETH__BIT(6) /* Rx buffer snoop enable,1=enable*/
+#define TxBSnoopEn ETH__BIT(14) /* Tx buffer snoop enable */
+#define RxDSnoopEn ETH__BIT(22) /* Rx descriptor snoop enable */
+#define TxDSnoopEn ETH__BIT(30) /* Tx descriptor snoop enable */
+
+#define ETH_ACTL_0_HI 0xf204
+/* Ethernet address control (High), snoop bits */
+#define HashSnoopEn ETH__BIT(6) /* Hash Table snoop enable */
+
+
+#define ETH_ACTL_1_LO 0xf220
+#define ETH_ACTL_1_HI 0xf224
+#define ETH_ACTL_2_LO 0xf240
+#define ETH_ACTL_2_HI 0xf244
+
+
+#endif /* _DEV_GTETHREG_H_ */
diff --git a/bsps/powerpc/beatnik/net/if_gfe/gtvar.h b/bsps/powerpc/beatnik/net/if_gfe/gtvar.h
new file mode 100644
index 0000000..00d72bf
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/gtvar.h
@@ -0,0 +1,170 @@
+/* $NetBSD: gtvar.h,v 1.7.4.1 2005/04/29 11:28:56 kent Exp $ */
+
+/*
+ * Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed for the NetBSD Project by
+ * Allegro Networks, Inc., and Wasabi Systems, Inc.
+ * 4. The name of Allegro Networks, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ * 5. The name of Wasabi Systems, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ALLEGRO NETWORKS, INC. AND
+ * WASABI SYSTEMS, INC. ``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 EITHER ALLEGRO NETWORKS, INC. OR WASABI SYSTEMS, INC.
+ * 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.
+ */
+
+/*
+ * gtvar.h -- placeholder for GT system controller driver
+ */
+#ifndef _DISCOVERY_DEV_GTVAR_H_
+#define _DISCOVERY_DEV_GTVAR_H_
+
+#include <sys/systm.h>
+
+struct gt_softc {
+#ifndef __rtems__
+ struct device gt_dev;
+ bus_dma_tag_t gt_dmat;
+ bus_space_tag_t gt_memt; /* the GT itself */
+ bus_space_tag_t gt_pci0_memt; /* PCI0 mem space */
+ bus_space_tag_t gt_pci0_iot; /* PCI0 i/o space */
+ boolean_t gt_pci0_host; /* We're host on PCI0 if TRUE */
+ bus_space_tag_t gt_pci1_memt; /* PCI1 mem space */
+ bus_space_tag_t gt_pci1_iot; /* PCI1 i/o space */
+ boolean_t gt_pci1_host; /* We're host on PCI1 if TRUE */
+
+ bus_space_handle_t gt_memh; /* to access the GT registers */
+#else
+ unsigned gt_memh;
+#endif
+ int gt_childmask; /* what children are present */
+};
+
+#define GT_CHILDOK(gt, ga, cd, pos, max) \
+ (((ga)->ga_unit) < (max) && \
+ !((gt)->gt_childmask & (1 << (((ga)->ga_unit) + (pos)))) && \
+ !strcmp((ga)->ga_name, (cd)->cd_name))
+
+#define GT_MPSCOK(gt, ga, cd) GT_CHILDOK((gt), (ga), (cd), 0, 2)
+#define GT_PCIOK(gt, ga, cd) GT_CHILDOK((gt), (ga), (cd), 2, 2)
+#define GT_ETHEROK(gt, ga, cd) GT_CHILDOK((gt), (ga), (cd), 4, 3)
+#define GT_OBIOOK(gt, ga, cd) GT_CHILDOK((gt), (ga), (cd), 7, 5)
+#define GT_I2COK(gt, ga, cd) GT_CHILDOK((gt), (ga), (cd), 12, 1)
+
+#define GT_CHILDFOUND(gt, ga, pos) \
+ ((void)(((gt)->gt_childmask |= (1 << (((ga)->ga_unit) + (pos))))))
+
+#define GT_MPSCFOUND(gt, ga) GT_CHILDFOUND((gt), (ga), 0)
+#define GT_PCIFOUND(gt, ga) GT_CHILDFOUND((gt), (ga), 2)
+#define GT_ETHERFOUND(gt, ga) GT_CHILDFOUND((gt), (ga), 4)
+#define GT_OBIOFOUND(gt, ga) GT_CHILDFOUND((gt), (ga), 7)
+#define GT_I2CFOUND(gt, ga) GT_CHILDFOUND((gt), (ga), 12)
+
+#ifndef __rtems__
+struct gt_attach_args {
+ const char *ga_name; /* class name of device */
+ bus_dma_tag_t ga_dmat; /* dma tag */
+ bus_space_tag_t ga_memt; /* GT bus space tag */
+ bus_space_handle_t ga_memh; /* GT bus space handle */
+ int ga_unit; /* instance of ga_name */
+};
+
+struct obio_attach_args {
+ const char *oa_name; /* call name of device */
+ bus_space_tag_t oa_memt; /* bus space tag */
+ bus_addr_t oa_offset; /* offset (absolute) to device */
+ bus_size_t oa_size; /* size (strided) of device */
+ int oa_irq; /* irq */
+};
+#endif
+
+#ifdef _KERNEL
+#ifndef __rtems__
+#include "locators.h"
+#endif
+
+#ifdef DEBUG
+extern int gtpci_debug;
+#endif
+
+/*
+ * Locators for GT private devices, as specified to config.
+ */
+#define GT_UNK_UNIT GTCF_UNIT_DEFAULT /* wcarded 'function' */
+
+#define OBIO_UNK_OFFSET OBIOCF_OFFSET_DEFAULT /* wcarded 'offset' */
+
+#define OBIO_UNK_SIZE OBIOCF_SIZE_DEFAULT /* wcarded 'size' */
+
+#define OBIO_UNK_IRQ OBIOCF_IRQ_DEFAULT /* wcarded 'irq' */
+
+void gt_attach_common(struct gt_softc *);
+uint32_t gt_read_mpp(void);
+int gt_cfprint(void *, const char *);
+
+#ifndef __rtems__
+/* int gt_bs_extent_init(struct discovery_bus_space *, char *); AKB */
+int gt_mii_read(struct device *, struct device *, int, int);
+void gt_mii_write(struct device *, struct device *, int, int, int);
+int gtget_macaddr(struct gt_softc *,int, char *);
+
+void gt_watchdog_service(void);
+bus_addr_t gt_dma_phys_to_bus_mem(bus_dma_tag_t, bus_addr_t);
+bus_addr_t gt_dma_bus_mem_to_phys(bus_dma_tag_t, bus_addr_t);
+
+#define gt_read(gt,o) \
+ bus_space_read_4((gt)->gt_memt, (gt)->gt_memh, (o))
+#define gt_write(gt,o,v) \
+ bus_space_write_4((gt)->gt_memt, (gt)->gt_memh, (o), (v))
+#else
+#endif
+
+#if defined(__powerpc__)
+static __inline volatile int
+atomic_add(volatile int *p, int v)
+{
+ int rv;
+ int rtmp;
+
+ __asm __volatile(
+ "1: lwarx %0,0,%3\n"
+ " add %1,%4,%0\n"
+ " stwcx. %1,0,%3\n"
+ " bne- 1b\n"
+ " sync"
+ : "=&r"(rv), "=&r"(rtmp), "=m"(*p)
+ : "r"(p), "r"(v), "m"(*p)
+ : "cc");
+
+ return rv;
+}
+
+#endif /* __powerpc__ */
+
+#endif /* _KERNEL */
+
+#endif /* _DISCOVERY_DEV_GTVAR_H_ */
diff --git a/bsps/powerpc/beatnik/net/if_gfe/if_gfe.c b/bsps/powerpc/beatnik/net/if_gfe/if_gfe.c
new file mode 100644
index 0000000..7b29717
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/if_gfe.c
@@ -0,0 +1,2648 @@
+/* $NetBSD: if_gfe.c,v 1.13.8.1 2005/04/29 11:28:56 kent Exp $ */
+
+/*
+ * Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * All rights reserved.
+ *
+ * Copyright 2004: Enable hardware cache snooping. Kate Feng <feng1@bnl.gov>
+ *
+ * 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed for the NetBSD Project by
+ * Allegro Networks, Inc., and Wasabi Systems, Inc.
+ * 4. The name of Allegro Networks, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ * 5. The name of Wasabi Systems, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ALLEGRO NETWORKS, INC. AND
+ * WASABI SYSTEMS, INC. ``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 EITHER ALLEGRO NETWORKS, INC. OR WASABI SYSTEMS, INC.
+ * 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.
+ */
+
+/*
+ * if_gfe.c -- GT ethernet MAC driver
+ */
+
+/* Enable hardware cache snooping;
+ * Copyright Shuchen K. Feng <feng1@bnl.gov>, 2004
+ */
+
+#ifdef __rtems__
+#include "rtemscompat_defs.h"
+#include "../porting/rtemscompat.h"
+#include <string.h>
+#include <stdio.h>
+#include <inttypes.h>
+#endif
+
+#include <sys/cdefs.h>
+#ifndef __rtems__
+__KERNEL_RCSID(0, "$NetBSD: if_gfe.c,v 1.13.8.1 2005/04/29 11:28:56 kent Exp $");
+
+#include "opt_inet.h"
+#include "bpfilter.h"
+#endif
+
+#include <sys/param.h>
+#include <sys/types.h>
+#ifndef __rtems__
+#include <sys/inttypes.h>
+#include <sys/queue.h>
+#endif
+
+#ifndef __rtems__
+#include <uvm/uvm_extern.h>
+
+#include <sys/callout.h>
+#include <sys/device.h>
+#endif
+#include <sys/errno.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#ifndef __rtems__
+#include <machine/bus.h>
+#endif
+
+#include <net/if.h>
+#include <net/if_dl.h>
+#include <net/if_media.h>
+#ifndef __rtems__
+#include <net/if_ether.h>
+#else
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <net/ethernet.h>
+#include <rtems/rtems_mii_ioctl.h>
+#endif
+
+#ifdef INET
+#include <netinet/in.h>
+#ifndef __rtems__
+#include <netinet/if_inarp.h>
+#endif
+#endif
+#if NBPFILTER > 0
+#include <net/bpf.h>
+#endif
+
+#ifndef __rtems__
+#include <dev/mii/miivar.h>
+
+#include <dev/marvell/gtintrreg.h>
+#include <dev/marvell/gtethreg.h>
+
+#include <dev/marvell/gtvar.h>
+#include <dev/marvell/if_gfevar.h>
+#else
+#include <bsp/gtintrreg.h>
+#include <bsp/gtreg.h>
+#include "gtethreg.h"
+
+#include "gtvar.h"
+#include "if_gfevar.h"
+#include "../porting/rtemscompat1.h"
+#define ether_sprintf ether_sprintf_macro
+#endif
+
+#define GE_READ(sc, reg) \
+ bus_space_read_4((sc)->sc_gt_memt, (sc)->sc_memh, ETH__ ## reg)
+#define GE_WRITE(sc, reg, v) \
+ bus_space_write_4((sc)->sc_gt_memt, (sc)->sc_memh, ETH__ ## reg, (v))
+
+#define GT_READ(sc, reg) \
+ bus_space_read_4((sc)->sc_gt_memt, (sc)->sc_gt_memh, reg)
+#define GT_WRITE(sc, reg, v) \
+ bus_space_write_4((sc)->sc_gt_memt, (sc)->sc_gt_memh, reg, (v))
+
+#define GE_DEBUG
+#if 0
+#define GE_NOHASH
+#define GE_NORX
+#endif
+
+#ifdef GE_DEBUG
+#define GE_DPRINTF(sc, a) do \
+ if ((sc)->sc_ec.ec_if.if_flags & IFF_DEBUG) \
+ printf a; \
+ while (0)
+#define GE_FUNC_ENTER(sc, func) GE_DPRINTF(sc, ("[" func))
+#define GE_FUNC_EXIT(sc, str) GE_DPRINTF(sc, (str "]"))
+#else
+#define GE_DPRINTF(sc, a) do { } while (0)
+#define GE_FUNC_ENTER(sc, func) do { } while (0)
+#define GE_FUNC_EXIT(sc, str) do { } while (0)
+#endif
+enum gfe_whack_op {
+ GE_WHACK_START, GE_WHACK_RESTART,
+ GE_WHACK_CHANGE, GE_WHACK_STOP
+};
+
+enum gfe_hash_op {
+ GE_HASH_ADD, GE_HASH_REMOVE,
+};
+
+
+#if 1
+#define htogt32(a) htobe32(a)
+#define gt32toh(a) be32toh(a)
+#else
+#define htogt32(a) htole32(a)
+#define gt32toh(a) le32toh(a)
+#endif
+
+#ifdef __rtems__
+#define htobe32 htonl
+#define be32toh ntohl
+#endif
+
+#define GE_RXDSYNC(sc, rxq, n, ops) \
+ bus_dmamap_sync((sc)->sc_dmat, (rxq)->rxq_desc_mem.gdm_map, \
+ (n) * sizeof((rxq)->rxq_descs[0]), sizeof((rxq)->rxq_descs[0]), \
+ (ops))
+#define GE_RXDPRESYNC(sc, rxq, n) \
+ GE_RXDSYNC(sc, rxq, n, BUS_DMASYNC_PREREAD|BUS_DMASYNC_PREWRITE)
+#define GE_RXDPOSTSYNC(sc, rxq, n) \
+ GE_RXDSYNC(sc, rxq, n, BUS_DMASYNC_POSTREAD|BUS_DMASYNC_POSTWRITE)
+
+#define GE_TXDSYNC(sc, txq, n, ops) \
+ bus_dmamap_sync((sc)->sc_dmat, (txq)->txq_desc_mem.gdm_map, \
+ (n) * sizeof((txq)->txq_descs[0]), sizeof((txq)->txq_descs[0]), \
+ (ops))
+#define GE_TXDPRESYNC(sc, txq, n) \
+ GE_TXDSYNC(sc, txq, n, BUS_DMASYNC_PREREAD|BUS_DMASYNC_PREWRITE)
+#define GE_TXDPOSTSYNC(sc, txq, n) \
+ GE_TXDSYNC(sc, txq, n, BUS_DMASYNC_POSTREAD|BUS_DMASYNC_POSTWRITE)
+
+#define STATIC
+
+#ifndef __rtems__
+STATIC int gfe_match (struct device *, struct cfdata *, void *);
+STATIC void gfe_attach (struct device *, struct device *, void *);
+#else
+STATIC int gfe_probe (device_t);
+STATIC int gfe_attach (device_t);
+STATIC void gfe_init (void*);
+#endif
+
+STATIC int gfe_dmamem_alloc(struct gfe_softc *, struct gfe_dmamem *, int,
+ size_t, int);
+STATIC void gfe_dmamem_free(struct gfe_softc *, struct gfe_dmamem *);
+
+#ifndef __rtems__
+STATIC int gfe_ifioctl (struct ifnet *, u_long, caddr_t);
+#else
+STATIC int gfe_ifioctl (struct ifnet *, ioctl_command_t, caddr_t);
+#endif
+STATIC void gfe_ifstart (struct ifnet *);
+STATIC void gfe_ifwatchdog (struct ifnet *);
+
+#ifndef __rtems__
+STATIC int gfe_mii_mediachange (struct ifnet *);
+STATIC void gfe_mii_mediastatus (struct ifnet *, struct ifmediareq *);
+STATIC int gfe_mii_read (struct device *, int, int);
+STATIC void gfe_mii_write (struct device *, int, int, int);
+STATIC void gfe_mii_statchg (struct device *);
+#endif
+
+STATIC void gfe_tick(void *arg);
+
+STATIC void gfe_tx_restart(void *);
+STATIC void gfe_assign_desc(volatile struct gt_eth_desc *, struct mbuf *,
+ uint32_t);
+STATIC int gfe_tx_enqueue(struct gfe_softc *, enum gfe_txprio);
+STATIC uint32_t gfe_tx_done(struct gfe_softc *, enum gfe_txprio, uint32_t);
+STATIC void gfe_tx_cleanup(struct gfe_softc *, enum gfe_txprio, int);
+STATIC int gfe_tx_txqalloc(struct gfe_softc *, enum gfe_txprio);
+STATIC int gfe_tx_start(struct gfe_softc *, enum gfe_txprio);
+STATIC void gfe_tx_stop(struct gfe_softc *, enum gfe_whack_op);
+
+STATIC void gfe_rx_cleanup(struct gfe_softc *, enum gfe_rxprio);
+STATIC void gfe_rx_get(struct gfe_softc *, enum gfe_rxprio);
+STATIC int gfe_rx_prime(struct gfe_softc *);
+STATIC uint32_t gfe_rx_process(struct gfe_softc *, uint32_t, uint32_t);
+STATIC int gfe_rx_rxqalloc(struct gfe_softc *, enum gfe_rxprio);
+STATIC int gfe_rx_rxqinit(struct gfe_softc *, enum gfe_rxprio);
+STATIC void gfe_rx_stop(struct gfe_softc *, enum gfe_whack_op);
+
+STATIC int gfe_intr(void *);
+
+STATIC int gfe_whack(struct gfe_softc *, enum gfe_whack_op);
+
+STATIC int gfe_hash_compute(struct gfe_softc *, const uint8_t [ETHER_ADDR_LEN]);
+STATIC int gfe_hash_entry_op(struct gfe_softc *, enum gfe_hash_op,
+ enum gfe_rxprio, const uint8_t [ETHER_ADDR_LEN]);
+#ifndef __rtems__
+STATIC int gfe_hash_multichg(struct ethercom *, const struct ether_multi *,
+ u_long);
+#endif
+STATIC int gfe_hash_fill(struct gfe_softc *);
+STATIC int gfe_hash_alloc(struct gfe_softc *);
+
+#ifndef __rtems__
+/* Linkup to the rest of the kernel */
+CFATTACH_DECL(gfe, sizeof(struct gfe_softc),
+ gfe_match, gfe_attach, NULL, NULL);
+#else
+net_drv_tbl_t METHODS = {
+ n_probe : gfe_probe,
+ n_attach : gfe_attach,
+ n_detach : 0,
+ n_intr : (void (*)(void*))gfe_intr,
+};
+
+int
+gfe_mii_read(int phy, void *arg, unsigned reg, uint32_t *pval);
+int
+gfe_mii_write(int phy, void *arg, unsigned reg, uint32_t val);
+
+struct rtems_mdio_info
+gfe_mdio_access = {
+ mdio_r: gfe_mii_read,
+ mdio_w: gfe_mii_write,
+ has_gmii: 0
+};
+
+#endif
+
+extern struct cfdriver gfe_cd;
+
+#ifndef __rtems__
+int
+gfe_match(struct device *parent, struct cfdata *cf, void *aux)
+{
+ struct gt_softc *gt = (struct gt_softc *) parent;
+ struct gt_attach_args *ga = aux;
+ uint8_t enaddr[6];
+
+ if (!GT_ETHEROK(gt, ga, &gfe_cd))
+ return 0;
+
+ if (gtget_macaddr(gt, ga->ga_unit, enaddr) < 0)
+ return 0;
+
+ if (enaddr[0] == 0 && enaddr[1] == 0 && enaddr[2] == 0 &&
+ enaddr[3] == 0 && enaddr[4] == 0 && enaddr[5] == 0)
+ return 0;
+
+ return 1;
+}
+#else
+int
+gfe_probe(device_t dev)
+{
+ switch ( BSP_getDiscoveryVersion(0) ) {
+ case GT_64260_A:
+ case GT_64260_B:
+ return 0;
+ default:
+ break;
+ }
+ return -1;
+}
+
+void
+gfe_init(void *arg)
+{
+struct gfe_softc *sc = arg;
+ if ( sc->sc_ec.ec_if.if_flags & IFF_RUNNING )
+ gfe_whack(sc, GE_WHACK_RESTART);
+ else
+ gfe_whack(sc, GE_WHACK_START);
+}
+#endif
+
+/*
+ * Attach this instance, and then all the sub-devices
+ */
+#ifndef __rtems__
+void
+gfe_attach(struct device *parent, struct device *self, void *aux)
+#else
+int
+gfe_attach(device_t dev)
+#endif
+{
+#ifndef __rtems__
+ struct gt_attach_args * const ga = aux;
+ struct gt_softc * const gt = (struct gt_softc *) parent;
+ struct gfe_softc * const sc = (struct gfe_softc *) self;
+#else
+ struct gfe_softc * const sc = device_get_softc(dev);
+#endif
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+ uint32_t data;
+ uint8_t enaddr[6];
+ int phyaddr;
+ uint32_t sdcr;
+ int error;
+#ifdef __rtems__
+ SPRINTFVARDECL;
+#endif
+
+#ifndef __rtems__
+ GT_ETHERFOUND(gt, ga);
+
+ sc->sc_gt_memt = ga->ga_memt;
+ sc->sc_gt_memh = ga->ga_memh;
+ sc->sc_dmat = ga->ga_dmat;
+ sc->sc_macno = ga->ga_unit;
+
+ if (bus_space_subregion(sc->sc_gt_memt, sc->sc_gt_memh,
+ ETH_BASE(sc->sc_macno), ETH_SIZE, &sc->sc_memh)) {
+ aprint_error(": failed to map registers\n");
+ }
+
+ callout_init(&sc->sc_co);
+#else
+ /* sc_macno, irq_no and sc_gt_memh must be filled in by 'setup' */
+
+ /* make ring sizes even numbers so that we have always multiple
+ * cache lines (paranoia)
+ */
+ if ( (sc->num_rxdesc = dev->d_ifconfig->rbuf_count) & 1 )
+ sc->num_rxdesc++;
+ if ( 0 == sc->num_rxdesc )
+ sc->num_rxdesc = 64;
+
+ if ( (sc->num_txdesc = dev->d_ifconfig->xbuf_count) & 1 )
+ sc->num_txdesc++;
+ if ( 0 == sc->num_txdesc )
+ sc->num_txdesc = 256;
+
+ /* Enable hardware cache snooping;
+ * Copyright Shuchen K. Feng <feng1@bnl.gov>, 2004
+ */
+ /* regs are eth0: 0xf200/0xf204, eth1 0xf220/0xf224, eth2: 0xf240/0xf244 */
+ {
+ uint32_t v;
+ v = GT_READ(sc, ETH_ACTL_0_LO + (sc->sc_macno<<5));
+ v |= RxBSnoopEn|TxBSnoopEn|RxDSnoopEn|TxDSnoopEn;
+ GT_WRITE(sc, ETH_ACTL_0_LO + (sc->sc_macno<<5), v);
+
+ v = GT_READ(sc, ETH_ACTL_0_HI + (sc->sc_macno<<5));
+ v |= HashSnoopEn;
+ GT_WRITE(sc, ETH_ACTL_0_HI + (sc->sc_macno<<5), v);
+ }
+
+#endif
+
+ data = bus_space_read_4(sc->sc_gt_memt, sc->sc_gt_memh, ETH_EPAR);
+#ifdef __rtems__
+ sc->sc_phyaddr =
+#endif
+ phyaddr = ETH_EPAR_PhyAD_GET(data, sc->sc_macno);
+
+#ifndef __rtems__
+ gtget_macaddr(gt, sc->sc_macno, enaddr);
+#else
+ memset( enaddr, 0, ETHER_ADDR_LEN );
+ if ( !memcmp(enaddr, sc->arpcom.ac_enaddr, ETHER_ADDR_LEN) ) {
+ aprint_error(": MAC address not set (pass to rtems_gfe_setup())\n");
+ return -1;
+ }
+ /* mac address needs to be provided by 'setup' */
+ memcpy(enaddr, sc->arpcom.ac_enaddr, ETHER_ADDR_LEN);
+#endif
+
+ sc->sc_pcr = GE_READ(sc, EPCR);
+ sc->sc_pcxr = GE_READ(sc, EPCXR);
+ sc->sc_intrmask = GE_READ(sc, EIMR) | ETH_IR_MIIPhySTC;
+
+ aprint_normal(": address %s", ether_sprintf(enaddr));
+
+#if defined(DEBUG)
+ aprint_normal(", pcr %#x, pcxr %#x", sc->sc_pcr, sc->sc_pcxr);
+#endif
+
+ sc->sc_pcxr &= ~ETH_EPCXR_PRIOrx_Override;
+#ifndef __rtems__
+ if (sc->sc_dev.dv_cfdata->cf_flags & 1) {
+ aprint_normal(", phy %d (rmii)", phyaddr);
+ sc->sc_pcxr |= ETH_EPCXR_RMIIEn;
+ } else
+#endif
+ {
+ aprint_normal(", phy %d (mii)", phyaddr);
+ sc->sc_pcxr &= ~ETH_EPCXR_RMIIEn;
+ }
+#ifndef __rtems__
+ if (sc->sc_dev.dv_cfdata->cf_flags & 2)
+ sc->sc_flags |= GE_NOFREE;
+#endif
+ sc->sc_pcxr &= ~(3 << 14);
+ sc->sc_pcxr |= (ETH_EPCXR_MFL_1536 << 14);
+
+ if (sc->sc_pcr & ETH_EPCR_EN) {
+ int tries = 1000;
+ /*
+ * Abort transmitter and receiver and wait for them to quiese
+ */
+ GE_WRITE(sc, ESDCMR, ETH_ESDCMR_AR|ETH_ESDCMR_AT);
+ do {
+ delay(100);
+ } while (tries-- > 0 && (GE_READ(sc, ESDCMR) & (ETH_ESDCMR_AR|ETH_ESDCMR_AT)));
+ }
+
+ sc->sc_pcr &= ~(ETH_EPCR_EN | ETH_EPCR_RBM | ETH_EPCR_PM | ETH_EPCR_PBF);
+
+#if defined(DEBUG)
+ aprint_normal(", pcr %#x, pcxr %#x", sc->sc_pcr, sc->sc_pcxr);
+#endif
+
+ /*
+ * Now turn off the GT. If it didn't quiese, too ***ing bad.
+ */
+ GE_WRITE(sc, EPCR, sc->sc_pcr);
+#ifndef __rtems__
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+#else
+ GE_WRITE(sc, EICR, 0);
+ GE_WRITE(sc, EIMR, 0);
+#endif
+ sdcr = GE_READ(sc, ESDCR);
+ ETH_ESDCR_BSZ_SET(sdcr, ETH_ESDCR_BSZ_4);
+ sdcr |= ETH_ESDCR_RIFB;
+ GE_WRITE(sc, ESDCR, sdcr);
+ sc->sc_max_frame_length = 1536;
+
+ aprint_normal("\n");
+#ifndef __rtems__
+ sc->sc_mii.mii_ifp = ifp;
+ sc->sc_mii.mii_readreg = gfe_mii_read;
+ sc->sc_mii.mii_writereg = gfe_mii_write;
+ sc->sc_mii.mii_statchg = gfe_mii_statchg;
+
+ ifmedia_init(&sc->sc_mii.mii_media, 0, gfe_mii_mediachange,
+ gfe_mii_mediastatus);
+
+ mii_attach(&sc->sc_dev, &sc->sc_mii, 0xffffffff, phyaddr,
+ MII_OFFSET_ANY, MIIF_NOISOLATE);
+ if (LIST_FIRST(&sc->sc_mii.mii_phys) == NULL) {
+ ifmedia_add(&sc->sc_mii.mii_media, IFM_ETHER|IFM_NONE, 0, NULL);
+ ifmedia_set(&sc->sc_mii.mii_media, IFM_ETHER|IFM_NONE);
+ } else {
+ ifmedia_set(&sc->sc_mii.mii_media, IFM_ETHER|IFM_AUTO);
+ }
+
+ strcpy(ifp->if_xname, sc->sc_dev.dv_xname);
+#else
+ if_initname(ifp, device_get_name(dev), device_get_unit(dev));
+ ifp->if_mtu = ETHERMTU;
+ ifp->if_output = ether_output;
+ ifp->if_init = gfe_init;
+ ifp->if_snd.ifq_maxlen = GE_TXDESC_MAX - 1;
+ ifp->if_baudrate = 10000000;
+#endif
+ ifp->if_softc = sc;
+ /* ifp->if_mowner = &sc->sc_mowner; */
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+#if 0
+ ifp->if_flags |= IFF_DEBUG;
+#endif
+ ifp->if_ioctl = gfe_ifioctl;
+ ifp->if_start = gfe_ifstart;
+ ifp->if_watchdog = gfe_ifwatchdog;
+
+ if (sc->sc_flags & GE_NOFREE) {
+ error = gfe_rx_rxqalloc(sc, GE_RXPRIO_HI);
+ if (!error)
+ error = gfe_rx_rxqalloc(sc, GE_RXPRIO_MEDHI);
+ if (!error)
+ error = gfe_rx_rxqalloc(sc, GE_RXPRIO_MEDLO);
+ if (!error)
+ error = gfe_rx_rxqalloc(sc, GE_RXPRIO_LO);
+ if (!error)
+ error = gfe_tx_txqalloc(sc, GE_TXPRIO_HI);
+ if (!error)
+ error = gfe_hash_alloc(sc);
+ if (error)
+ aprint_error(
+ "%s: failed to allocate resources: %d\n",
+ ifp->if_xname, error);
+ }
+
+ if_attach(ifp);
+#ifndef __rtems__
+ ether_ifattach(ifp, enaddr);
+#else
+ ether_ifattach(ifp);
+#endif
+#if NBPFILTER > 0
+ bpfattach(ifp, DLT_EN10MB, sizeof(struct ether_header));
+#endif
+#if NRND > 0
+ rnd_attach_source(&sc->sc_rnd_source, self->dv_xname, RND_TYPE_NET, 0);
+#endif
+#ifndef __rtems__
+ intr_establish(IRQ_ETH0 + sc->sc_macno, IST_LEVEL, IPL_NET,
+ gfe_intr, sc);
+#else
+ return 0;
+#endif
+}
+
+int
+gfe_dmamem_alloc(struct gfe_softc *sc, struct gfe_dmamem *gdm, int maxsegs,
+ size_t size, int flags)
+{
+ int error = 0;
+ GE_FUNC_ENTER(sc, "gfe_dmamem_alloc");
+
+ KASSERT(gdm->gdm_kva == NULL);
+ gdm->gdm_size = size;
+ gdm->gdm_maxsegs = maxsegs;
+
+#ifndef __rtems__
+ error = bus_dmamem_alloc(sc->sc_dmat, gdm->gdm_size, PAGE_SIZE,
+ gdm->gdm_size, gdm->gdm_segs, gdm->gdm_maxsegs, &gdm->gdm_nsegs,
+ BUS_DMA_NOWAIT);
+ if (error)
+ goto fail;
+
+ error = bus_dmamem_map(sc->sc_dmat, gdm->gdm_segs, gdm->gdm_nsegs,
+ gdm->gdm_size, &gdm->gdm_kva, flags | BUS_DMA_NOWAIT);
+ if (error)
+ goto fail;
+
+ error = bus_dmamap_create(sc->sc_dmat, gdm->gdm_size, gdm->gdm_nsegs,
+ gdm->gdm_size, 0, BUS_DMA_ALLOCNOW|BUS_DMA_NOWAIT, &gdm->gdm_map);
+ if (error)
+ goto fail;
+
+ error = bus_dmamap_load(sc->sc_dmat, gdm->gdm_map, gdm->gdm_kva,
+ gdm->gdm_size, NULL, BUS_DMA_NOWAIT);
+ if (error)
+ goto fail;
+#else
+ gdm->gdm_segs[0].ds_len = size;
+
+ /* FIXME: probably we can relax the alignment */
+ if ( ! ( gdm->gdm_unaligned_buf = malloc( size + PAGE_SIZE - 1, M_DEVBUF, M_NOWAIT ) ) )
+ goto fail;
+
+ gdm->gdm_map = gdm;
+ gdm->gdm_nsegs = 1;
+ gdm->gdm_kva = (caddr_t)(gdm->gdm_segs[0].ds_addr = _DO_ALIGN(gdm->gdm_unaligned_buf, PAGE_SIZE));
+#endif
+
+ /* invalidate from cache */
+ bus_dmamap_sync(sc->sc_dmat, gdm->gdm_map, 0, gdm->gdm_size,
+ BUS_DMASYNC_PREREAD);
+fail:
+ if (error) {
+ gfe_dmamem_free(sc, gdm);
+ GE_DPRINTF(sc, (":err=%d", error));
+ }
+ GE_DPRINTF(sc, (":kva=%p/%#x,map=%p,nsegs=%d,pa=%" PRIx32 "/%" PRIx32,
+ gdm->gdm_kva, gdm->gdm_size, gdm->gdm_map, gdm->gdm_map->dm_nsegs,
+ gdm->gdm_map->dm_segs->ds_addr, gdm->gdm_map->dm_segs->ds_len));
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+void
+gfe_dmamem_free(struct gfe_softc *sc, struct gfe_dmamem *gdm)
+{
+ GE_FUNC_ENTER(sc, "gfe_dmamem_free");
+#ifndef __rtems__
+ if (gdm->gdm_map)
+ bus_dmamap_destroy(sc->sc_dmat, gdm->gdm_map);
+ if (gdm->gdm_kva)
+ bus_dmamem_unmap(sc->sc_dmat, gdm->gdm_kva, gdm->gdm_size);
+ if (gdm->gdm_nsegs > 0)
+ bus_dmamem_free(sc->sc_dmat, gdm->gdm_segs, gdm->gdm_nsegs);
+#else
+ if (gdm->gdm_nsegs > 0)
+ free(gdm->gdm_unaligned_buf, M_DEVBUF);
+#endif
+ gdm->gdm_map = NULL;
+ gdm->gdm_kva = NULL;
+ gdm->gdm_nsegs = 0;
+ GE_FUNC_EXIT(sc, "");
+}
+
+#ifndef __rtems__
+int
+gfe_ifioctl(struct ifnet *ifp, u_long cmd, caddr_t data)
+#else
+int
+gfe_ifioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data)
+#endif
+{
+ struct gfe_softc * const sc = ifp->if_softc;
+ struct ifreq *ifr = (struct ifreq *) data;
+#ifndef __rtems__
+ struct ifaddr *ifa = (struct ifaddr *) data;
+#endif
+ int s, error = 0;
+
+ GE_FUNC_ENTER(sc, "gfe_ifioctl");
+ s = splnet();
+
+ switch (cmd) {
+#ifndef __rtems__
+ case SIOCSIFADDR:
+ ifp->if_flags |= IFF_UP;
+ switch (ifa->ifa_addr->sa_family) {
+#ifdef INET
+ case AF_INET:
+ error = gfe_whack(sc, GE_WHACK_START);
+ if (error == 0)
+ arp_ifinit(ifp, ifa);
+ break;
+#endif
+ default:
+ error = gfe_whack(sc, GE_WHACK_START);
+ break;
+ }
+ break;
+#endif
+
+ case SIOCSIFFLAGS:
+ if ((sc->sc_ec.ec_if.if_flags & IFF_PROMISC) == 0)
+ sc->sc_pcr &= ~ETH_EPCR_PM;
+ else
+ sc->sc_pcr |= ETH_EPCR_PM;
+ switch (ifp->if_flags & (IFF_UP|IFF_RUNNING)) {
+ case IFF_UP|IFF_RUNNING:/* active->active, update */
+ error = gfe_whack(sc, GE_WHACK_CHANGE);
+ break;
+ case IFF_RUNNING: /* not up, so we stop */
+ error = gfe_whack(sc, GE_WHACK_STOP);
+ break;
+ case IFF_UP: /* not running, so we start */
+ error = gfe_whack(sc, GE_WHACK_START);
+ break;
+ case 0: /* idle->idle: do nothing */
+ break;
+ }
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ error = (cmd == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &sc->sc_ec)
+ : ether_delmulti(ifr, &sc->sc_ec);
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING)
+#if !defined(__rtems__)
+ error = gfe_whack(sc, GE_WHACK_CHANGE);
+#else
+ /* doing GE_WHACK_CHANGE seems wrong - that
+ * doesn't do anything to the hash table.
+ * Therefore we perform a stop/start sequence.
+ */
+ {
+ error = gfe_whack(sc, GE_WHACK_STOP);
+ if ( error )
+ break;
+ error = gfe_whack(sc, GE_WHACK_START);
+ }
+#endif
+ else
+ error = 0;
+ }
+ break;
+
+ case SIOCSIFMTU:
+ if (ifr->ifr_mtu > ETHERMTU || ifr->ifr_mtu < ETHERMIN) {
+ error = EINVAL;
+ break;
+ }
+ ifp->if_mtu = ifr->ifr_mtu;
+ break;
+
+ case SIOCSIFMEDIA:
+ case SIOCGIFMEDIA:
+#ifndef __rtems__
+ error = ifmedia_ioctl(ifp, ifr, &sc->sc_mii.mii_media, cmd);
+#else
+ error = rtems_mii_ioctl(&gfe_mdio_access, sc, cmd, &ifr->ifr_media);
+#endif
+ break;
+
+ default:
+#ifndef __rtems__
+ error = EINVAL;
+#else
+ error = ether_ioctl(ifp, cmd, data);
+#endif
+ break;
+ }
+ splx(s);
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+void
+gfe_ifstart(struct ifnet *ifp)
+{
+ struct gfe_softc * const sc = ifp->if_softc;
+ struct mbuf *m;
+
+ GE_FUNC_ENTER(sc, "gfe_ifstart");
+
+ if ((ifp->if_flags & IFF_RUNNING) == 0) {
+ GE_FUNC_EXIT(sc, "$");
+ return;
+ }
+
+ for (;;) {
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (m == NULL) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ GE_FUNC_EXIT(sc, "");
+ return;
+ }
+
+ /*
+ * No space in the pending queue? try later.
+ */
+ if (IF_QFULL(&sc->sc_txq[GE_TXPRIO_HI].txq_pendq))
+ break;
+
+ /*
+ * Try to enqueue a mbuf to the device. If that fails, we
+ * can always try to map the next mbuf.
+ */
+ IF_ENQUEUE(&sc->sc_txq[GE_TXPRIO_HI].txq_pendq, m);
+ GE_DPRINTF(sc, (">"));
+#ifndef GE_NOTX
+ (void) gfe_tx_enqueue(sc, GE_TXPRIO_HI);
+#endif
+ }
+
+ /*
+ * Attempt to queue the mbuf for send failed.
+ */
+ IF_PREPEND(&ifp->if_snd, m);
+ ifp->if_flags |= IFF_OACTIVE;
+ GE_FUNC_EXIT(sc, "%%");
+}
+
+void
+gfe_ifwatchdog(struct ifnet *ifp)
+{
+ struct gfe_softc * const sc = ifp->if_softc;
+ struct gfe_txqueue * const txq = &sc->sc_txq[GE_TXPRIO_HI];
+
+ GE_FUNC_ENTER(sc, "gfe_ifwatchdog");
+ printf("%s: device timeout", sc->sc_dev.dv_xname);
+ if (ifp->if_flags & IFF_RUNNING) {
+ uint32_t curtxdnum = (bus_space_read_4(sc->sc_gt_memt, sc->sc_gt_memh, txq->txq_ectdp) - txq->txq_desc_busaddr) / sizeof(txq->txq_descs[0]);
+ GE_TXDPOSTSYNC(sc, txq, txq->txq_fi);
+ GE_TXDPOSTSYNC(sc, txq, curtxdnum);
+ printf(" (fi=%d(%#" PRIx32 "),lo=%d,cur=%" PRIx32 "(%#" PRIx32 "),icm=%#" PRIx32 ") ",
+ txq->txq_fi, txq->txq_descs[txq->txq_fi].ed_cmdsts,
+ txq->txq_lo, curtxdnum, txq->txq_descs[curtxdnum].ed_cmdsts,
+ GE_READ(sc, EICR));
+ GE_TXDPRESYNC(sc, txq, txq->txq_fi);
+ GE_TXDPRESYNC(sc, txq, curtxdnum);
+ }
+ printf("\n");
+ ifp->if_oerrors++;
+ (void) gfe_whack(sc, GE_WHACK_RESTART);
+ GE_FUNC_EXIT(sc, "");
+}
+
+#ifdef __rtems__
+static struct mbuf *
+gfe_newbuf(struct mbuf *m)
+{
+ if ( !m ) {
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if ( !m )
+ return 0;
+ MCLGET(m, M_DONTWAIT);
+ if ( !(M_EXT & m->m_flags) ) {
+ m_freem(m);
+ return 0;
+ }
+ } else {
+ m->m_data = m->m_ext.ext_buf;
+ }
+ m->m_len = m->m_pkthdr.len = MCLBYTES;
+#if 0
+ m_adj(m, 2); /* so payload is 16-byte aligned */
+#endif
+ return m;
+}
+#endif
+
+int
+gfe_rx_rxqalloc(struct gfe_softc *sc, enum gfe_rxprio rxprio)
+{
+ struct gfe_rxqueue * const rxq = &sc->sc_rxq[rxprio];
+ int error;
+
+ GE_FUNC_ENTER(sc, "gfe_rx_rxqalloc");
+ GE_DPRINTF(sc, ("(%d)", rxprio));
+
+ error = gfe_dmamem_alloc(sc, &rxq->rxq_desc_mem, 1,
+ GE_RXDESC_MEMSIZE, BUS_DMA_NOCACHE);
+ if (error) {
+ GE_FUNC_EXIT(sc, "!!");
+ return error;
+ }
+
+#ifndef __rtems__
+ error = gfe_dmamem_alloc(sc, &rxq->rxq_buf_mem, GE_RXBUF_NSEGS,
+ GE_RXBUF_MEMSIZE, 0);
+#else
+ if ( ! (rxq->rxq_bufs = malloc( sizeof(*rxq->rxq_bufs) * GE_RXDESC_MAX, M_DEVBUF, M_NOWAIT ) ) ) {
+ error = -1;
+ } else {
+ int i;
+ for ( i = 0; i<GE_RXDESC_MAX; i++ ) {
+ if ( !(rxq->rxq_bufs[i] = gfe_newbuf(0)) ) {
+ fprintf(stderr,"gfe: Not enough mbuf clusters to initialize RX ring!\n");
+ while (--i >=0 ) {
+ m_freem(rxq->rxq_bufs[i]);
+ }
+ free(rxq->rxq_bufs, M_DEVBUF);
+ rxq->rxq_bufs = 0;
+ error = -1;
+ break;
+ }
+ }
+ }
+#endif
+ if (error) {
+ GE_FUNC_EXIT(sc, "!!!");
+ return error;
+ }
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+int
+gfe_rx_rxqinit(struct gfe_softc *sc, enum gfe_rxprio rxprio)
+{
+ struct gfe_rxqueue * const rxq = &sc->sc_rxq[rxprio];
+ volatile struct gt_eth_desc *rxd;
+#ifndef __rtems__
+ const bus_dma_segment_t *ds;
+#endif
+ int idx;
+ bus_addr_t nxtaddr;
+#ifndef __rtems__
+ bus_size_t boff;
+#endif
+
+ GE_FUNC_ENTER(sc, "gfe_rx_rxqinit");
+ GE_DPRINTF(sc, ("(%d)", rxprio));
+
+ if ((sc->sc_flags & GE_NOFREE) == 0) {
+ int error = gfe_rx_rxqalloc(sc, rxprio);
+ if (error) {
+ GE_FUNC_EXIT(sc, "!");
+ return error;
+ }
+ } else {
+ KASSERT(rxq->rxq_desc_mem.gdm_kva != NULL);
+#ifndef __rtems__
+ KASSERT(rxq->rxq_buf_mem.gdm_kva != NULL);
+#else
+ KASSERT(rxq->rxq_bufs != NULL);
+#endif
+ }
+
+ memset(rxq->rxq_desc_mem.gdm_kva, 0, GE_RXDESC_MEMSIZE);
+
+ rxq->rxq_descs =
+ (volatile struct gt_eth_desc *) rxq->rxq_desc_mem.gdm_kva;
+ rxq->rxq_desc_busaddr = rxq->rxq_desc_mem.gdm_map->dm_segs[0].ds_addr;
+#ifndef __rtems__
+ rxq->rxq_bufs = (struct gfe_rxbuf *) rxq->rxq_buf_mem.gdm_kva;
+#endif
+ rxq->rxq_fi = 0;
+ rxq->rxq_active = GE_RXDESC_MAX;
+ for (idx = 0, rxd = rxq->rxq_descs,
+#ifndef __rtems__
+ boff = 0, ds = rxq->rxq_buf_mem.gdm_map->dm_segs,
+#endif
+ nxtaddr = rxq->rxq_desc_busaddr + sizeof(*rxd);
+ idx < GE_RXDESC_MAX;
+ idx++, rxd++, nxtaddr += sizeof(*rxd)) {
+#ifndef __rtems__
+ rxd->ed_lencnt = htogt32(GE_RXBUF_SIZE << 16);
+#else
+ rxd->ed_lencnt = htogt32(MCLBYTES << 16);
+#endif
+ rxd->ed_cmdsts = htogt32(RX_CMD_F|RX_CMD_L|RX_CMD_O|RX_CMD_EI);
+#ifndef __rtems__
+ rxd->ed_bufptr = htogt32(ds->ds_addr + boff);
+#else
+ rxd->ed_bufptr = htogt32(mtod(rxq->rxq_bufs[idx], uint32_t));
+#endif
+ /*
+ * update the nxtptr to point to the next txd.
+ */
+ if (idx == GE_RXDESC_MAX - 1)
+ nxtaddr = rxq->rxq_desc_busaddr;
+ rxd->ed_nxtptr = htogt32(nxtaddr);
+#ifndef __rtems__
+ boff += GE_RXBUF_SIZE;
+ if (boff == ds->ds_len) {
+ ds++;
+ boff = 0;
+ }
+#endif
+ }
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_desc_mem.gdm_map, 0,
+ rxq->rxq_desc_mem.gdm_map->dm_mapsize,
+ BUS_DMASYNC_PREREAD|BUS_DMASYNC_PREWRITE);
+#ifndef __rtems__
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_buf_mem.gdm_map, 0,
+ rxq->rxq_buf_mem.gdm_map->dm_mapsize,
+ BUS_DMASYNC_PREREAD);
+#else
+ /* FIXME: we leave this call in here so compilation fails
+ * if bus_dmamap_sync() is ever fleshed-out to implement
+ * software cache coherency...
+ */
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_buf_mem.gdm_map, 0,
+ rxq->rxq_buf_mem.gdm_map->dm_mapsize,
+ BUS_DMASYNC_PREREAD);
+#endif
+
+ rxq->rxq_intrbits = ETH_IR_RxBuffer|ETH_IR_RxError;
+ switch (rxprio) {
+ case GE_RXPRIO_HI:
+ rxq->rxq_intrbits |= ETH_IR_RxBuffer_3|ETH_IR_RxError_3;
+ rxq->rxq_efrdp = ETH_EFRDP3(sc->sc_macno);
+ rxq->rxq_ecrdp = ETH_ECRDP3(sc->sc_macno);
+ break;
+ case GE_RXPRIO_MEDHI:
+ rxq->rxq_intrbits |= ETH_IR_RxBuffer_2|ETH_IR_RxError_2;
+ rxq->rxq_efrdp = ETH_EFRDP2(sc->sc_macno);
+ rxq->rxq_ecrdp = ETH_ECRDP2(sc->sc_macno);
+ break;
+ case GE_RXPRIO_MEDLO:
+ rxq->rxq_intrbits |= ETH_IR_RxBuffer_1|ETH_IR_RxError_1;
+ rxq->rxq_efrdp = ETH_EFRDP1(sc->sc_macno);
+ rxq->rxq_ecrdp = ETH_ECRDP1(sc->sc_macno);
+ break;
+ case GE_RXPRIO_LO:
+ rxq->rxq_intrbits |= ETH_IR_RxBuffer_0|ETH_IR_RxError_0;
+ rxq->rxq_efrdp = ETH_EFRDP0(sc->sc_macno);
+ rxq->rxq_ecrdp = ETH_ECRDP0(sc->sc_macno);
+ break;
+ }
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+}
+
+void
+gfe_rx_get(struct gfe_softc *sc, enum gfe_rxprio rxprio)
+{
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+ struct gfe_rxqueue * const rxq = &sc->sc_rxq[rxprio];
+#ifndef __rtems__
+ struct mbuf *m = rxq->rxq_curpkt;
+#else
+ struct mbuf *m;
+#endif
+
+ GE_FUNC_ENTER(sc, "gfe_rx_get");
+ GE_DPRINTF(sc, ("(%d)", rxprio));
+
+ while (rxq->rxq_active > 0) {
+ volatile struct gt_eth_desc *rxd = &rxq->rxq_descs[rxq->rxq_fi];
+#ifndef __rtems__
+ struct gfe_rxbuf *rxb = &rxq->rxq_bufs[rxq->rxq_fi];
+#else
+ struct mbuf **rxb = &rxq->rxq_bufs[rxq->rxq_fi];
+#endif
+ const struct ether_header *eh;
+ unsigned int cmdsts;
+ size_t buflen;
+
+ GE_RXDPOSTSYNC(sc, rxq, rxq->rxq_fi);
+ cmdsts = gt32toh(rxd->ed_cmdsts);
+ GE_DPRINTF(sc, (":%d=%#x", rxq->rxq_fi, cmdsts));
+ rxq->rxq_cmdsts = cmdsts;
+ /*
+ * Sometimes the GE "forgets" to reset the ownership bit.
+ * But if the length has been rewritten, the packet is ours
+ * so pretend the O bit is set.
+ */
+ buflen = gt32toh(rxd->ed_lencnt) & 0xffff;
+ if ((cmdsts & RX_CMD_O) && buflen == 0) {
+ GE_RXDPRESYNC(sc, rxq, rxq->rxq_fi);
+ break;
+ }
+
+ /*
+ * If this is not a single buffer packet with no errors
+ * or for some reason it's bigger than our frame size,
+ * ignore it and go to the next packet.
+ */
+ if ((cmdsts & (RX_CMD_F|RX_CMD_L|RX_STS_ES)) !=
+ (RX_CMD_F|RX_CMD_L) ||
+ buflen > sc->sc_max_frame_length) {
+ GE_DPRINTF(sc, ("!"));
+ --rxq->rxq_active;
+ ifp->if_ipackets++;
+ ifp->if_ierrors++;
+
+ *rxb = gfe_newbuf(*rxb);
+ goto give_it_back;
+ }
+
+ /* CRC is included with the packet; trim it off. */
+ buflen -= ETHER_CRC_LEN;
+
+#ifndef __rtems__
+ if (m == NULL) {
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if (m == NULL) {
+ GE_DPRINTF(sc, ("?"));
+ break;
+ }
+ }
+ if ((m->m_flags & M_EXT) == 0 && buflen > MHLEN - 2) {
+ MCLGET(m, M_DONTWAIT);
+ if ((m->m_flags & M_EXT) == 0) {
+ GE_DPRINTF(sc, ("?"));
+ break;
+ }
+ }
+ m->m_data += 2;
+ m->m_len = 0;
+ m->m_pkthdr.len = 0;
+ m->m_pkthdr.rcvif = ifp;
+#else
+ if ( ! (m=gfe_newbuf(0)) ) {
+ /* recycle old buffer */
+ *rxb = gfe_newbuf(*rxb);
+ goto give_it_back;
+ }
+ /* swap mbufs */
+ {
+ struct mbuf *tmp = *rxb;
+ *rxb = m;
+ m = tmp;
+ rxd->ed_bufptr = htogt32(mtod(*rxb, uint32_t));
+ }
+#endif
+ rxq->rxq_cmdsts = cmdsts;
+ --rxq->rxq_active;
+
+#ifdef __rtems__
+ /* FIXME: we leave this call in here so compilation fails
+ * if bus_dmamap_sync() is ever fleshed-out to implement
+ * software cache coherency...
+ */
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_buf_mem.gdm_map,
+ rxq->rxq_fi * sizeof(*rxb), buflen, BUS_DMASYNC_POSTREAD);
+#else
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_buf_mem.gdm_map,
+ rxq->rxq_fi * sizeof(*rxb), buflen, BUS_DMASYNC_POSTREAD);
+
+ KASSERT(m->m_len == 0 && m->m_pkthdr.len == 0);
+ memcpy(m->m_data + m->m_len, rxb->rb_data, buflen);
+#endif
+
+ m->m_len = buflen;
+ m->m_pkthdr.len = buflen;
+
+ ifp->if_ipackets++;
+#if NBPFILTER > 0
+ if (ifp->if_bpf != NULL)
+ bpf_mtap(ifp->if_bpf, m);
+#endif
+
+ eh = (const struct ether_header *) m->m_data;
+ if ((ifp->if_flags & IFF_PROMISC) ||
+ (rxq->rxq_cmdsts & RX_STS_M) == 0 ||
+ (rxq->rxq_cmdsts & RX_STS_HE) ||
+ (eh->ether_dhost[0] & 1) != 0 ||
+ memcmp(eh->ether_dhost,
+#ifndef __rtems__
+ LLADDR(ifp->if_sadl),
+#else
+ sc->sc_ec.ac_enaddr,
+#endif
+ ETHER_ADDR_LEN) == 0) {
+#ifndef __rtems__
+ (*ifp->if_input)(ifp, m);
+ m = NULL;
+#else
+ DO_ETHER_INPUT_SKIPPING_ETHER_HEADER(ifp,m);
+#endif
+ GE_DPRINTF(sc, (">"));
+ } else {
+#ifndef __rtems__
+ m->m_len = 0;
+ m->m_pkthdr.len = 0;
+#else
+ m_freem(m);
+#endif
+ GE_DPRINTF(sc, ("+"));
+ }
+ rxq->rxq_cmdsts = 0;
+
+ give_it_back:
+ rxd->ed_lencnt &= ~0xffff; /* zero out length */
+ rxd->ed_cmdsts = htogt32(RX_CMD_F|RX_CMD_L|RX_CMD_O|RX_CMD_EI);
+#if 0
+ GE_DPRINTF(sc, ("([%d]->%08lx.%08lx.%08lx.%08lx)",
+ rxq->rxq_fi,
+ ((unsigned long *)rxd)[0], ((unsigned long *)rxd)[1],
+ ((unsigned long *)rxd)[2], ((unsigned long *)rxd)[3]));
+#endif
+ GE_RXDPRESYNC(sc, rxq, rxq->rxq_fi);
+ if (++rxq->rxq_fi == GE_RXDESC_MAX)
+ rxq->rxq_fi = 0;
+ rxq->rxq_active++;
+ }
+#ifndef __rtems__
+ rxq->rxq_curpkt = m;
+#endif
+ GE_FUNC_EXIT(sc, "");
+}
+
+uint32_t
+gfe_rx_process(struct gfe_softc *sc, uint32_t cause, uint32_t intrmask)
+{
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+ struct gfe_rxqueue *rxq;
+ uint32_t rxbits;
+#define RXPRIO_DECODER 0xffffaa50
+ GE_FUNC_ENTER(sc, "gfe_rx_process");
+
+ rxbits = ETH_IR_RxBuffer_GET(cause);
+ while (rxbits) {
+ enum gfe_rxprio rxprio = (RXPRIO_DECODER >> (rxbits * 2)) & 3;
+ GE_DPRINTF(sc, ("%1" PRIx32, rxbits));
+ rxbits &= ~(1 << rxprio);
+ gfe_rx_get(sc, rxprio);
+ }
+
+ rxbits = ETH_IR_RxError_GET(cause);
+ while (rxbits) {
+ enum gfe_rxprio rxprio = (RXPRIO_DECODER >> (rxbits * 2)) & 3;
+ uint32_t masks[(GE_RXDESC_MAX + 31) / 32];
+ int idx;
+ rxbits &= ~(1 << rxprio);
+ rxq = &sc->sc_rxq[rxprio];
+ sc->sc_idlemask |= (rxq->rxq_intrbits & ETH_IR_RxBits);
+ intrmask &= ~(rxq->rxq_intrbits & ETH_IR_RxBits);
+ if ((sc->sc_tickflags & GE_TICK_RX_RESTART) == 0) {
+ sc->sc_tickflags |= GE_TICK_RX_RESTART;
+ callout_reset(&sc->sc_co, 1, gfe_tick, sc);
+ }
+ ifp->if_ierrors++;
+ GE_DPRINTF(sc, ("%s: rx queue %d filled at %u\n",
+ sc->sc_dev.dv_xname, rxprio, rxq->rxq_fi));
+ memset(masks, 0, sizeof(masks));
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_desc_mem.gdm_map,
+ 0, rxq->rxq_desc_mem.gdm_size,
+ BUS_DMASYNC_POSTREAD|BUS_DMASYNC_POSTWRITE);
+ for (idx = 0; idx < GE_RXDESC_MAX; idx++) {
+ volatile struct gt_eth_desc *rxd = &rxq->rxq_descs[idx];
+
+ if (RX_CMD_O & gt32toh(rxd->ed_cmdsts))
+ masks[idx/32] |= 1 << (idx & 31);
+ }
+ bus_dmamap_sync(sc->sc_dmat, rxq->rxq_desc_mem.gdm_map,
+ 0, rxq->rxq_desc_mem.gdm_size,
+ BUS_DMASYNC_PREREAD|BUS_DMASYNC_PREWRITE);
+#if defined(DEBUG)
+ printf("%s: rx queue %d filled at %u=%#x(%#x/%#x)\n",
+ sc->sc_dev.dv_xname, rxprio, rxq->rxq_fi,
+ rxq->rxq_cmdsts, masks[0], masks[1]);
+#endif
+ }
+ if ((intrmask & ETH_IR_RxBits) == 0)
+ intrmask &= ~(ETH_IR_RxBuffer|ETH_IR_RxError);
+
+ GE_FUNC_EXIT(sc, "");
+ return intrmask;
+}
+
+int
+gfe_rx_prime(struct gfe_softc *sc)
+{
+ struct gfe_rxqueue *rxq;
+ int error;
+
+ GE_FUNC_ENTER(sc, "gfe_rx_prime");
+
+ error = gfe_rx_rxqinit(sc, GE_RXPRIO_HI);
+ if (error)
+ goto bail;
+ rxq = &sc->sc_rxq[GE_RXPRIO_HI];
+ if ((sc->sc_flags & GE_RXACTIVE) == 0) {
+ GE_WRITE(sc, EFRDP3, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP3, rxq->rxq_desc_busaddr);
+ }
+ sc->sc_intrmask |= rxq->rxq_intrbits;
+
+ error = gfe_rx_rxqinit(sc, GE_RXPRIO_MEDHI);
+ if (error)
+ goto bail;
+ if ((sc->sc_flags & GE_RXACTIVE) == 0) {
+ rxq = &sc->sc_rxq[GE_RXPRIO_MEDHI];
+ GE_WRITE(sc, EFRDP2, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP2, rxq->rxq_desc_busaddr);
+ sc->sc_intrmask |= rxq->rxq_intrbits;
+ }
+
+ error = gfe_rx_rxqinit(sc, GE_RXPRIO_MEDLO);
+ if (error)
+ goto bail;
+ if ((sc->sc_flags & GE_RXACTIVE) == 0) {
+ rxq = &sc->sc_rxq[GE_RXPRIO_MEDLO];
+ GE_WRITE(sc, EFRDP1, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP1, rxq->rxq_desc_busaddr);
+ sc->sc_intrmask |= rxq->rxq_intrbits;
+ }
+
+ error = gfe_rx_rxqinit(sc, GE_RXPRIO_LO);
+ if (error)
+ goto bail;
+ if ((sc->sc_flags & GE_RXACTIVE) == 0) {
+ rxq = &sc->sc_rxq[GE_RXPRIO_LO];
+ GE_WRITE(sc, EFRDP0, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP0, rxq->rxq_desc_busaddr);
+ sc->sc_intrmask |= rxq->rxq_intrbits;
+ }
+
+ bail:
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+void
+gfe_rx_cleanup(struct gfe_softc *sc, enum gfe_rxprio rxprio)
+{
+ struct gfe_rxqueue *rxq = &sc->sc_rxq[rxprio];
+ GE_FUNC_ENTER(sc, "gfe_rx_cleanup");
+ if (rxq == NULL) {
+ GE_FUNC_EXIT(sc, "");
+ return;
+ }
+
+#ifndef __rtems__
+ if (rxq->rxq_curpkt)
+ m_freem(rxq->rxq_curpkt);
+#endif
+ if ((sc->sc_flags & GE_NOFREE) == 0) {
+ gfe_dmamem_free(sc, &rxq->rxq_desc_mem);
+#ifndef __rtems__
+ gfe_dmamem_free(sc, &rxq->rxq_buf_mem);
+#else
+ if ( rxq->rxq_bufs ) {
+ int i;
+ for ( i=0; i<GE_RXDESC_MAX; i++ ) {
+ if ( rxq->rxq_bufs[i] ) {
+ m_freem(rxq->rxq_bufs[i]);
+ }
+ }
+ free(rxq->rxq_bufs, M_DEVBUF);
+ }
+#endif
+ }
+ GE_FUNC_EXIT(sc, "");
+}
+
+void
+gfe_rx_stop(struct gfe_softc *sc, enum gfe_whack_op op)
+{
+ GE_FUNC_ENTER(sc, "gfe_rx_stop");
+ sc->sc_flags &= ~GE_RXACTIVE;
+ sc->sc_idlemask &= ~(ETH_IR_RxBits|ETH_IR_RxBuffer|ETH_IR_RxError);
+ sc->sc_intrmask &= ~(ETH_IR_RxBits|ETH_IR_RxBuffer|ETH_IR_RxError);
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ GE_WRITE(sc, ESDCMR, ETH_ESDCMR_AR);
+ do {
+ delay(10);
+ } while (GE_READ(sc, ESDCMR) & ETH_ESDCMR_AR);
+ gfe_rx_cleanup(sc, GE_RXPRIO_HI);
+ gfe_rx_cleanup(sc, GE_RXPRIO_MEDHI);
+ gfe_rx_cleanup(sc, GE_RXPRIO_MEDLO);
+ gfe_rx_cleanup(sc, GE_RXPRIO_LO);
+ GE_FUNC_EXIT(sc, "");
+}
+
+void
+gfe_tick(void *arg)
+{
+ struct gfe_softc * const sc = arg;
+ uint32_t intrmask;
+ unsigned int tickflags;
+ int s;
+
+ GE_FUNC_ENTER(sc, "gfe_tick");
+
+ s = splnet();
+
+ tickflags = sc->sc_tickflags;
+ sc->sc_tickflags = 0;
+ intrmask = sc->sc_intrmask;
+ if (tickflags & GE_TICK_TX_IFSTART)
+ gfe_ifstart(&sc->sc_ec.ec_if);
+ if (tickflags & GE_TICK_RX_RESTART) {
+ intrmask |= sc->sc_idlemask;
+ if (sc->sc_idlemask & (ETH_IR_RxBuffer_3|ETH_IR_RxError_3)) {
+ struct gfe_rxqueue *rxq = &sc->sc_rxq[GE_RXPRIO_HI];
+ rxq->rxq_fi = 0;
+ GE_WRITE(sc, EFRDP3, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP3, rxq->rxq_desc_busaddr);
+ }
+ if (sc->sc_idlemask & (ETH_IR_RxBuffer_2|ETH_IR_RxError_2)) {
+ struct gfe_rxqueue *rxq = &sc->sc_rxq[GE_RXPRIO_MEDHI];
+ rxq->rxq_fi = 0;
+ GE_WRITE(sc, EFRDP2, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP2, rxq->rxq_desc_busaddr);
+ }
+ if (sc->sc_idlemask & (ETH_IR_RxBuffer_1|ETH_IR_RxError_1)) {
+ struct gfe_rxqueue *rxq = &sc->sc_rxq[GE_RXPRIO_MEDLO];
+ rxq->rxq_fi = 0;
+ GE_WRITE(sc, EFRDP1, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP1, rxq->rxq_desc_busaddr);
+ }
+ if (sc->sc_idlemask & (ETH_IR_RxBuffer_0|ETH_IR_RxError_0)) {
+ struct gfe_rxqueue *rxq = &sc->sc_rxq[GE_RXPRIO_LO];
+ rxq->rxq_fi = 0;
+ GE_WRITE(sc, EFRDP0, rxq->rxq_desc_busaddr);
+ GE_WRITE(sc, ECRDP0, rxq->rxq_desc_busaddr);
+ }
+ sc->sc_idlemask = 0;
+ }
+ if (intrmask != sc->sc_intrmask) {
+ sc->sc_intrmask = intrmask;
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ }
+ gfe_intr(sc);
+ splx(s);
+
+ GE_FUNC_EXIT(sc, "");
+}
+
+static int
+gfe_free_slots(struct gfe_softc *sc, struct gfe_txqueue *const txq)
+{
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+#ifndef __rtems__
+ const int dcache_line_size = curcpu()->ci_ci.dcache_line_size;
+#endif
+ int got = 0;
+ int fi = txq->txq_fi;
+ volatile struct gt_eth_desc *txd = &txq->txq_descs[fi];
+ uint32_t cmdsts;
+#ifndef __rtems__
+ size_t pktlen;
+#endif
+
+ GE_FUNC_ENTER(sc, "gfe_free_slots");
+
+#ifdef __rtems__
+ do {
+#endif
+ GE_TXDPOSTSYNC(sc, txq, fi);
+ if ((cmdsts = gt32toh(txd->ed_cmdsts)) & TX_CMD_O) {
+ int nextin;
+
+ if (txq->txq_nactive == 1) {
+ GE_TXDPRESYNC(sc, txq, fi);
+ GE_FUNC_EXIT(sc, "");
+ return -1;
+ }
+ /*
+ * Sometimes the Discovery forgets to update the
+ * ownership bit in the descriptor. See if we own the
+ * descriptor after it (since we know we've turned
+ * that to the Discovery and if we own it now then the
+ * Discovery gave it back). If we do, we know the
+ * Discovery gave back this one but forgot to mark it
+ * as ours.
+ */
+ nextin = fi + 1;
+ if (nextin == GE_TXDESC_MAX)
+ nextin = 0;
+ GE_TXDPOSTSYNC(sc, txq, nextin);
+ if (gt32toh(txq->txq_descs[nextin].ed_cmdsts) & TX_CMD_O) {
+ GE_TXDPRESYNC(sc, txq, fi);
+ GE_TXDPRESYNC(sc, txq, nextin);
+ GE_FUNC_EXIT(sc, "");
+ return -1;
+ }
+#ifdef DEBUG
+ printf("%s: gfe_free_slots: transmitter resynced at %d\n",
+ sc->sc_dev.dv_xname, fi);
+#endif
+ }
+ got++;
+#ifdef __rtems__
+ txd++;
+ fi++;
+ } while ( ! ( TX_CMD_LAST & cmdsts ) );
+
+ { struct mbuf *m;
+ IF_DEQUEUE(&txq->txq_sentq, m);
+ m_freem(m);
+ }
+#endif
+#if 0
+ GE_DPRINTF(sc, ("([%d]<-%08lx.%08lx.%08lx.%08lx)",
+ txq->txq_lo,
+ ((unsigned long *)txd)[0], ((unsigned long *)txd)[1],
+ ((unsigned long *)txd)[2], ((unsigned long *)txd)[3]));
+#endif
+ GE_DPRINTF(sc, ("(%d)", fi));
+ txq->txq_fi = fi;
+ if ( txq->txq_fi >= GE_TXDESC_MAX)
+ txq->txq_fi -= GE_TXDESC_MAX;
+#ifndef __rtems__
+ txq->txq_inptr = gt32toh(txd->ed_bufptr) - txq->txq_buf_busaddr;
+ pktlen = (gt32toh(txd->ed_lencnt) >> 16) & 0xffff;
+ bus_dmamap_sync(sc->sc_dmat, txq->txq_buf_mem.gdm_map,
+ txq->txq_inptr, pktlen, BUS_DMASYNC_POSTWRITE);
+ txq->txq_inptr += roundup(pktlen, dcache_line_size);
+#endif
+
+ /* statistics */
+ ifp->if_opackets++;
+#ifdef __rtems__
+ /* FIXME: should we check errors on every fragment? */
+#endif
+ if (cmdsts & TX_STS_ES)
+ ifp->if_oerrors++;
+
+ /* txd->ed_bufptr = 0; */
+
+ txq->txq_nactive -= got;
+
+ GE_FUNC_EXIT(sc, "");
+
+ return got;
+}
+
+#ifndef __rtems__
+int
+gfe_tx_enqueue(struct gfe_softc *sc, enum gfe_txprio txprio)
+{
+#ifndef __rtems__
+ const int dcache_line_size = curcpu()->ci_ci.dcache_line_size;
+#else
+#ifndef PPC_CACHE_ALIGNMENT
+#error "Unknown cache alignment for your CPU"
+#endif
+ const int dcache_line_size = PPC_CACHE_ALIGNMENT;
+#endif
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+ volatile struct gt_eth_desc * const txd = &txq->txq_descs[txq->txq_lo];
+ uint32_t intrmask = sc->sc_intrmask;
+ size_t buflen;
+ struct mbuf *m;
+
+ GE_FUNC_ENTER(sc, "gfe_tx_enqueue");
+
+ /*
+ * Anything in the pending queue to enqueue? if not, punt. Likewise
+ * if the txq is not yet created.
+ * otherwise grab its dmamap.
+ */
+ if (txq == NULL || (m = txq->txq_pendq.ifq_head) == NULL) {
+ GE_FUNC_EXIT(sc, "-");
+ return 0;
+ }
+
+ /*
+ * Have we [over]consumed our limit of descriptors?
+ * Do we have enough free descriptors?
+ */
+ if (GE_TXDESC_MAX == txq->txq_nactive + 2) {
+ if ( gfe_free_slots(sc, txq) <= 0 )
+ return 0;
+ }
+
+ buflen = roundup(m->m_pkthdr.len, dcache_line_size);
+
+ /*
+ * If this packet would wrap around the end of the buffer, reset back
+ * to the beginning.
+ */
+ if (txq->txq_outptr + buflen > GE_TXBUF_SIZE) {
+ txq->txq_ei_gapcount += GE_TXBUF_SIZE - txq->txq_outptr;
+ txq->txq_outptr = 0;
+ }
+
+ /*
+ * Make sure the output packet doesn't run over the beginning of
+ * what we've already given the GT.
+ */
+ if (txq->txq_nactive > 0 && txq->txq_outptr <= txq->txq_inptr &&
+ txq->txq_outptr + buflen > txq->txq_inptr) {
+ intrmask |= txq->txq_intrbits &
+ (ETH_IR_TxBufferHigh|ETH_IR_TxBufferLow);
+ if (sc->sc_intrmask != intrmask) {
+ sc->sc_intrmask = intrmask;
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ }
+ GE_FUNC_EXIT(sc, "#");
+ return 0;
+ }
+
+ /*
+ * The end-of-list descriptor we put on last time is the starting point
+ * for this packet. The GT is supposed to terminate list processing on
+ * a NULL nxtptr but that currently is broken so a CPU-owned descriptor
+ * must terminate the list.
+ */
+ intrmask = sc->sc_intrmask;
+
+ m_copydata(m, 0, m->m_pkthdr.len,
+ txq->txq_buf_mem.gdm_kva + txq->txq_outptr);
+ bus_dmamap_sync(sc->sc_dmat, txq->txq_buf_mem.gdm_map,
+ txq->txq_outptr, buflen, BUS_DMASYNC_PREWRITE);
+ txd->ed_bufptr = htogt32(txq->txq_buf_busaddr + txq->txq_outptr);
+ txd->ed_lencnt = htogt32(m->m_pkthdr.len << 16);
+ GE_TXDPRESYNC(sc, txq, txq->txq_lo);
+
+ /*
+ * Request a buffer interrupt every 2/3 of the way thru the transmit
+ * buffer.
+ */
+ txq->txq_ei_gapcount += buflen;
+ if (txq->txq_ei_gapcount > 2 * GE_TXBUF_SIZE / 3) {
+ txd->ed_cmdsts = htogt32(TX_CMD_FIRST|TX_CMD_LAST|TX_CMD_EI);
+ txq->txq_ei_gapcount = 0;
+ } else {
+ txd->ed_cmdsts = htogt32(TX_CMD_FIRST|TX_CMD_LAST);
+ }
+#if 0
+ GE_DPRINTF(sc, ("([%d]->%08lx.%08lx.%08lx.%08lx)", txq->txq_lo,
+ ((unsigned long *)txd)[0], ((unsigned long *)txd)[1],
+ ((unsigned long *)txd)[2], ((unsigned long *)txd)[3]));
+#endif
+ GE_TXDPRESYNC(sc, txq, txq->txq_lo);
+
+ txq->txq_outptr += buflen;
+ /*
+ * Tell the SDMA engine to "Fetch!"
+ */
+ GE_WRITE(sc, ESDCMR,
+ txq->txq_esdcmrbits & (ETH_ESDCMR_TXDH|ETH_ESDCMR_TXDL));
+
+ GE_DPRINTF(sc, ("(%d)", txq->txq_lo));
+
+ /*
+ * Update the last out appropriately.
+ */
+ txq->txq_nactive++;
+ if (++txq->txq_lo == GE_TXDESC_MAX)
+ txq->txq_lo = 0;
+
+ /*
+ * Move mbuf from the pending queue to the snd queue.
+ */
+ IF_DEQUEUE(&txq->txq_pendq, m);
+#if NBPFILTER > 0
+ if (ifp->if_bpf != NULL)
+ bpf_mtap(ifp->if_bpf, m);
+#endif
+ m_freem(m);
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ /*
+ * Since we have put an item into the packet queue, we now want
+ * an interrupt when the transmit queue finishes processing the
+ * list. But only update the mask if needs changing.
+ */
+ intrmask |= txq->txq_intrbits & (ETH_IR_TxEndHigh|ETH_IR_TxEndLow);
+ if (sc->sc_intrmask != intrmask) {
+ sc->sc_intrmask = intrmask;
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ }
+ if (ifp->if_timer == 0)
+ ifp->if_timer = 5;
+ GE_FUNC_EXIT(sc, "*");
+ return 1;
+}
+
+#else
+
+#ifdef __PPC__
+static inline void membarrier(void)
+{
+ asm volatile("sync":::"memory");
+}
+#else
+#error "memory synchronization for your CPU not implemented"
+#endif
+
+
+void
+gfe_assign_desc(volatile struct gt_eth_desc *const d, struct mbuf *m, uint32_t flags)
+{
+ d->ed_cmdsts = htogt32(flags | TX_CMD_GC | TX_CMD_P);
+ d->ed_bufptr = htogt32(mtod(m, uint32_t));
+ d->ed_lencnt = htogt32(m->m_len << 16);
+}
+
+int
+gfe_tx_enqueue(struct gfe_softc *sc, enum gfe_txprio txprio)
+{
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+ volatile struct gt_eth_desc * const txd = &txq->txq_descs[txq->txq_lo];
+#define NEXT_TXD(d) ((d)+1 < &txq->txq_descs[GE_TXDESC_MAX] ? (d)+1 : txq->txq_descs)
+ volatile struct gt_eth_desc *l,*d;
+ uint32_t intrmask = sc->sc_intrmask;
+ struct mbuf *m_head,*m,*m1;
+ int avail, used;
+
+ GE_FUNC_ENTER(sc, "gfe_tx_enqueue");
+
+ /*
+ * Anything in the pending queue to enqueue? if not, punt. Likewise
+ * if the txq is not yet created.
+ * otherwise grab its dmamap.
+ */
+ if (txq == NULL || (m_head = txq->txq_pendq.ifq_head) == NULL) {
+ GE_FUNC_EXIT(sc, "-");
+ return 0;
+ }
+
+ /* find 1st mbuf with actual data; m_head is not NULL at this point */
+ for ( m1=m_head; 0 == m1->m_len; ) {
+ if ( ! (m1=m1->m_next) ) {
+ /* nothing to send */
+ IF_DEQUEUE(&txq->txq_pendq, m_head);
+ m_freem(m_head);
+ return 0;
+ }
+ }
+
+ avail = GE_TXDESC_MAX - 1 - txq->txq_nactive;
+
+ if ( avail < 1 && (avail += gfe_free_slots(sc, txq)) < 1 )
+ return 0;
+
+ avail--;
+
+ l = txd;
+ d = NEXT_TXD(txd);
+
+ for ( m=m1->m_next, used = 1; m; m=m->m_next ) {
+ if ( 0 == m->m_len )
+ continue; /* skip empty mbufs */
+
+ if ( avail < 1 && (avail += gfe_free_slots(sc, txq)) < 1 ) {
+ /* not enough descriptors; cleanup */
+ for ( l = NEXT_TXD(txd); l!=d; l = NEXT_TXD(l) ) {
+ l->ed_cmdsts = 0;
+ avail++;
+ }
+ avail++;
+ if ( used >= GE_TXDESC_MAX-1 )
+ panic("mbuf chain (#%i) longer than TX ring (#%i); configuration error!",
+ used, GE_TXDESC_MAX-1);
+ return 0;
+ }
+ used++;
+ avail--;
+
+ /* fill this slot */
+ gfe_assign_desc(d, m, TX_CMD_O);
+
+ bus_dmamap_sync(sc->sc_dmat, /* TODO */,
+ mtod(m, uint32_t), m->m_len, BUS_DMASYNC_PREWRITE);
+
+ l = d;
+ d = NEXT_TXD(d);
+
+ GE_TXDPRESYNC(sc, txq, l - txq->txq_descs);
+ }
+
+ /* fill first slot */
+ gfe_assign_desc(txd, m1, TX_CMD_F);
+
+ bus_dmamap_sync(sc->sc_dmat, /* TODO */,
+ mtod(m1, uint32_t), m1->m_len, BUS_DMASYNC_PREWRITE);
+
+ /* tag last slot; this covers where 1st = last */
+ l->ed_cmdsts |= htonl(TX_CMD_L | TX_CMD_EI);
+
+ GE_TXDPRESYNC(sc, txq, l - txq->txq_descs);
+
+ /*
+ * The end-of-list descriptor we put on last time is the starting point
+ * for this packet. The GT is supposed to terminate list processing on
+ * a NULL nxtptr but that currently is broken so a CPU-owned descriptor
+ * must terminate the list.
+ */
+ d = NEXT_TXD(l);
+
+ out_be32((uint32_t*)&d->ed_cmdsts,0);
+
+ GE_TXDPRESYNC(sc, txq, d - txq->txq_descs);
+
+ membarrier();
+
+ /* turn over the whole chain by flipping the ownership of the first desc */
+ txd->ed_cmdsts |= htonl(TX_CMD_O);
+
+ GE_TXDPRESYNC(sc, txq, txq->txq_lo);
+
+
+ intrmask = sc->sc_intrmask;
+
+#if 0
+ GE_DPRINTF(sc, ("([%d]->%08lx.%08lx.%08lx.%08lx)", txq->txq_lo,
+ ((unsigned long *)txd)[0], ((unsigned long *)txd)[1],
+ ((unsigned long *)txd)[2], ((unsigned long *)txd)[3]));
+#endif
+
+ membarrier();
+
+ /*
+ * Tell the SDMA engine to "Fetch!"
+ */
+ GE_WRITE(sc, ESDCMR,
+ txq->txq_esdcmrbits & (ETH_ESDCMR_TXDH|ETH_ESDCMR_TXDL));
+
+ GE_DPRINTF(sc, ("(%d)", txq->txq_lo));
+
+ /*
+ * Update the last out appropriately.
+ */
+ txq->txq_nactive += used;
+ txq->txq_lo += used;
+ if ( txq->txq_lo >= GE_TXDESC_MAX )
+ txq->txq_lo -= GE_TXDESC_MAX;
+
+ /*
+ * Move mbuf from the pending queue to the snd queue.
+ */
+ IF_DEQUEUE(&txq->txq_pendq, m_head);
+
+ IF_ENQUEUE(&txq->txq_sentq, m_head);
+
+#if NBPFILTER > 0
+ if (ifp->if_bpf != NULL)
+ bpf_mtap(ifp->if_bpf, m_head);
+#endif
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ /*
+ * Since we have put an item into the packet queue, we now want
+ * an interrupt when the transmit queue finishes processing the
+ * list. But only update the mask if needs changing.
+ */
+ intrmask |= txq->txq_intrbits & (ETH_IR_TxEndHigh|ETH_IR_TxEndLow);
+ if (sc->sc_intrmask != intrmask) {
+ sc->sc_intrmask = intrmask;
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ }
+ if (ifp->if_timer == 0)
+ ifp->if_timer = 5;
+ GE_FUNC_EXIT(sc, "*");
+ return 1;
+}
+#endif
+
+uint32_t
+gfe_tx_done(struct gfe_softc *sc, enum gfe_txprio txprio, uint32_t intrmask)
+{
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+ struct ifnet * const ifp = &sc->sc_ec.ec_if;
+
+ GE_FUNC_ENTER(sc, "gfe_tx_done");
+
+ if (txq == NULL) {
+ GE_FUNC_EXIT(sc, "");
+ return intrmask;
+ }
+
+ while (txq->txq_nactive > 0) {
+ if ( gfe_free_slots(sc, txq) < 0 )
+ return intrmask;
+ ifp->if_timer = 5;
+ }
+ if (txq->txq_nactive != 0)
+ panic("%s: transmit fifo%d empty but active count (%d) not 0!",
+ sc->sc_dev.dv_xname, txprio, txq->txq_nactive);
+ ifp->if_timer = 0;
+ intrmask &= ~(txq->txq_intrbits & (ETH_IR_TxEndHigh|ETH_IR_TxEndLow));
+ intrmask &= ~(txq->txq_intrbits & (ETH_IR_TxBufferHigh|ETH_IR_TxBufferLow));
+ GE_FUNC_EXIT(sc, "");
+ return intrmask;
+}
+
+int
+gfe_tx_txqalloc(struct gfe_softc *sc, enum gfe_txprio txprio)
+{
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+ int error;
+
+ GE_FUNC_ENTER(sc, "gfe_tx_txqalloc");
+
+ error = gfe_dmamem_alloc(sc, &txq->txq_desc_mem, 1,
+ GE_TXDESC_MEMSIZE, BUS_DMA_NOCACHE);
+ if (error) {
+ GE_FUNC_EXIT(sc, "");
+ return error;
+ }
+#ifndef __rtems__
+ error = gfe_dmamem_alloc(sc, &txq->txq_buf_mem, 1, GE_TXBUF_SIZE, 0);
+ if (error) {
+ gfe_dmamem_free(sc, &txq->txq_desc_mem);
+ GE_FUNC_EXIT(sc, "");
+ return error;
+ }
+#endif
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+}
+
+int
+gfe_tx_start(struct gfe_softc *sc, enum gfe_txprio txprio)
+{
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+ volatile struct gt_eth_desc *txd;
+ unsigned int i;
+ bus_addr_t addr;
+
+ GE_FUNC_ENTER(sc, "gfe_tx_start");
+
+ sc->sc_intrmask &= ~(ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh|
+ ETH_IR_TxEndLow |ETH_IR_TxBufferLow);
+
+ if (sc->sc_flags & GE_NOFREE) {
+ KASSERT(txq->txq_desc_mem.gdm_kva != NULL);
+#ifndef __rtems__
+ KASSERT(txq->txq_buf_mem.gdm_kva != NULL);
+#endif
+ } else {
+ int error = gfe_tx_txqalloc(sc, txprio);
+ if (error) {
+ GE_FUNC_EXIT(sc, "!");
+ return error;
+ }
+ }
+
+ txq->txq_descs =
+ (volatile struct gt_eth_desc *) txq->txq_desc_mem.gdm_kva;
+ txq->txq_desc_busaddr = txq->txq_desc_mem.gdm_map->dm_segs[0].ds_addr;
+#ifndef __rtems__
+ txq->txq_buf_busaddr = txq->txq_buf_mem.gdm_map->dm_segs[0].ds_addr;
+#else
+ /* never used */
+ memset(&txq->txq_pendq,0,sizeof(txq->txq_pendq));
+ memset(&txq->txq_sentq,0,sizeof(txq->txq_sentq));
+ txq->txq_sentq.ifq_maxlen = 100000;
+#endif
+
+ txq->txq_pendq.ifq_maxlen = 10;
+#ifndef __rtems__
+ txq->txq_ei_gapcount = 0;
+#endif
+ txq->txq_nactive = 0;
+ txq->txq_fi = 0;
+ txq->txq_lo = 0;
+#ifndef __rtems__
+ txq->txq_ei_gapcount = 0;
+ txq->txq_inptr = GE_TXBUF_SIZE;
+ txq->txq_outptr = 0;
+#endif
+ for (i = 0, txd = txq->txq_descs,
+ addr = txq->txq_desc_busaddr + sizeof(*txd);
+ i < GE_TXDESC_MAX - 1;
+ i++, txd++, addr += sizeof(*txd)) {
+ /*
+ * update the nxtptr to point to the next txd.
+ */
+ txd->ed_cmdsts = 0;
+ txd->ed_nxtptr = htogt32(addr);
+ }
+ txq->txq_descs[GE_TXDESC_MAX-1].ed_nxtptr =
+ htogt32(txq->txq_desc_busaddr);
+ bus_dmamap_sync(sc->sc_dmat, txq->txq_desc_mem.gdm_map, 0,
+ GE_TXDESC_MEMSIZE, BUS_DMASYNC_PREREAD|BUS_DMASYNC_PREWRITE);
+
+ switch (txprio) {
+ case GE_TXPRIO_HI:
+ txq->txq_intrbits = ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh;
+ txq->txq_esdcmrbits = ETH_ESDCMR_TXDH;
+ txq->txq_epsrbits = ETH_EPSR_TxHigh;
+ txq->txq_ectdp = ETH_ECTDP1(sc->sc_macno);
+ GE_WRITE(sc, ECTDP1, txq->txq_desc_busaddr);
+ break;
+
+ case GE_TXPRIO_LO:
+ txq->txq_intrbits = ETH_IR_TxEndLow|ETH_IR_TxBufferLow;
+ txq->txq_esdcmrbits = ETH_ESDCMR_TXDL;
+ txq->txq_epsrbits = ETH_EPSR_TxLow;
+ txq->txq_ectdp = ETH_ECTDP0(sc->sc_macno);
+ GE_WRITE(sc, ECTDP0, txq->txq_desc_busaddr);
+ break;
+
+ case GE_TXPRIO_NONE:
+ break;
+ }
+#if 0
+ GE_DPRINTF(sc, ("(ectdp=%#x", txq->txq_ectdp));
+ gt_write(sc->sc_dev.dv_parent, txq->txq_ectdp, txq->txq_desc_busaddr);
+ GE_DPRINTF(sc, (")"));
+#endif
+
+ /*
+ * If we are restarting, there may be packets in the pending queue
+ * waiting to be enqueued. Try enqueuing packets from both priority
+ * queues until the pending queue is empty or there no room for them
+ * on the device.
+ */
+ while (gfe_tx_enqueue(sc, txprio))
+ continue;
+
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+}
+
+void
+gfe_tx_cleanup(struct gfe_softc *sc, enum gfe_txprio txprio, int flush)
+{
+ struct gfe_txqueue * const txq = &sc->sc_txq[txprio];
+
+ GE_FUNC_ENTER(sc, "gfe_tx_cleanup");
+ if (txq == NULL) {
+ GE_FUNC_EXIT(sc, "");
+ return;
+ }
+
+ if (!flush) {
+ GE_FUNC_EXIT(sc, "");
+ return;
+ }
+
+#ifdef __rtems__
+ /* reclaim mbufs that were never sent */
+ {
+ struct mbuf *m;
+ while ( txq->txq_sentq.ifq_head ) {
+ IF_DEQUEUE(&txq->txq_sentq, m);
+ m_freem(m);
+ }
+ }
+#endif
+
+ if ((sc->sc_flags & GE_NOFREE) == 0) {
+ gfe_dmamem_free(sc, &txq->txq_desc_mem);
+#ifndef __rtems__
+ gfe_dmamem_free(sc, &txq->txq_buf_mem);
+#endif
+ }
+ GE_FUNC_EXIT(sc, "-F");
+}
+
+void
+gfe_tx_stop(struct gfe_softc *sc, enum gfe_whack_op op)
+{
+ GE_FUNC_ENTER(sc, "gfe_tx_stop");
+
+ GE_WRITE(sc, ESDCMR, ETH_ESDCMR_STDH|ETH_ESDCMR_STDL);
+
+ sc->sc_intrmask = gfe_tx_done(sc, GE_TXPRIO_HI, sc->sc_intrmask);
+ sc->sc_intrmask = gfe_tx_done(sc, GE_TXPRIO_LO, sc->sc_intrmask);
+ sc->sc_intrmask &= ~(ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh|
+ ETH_IR_TxEndLow |ETH_IR_TxBufferLow);
+
+ gfe_tx_cleanup(sc, GE_TXPRIO_HI, op == GE_WHACK_STOP);
+ gfe_tx_cleanup(sc, GE_TXPRIO_LO, op == GE_WHACK_STOP);
+
+ sc->sc_ec.ec_if.if_timer = 0;
+ GE_FUNC_EXIT(sc, "");
+}
+
+int
+gfe_intr(void *arg)
+{
+ struct gfe_softc * const sc = arg;
+ uint32_t cause;
+ uint32_t intrmask = sc->sc_intrmask;
+ int claim = 0;
+ int cnt;
+
+ GE_FUNC_ENTER(sc, "gfe_intr");
+
+ for (cnt = 0; cnt < 4; cnt++) {
+ if (sc->sc_intrmask != intrmask) {
+ sc->sc_intrmask = intrmask;
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ }
+ cause = GE_READ(sc, EICR);
+ cause &= sc->sc_intrmask;
+ GE_DPRINTF(sc, (".%#" PRIx32, cause));
+ if (cause == 0)
+ break;
+
+ claim = 1;
+
+ GE_WRITE(sc, EICR, ~cause);
+#ifndef GE_NORX
+ if (cause & (ETH_IR_RxBuffer|ETH_IR_RxError))
+ intrmask = gfe_rx_process(sc, cause, intrmask);
+#endif
+
+#ifndef GE_NOTX
+ if (cause & (ETH_IR_TxBufferHigh|ETH_IR_TxEndHigh))
+ intrmask = gfe_tx_done(sc, GE_TXPRIO_HI, intrmask);
+ if (cause & (ETH_IR_TxBufferLow|ETH_IR_TxEndLow))
+ intrmask = gfe_tx_done(sc, GE_TXPRIO_LO, intrmask);
+#endif
+ if (cause & ETH_IR_MIIPhySTC) {
+ sc->sc_flags |= GE_PHYSTSCHG;
+ /* intrmask &= ~ETH_IR_MIIPhySTC; */
+ }
+ }
+
+ while (gfe_tx_enqueue(sc, GE_TXPRIO_HI))
+ continue;
+ while (gfe_tx_enqueue(sc, GE_TXPRIO_LO))
+ continue;
+
+ GE_FUNC_EXIT(sc, "");
+ return claim;
+}
+
+#ifndef __rtems__
+int
+gfe_mii_mediachange (struct ifnet *ifp)
+{
+ struct gfe_softc *sc = ifp->if_softc;
+
+ if (ifp->if_flags & IFF_UP)
+ mii_mediachg(&sc->sc_mii);
+
+ return (0);
+}
+void
+gfe_mii_mediastatus (struct ifnet *ifp, struct ifmediareq *ifmr)
+{
+ struct gfe_softc *sc = ifp->if_softc;
+
+ if (sc->sc_flags & GE_PHYSTSCHG) {
+ sc->sc_flags &= ~GE_PHYSTSCHG;
+ mii_pollstat(&sc->sc_mii);
+ }
+ ifmr->ifm_status = sc->sc_mii.mii_media_status;
+ ifmr->ifm_active = sc->sc_mii.mii_media_active;
+}
+
+int
+gfe_mii_read (struct device *self, int phy, int reg)
+{
+ return gt_mii_read(self, self->dv_parent, phy, reg);
+}
+
+void
+gfe_mii_write (struct device *self, int phy, int reg, int value)
+{
+ gt_mii_write(self, self->dv_parent, phy, reg, value);
+}
+
+void
+gfe_mii_statchg (struct device *self)
+{
+ /* struct gfe_softc *sc = (struct gfe_softc *) self; */
+ /* do nothing? */
+}
+
+#else
+int
+gfe_mii_read(int phy, void *arg, unsigned reg, uint32_t *pval)
+{
+ struct gfe_softc *sc = arg;
+ uint32_t data;
+ int count = 10000;
+
+ if ( 0 != phy )
+ return -1; /* invalid index */
+
+ phy = sc->sc_phyaddr;
+
+ do {
+ DELAY(10);
+ data = GT_READ(sc, ETH_ESMIR);
+ } while ((data & ETH_ESMIR_Busy) && count-- > 0);
+
+ if (count == 0) {
+ fprintf(stderr,"%s: mii read for phy %d reg %d busied out\n",
+ sc->sc_dev.dv_xname, phy, reg);
+ *pval = ETH_ESMIR_Value_GET(data);
+ return -1;
+ }
+
+ GT_WRITE(sc, ETH_ESMIR, ETH_ESMIR_READ(phy, reg));
+
+ count = 10000;
+ do {
+ DELAY(10);
+ data = GT_READ(sc, ETH_ESMIR);
+ } while ((data & ETH_ESMIR_ReadValid) == 0 && count-- > 0);
+
+ if (count == 0)
+ printf("%s: mii read for phy %d reg %d timed out\n",
+ sc->sc_dev.dv_xname, phy, reg);
+#if defined(GTMIIDEBUG)
+ printf("%s: mii_read(%d, %d): %#x data %#x\n",
+ sc->sc_dev.dv_xname, phy, reg,
+ data, ETH_ESMIR_Value_GET(data));
+#endif
+ *pval = ETH_ESMIR_Value_GET(data);
+ return 0;
+}
+
+int
+gfe_mii_write(int phy, void *arg, unsigned reg, uint32_t value)
+{
+ struct gfe_softc *sc = arg;
+ uint32_t data;
+ int count = 10000;
+
+ if ( 0 != phy )
+ return -1; /* invalid index */
+
+ phy = sc->sc_phyaddr;
+
+ do {
+ DELAY(10);
+ data = GT_READ(sc, ETH_ESMIR);
+ } while ((data & ETH_ESMIR_Busy) && count-- > 0);
+
+ if (count == 0) {
+ fprintf(stderr, "%s: mii write for phy %d reg %d busied out (busy)\n",
+ sc->sc_dev.dv_xname, phy, reg);
+ return -1;
+ }
+
+ GT_WRITE(sc, ETH_ESMIR,
+ ETH_ESMIR_WRITE(phy, reg, value));
+
+ count = 10000;
+ do {
+ DELAY(10);
+ data = GT_READ(sc, ETH_ESMIR);
+ } while ((data & ETH_ESMIR_Busy) && count-- > 0);
+
+ if (count == 0)
+ printf("%s: mii write for phy %d reg %d timed out\n",
+ sc->sc_dev.dv_xname, phy, reg);
+#if defined(GTMIIDEBUG)
+ printf("%s: mii_write(%d, %d, %#x)\n",
+ sc->sc_dev.dv_xname, phy, reg, value);
+#endif
+ return 0;
+}
+
+#endif
+int
+gfe_whack(struct gfe_softc *sc, enum gfe_whack_op op)
+{
+ int error = 0;
+ GE_FUNC_ENTER(sc, "gfe_whack");
+
+ switch (op) {
+ case GE_WHACK_RESTART:
+#ifndef GE_NOTX
+ gfe_tx_stop(sc, op);
+#endif
+ /* sc->sc_ec.ec_if.if_flags &= ~IFF_RUNNING; */
+ /* FALLTHROUGH */
+ case GE_WHACK_START:
+#ifndef GE_NOHASH
+ if (error == 0 && sc->sc_hashtable == NULL) {
+ error = gfe_hash_alloc(sc);
+ if (error)
+ break;
+ }
+ if (op != GE_WHACK_RESTART)
+ gfe_hash_fill(sc);
+#endif
+#ifndef GE_NORX
+ if (op != GE_WHACK_RESTART) {
+ error = gfe_rx_prime(sc);
+ if (error)
+ break;
+ }
+#endif
+#ifndef GE_NOTX
+ error = gfe_tx_start(sc, GE_TXPRIO_HI);
+ if (error)
+ break;
+#endif
+ sc->sc_ec.ec_if.if_flags |= IFF_RUNNING;
+ GE_WRITE(sc, EPCR, sc->sc_pcr | ETH_EPCR_EN);
+ GE_WRITE(sc, EPCXR, sc->sc_pcxr);
+ GE_WRITE(sc, EICR, 0);
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+#ifndef GE_NOHASH
+ GE_WRITE(sc, EHTPR, sc->sc_hash_mem.gdm_map->dm_segs->ds_addr);
+#endif
+#ifndef GE_NORX
+ GE_WRITE(sc, ESDCMR, ETH_ESDCMR_ERD);
+ sc->sc_flags |= GE_RXACTIVE;
+#endif
+ /* FALLTHROUGH */
+ case GE_WHACK_CHANGE:
+ GE_DPRINTF(sc, ("(pcr=%#" PRIx32 ",imr=%#" PRIx32 ")",
+ GE_READ(sc, EPCR), GE_READ(sc, EIMR)));
+ GE_WRITE(sc, EPCR, sc->sc_pcr | ETH_EPCR_EN);
+ GE_WRITE(sc, EIMR, sc->sc_intrmask);
+ gfe_ifstart(&sc->sc_ec.ec_if);
+ GE_DPRINTF(sc, ("(ectdp0=%#" PRIx32 ", ectdp1=%#" PRIx32 ")",
+ GE_READ(sc, ECTDP0), GE_READ(sc, ECTDP1)));
+ GE_FUNC_EXIT(sc, "");
+ return error;
+ case GE_WHACK_STOP:
+ break;
+ }
+
+#ifdef GE_DEBUG
+ if (error)
+ GE_DPRINTF(sc, (" failed: %d\n", error));
+#endif
+ GE_WRITE(sc, EPCR, sc->sc_pcr);
+ GE_WRITE(sc, EIMR, 0);
+ sc->sc_ec.ec_if.if_flags &= ~IFF_RUNNING;
+#ifndef GE_NOTX
+ gfe_tx_stop(sc, GE_WHACK_STOP);
+#endif
+#ifndef GE_NORX
+ gfe_rx_stop(sc, GE_WHACK_STOP);
+#endif
+#ifndef GE_NOHASH
+ if ((sc->sc_flags & GE_NOFREE) == 0) {
+ gfe_dmamem_free(sc, &sc->sc_hash_mem);
+ sc->sc_hashtable = NULL;
+ }
+#endif
+
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+int
+gfe_hash_compute(struct gfe_softc *sc, const uint8_t eaddr[ETHER_ADDR_LEN])
+{
+ uint32_t w0, add0, add1;
+ uint32_t result;
+#ifdef __rtems__
+ SPRINTFVARDECL;
+#endif
+
+ GE_FUNC_ENTER(sc, "gfe_hash_compute");
+ add0 = ((uint32_t) eaddr[5] << 0) |
+ ((uint32_t) eaddr[4] << 8) |
+ ((uint32_t) eaddr[3] << 16);
+
+ add0 = ((add0 & 0x00f0f0f0) >> 4) | ((add0 & 0x000f0f0f) << 4);
+ add0 = ((add0 & 0x00cccccc) >> 2) | ((add0 & 0x00333333) << 2);
+ add0 = ((add0 & 0x00aaaaaa) >> 1) | ((add0 & 0x00555555) << 1);
+
+ add1 = ((uint32_t) eaddr[2] << 0) |
+ ((uint32_t) eaddr[1] << 8) |
+ ((uint32_t) eaddr[0] << 16);
+
+ add1 = ((add1 & 0x00f0f0f0) >> 4) | ((add1 & 0x000f0f0f) << 4);
+ add1 = ((add1 & 0x00cccccc) >> 2) | ((add1 & 0x00333333) << 2);
+ add1 = ((add1 & 0x00aaaaaa) >> 1) | ((add1 & 0x00555555) << 1);
+
+ GE_DPRINTF(sc, ("%s=", ether_sprintf(eaddr)));
+ /*
+ * hashResult is the 15 bits Hash entry address.
+ * ethernetADD is a 48 bit number, which is derived from the Ethernet
+ * MAC address, by nibble swapping in every byte (i.e MAC address
+ * of 0x123456789abc translates to ethernetADD of 0x21436587a9cb).
+ */
+
+ if ((sc->sc_pcr & ETH_EPCR_HM) == 0) {
+ /*
+ * hashResult[14:0] = hashFunc0(ethernetADD[47:0])
+ *
+ * hashFunc0 calculates the hashResult in the following manner:
+ * hashResult[ 8:0] = ethernetADD[14:8,1,0]
+ * XOR ethernetADD[23:15] XOR ethernetADD[32:24]
+ */
+ result = (add0 & 3) | ((add0 >> 6) & ~3);
+ result ^= (add0 >> 15) ^ (add1 >> 0);
+ result &= 0x1ff;
+ /*
+ * hashResult[14:9] = ethernetADD[7:2]
+ */
+ result |= (add0 & ~3) << 7; /* excess bits will be masked */
+ GE_DPRINTF(sc, ("0(%#"PRIx32")", result & 0x7fff));
+ } else {
+#define TRIBITFLIP 073516240 /* yes its in octal */
+ /*
+ * hashResult[14:0] = hashFunc1(ethernetADD[47:0])
+ *
+ * hashFunc1 calculates the hashResult in the following manner:
+ * hashResult[08:00] = ethernetADD[06:14]
+ * XOR ethernetADD[15:23] XOR ethernetADD[24:32]
+ */
+ w0 = ((add0 >> 6) ^ (add0 >> 15) ^ (add1)) & 0x1ff;
+ /*
+ * Now bitswap those 9 bits
+ */
+ result = 0;
+ result |= ((TRIBITFLIP >> (((w0 >> 0) & 7) * 3)) & 7) << 6;
+ result |= ((TRIBITFLIP >> (((w0 >> 3) & 7) * 3)) & 7) << 3;
+ result |= ((TRIBITFLIP >> (((w0 >> 6) & 7) * 3)) & 7) << 0;
+
+ /*
+ * hashResult[14:09] = ethernetADD[00:05]
+ */
+ result |= ((TRIBITFLIP >> (((add0 >> 0) & 7) * 3)) & 7) << 12;
+ result |= ((TRIBITFLIP >> (((add0 >> 3) & 7) * 3)) & 7) << 9;
+ GE_DPRINTF(sc, ("1(%#"PRIx32")", result));
+ }
+ GE_FUNC_EXIT(sc, "");
+ return result & ((sc->sc_pcr & ETH_EPCR_HS_512) ? 0x7ff : 0x7fff);
+}
+
+int
+gfe_hash_entry_op(struct gfe_softc *sc, enum gfe_hash_op op,
+ enum gfe_rxprio prio, const uint8_t eaddr[ETHER_ADDR_LEN])
+{
+ uint64_t he;
+ uint64_t *maybe_he_p = NULL;
+ int limit;
+ int hash;
+#ifndef __rtems__
+ int maybe_hash = 0;
+#endif /* __rtems__ */
+
+ GE_FUNC_ENTER(sc, "gfe_hash_entry_op");
+
+ hash = gfe_hash_compute(sc, eaddr);
+
+ if (sc->sc_hashtable == NULL) {
+ panic("%s:%d: hashtable == NULL!", sc->sc_dev.dv_xname,
+ __LINE__);
+ }
+
+ /*
+ * Assume we are going to insert so create the hash entry we
+ * are going to insert. We also use it to match entries we
+ * will be removing.
+ */
+ he = ((uint64_t) eaddr[5] << 43) |
+ ((uint64_t) eaddr[4] << 35) |
+ ((uint64_t) eaddr[3] << 27) |
+ ((uint64_t) eaddr[2] << 19) |
+ ((uint64_t) eaddr[1] << 11) |
+ ((uint64_t) eaddr[0] << 3) |
+ HSH_PRIO_INS(prio) | HSH_V | HSH_R;
+
+ /*
+ * The GT will search upto 12 entries for a hit, so we must mimic that.
+ */
+ hash &= sc->sc_hashmask / sizeof(he);
+ for (limit = HSH_LIMIT; limit > 0 ; --limit) {
+ /*
+ * Does the GT wrap at the end, stop at the, or overrun the
+ * end? Assume it wraps for now. Stash a copy of the
+ * current hash entry.
+ */
+ uint64_t *he_p = &sc->sc_hashtable[hash];
+ uint64_t thishe = *he_p;
+
+ /*
+ * If the hash entry isn't valid, that break the chain. And
+ * this entry a good candidate for reuse.
+ */
+ if ((thishe & HSH_V) == 0) {
+ maybe_he_p = he_p;
+ break;
+ }
+
+ /*
+ * If the hash entry has the same address we are looking for
+ * then ... if we are removing and the skip bit is set, its
+ * already been removed. if are adding and the skip bit is
+ * clear, then its already added. In either return EBUSY
+ * indicating the op has already been done. Otherwise flip
+ * the skip bit and return 0.
+ */
+ if (((he ^ thishe) & HSH_ADDR_MASK) == 0) {
+ if (((op == GE_HASH_REMOVE) && (thishe & HSH_S)) ||
+ ((op == GE_HASH_ADD) && (thishe & HSH_S) == 0))
+ return EBUSY;
+ *he_p = thishe ^ HSH_S;
+ bus_dmamap_sync(sc->sc_dmat, sc->sc_hash_mem.gdm_map,
+ hash * sizeof(he), sizeof(he),
+ BUS_DMASYNC_PREWRITE);
+ GE_FUNC_EXIT(sc, "^");
+ return 0;
+ }
+
+ /*
+ * If we haven't found a slot for the entry and this entry
+ * is currently being skipped, return this entry.
+ */
+ if (maybe_he_p == NULL && (thishe & HSH_S)) {
+ maybe_he_p = he_p;
+#ifndef __rtems__
+ maybe_hash = hash;
+#endif /* __rtems__ */
+ }
+
+ hash = (hash + 1) & (sc->sc_hashmask / sizeof(he));
+ }
+
+ /*
+ * If we got here, then there was no entry to remove.
+ */
+ if (op == GE_HASH_REMOVE) {
+ GE_FUNC_EXIT(sc, "?");
+ return ENOENT;
+ }
+
+ /*
+ * If we couldn't find a slot, return an error.
+ */
+ if (maybe_he_p == NULL) {
+ GE_FUNC_EXIT(sc, "!");
+ return ENOSPC;
+ }
+
+ /* Update the entry.
+ */
+ *maybe_he_p = he;
+ bus_dmamap_sync(sc->sc_dmat, sc->sc_hash_mem.gdm_map,
+ maybe_hash * sizeof(he), sizeof(he), BUS_DMASYNC_PREWRITE);
+ GE_FUNC_EXIT(sc, "+");
+ return 0;
+}
+
+#ifndef __rtems__
+int
+gfe_hash_multichg(struct ethercom *ec, const struct ether_multi *enm, u_long cmd)
+{
+ struct gfe_softc * const sc = ec->ec_if.if_softc;
+ int error;
+ enum gfe_hash_op op;
+ enum gfe_rxprio prio;
+#ifdef __rtems__
+ SPRINTFVARDECL;
+#endif
+
+ GE_FUNC_ENTER(sc, "hash_multichg");
+ /*
+ * Is this a wildcard entry? If so and its being removed, recompute.
+ */
+ if (memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN) != 0) {
+ if (cmd == SIOCDELMULTI) {
+ GE_FUNC_EXIT(sc, "");
+ return ENETRESET;
+ }
+
+ /*
+ * Switch in
+ */
+ sc->sc_flags |= GE_ALLMULTI;
+ if ((sc->sc_pcr & ETH_EPCR_PM) == 0) {
+ sc->sc_pcr |= ETH_EPCR_PM;
+ GE_WRITE(sc, EPCR, sc->sc_pcr);
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+ }
+ GE_FUNC_EXIT(sc, "");
+ return ENETRESET;
+ }
+
+ prio = GE_RXPRIO_MEDLO;
+ op = (cmd == SIOCDELMULTI ? GE_HASH_REMOVE : GE_HASH_ADD);
+
+ if (sc->sc_hashtable == NULL) {
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+ }
+
+ error = gfe_hash_entry_op(sc, op, prio, enm->enm_addrlo);
+ if (error == EBUSY) {
+ printf("%s: multichg: tried to %s %s again\n",
+ sc->sc_dev.dv_xname,
+ cmd == SIOCDELMULTI ? "remove" : "add",
+ ether_sprintf(enm->enm_addrlo));
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+ }
+
+ if (error == ENOENT) {
+ printf("%s: multichg: failed to remove %s: not in table\n",
+ sc->sc_dev.dv_xname,
+ ether_sprintf(enm->enm_addrlo));
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+ }
+
+ if (error == ENOSPC) {
+ printf("%s: multichg: failed to add %s: no space; regenerating table\n",
+ sc->sc_dev.dv_xname,
+ ether_sprintf(enm->enm_addrlo));
+ GE_FUNC_EXIT(sc, "");
+ return ENETRESET;
+ }
+ GE_DPRINTF(sc, ("%s: multichg: %s: %s succeeded\n",
+ sc->sc_dev.dv_xname,
+ cmd == SIOCDELMULTI ? "remove" : "add",
+ ether_sprintf(enm->enm_addrlo)));
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+}
+#endif
+
+int
+gfe_hash_fill(struct gfe_softc *sc)
+{
+ struct ether_multistep step;
+ struct ether_multi *enm;
+ int error;
+
+ GE_FUNC_ENTER(sc, "gfe_hash_fill");
+
+#ifndef __rtems__
+ error = gfe_hash_entry_op(sc, GE_HASH_ADD, GE_RXPRIO_HI,
+ LLADDR(sc->sc_ec.ec_if.if_sadl));
+#else
+ error = gfe_hash_entry_op(sc, GE_HASH_ADD, GE_RXPRIO_HI, sc->sc_ec.ac_enaddr);
+#endif
+ if (error) {
+ GE_FUNC_EXIT(sc, "!");
+ return error;
+ }
+
+ sc->sc_flags &= ~GE_ALLMULTI;
+ if ((sc->sc_ec.ec_if.if_flags & IFF_PROMISC) == 0)
+ sc->sc_pcr &= ~ETH_EPCR_PM;
+ else
+ sc->sc_pcr |= ETH_EPCR_PM;
+ ETHER_FIRST_MULTI(step, &sc->sc_ec, enm);
+ while (enm != NULL) {
+ if (memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN)) {
+ sc->sc_flags |= GE_ALLMULTI;
+ sc->sc_pcr |= ETH_EPCR_PM;
+ } else {
+ error = gfe_hash_entry_op(sc, GE_HASH_ADD,
+ GE_RXPRIO_MEDLO, enm->enm_addrlo);
+ if (error == ENOSPC)
+ break;
+ }
+ ETHER_NEXT_MULTI(step, enm);
+ }
+
+ GE_FUNC_EXIT(sc, "");
+ return error;
+}
+
+int
+gfe_hash_alloc(struct gfe_softc *sc)
+{
+ int error;
+ GE_FUNC_ENTER(sc, "gfe_hash_alloc");
+ sc->sc_hashmask = (sc->sc_pcr & ETH_EPCR_HS_512 ? 16 : 256)*1024 - 1;
+ error = gfe_dmamem_alloc(sc, &sc->sc_hash_mem, 1, sc->sc_hashmask + 1,
+ BUS_DMA_NOCACHE);
+ if (error) {
+ printf("%s: failed to allocate %d bytes for hash table: %d\n",
+ sc->sc_dev.dv_xname, sc->sc_hashmask + 1, error);
+ GE_FUNC_EXIT(sc, "");
+ return error;
+ }
+ sc->sc_hashtable = (uint64_t *) sc->sc_hash_mem.gdm_kva;
+ memset(sc->sc_hashtable, 0, sc->sc_hashmask + 1);
+ bus_dmamap_sync(sc->sc_dmat, sc->sc_hash_mem.gdm_map,
+ 0, sc->sc_hashmask + 1, BUS_DMASYNC_PREWRITE);
+ GE_FUNC_EXIT(sc, "");
+ return 0;
+}
diff --git a/bsps/powerpc/beatnik/net/if_gfe/if_gfe_rtems.c b/bsps/powerpc/beatnik/net/if_gfe/if_gfe_rtems.c
new file mode 100644
index 0000000..9ed814e
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/if_gfe_rtems.c
@@ -0,0 +1,129 @@
+/* Author: T. Straumann <strauman@slac.stanford.edu>; see ../../LICENSE */
+#include "rtemscompat_defs.h"
+#include "../porting/rtemscompat.h"
+#include "gtethreg.h"
+
+#include <bsp/early_enet_link_status.h>
+#include <bsp/if_gfe_pub.h>
+#include <bsp/irq.h>
+
+/* from if_gfe.c */
+#define GE_READ(sc, reg) \
+ bus_space_read_4((sc)->sc_gt_memt, (sc)->sc_memh, ETH__ ## reg)
+#define GE_WRITE(sc, reg, v) \
+ bus_space_write_4((sc)->sc_gt_memt, (sc)->sc_memh, ETH__ ## reg, (v))
+
+#define GT_READ(sc, reg) \
+ bus_space_read_4((sc)->sc_gt_memt, (sc)->sc_gt_memh, reg)
+#define GT_WRITE(sc, reg, v) \
+ bus_space_write_4((sc)->sc_gt_memt, (sc)->sc_gt_memh, reg, (v))
+
+#include "../porting/if_xxx_rtems.c"
+
+#include <bsp.h>
+#include <libcpu/io.h>
+
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_setup)(
+ int unit,
+ char *ea,
+ uint32_t base_addr)
+{
+struct NET_SOFTC *sc;
+
+ if ( !ea ) {
+ fprintf(stderr,"Station address argument missing\n");
+ return 0;
+ }
+
+ if ( !(sc=net_drv_check_unit(unit)) ) {
+ fprintf(stderr,"Bad unit number -- (not enought driver slots?)\n");
+ return 0;
+ }
+
+ unit--;
+
+#ifdef DEBUG_MODULAR
+ if ( !METHODSPTR ) {
+ fprintf(stderr,"Methods not set -- module not loaded?\n");
+ return 0;
+ }
+#endif
+
+ if ( !base_addr ) {
+#ifdef BSP_MV64x60_BASE
+ base_addr = BSP_MV64x60_BASE;
+#else
+ fprintf(stderr,"Missing GT64260 base address\n");
+ return 0;
+#endif
+ }
+ sc->sc_gt_memh = base_addr;
+ /* must set this as well to indicate that the device is set up */
+ sc->NET_SOFTC_BHANDLE_FIELD = base_addr + 0x2400 + (unit<<10);
+ sc->sc_macno = unit;
+ memcpy( sc->arpcom.ac_enaddr, ea, ETHER_ADDR_LEN);
+
+ if ( 0 == METHODSPTR->n_probe(&THEDEVS[unit]) ) {
+ printf(NETDRIVER": Unit %i set up\n", unit + 1);
+ sc->irq_no = BSP_IRQ_ETH0 + unit;
+ return 1;
+ }
+ return 0;
+}
+
+static int
+gfe_early_init(int idx)
+{
+struct gfe_softc *sc;
+uint32_t d;
+
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+
+ sc = device_get_softc(&the_gfe_devs[idx]);
+ d = bus_space_read_4(sc->sc_gt_memt, sc->sc_gt_memh, ETH_EPAR);
+
+ sc->sc_phyaddr = ETH_EPAR_PhyAD_GET(d, sc->sc_macno);
+ sc->sc_dev.dv_xname = NETDRIVER;
+ return 0;
+}
+
+static int
+gfe_early_read_phy(int idx, unsigned reg)
+{
+uint32_t rval;
+struct gfe_softc *sc;
+
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+
+ sc = device_get_softc(&the_gfe_devs[idx]);
+
+ if ( gfe_mii_read( 0, sc, reg, &rval) )
+ return -1;
+ return rval & 0xffff;
+}
+
+
+static int
+gfe_early_write_phy(int idx, unsigned reg, unsigned val)
+{
+struct gfe_softc *sc;
+
+ if ( idx < 0 || idx >= NETDRIVER_SLOTS )
+ return -1;
+
+ sc = device_get_softc(&the_gfe_devs[idx]);
+
+ return gfe_mii_write( 0, sc, reg, val);
+}
+
+rtems_bsdnet_early_link_check_ops
+rtems_gfe_early_link_check_ops = {
+ init: gfe_early_init,
+ read_phy: gfe_early_read_phy,
+ write_phy: gfe_early_write_phy,
+ name: NETDRIVER,
+ num_slots: NETDRIVER_SLOTS
+};
diff --git a/bsps/powerpc/beatnik/net/if_gfe/if_gfevar.h b/bsps/powerpc/beatnik/net/if_gfe/if_gfevar.h
new file mode 100644
index 0000000..cbb9609
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/if_gfevar.h
@@ -0,0 +1,225 @@
+#ifndef IF_GFEVAR_H
+#define IF_GFEVAR_H
+/* $NetBSD: if_gfevar.h,v 1.4.10.1 2005/04/29 11:28:56 kent Exp $ */
+
+/*
+ * Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed for the NetBSD Project by
+ * Allegro Networks, Inc., and Wasabi Systems, Inc.
+ * 4. The name of Allegro Networks, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ * 5. The name of Wasabi Systems, Inc. may not be used to endorse
+ * or promote products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY ALLEGRO NETWORKS, INC. AND
+ * WASABI SYSTEMS, INC. ``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 EITHER ALLEGRO NETWORKS, INC. OR WASABI SYSTEMS, INC.
+ * 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.
+ */
+
+/* NOTE: GE_RXDESC_MAX * 16 <= GE_RXDESC_MEMSIZE */
+/* NOTE: the driver needs 4*GE_RXDESC_MAX mbuf clusters (4 queues) */
+#ifndef __rtems__
+#define GE_RXDESC_MEMSIZE (1 * PAGE_SIZE)
+#define GE_RXDESC_MAX 64
+#define GE_RXBUF_SIZE 2048
+#define GE_RXBUF_MEMSIZE (GE_RXDESC_MAX*GE_RXBUF_SIZE)
+#else
+#define GE_RXDESC_MEMSIZE (GE_RXDESC_MAX * sizeof(struct gt_eth_desc))
+#define GE_RXDESC_MAX (sc->num_rxdesc)
+#define GE_RXBUF_MEMSIZE 0
+#endif
+
+#define GE_RXBUF_NSEGS ((GE_RXBUF_MEMSIZE/PAGE_SIZE)+1)
+#define GE_DMSEG_MAX (GE_RXBUF_NSEGS)
+
+struct gfe_dmamem {
+ bus_dmamap_t gdm_map; /* dmamem'ed memory */
+#ifdef __rtems__
+ void *gdm_unaligned_buf;
+#endif
+ caddr_t gdm_kva; /* kva of tx memory */
+ int gdm_nsegs; /* # of segment in gdm_segs */
+ int gdm_maxsegs; /* maximum # of segments allowed */
+ size_t gdm_size; /* size of memory region */
+ bus_dma_segment_t gdm_segs[GE_DMSEG_MAX]; /* dma segment of tx memory */
+};
+
+/* With a 4096 page size, we get 256 descriptors per page.
+ */
+#ifndef __rtems__
+#define GE_TXDESC_MEMSIZE (1 * PAGE_SIZE)
+#define GE_TXDESC_MAX (GE_TXDESC_MEMSIZE / 16)
+#define GE_TXBUF_SIZE (4 * PAGE_SIZE)
+#else
+#define GE_TXDESC_MEMSIZE (sc->num_txdesc * sizeof(struct gt_eth_desc))
+#define GE_TXDESC_MAX (sc->num_txdesc)
+#endif
+
+struct gfe_txqueue {
+ struct ifqueue txq_pendq; /* these are ready to go to the GT */
+ struct ifqueue txq_sentq;
+ struct gfe_dmamem txq_desc_mem; /* transmit descriptor memory */
+#ifndef __rtems__
+ struct gfe_dmamem txq_buf_mem; /* transmit buffer memory */
+#endif
+ unsigned int txq_lo; /* next to be given to GT */
+ unsigned int txq_fi; /* next to be returned to CPU */
+#ifndef __rtems__
+ unsigned int txq_ei_gapcount; /* counter until next EI */
+#endif
+ unsigned int txq_nactive; /* number of active descriptors */
+#ifndef __rtems__
+ unsigned int txq_outptr; /* where to put next transmit packet */
+ unsigned int txq_inptr; /* start of 1st queued tx packet */
+#endif
+ uint32_t txq_intrbits; /* bits to write to EIMR */
+ uint32_t txq_esdcmrbits; /* bits to write to ESDCMR */
+ uint32_t txq_epsrbits; /* bits to test with EPSR */
+ volatile struct gt_eth_desc *txq_descs; /* ptr to tx descriptors */
+ bus_addr_t txq_ectdp; /* offset to cur. tx desc ptr reg */
+ bus_addr_t txq_desc_busaddr; /* bus addr of tx descriptors */
+#ifndef __rtems__
+ bus_addr_t txq_buf_busaddr; /* bus addr of tx buffers */
+#endif
+};
+
+/* With a 4096 page size, we get 256 descriptors per page. We want 1024
+ * which will give us about 8ms of 64 byte packets (2ms for each priority
+ * queue).
+ */
+
+#ifndef __rtems__
+struct gfe_rxbuf {
+ uint8_t rb_data[GE_RXBUF_SIZE];
+};
+#endif
+
+struct gfe_rxqueue {
+ struct gfe_dmamem rxq_desc_mem; /* receive descriptor memory */
+#ifndef __rtems__
+ struct gfe_dmamem rxq_buf_mem; /* receive buffer memory */
+ struct mbuf *rxq_curpkt; /* mbuf for current packet */
+#endif
+ volatile struct gt_eth_desc *rxq_descs;
+#ifndef __rtems__
+ struct gfe_rxbuf *rxq_bufs;
+#else
+ struct mbuf **rxq_bufs;
+#endif
+ unsigned int rxq_fi; /* next to be returned to CPU */
+ unsigned int rxq_active; /* # of descriptors given to GT */
+ uint32_t rxq_intrbits; /* bits to write to EIMR */
+ bus_addr_t rxq_desc_busaddr; /* bus addr of rx descriptors */
+ uint32_t rxq_cmdsts; /* save cmdsts from first descriptor */
+ bus_size_t rxq_efrdp;
+ bus_size_t rxq_ecrdp;
+};
+
+enum gfe_txprio {
+ GE_TXPRIO_HI=1,
+ GE_TXPRIO_LO=0,
+ GE_TXPRIO_NONE=2
+};
+enum gfe_rxprio {
+ GE_RXPRIO_HI=3,
+ GE_RXPRIO_MEDHI=2,
+ GE_RXPRIO_MEDLO=1,
+ GE_RXPRIO_LO=0
+};
+
+#ifdef __rtems__
+#define sc_ec arpcom
+#define ec_if ac_if
+#define sc_dev arpcom
+#define dv_xname ac_if.if_name
+#endif
+
+struct gfe_softc {
+#ifndef __rtems__
+ struct device sc_dev; /* must be first */
+ struct ethercom sc_ec; /* common ethernet glue */
+ struct callout sc_co; /* resource recovery */
+ mii_data_t sc_mii; /* mii interface */
+
+ /*
+ *
+ */
+ bus_space_tag_t sc_gt_memt;
+ bus_space_handle_t sc_gt_memh;
+ bus_space_handle_t sc_memh; /* subregion for ethernet */
+ bus_dma_tag_t sc_dmat;
+#else
+ struct arpcom sc_ec;
+ unsigned sc_gt_memh;
+ unsigned sc_memh;
+ unsigned char irq_no;
+ rtems_id tid;
+ int sc_phyaddr;
+ int num_rxdesc, num_txdesc;
+#endif
+ int sc_macno; /* which mac? 0, 1, or 2 */
+
+ unsigned int sc_tickflags;
+#define GE_TICK_TX_IFSTART 0x0001
+#define GE_TICK_RX_RESTART 0x0002
+ unsigned int sc_flags;
+#define GE_ALLMULTI 0x0001
+#define GE_PHYSTSCHG 0x0002
+#define GE_RXACTIVE 0x0004
+#define GE_NOFREE 0x0008 /* Don't free on disable */
+ uint32_t sc_pcr; /* current EPCR value */
+ uint32_t sc_pcxr; /* current EPCXR value */
+ uint32_t sc_intrmask; /* current EIMR value */
+ uint32_t sc_idlemask; /* suspended EIMR bits */
+ size_t sc_max_frame_length; /* maximum frame length */
+
+ /*
+ * Hash table related members
+ */
+ struct gfe_dmamem sc_hash_mem; /* dma'ble hash table */
+ uint64_t *sc_hashtable;
+ unsigned int sc_hashmask; /* 0x1ff or 0x1fff */
+
+ /*
+ * Transmit related members
+ */
+ struct gfe_txqueue sc_txq[2]; /* High & Low transmit queues */
+
+ /*
+ * Receive related members
+ */
+ struct gfe_rxqueue sc_rxq[4]; /* Hi/MedHi/MedLo/Lo receive queues */
+};
+
+#ifdef __rtems__
+int
+gfe_mii_read(int phy, void *arg, unsigned reg, uint32_t *pval);
+
+int
+gfe_mii_write(int phy, void *arg, unsigned reg, uint32_t value);
+#endif
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/if_gfe/rtemscompat_defs.h b/bsps/powerpc/beatnik/net/if_gfe/rtemscompat_defs.h
new file mode 100644
index 0000000..971b1d3
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_gfe/rtemscompat_defs.h
@@ -0,0 +1,161 @@
+#ifndef RTEMS_COMPAT_DEFS_H
+#define RTEMS_COMPAT_DEFS_H
+
+#include <stdint.h>
+#include <stddef.h>
+
+/* Number of device instances the driver should support
+ * - may be limited to 1 depending on IRQ API
+ * (braindamaged PC586 and powerpc)
+ */
+#define NETDRIVER_SLOTS 1
+/* String name to print with error messages */
+#define NETDRIVER "gfe"
+/* Name snippet used to make global symbols unique to this driver */
+#define NETDRIVER_PREFIX gfe
+
+/* Define according to endianness of the *ethernet*chip*
+ * (not the CPU - most probably are LE)
+ * This must be either NET_CHIP_LE or NET_CHIP_BE
+ */
+
+#define NET_CHIP_LE
+#undef NET_CHIP_BE
+
+/* Define either NET_CHIP_MEM_IO or NET_CHIP_PORT_IO,
+ * depending whether the CPU sees it in memory address space
+ * or (e.g. x86) uses special I/O instructions.
+ */
+#define NET_CHIP_MEM_IO
+#undef NET_CHIP_PORT_IO
+
+/* The name of the hijacked 'bus handle' field in the softc
+ * structure. We use this field to store the chip's base address.
+ */
+#define NET_SOFTC_BHANDLE_FIELD sc_memh
+
+/* define the names of the 'if_XXXreg.h' and 'if_XXXvar.h' headers
+ * (only if present, i.e., if the BSDNET driver has no respective
+ * header, leave this undefined).
+ *
+ */
+#undef IF_REG_HEADER
+#define IF_VAR_HEADER "../if_gfe/if_gfevar.h"
+
+/* define if a pci device */
+/*
+#define NETDRIVER_PCI <bsp/pci.h>
+*/
+#undef NETDRIVER_PCI
+
+/* Macros to disable and enable interrupts, respectively.
+ * The 'disable' macro is expanded in the ISR, the 'enable'
+ * macro is expanded in the driver task.
+ * The global network semaphore usually provides mutex
+ * protection of the device registers.
+ * Special care must be taken when coding the 'disable' macro,
+ * however to MAKE SURE THERE ARE NO OTHER SIDE EFFECTS such
+ * as:
+ * - macro must not clear any status flags
+ * - macro must save/restore any context information
+ * (e.g., a address register pointer or a bank switch register)
+ *
+ * ARGUMENT: the macro arg is a pointer to the driver's 'softc' structure
+ */
+
+#define NET_DISABLE_IRQS(sc) GE_WRITE(sc, EIMR, 0)
+#define NET_ENABLE_IRQS(sc) GE_WRITE(sc, EIMR, sc->sc_intrmask)
+
+/* Driver may provide a macro/function to copy the hardware address
+ * from the device into 'softc.arpcom'.
+ * If this is undefined, the driver must to the copy itself.
+ * Preferrably, it should check soft.arpcom.ac_enaddr for all
+ * zeros and leave it alone if it is nonzero, i.e., write it
+ * to the hardware.
+#define NET_READ_MAC_ADDR(sc)
+ */
+
+typedef struct {
+ uint32_t ds_addr;
+ uint32_t ds_len;
+} bus_dma_segment_t;
+
+#define dm_segs gdm_segs
+#define dm_nsegs gdm_nsegs
+typedef struct gfe_dmamem *bus_dmamap_t;
+
+typedef uint32_t bus_addr_t;
+typedef uint32_t bus_size_t;
+
+typedef struct device blah;
+
+#define BUS_DMA_NOCACHE 0xdeadbeef
+
+#ifdef __PPC__
+#define bus_dmamap_sync(args...) do { __asm__ volatile("sync":::"memory"); } while(0)
+#else
+#error "Dont' know how to sync memory on your CPU"
+#endif
+
+int ether_sprintf_r(const unsigned char *enaddr, char *buf, int len);
+
+/* we have it although we're not ansi */
+int snprintf(char *, size_t, const char *,...);
+
+#include <string.h>
+
+/* declare in every routine using ether_sprintf */
+#define SPRINTFVARDECL char rtems_sprintf_local_buf[3*6] /* ethernet string */
+
+#define ether_sprintf_macro(a) \
+ (snprintf(rtems_sprintf_local_buf, \
+ sizeof(rtems_sprintf_local_buf), \
+ "%02X:%02X:%02X:%02X:%02X:%02X", \
+ a[0],a[1],a[2],a[3],a[4],a[5]) ? \
+ rtems_sprintf_local_buf : 0 \
+ )
+
+
+#define aprint_normal(args...) printf(args)
+#define aprint_error(args...) fprintf(stderr,args)
+
+#define delay(arg) DELAY(arg)
+
+#define KASSERT(a...) do {} while (0)
+
+#define gfe_assign_desc _bsd_gfe_assign_desc
+#define gfe_attach _bsd_gfe_attach
+#define gfe_dbg_config _bsd_gfe_dbg_config
+#define gfe_dmamem_alloc _bsd_gfe_dmamem_alloc
+#define gfe_dmamem_free _bsd_gfe_dmamem_free
+#define gfe_hash_alloc _bsd_gfe_hash_alloc
+#define gfe_hash_compute _bsd_gfe_hash_compute
+#define gfe_hash_entry_op _bsd_gfe_hash_entry_op
+#define gfe_hash_fill _bsd_gfe_hash_fill
+#define gfe_ifioctl _bsd_gfe_ifioctl
+#define gfe_ifstart _bsd_gfe_ifstart
+#define gfe_ifwatchdog _bsd_gfe_ifwatchdog
+#define gfe_init _bsd_gfe_init
+#define gfe_intr _bsd_gfe_intr
+#define gfe_mdio_access _bsd_gfe_mdio_access
+#define gfe_mii_read _bsd_gfe_mii_read
+#define gfe_mii_write _bsd_gfe_mii_write
+#define gfe_probe _bsd_gfe_probe
+#define gfe_rx_cleanup _bsd_gfe_rx_cleanup
+#define gfe_rx_get _bsd_gfe_rx_get
+#define gfe_rx_prime _bsd_gfe_rx_prime
+#define gfe_rx_process _bsd_gfe_rx_process
+#define gfe_rx_rxqalloc _bsd_gfe_rx_rxqalloc
+#define gfe_rx_rxqinit _bsd_gfe_rx_rxqinit
+#define gfe_rx_stop _bsd_gfe_rx_stop
+#define gfe_tick _bsd_gfe_tick
+#define gfe_tx_cleanup _bsd_gfe_tx_cleanup
+#define gfe_tx_done _bsd_gfe_tx_done
+#define gfe_tx_enqueue _bsd_gfe_tx_enqueue
+#define gfe_tx_start _bsd_gfe_tx_start
+#define gfe_tx_stop _bsd_gfe_tx_stop
+#define gfe_tx_txqalloc _bsd_gfe_tx_txqalloc
+#define gfe_whack _bsd_gfe_whack
+#define the_gfe_devs _bsd_the_gfe_devs
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c
new file mode 100644
index 0000000..85ab038
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_mve/mv643xx_eth.c
@@ -0,0 +1,3318 @@
+/* RTEMS driver for the mv643xx gigabit ethernet chip */
+
+/* Acknowledgement:
+ *
+ * Valuable information for developing this driver was obtained
+ * from the linux open-source driver mv643xx_eth.c which was written
+ * by the following people and organizations:
+ *
+ * Matthew Dharm <mdharm@momenco.com>
+ * rabeeh@galileo.co.il
+ * PMC-Sierra, Inc., Manish Lachwani
+ * Ralf Baechle <ralf@linux-mips.org>
+ * MontaVista Software, Inc., Dale Farnsworth <dale@farnsworth.org>
+ * Steven J. Hill <sjhill1@rockwellcollins.com>/<sjhill@realitydiluted.com>
+ *
+ * Note however, that in spite of the identical name of this file
+ * (and some of the symbols used herein) this file provides a
+ * new implementation and is the original work by the author.
+ */
+
+/*
+ * Authorship
+ * ----------
+ * This software (mv643xx ethernet driver for RTEMS) was
+ * created by Till Straumann <strauman@slac.stanford.edu>, 2005-2007,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * The 'mv643xx ethernet driver for RTEMS' was produced by
+ * the Stanford Linear Accelerator Center, Stanford University,
+ * under Contract DE-AC03-76SFO0515 with the Department of Energy.
+ *
+ * Government disclaimer of liability
+ * ----------------------------------
+ * Neither the United States nor the United States Department of Energy,
+ * nor any of their employees, makes any warranty, express or implied, or
+ * assumes any legal liability or responsibility for the accuracy,
+ * completeness, or usefulness of any data, apparatus, product, or process
+ * disclosed, or represents that its use would not infringe privately owned
+ * rights.
+ *
+ * Stanford disclaimer of liability
+ * --------------------------------
+ * Stanford University makes no representations or warranties, express or
+ * implied, nor assumes any liability for the use of this software.
+ *
+ * Stanford disclaimer of copyright
+ * --------------------------------
+ * Stanford University, owner of the copyright, hereby disclaims its
+ * copyright and all other rights in this software. Hence, anyone may
+ * freely use it for any purpose without restriction.
+ *
+ * Maintenance of notices
+ * ----------------------
+ * In the interest of clarity regarding the origin and status of this
+ * SLAC software, this and all the preceding Stanford University notices
+ * are to remain affixed to any copy or derivative of this software made
+ * or distributed by the recipient and are to be affixed to any copy of
+ * software made or distributed by the recipient that contains a copy or
+ * derivative of this software.
+ *
+ * ------------------ SLAC Software Notices, Set 4 OTT.002a, 2004 FEB 03
+ */
+
+/*
+ * NOTE: Some register (e.g., the SMI register) are SHARED among the
+ * three devices. Concurrent access protection is provided by
+ * the global networking semaphore.
+ * If other drivers are running on a subset of IFs then proper
+ * locking of all shared registers must be implemented!
+ *
+ * Some things I learned about this hardware can be found
+ * further down...
+ */
+
+#ifndef KERNEL
+#define KERNEL
+#endif
+#ifndef _KERNEL
+#define _KERNEL
+#endif
+
+#include <rtems.h>
+#include <rtems/bspIo.h>
+#include <rtems/error.h>
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <bsp/gtreg.h>
+#include <libcpu/byteorder.h>
+
+#include <sys/param.h>
+#include <sys/proc.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <dev/mii/mii.h>
+#include <net/if_var.h>
+#include <net/if_media.h>
+
+/* Not so nice; would be more elegant not to depend on C library but the
+ * RTEMS-specific ioctl for dumping statistics needs stdio anyways.
+ */
+
+/*#define NDEBUG effectively removes all assertions
+ * If defining NDEBUG, MAKE SURE assert() EXPRESSION HAVE NO SIDE_EFFECTS!!
+ * This driver DOES have side-effects, so DONT DEFINE NDEBUG
+ * Performance-critical assertions are removed by undefining MVETH_TESTING.
+ */
+
+#undef NDEBUG
+#include <assert.h>
+#include <stdio.h>
+#include <errno.h>
+#include <inttypes.h>
+
+#include <rtems/rtems_bsdnet.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/ethernet.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <rtems/rtems_mii_ioctl.h>
+#include <bsp/early_enet_link_status.h>
+#include <bsp/if_mve_pub.h>
+
+/* CONFIGURABLE PARAMETERS */
+
+/* Enable Hardware Snooping; if this is disabled (undefined),
+ * cache coherency is maintained by software.
+ */
+#undef ENABLE_HW_SNOOPING
+
+/* Compile-time debugging features */
+
+/* Enable paranoia assertions and checks; reduce # of descriptors to minimum for stressing */
+#undef MVETH_TESTING
+
+/* Enable debugging messages and some support routines (dump rings etc.) */
+#undef MVETH_DEBUG
+
+/* Hack for driver development; rtems bsdnet doesn't implement detaching an interface :-(
+ * but this hack allows us to unload/reload the driver module which makes development
+ * a lot less painful.
+ */
+#undef MVETH_DETACH_HACK
+
+/* Ring sizes */
+
+#ifdef MVETH_TESTING
+
+/* hard and small defaults */
+#undef MV643XX_RX_RING_SIZE
+#define MV643XX_RX_RING_SIZE 2
+#undef MV643XX_TX_RING_SIZE
+#define MV643XX_TX_RING_SIZE 4
+
+#else /* MVETH_TESTING */
+
+/* Define default ring sizes, allow override from bsp.h, Makefile,... and from ifcfg->rbuf_count/xbuf_count */
+
+#ifndef MV643XX_RX_RING_SIZE
+#define MV643XX_RX_RING_SIZE 40 /* attached buffers are always 2k clusters, i.e., this
+ * driver - with a configured ring size of 40 - constantly
+ * locks 80k of cluster memory - your app config better
+ * provides enough space!
+ */
+#endif
+
+#ifndef MV643XX_TX_RING_SIZE
+/* NOTE: tx ring size MUST be > max. # of fragments / mbufs in a chain;
+ * in 'TESTING' mode, special code is compiled in to repackage
+ * chains that are longer than the ring size. Normally, this is
+ * disabled for sake of speed.
+ * I observed chains of >17 entries regularly!
+ *
+ * Also, TX_NUM_TAG_SLOTS (1) must be left empty as a marker, hence
+ * the ring size must be > max. #frags + 1.
+ */
+#define MV643XX_TX_RING_SIZE 200 /* these are smaller fragments and not occupied when
+ * the driver is idle.
+ */
+#endif
+
+#endif /* MVETH_TESTING */
+
+/* How many instances to we support (bsp.h could override) */
+#ifndef MV643XXETH_NUM_DRIVER_SLOTS
+#define MV643XXETH_NUM_DRIVER_SLOTS 2
+#endif
+
+#define TX_NUM_TAG_SLOTS 1 /* leave room for tag; must not be 0 */
+
+/* This is REAL; chip reads from 64-bit down-aligned buffer
+ * if the buffer size is < 8 !!! for buffer sizes 8 and upwards
+ * alignment is not an issue. This was verified using the
+ * 'mve_smallbuf_test.c'
+ */
+#define ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
+
+/* Chip register configuration values */
+#define MVETH_PORT_CONFIG_VAL (0 \
+ | MV643XX_ETH_DFLT_RX_Q(0) \
+ | MV643XX_ETH_DFLT_RX_ARP_Q(0) \
+ | MV643XX_ETH_DFLT_RX_TCP_Q(0) \
+ | MV643XX_ETH_DFLT_RX_UDP_Q(0) \
+ | MV643XX_ETH_DFLT_RX_BPDU_Q(0) \
+ )
+
+
+#define MVETH_PORT_XTEND_CONFIG_VAL 0
+
+#ifdef OLDCONFIGVAL
+#define MVETH_SERIAL_CTRL_CONFIG_VAL (0 \
+ | MV643XX_ETH_FORCE_LINK_PASS \
+ | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_FLOWCTL \
+ | MV643XX_ETH_ADVERTISE_SYMMETRIC_FLOWCTL \
+ | MV643XX_ETH_BIT9_UNKNOWN \
+ | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE \
+ | MV643XX_ETH_SC_MAX_RX_1552 \
+ | MV643XX_ETH_SET_FULL_DUPLEX \
+ | MV643XX_ETH_ENBL_FLOWCTL_TX_RX_IN_FD \
+ )
+#endif
+/* If we enable autoneg (duplex, speed, ...) then it seems
+ * that the chip automatically updates link settings
+ * (correct link settings are reflected in PORT_STATUS_R).
+ * However, when we disable aneg in the PHY then things
+ * can get messed up and the port doesn't work anymore.
+ * => we follow the linux driver in disabling all aneg
+ * in the serial config reg. and manually updating the
+ * speed & duplex bits when the phy link status changes.
+ * FIXME: don't know what to do about pause/flow-ctrl.
+ * It is best to just use ANEG anyways!!!
+ */
+#define MVETH_SERIAL_CTRL_CONFIG_VAL (0 \
+ | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_DUPLEX \
+ | MV643XX_ETH_DISABLE_AUTO_NEG_FOR_FLOWCTL \
+ | MV643XX_ETH_ADVERTISE_SYMMETRIC_FLOWCTL \
+ | MV643XX_ETH_BIT9_UNKNOWN \
+ | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE \
+ | MV643XX_ETH_DISABLE_AUTO_NEG_SPEED_GMII \
+ | MV643XX_ETH_SC_MAX_RX_1552 \
+ )
+
+#define MVETH_SERIAL_CTRL_CONFIG_MSK (0 \
+ | MV643XX_ETH_SERIAL_PORT_ENBL \
+ | MV643XX_ETH_FORCE_LINK_PASS \
+ | MV643XX_ETH_SC_MAX_RX_MASK \
+ )
+
+
+#ifdef __PPC__
+#define MVETH_SDMA_CONFIG_VAL (0 \
+ | MV643XX_ETH_RX_BURST_SZ_4_64BIT \
+ | MV643XX_ETH_TX_BURST_SZ_4_64BIT \
+ )
+#else
+#define MVETH_SDMA_CONFIG_VAL (0 \
+ | MV643XX_ETH_RX_BURST_SZ_16_64BIT \
+ | MV643XX_ETH_TX_BURST_SZ_16_64BIT \
+ )
+#endif
+
+/* minimal frame size we accept */
+#define MVETH_MIN_FRAMSZ_CONFIG_VAL 40
+
+/* END OF CONFIGURABLE SECTION */
+
+/*
+ * Here's stuff I learned about this chip:
+ *
+ *
+ * RX interrupt flags:
+ *
+ * broadcast packet RX: 0x00000005
+ * last buf: 0x00000c05
+ * overrun: 0x00000c00
+ * unicast packet RX: 0x00000005
+ * bad CRC received: 0x00000005
+ *
+ * clearing 0x00000004 -> clears 0x00000001
+ * clearing 0x00000400 -> clears 0x00000800
+ *
+ * --> 0x0801 are probably some sort of summary bits.
+ *
+ * TX interrupt flags:
+ *
+ * broadcast packet in 1 buf: xcause: 0x00000001 (cause 0x00080000)
+ * into disconn. link: " "
+ *
+ * in some cases, I observed xcause: 0x00000101 (reason for 0x100 unknown
+ * but the linux driver accepts it also).
+ *
+ *
+ * Here a few more ugly things about this piece of hardware I learned
+ * (painfully, painfully; spending many many hours & nights :-()
+ *
+ * a) Especially in the case of 'chained' descriptors, the DMA keeps
+ * clobbering 'cmd_sts' long after it cleared the OWNership flag!!!
+ * Only after the whole chain is processed (OWN cleared on the
+ * last descriptor) it is safe to change cmd_sts.
+ * However, in the case of hardware snooping I found that the
+ * last descriptor in chain has its cmd_sts still clobbered *after*
+ * checking ownership!, I.e.,
+ * if ( ! OWN & cmd_sts ) {
+ * cmd_sts = 0;
+ * }
+ * --> sometimes, cmd_sts is STILL != 0 here
+ *
+ * b) Sometimes, the OWNership flag is *not cleared*.
+ *
+ * c) Weird things happen if the chip finds a descriptor with 'OWN'
+ * still set (i.e., not properly loaded), i.e., corrupted packets
+ * are sent [with OK checksum since the chip calculates it].
+ *
+ * Combine a+b+c and we end up with a real mess.
+ *
+ * The fact that the chip doesn't reliably reset OWN and that OTOH,
+ * it can't be reliably reset by the driver and still, the chip needs
+ * it for proper communication doesn't make things easy...
+ *
+ * Here the basic workarounds:
+ *
+ * - In addition to check OWN, the scavenger compares the "currently
+ * served desc" register to the descriptor it tries to recover and
+ * ignores OWN if they do not match. Hope this is OK.
+ * Otherwise, we could scan the list of used descriptors and proceed
+ * recycling descriptors if we find a !OWNed one behind the target...
+ *
+ * - Always keep an empty slot around to mark the end of the list of
+ * jobs. The driver clears the descriptor ahead when enqueueing a new
+ * packet.
+ */
+
+#define DRVNAME "mve"
+#define MAX_NUM_SLOTS 3
+
+#if MV643XXETH_NUM_DRIVER_SLOTS > MAX_NUM_SLOTS
+#error "mv643xxeth: only MAX_NUM_SLOTS supported"
+#endif
+
+#ifdef NDEBUG
+#error "Driver uses assert() statements with side-effects; MUST NOT define NDEBUG"
+#endif
+
+#ifdef MVETH_DEBUG
+#define STATIC
+#else
+#define STATIC static
+#endif
+
+#define TX_AVAILABLE_RING_SIZE(mp) ((mp)->xbuf_count - (TX_NUM_TAG_SLOTS))
+
+/* macros for ring alignment; proper alignment is a hardware req; . */
+
+#ifdef ENABLE_HW_SNOOPING
+
+#define RING_ALIGNMENT 16
+/* rx buffers must be 64-bit aligned (chip requirement) */
+#define RX_BUF_ALIGNMENT 8
+
+#else /* ENABLE_HW_SNOOPING */
+
+/* Software cache management */
+
+#ifndef __PPC__
+#error "Dont' know how to deal with cache on this CPU architecture"
+#endif
+
+/* Ring entries are 32 bytes; coherency-critical chunks are 16 -> software coherency
+ * management works for cache line sizes of 16 and 32 bytes only. If the line size
+ * is bigger, the descriptors could be padded...
+ */
+#if PPC_CACHE_ALIGMENT != 16 && PPC_CACHE_ALIGNMENT != 32
+#error "Cache line size must be 16 or 32"
+#else
+#define RING_ALIGNMENT PPC_CACHE_ALIGNMENT
+#define RX_BUF_ALIGNMENT PPC_CACHE_ALIGNMENT
+#endif
+
+#endif /* ENABLE_HW_SNOOPING */
+
+
+/* HELPER MACROS */
+
+/* Align base to alignment 'a' */
+#define MV643XX_ALIGN(b, a) ((((uint32_t)(b)) + (a)-1) & (~((a)-1)))
+
+#define NOOP() do {} while(0)
+
+/* Function like macros */
+#define MV_READ(off) \
+ ld_le32((volatile uint32_t *)(BSP_MV64x60_BASE + (off)))
+#define MV_WRITE(off, data) \
+ st_le32((volatile uint32_t *)(BSP_MV64x60_BASE + (off)), ((unsigned)data))
+
+
+/* ENET window mapped 1:1 to CPU addresses by our BSP/MotLoad
+ * -- if this is changed, we should think about caching the 'next' and 'buf' pointers.
+ */
+#define CPUADDR2ENET(a) ((Dma_addr_t)(a))
+#define ENET2CPUADDR(a) (a)
+
+#if 1 /* Whether to automatically try to reclaim descriptors when enqueueing new packets */
+#define MVETH_CLEAN_ON_SEND(mp) (BSP_mve_swipe_tx(mp))
+#else
+#define MVETH_CLEAN_ON_SEND(mp) (-1)
+#endif
+
+#define NEXT_TXD(d) (d)->next
+#define NEXT_RXD(d) (d)->next
+
+/* REGISTER AND DESCRIPTOR OFFSET AND BIT DEFINITIONS */
+
+/* Descriptor Definitions */
+/* Rx descriptor */
+#define RDESC_ERROR (1<< 0) /* Error summary */
+
+/* Error code (bit 1&2) is only valid if summary bit is set */
+#define RDESC_CRC_ERROR ( 1)
+#define RDESC_OVERRUN_ERROR ( 3)
+#define RDESC_MAX_FRAMELENGTH_ERROR ( 5)
+#define RDESC_RESOURCE_ERROR ( 7)
+
+#define RDESC_LAST (1<<26) /* Last Descriptor */
+#define RDESC_FRST (1<<27) /* First Descriptor */
+#define RDESC_INT_ENA (1<<29) /* Enable Interrupts */
+#define RDESC_DMA_OWNED (1<<31)
+
+/* Tx descriptor */
+#define TDESC_ERROR (1<< 0) /* Error summary */
+#define TDESC_ZERO_PAD (1<<19)
+#define TDESC_LAST (1<<20) /* Last Descriptor */
+#define TDESC_FRST (1<<21) /* First Descriptor */
+#define TDESC_GEN_CRC (1<<22)
+#define TDESC_INT_ENA (1<<23) /* Enable Interrupts */
+#define TDESC_DMA_OWNED (1<<31)
+
+
+
+/* Register Definitions */
+#define MV643XX_ETH_PHY_ADDR_R (0x2000)
+#define MV643XX_ETH_SMI_R (0x2004)
+#define MV643XX_ETH_SMI_BUSY (1<<28)
+#define MV643XX_ETH_SMI_VALID (1<<27)
+#define MV643XX_ETH_SMI_OP_WR (0<<26)
+#define MV643XX_ETH_SMI_OP_RD (1<<26)
+
+#define MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port) (0x2448 + ((port)<<10))
+#define MV643XX_ETH_TX_START(queue) (0x0001<<(queue))
+#define MV643XX_ETH_TX_STOP(queue) (0x0100<<(queue))
+#define MV643XX_ETH_TX_START_M(queues) ((queues)&0xff)
+#define MV643XX_ETH_TX_STOP_M(queues) (((queues)&0xff)<<8)
+#define MV643XX_ETH_TX_STOP_ALL (0xff00)
+#define MV643XX_ETH_TX_ANY_RUNNING (0x00ff)
+
+#define MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(port) (0x2680 + ((port)<<10))
+#define MV643XX_ETH_RX_START(queue) (0x0001<<(queue))
+#define MV643XX_ETH_RX_STOP(queue) (0x0100<<(queue))
+#define MV643XX_ETH_RX_STOP_ALL (0xff00)
+#define MV643XX_ETH_RX_ANY_RUNNING (0x00ff)
+
+#define MV643XX_ETH_CURRENT_SERVED_TX_DESC(port) (0x2684 + ((port)<<10))
+
+/* The chip puts the ethernet header at offset 2 into the buffer so
+ * that the payload is aligned
+ */
+#define ETH_RX_OFFSET 2
+#define ETH_CRC_LEN 4 /* strip FCS at end of packet */
+
+
+#define MV643XX_ETH_INTERRUPT_CAUSE_R(port) (0x2460 + ((port)<<10))
+/* not fully understood; RX seems to raise 0x0005 or 0x0c05 if last buffer is filled and 0x0c00
+ * if there are no buffers
+ */
+#define MV643XX_ETH_ALL_IRQS (0x0007ffff)
+#define MV643XX_ETH_KNOWN_IRQS (0x00000c05)
+#define MV643XX_ETH_IRQ_EXT_ENA (1<<1)
+#define MV643XX_ETH_IRQ_RX_DONE (1<<2)
+#define MV643XX_ETH_IRQ_RX_NO_DESC (1<<10)
+
+#define MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(port) (0x2464 + ((port)<<10))
+/* not fully understood; TX seems to raise 0x0001 and link change is 0x00010000
+ * if there are no buffers
+ */
+#define MV643XX_ETH_ALL_EXT_IRQS (0x0011ffff)
+#define MV643XX_ETH_KNOWN_EXT_IRQS (0x00010101)
+#define MV643XX_ETH_EXT_IRQ_TX_DONE (1<<0)
+#define MV643XX_ETH_EXT_IRQ_LINK_CHG (1<<16)
+#define MV643XX_ETH_INTERRUPT_ENBL_R(port) (0x2468 + ((port)<<10))
+#define MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(port) (0x246c + ((port)<<10))
+
+/* port configuration */
+#define MV643XX_ETH_PORT_CONFIG_R(port) (0x2400 + ((port)<<10))
+#define MV643XX_ETH_UNICAST_PROMISC_MODE (1<<0)
+#define MV643XX_ETH_DFLT_RX_Q(q) ((q)<<1)
+#define MV643XX_ETH_DFLT_RX_ARP_Q(q) ((q)<<4)
+#define MV643XX_ETH_REJ_BCAST_IF_NOT_IP_OR_ARP (1<<7)
+#define MV643XX_ETH_REJ_BCAST_IF_IP (1<<8)
+#define MV643XX_ETH_REJ_BCAST_IF_ARP (1<<9)
+#define MV643XX_ETH_TX_AM_NO_UPDATE_ERR_SUMMARY (1<<12)
+#define MV643XX_ETH_CAPTURE_TCP_FRAMES_ENBL (1<<14)
+#define MV643XX_ETH_CAPTURE_UDP_FRAMES_ENBL (1<<15)
+#define MV643XX_ETH_DFLT_RX_TCP_Q(q) ((q)<<16)
+#define MV643XX_ETH_DFLT_RX_UDP_Q(q) ((q)<<19)
+#define MV643XX_ETH_DFLT_RX_BPDU_Q(q) ((q)<<22)
+
+
+
+#define MV643XX_ETH_PORT_CONFIG_XTEND_R(port) (0x2404 + ((port)<<10))
+#define MV643XX_ETH_CLASSIFY_ENBL (1<<0)
+#define MV643XX_ETH_SPAN_BPDU_PACKETS_AS_NORMAL (0<<1)
+#define MV643XX_ETH_SPAN_BPDU_PACKETS_2_Q7 (1<<1)
+#define MV643XX_ETH_PARTITION_DISBL (0<<2)
+#define MV643XX_ETH_PARTITION_ENBL (1<<2)
+
+#define MV643XX_ETH_SDMA_CONFIG_R(port) (0x241c + ((port)<<10))
+#define MV643XX_ETH_SDMA_RIFB (1<<0)
+#define MV643XX_ETH_RX_BURST_SZ_1_64BIT (0<<1)
+#define MV643XX_ETH_RX_BURST_SZ_2_64BIT (1<<1)
+#define MV643XX_ETH_RX_BURST_SZ_4_64BIT (2<<1)
+#define MV643XX_ETH_RX_BURST_SZ_8_64BIT (3<<1)
+#define MV643XX_ETH_RX_BURST_SZ_16_64BIT (4<<1)
+#define MV643XX_ETH_SMDA_BLM_RX_NO_SWAP (1<<4)
+#define MV643XX_ETH_SMDA_BLM_TX_NO_SWAP (1<<5)
+#define MV643XX_ETH_SMDA_DESC_BYTE_SWAP (1<<6)
+#define MV643XX_ETH_TX_BURST_SZ_1_64BIT (0<<22)
+#define MV643XX_ETH_TX_BURST_SZ_2_64BIT (1<<22)
+#define MV643XX_ETH_TX_BURST_SZ_4_64BIT (2<<22)
+#define MV643XX_ETH_TX_BURST_SZ_8_64BIT (3<<22)
+#define MV643XX_ETH_TX_BURST_SZ_16_64BIT (4<<22)
+
+#define MV643XX_ETH_RX_MIN_FRAME_SIZE_R(port) (0x247c + ((port)<<10))
+
+
+#define MV643XX_ETH_SERIAL_CONTROL_R(port) (0x243c + ((port)<<10))
+#define MV643XX_ETH_SERIAL_PORT_ENBL (1<<0) /* Enable serial port */
+#define MV643XX_ETH_FORCE_LINK_PASS (1<<1)
+#define MV643XX_ETH_DISABLE_AUTO_NEG_FOR_DUPLEX (1<<2)
+#define MV643XX_ETH_DISABLE_AUTO_NEG_FOR_FLOWCTL (1<<3)
+#define MV643XX_ETH_ADVERTISE_SYMMETRIC_FLOWCTL (1<<4)
+#define MV643XX_ETH_FORCE_FC_MODE_TX_PAUSE_DIS (1<<5)
+#define MV643XX_ETH_FORCE_BP_MODE_JAM_TX (1<<7)
+#define MV643XX_ETH_FORCE_BP_MODE_JAM_TX_ON_RX_ERR (1<<8)
+#define MV643XX_ETH_BIT9_UNKNOWN (1<<9) /* unknown purpose; linux sets this */
+#define MV643XX_ETH_FORCE_LINK_FAIL_DISABLE (1<<10)
+#define MV643XX_ETH_RETRANSMIT_FOREVER (1<<11) /* limit to 16 attempts if clear */
+#define MV643XX_ETH_DISABLE_AUTO_NEG_SPEED_GMII (1<<13)
+#define MV643XX_ETH_DTE_ADV_1 (1<<14)
+#define MV643XX_ETH_AUTO_NEG_BYPASS_ENBL (1<<15)
+#define MV643XX_ETH_RESTART_AUTO_NEG (1<<16)
+#define MV643XX_ETH_SC_MAX_RX_1518 (0<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_1522 (1<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_1552 (2<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_9022 (3<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_9192 (4<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_9700 (5<<17) /* Limit RX packet size */
+#define MV643XX_ETH_SC_MAX_RX_MASK (7<<17) /* bitmask */
+#define MV643XX_ETH_SET_EXT_LOOPBACK (1<<20)
+#define MV643XX_ETH_SET_FULL_DUPLEX (1<<21)
+#define MV643XX_ETH_ENBL_FLOWCTL_TX_RX_IN_FD (1<<22) /* enable flow ctrl on rx and tx in full-duplex */
+#define MV643XX_ETH_SET_GMII_SPEED_1000 (1<<23) /* 10/100 if clear */
+#define MV643XX_ETH_SET_MII_SPEED_100 (1<<24) /* 10 if clear */
+
+#define MV643XX_ETH_PORT_STATUS_R(port) (0x2444 + ((port)<<10))
+
+#define MV643XX_ETH_PORT_STATUS_MODE_10_BIT (1<<0)
+#define MV643XX_ETH_PORT_STATUS_LINK_UP (1<<1)
+#define MV643XX_ETH_PORT_STATUS_FDX (1<<2)
+#define MV643XX_ETH_PORT_STATUS_FC (1<<3)
+#define MV643XX_ETH_PORT_STATUS_1000 (1<<4)
+#define MV643XX_ETH_PORT_STATUS_100 (1<<5)
+/* PSR bit 6 unknown */
+#define MV643XX_ETH_PORT_STATUS_TX_IN_PROGRESS (1<<7)
+#define MV643XX_ETH_PORT_STATUS_ANEG_BYPASSED (1<<8)
+#define MV643XX_ETH_PORT_STATUS_PARTITION (1<<9)
+#define MV643XX_ETH_PORT_STATUS_TX_FIFO_EMPTY (1<<10)
+
+#define MV643XX_ETH_MIB_COUNTERS(port) (0x3000 + ((port)<<7))
+#define MV643XX_ETH_NUM_MIB_COUNTERS 32
+
+#define MV643XX_ETH_MIB_GOOD_OCTS_RCVD_LO (0)
+#define MV643XX_ETH_MIB_GOOD_OCTS_RCVD_HI (1<<2)
+#define MV643XX_ETH_MIB_BAD_OCTS_RCVD (2<<2)
+#define MV643XX_ETH_MIB_INTERNAL_MAC_TX_ERR (3<<2)
+#define MV643XX_ETH_MIB_GOOD_FRAMES_RCVD (4<<2)
+#define MV643XX_ETH_MIB_BAD_FRAMES_RCVD (5<<2)
+#define MV643XX_ETH_MIB_BCAST_FRAMES_RCVD (6<<2)
+#define MV643XX_ETH_MIB_MCAST_FRAMES_RCVD (7<<2)
+#define MV643XX_ETH_MIB_FRAMES_64_OCTS (8<<2)
+#define MV643XX_ETH_MIB_FRAMES_65_127_OCTS (9<<2)
+#define MV643XX_ETH_MIB_FRAMES_128_255_OCTS (10<<2)
+#define MV643XX_ETH_MIB_FRAMES_256_511_OCTS (11<<2)
+#define MV643XX_ETH_MIB_FRAMES_512_1023_OCTS (12<<2)
+#define MV643XX_ETH_MIB_FRAMES_1024_MAX_OCTS (13<<2)
+#define MV643XX_ETH_MIB_GOOD_OCTS_SENT_LO (14<<2)
+#define MV643XX_ETH_MIB_GOOD_OCTS_SENT_HI (15<<2)
+#define MV643XX_ETH_MIB_GOOD_FRAMES_SENT (16<<2)
+#define MV643XX_ETH_MIB_EXCESSIVE_COLL (17<<2)
+#define MV643XX_ETH_MIB_MCAST_FRAMES_SENT (18<<2)
+#define MV643XX_ETH_MIB_BCAST_FRAMES_SENT (19<<2)
+#define MV643XX_ETH_MIB_UNREC_MAC_CTRL_RCVD (20<<2)
+#define MV643XX_ETH_MIB_FC_SENT (21<<2)
+#define MV643XX_ETH_MIB_GOOD_FC_RCVD (22<<2)
+#define MV643XX_ETH_MIB_BAD_FC_RCVD (23<<2)
+#define MV643XX_ETH_MIB_UNDERSIZE_RCVD (24<<2)
+#define MV643XX_ETH_MIB_FRAGMENTS_RCVD (25<<2)
+#define MV643XX_ETH_MIB_OVERSIZE_RCVD (26<<2)
+#define MV643XX_ETH_MIB_JABBER_RCVD (27<<2)
+#define MV643XX_ETH_MIB_MAC_RX_ERR (28<<2)
+#define MV643XX_ETH_MIB_BAD_CRC_EVENT (29<<2)
+#define MV643XX_ETH_MIB_COLL (30<<2)
+#define MV643XX_ETH_MIB_LATE_COLL (31<<2)
+
+#define MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(port) (0x3400+((port)<<10))
+#define MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(port) (0x3500+((port)<<10))
+#define MV643XX_ETH_DA_FILTER_UNICAST_TBL(port) (0x3600+((port)<<10))
+#define MV643XX_ETH_NUM_MCAST_ENTRIES 64
+#define MV643XX_ETH_NUM_UNICAST_ENTRIES 4
+
+#define MV643XX_ETH_BAR_0 (0x2200)
+#define MV643XX_ETH_SIZE_R_0 (0x2204)
+#define MV643XX_ETH_BAR_1 (0x2208)
+#define MV643XX_ETH_SIZE_R_1 (0x220c)
+#define MV643XX_ETH_BAR_2 (0x2210)
+#define MV643XX_ETH_SIZE_R_2 (0x2214)
+#define MV643XX_ETH_BAR_3 (0x2218)
+#define MV643XX_ETH_SIZE_R_3 (0x221c)
+#define MV643XX_ETH_BAR_4 (0x2220)
+#define MV643XX_ETH_SIZE_R_4 (0x2224)
+#define MV643XX_ETH_BAR_5 (0x2228)
+#define MV643XX_ETH_SIZE_R_5 (0x222c)
+#define MV643XX_ETH_NUM_BARS 6
+
+/* Bits in the BAR reg to program cache snooping */
+#define MV64360_ENET2MEM_SNOOP_NONE 0x0000
+#define MV64360_ENET2MEM_SNOOP_WT 0x1000
+#define MV64360_ENET2MEM_SNOOP_WB 0x2000
+#define MV64360_ENET2MEM_SNOOP_MSK 0x3000
+
+
+#define MV643XX_ETH_BAR_ENBL_R (0x2290)
+#define MV643XX_ETH_BAR_DISABLE(bar) (1<<(bar))
+#define MV643XX_ETH_BAR_DISBL_ALL 0x3f
+
+#define MV643XX_ETH_RX_Q0_CURRENT_DESC_PTR(port) (0x260c+((port)<<10))
+#define MV643XX_ETH_RX_Q1_CURRENT_DESC_PTR(port) (0x261c+((port)<<10))
+#define MV643XX_ETH_RX_Q2_CURRENT_DESC_PTR(port) (0x262c+((port)<<10))
+#define MV643XX_ETH_RX_Q3_CURRENT_DESC_PTR(port) (0x263c+((port)<<10))
+#define MV643XX_ETH_RX_Q4_CURRENT_DESC_PTR(port) (0x264c+((port)<<10))
+#define MV643XX_ETH_RX_Q5_CURRENT_DESC_PTR(port) (0x265c+((port)<<10))
+#define MV643XX_ETH_RX_Q6_CURRENT_DESC_PTR(port) (0x266c+((port)<<10))
+#define MV643XX_ETH_RX_Q7_CURRENT_DESC_PTR(port) (0x267c+((port)<<10))
+
+#define MV643XX_ETH_TX_Q0_CURRENT_DESC_PTR(port) (0x26c0+((port)<<10))
+#define MV643XX_ETH_TX_Q1_CURRENT_DESC_PTR(port) (0x26c4+((port)<<10))
+#define MV643XX_ETH_TX_Q2_CURRENT_DESC_PTR(port) (0x26c8+((port)<<10))
+#define MV643XX_ETH_TX_Q3_CURRENT_DESC_PTR(port) (0x26cc+((port)<<10))
+#define MV643XX_ETH_TX_Q4_CURRENT_DESC_PTR(port) (0x26d0+((port)<<10))
+#define MV643XX_ETH_TX_Q5_CURRENT_DESC_PTR(port) (0x26d4+((port)<<10))
+#define MV643XX_ETH_TX_Q6_CURRENT_DESC_PTR(port) (0x26d8+((port)<<10))
+#define MV643XX_ETH_TX_Q7_CURRENT_DESC_PTR(port) (0x26dc+((port)<<10))
+
+#define MV643XX_ETH_MAC_ADDR_LO(port) (0x2414+((port)<<10))
+#define MV643XX_ETH_MAC_ADDR_HI(port) (0x2418+((port)<<10))
+
+/* TYPE DEFINITIONS */
+
+/* just to make the purpose explicit; vars of this
+ * type may need CPU-dependent address translation,
+ * endian conversion etc.
+ */
+typedef uint32_t Dma_addr_t;
+
+typedef volatile struct mveth_rx_desc {
+#ifndef __BIG_ENDIAN__
+#error "descriptor declaration not implemented for little endian machines"
+#endif
+ uint16_t byte_cnt;
+ uint16_t buf_size;
+ uint32_t cmd_sts; /* control and status */
+ Dma_addr_t next_desc_ptr; /* next descriptor (as seen from DMA) */
+ Dma_addr_t buf_ptr;
+ /* fields below here are not used by the chip */
+ void *u_buf; /* user buffer */
+ volatile struct mveth_rx_desc *next; /* next descriptor (CPU address; next_desc_ptr is a DMA address) */
+ uint32_t pad[2];
+} __attribute__(( aligned(RING_ALIGNMENT) )) MvEthRxDescRec, *MvEthRxDesc;
+
+typedef volatile struct mveth_tx_desc {
+#ifndef __BIG_ENDIAN__
+#error "descriptor declaration not implemented for little endian machines"
+#endif
+ uint16_t byte_cnt;
+ uint16_t l4i_chk;
+ uint32_t cmd_sts; /* control and status */
+ Dma_addr_t next_desc_ptr; /* next descriptor (as seen from DMA) */
+ Dma_addr_t buf_ptr;
+ /* fields below here are not used by the chip */
+ uint32_t workaround[2]; /* use this space to work around the 8byte problem (is this real?) */
+ void *u_buf; /* user buffer */
+ volatile struct mveth_tx_desc *next; /* next descriptor (CPU address; next_desc_ptr is a DMA address) */
+} __attribute__(( aligned(RING_ALIGNMENT) )) MvEthTxDescRec, *MvEthTxDesc;
+
+/* Assume there are never more then 64k aliasing entries */
+typedef uint16_t Mc_Refcnt[MV643XX_ETH_NUM_MCAST_ENTRIES*4];
+
+/* driver private data and bsdnet interface structure */
+struct mveth_private {
+ MvEthRxDesc rx_ring; /* pointers to aligned ring area */
+ MvEthTxDesc tx_ring; /* pointers to aligned ring area */
+ MvEthRxDesc ring_area; /* allocated ring area */
+ int rbuf_count, xbuf_count; /* saved ring sizes from ifconfig */
+ int port_num;
+ int phy;
+ MvEthRxDesc d_rx_t; /* tail of the RX ring; next received packet */
+ MvEthTxDesc d_tx_t, d_tx_h;
+ uint32_t rx_desc_dma, tx_desc_dma; /* ring address as seen by DMA; (1:1 on this BSP) */
+ int avail;
+ void (*isr)(void*);
+ void *isr_arg;
+ /* Callbacks to handle buffers */
+ void (*cleanup_txbuf)(void*, void*, int); /* callback to cleanup TX buffer */
+ void *cleanup_txbuf_arg;
+ void *(*alloc_rxbuf)(int *psize, uintptr_t *paddr); /* allocate RX buffer */
+ void (*consume_rxbuf)(void*, void*, int); /* callback to consume RX buffer */
+ void *consume_rxbuf_arg;
+ rtems_id tid;
+ uint32_t irq_mask; /* IRQs we use */
+ uint32_t xirq_mask;
+ int promisc;
+ struct {
+ unsigned irqs;
+ unsigned maxchain;
+ unsigned repack;
+ unsigned packet;
+ unsigned odrops; /* no counter in core code */
+ struct {
+ uint64_t good_octs_rcvd; /* 64-bit */
+ uint32_t bad_octs_rcvd;
+ uint32_t internal_mac_tx_err;
+ uint32_t good_frames_rcvd;
+ uint32_t bad_frames_rcvd;
+ uint32_t bcast_frames_rcvd;
+ uint32_t mcast_frames_rcvd;
+ uint32_t frames_64_octs;
+ uint32_t frames_65_127_octs;
+ uint32_t frames_128_255_octs;
+ uint32_t frames_256_511_octs;
+ uint32_t frames_512_1023_octs;
+ uint32_t frames_1024_max_octs;
+ uint64_t good_octs_sent; /* 64-bit */
+ uint32_t good_frames_sent;
+ uint32_t excessive_coll;
+ uint32_t mcast_frames_sent;
+ uint32_t bcast_frames_sent;
+ uint32_t unrec_mac_ctrl_rcvd;
+ uint32_t fc_sent;
+ uint32_t good_fc_rcvd;
+ uint32_t bad_fc_rcvd;
+ uint32_t undersize_rcvd;
+ uint32_t fragments_rcvd;
+ uint32_t oversize_rcvd;
+ uint32_t jabber_rcvd;
+ uint32_t mac_rx_err;
+ uint32_t bad_crc_event;
+ uint32_t coll;
+ uint32_t late_coll;
+ } mib;
+ } stats;
+ struct {
+ Mc_Refcnt specl, other;
+ } mc_refcnt;
+};
+
+/* stuff needed for bsdnet support */
+struct mveth_bsdsupp {
+ int oif_flags; /* old / cached if_flags */
+};
+
+struct mveth_softc {
+ struct arpcom arpcom;
+ struct mveth_bsdsupp bsd;
+ struct mveth_private pvt;
+};
+
+/* GLOBAL VARIABLES */
+#ifdef MVETH_DEBUG_TX_DUMP
+int mveth_tx_dump = 0;
+#endif
+
+/* THE array of driver/bsdnet structs */
+
+/* If detaching/module unloading is enabled, the main driver data
+ * structure must remain in memory; hence it must reside in its own
+ * 'dummy' module...
+ */
+#ifdef MVETH_DETACH_HACK
+extern
+#else
+STATIC
+#endif
+struct mveth_softc theMvEths[MV643XXETH_NUM_DRIVER_SLOTS]
+#ifndef MVETH_DETACH_HACK
+= {{{{0}},}}
+#endif
+;
+
+/* daemon task id */
+STATIC rtems_id mveth_tid = 0;
+/* register access protection mutex */
+STATIC rtems_id mveth_mtx = 0;
+#define REGLOCK() do { \
+ if ( RTEMS_SUCCESSFUL != rtems_semaphore_obtain(mveth_mtx, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ) \
+ rtems_panic(DRVNAME": unable to lock register protection mutex"); \
+ } while (0)
+#define REGUNLOCK() rtems_semaphore_release(mveth_mtx)
+
+/* Format strings for statistics messages */
+static const char *mibfmt[] = {
+ " GOOD_OCTS_RCVD: %"PRIu64"\n",
+ 0,
+ " BAD_OCTS_RCVD: %"PRIu32"\n",
+ " INTERNAL_MAC_TX_ERR: %"PRIu32"\n",
+ " GOOD_FRAMES_RCVD: %"PRIu32"\n",
+ " BAD_FRAMES_RCVD: %"PRIu32"\n",
+ " BCAST_FRAMES_RCVD: %"PRIu32"\n",
+ " MCAST_FRAMES_RCVD: %"PRIu32"\n",
+ " FRAMES_64_OCTS: %"PRIu32"\n",
+ " FRAMES_65_127_OCTS: %"PRIu32"\n",
+ " FRAMES_128_255_OCTS: %"PRIu32"\n",
+ " FRAMES_256_511_OCTS: %"PRIu32"\n",
+ " FRAMES_512_1023_OCTS:%"PRIu32"\n",
+ " FRAMES_1024_MAX_OCTS:%"PRIu32"\n",
+ " GOOD_OCTS_SENT: %"PRIu64"\n",
+ 0,
+ " GOOD_FRAMES_SENT: %"PRIu32"\n",
+ " EXCESSIVE_COLL: %"PRIu32"\n",
+ " MCAST_FRAMES_SENT: %"PRIu32"\n",
+ " BCAST_FRAMES_SENT: %"PRIu32"\n",
+ " UNREC_MAC_CTRL_RCVD: %"PRIu32"\n",
+ " FC_SENT: %"PRIu32"\n",
+ " GOOD_FC_RCVD: %"PRIu32"\n",
+ " BAD_FC_RCVD: %"PRIu32"\n",
+ " UNDERSIZE_RCVD: %"PRIu32"\n",
+ " FRAGMENTS_RCVD: %"PRIu32"\n",
+ " OVERSIZE_RCVD: %"PRIu32"\n",
+ " JABBER_RCVD: %"PRIu32"\n",
+ " MAC_RX_ERR: %"PRIu32"\n",
+ " BAD_CRC_EVENT: %"PRIu32"\n",
+ " COLL: %"PRIu32"\n",
+ " LATE_COLL: %"PRIu32"\n",
+};
+
+/* Interrupt Handler Connection */
+
+/* forward decls + implementation for IRQ API funcs */
+
+static void mveth_isr(rtems_irq_hdl_param unit);
+static void mveth_isr_1(rtems_irq_hdl_param unit);
+static void noop(const rtems_irq_connect_data *unused) {}
+static int noop1(const rtems_irq_connect_data *unused) { return 0; }
+
+static rtems_irq_connect_data irq_data[MAX_NUM_SLOTS] = {
+ {
+ BSP_IRQ_ETH0,
+ 0,
+ (rtems_irq_hdl_param)0,
+ noop,
+ noop,
+ noop1
+ },
+ {
+ BSP_IRQ_ETH1,
+ 0,
+ (rtems_irq_hdl_param)1,
+ noop,
+ noop,
+ noop1
+ },
+ {
+ BSP_IRQ_ETH2,
+ 0,
+ (rtems_irq_hdl_param)2,
+ noop,
+ noop,
+ noop1
+ },
+};
+
+/* MII Ioctl Interface */
+
+STATIC unsigned
+mveth_mii_read(struct mveth_private *mp, unsigned addr);
+
+STATIC unsigned
+mveth_mii_write(struct mveth_private *mp, unsigned addr, unsigned v);
+
+
+/* mdio / mii interface wrappers for rtems_mii_ioctl API */
+
+static int mveth_mdio_r(int phy, void *uarg, unsigned reg, uint32_t *pval)
+{
+ if ( phy > 1 )
+ return -1;
+
+ *pval = mveth_mii_read(uarg, reg);
+ return 0;
+}
+
+static int mveth_mdio_w(int phy, void *uarg, unsigned reg, uint32_t val)
+{
+ if ( phy > 1 )
+ return -1;
+ mveth_mii_write(uarg, reg, val);
+ return 0;
+}
+
+static struct rtems_mdio_info mveth_mdio = {
+ mdio_r: mveth_mdio_r,
+ mdio_w: mveth_mdio_w,
+ has_gmii: 1,
+};
+
+/* LOW LEVEL SUPPORT ROUTINES */
+
+/* Software Cache Coherency */
+#ifndef ENABLE_HW_SNOOPING
+#ifndef __PPC__
+#error "Software cache coherency maintenance is not implemented for your CPU architecture"
+#endif
+
+static inline unsigned INVAL_DESC(volatile void *d)
+{
+typedef const char cache_line[PPC_CACHE_ALIGNMENT];
+ asm volatile("dcbi 0, %1":"=m"(*(cache_line*)d):"r"(d));
+ return (unsigned)d; /* so this can be used in comma expression */
+}
+
+static inline void FLUSH_DESC(volatile void *d)
+{
+typedef const char cache_line[PPC_CACHE_ALIGNMENT];
+ asm volatile("dcbf 0, %0"::"r"(d),"m"(*(cache_line*)d));
+}
+
+static inline void FLUSH_BARRIER(void)
+{
+ asm volatile("eieio");
+}
+
+/* RX buffers are always cache-line aligned
+ * ASSUMPTIONS:
+ * - 'addr' is cache aligned
+ * - len is a multiple >0 of cache lines
+ */
+static inline void INVAL_BUF(register uintptr_t addr, register int len)
+{
+typedef char maxbuf[2048]; /* more than an ethernet packet */
+ do {
+ len -= RX_BUF_ALIGNMENT;
+ asm volatile("dcbi %0, %1"::"b"(addr),"r"(len));
+ } while (len > 0);
+ asm volatile("":"=m"(*(maxbuf*)addr));
+}
+
+/* Flushing TX buffers is a little bit trickier; we don't really know their
+ * alignment but *assume* adjacent addresses are covering 'ordinary' memory
+ * so that flushing them does no harm!
+ */
+static inline void FLUSH_BUF(register uintptr_t addr, register int len)
+{
+ asm volatile("":::"memory");
+ len = MV643XX_ALIGN(len, RX_BUF_ALIGNMENT);
+ do {
+ asm volatile("dcbf %0, %1"::"b"(addr),"r"(len));
+ len -= RX_BUF_ALIGNMENT;
+ } while ( len >= 0 );
+}
+
+#else /* hardware snooping enabled */
+
+/* inline this to silence compiler warnings */
+static inline int INVAL_DESC(volatile void *d)
+{ return 0; }
+
+#define FLUSH_DESC(d) NOOP()
+#define INVAL_BUF(b,l) NOOP()
+#define FLUSH_BUF(b,l) NOOP()
+#define FLUSH_BARRIER() NOOP()
+
+#endif /* cache coherency support */
+
+/* Synchronize memory access */
+#ifdef __PPC__
+static inline void membarrier(void)
+{
+ asm volatile("sync":::"memory");
+}
+#else
+#error "memory barrier instruction not defined (yet) for this CPU"
+#endif
+
+/* Enable and disable interrupts at the device */
+static inline void
+mveth_enable_irqs(struct mveth_private *mp, uint32_t mask)
+{
+rtems_interrupt_level l;
+uint32_t val;
+ rtems_interrupt_disable(l);
+
+ val = MV_READ(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num));
+ val = (val | mask | MV643XX_ETH_IRQ_EXT_ENA) & mp->irq_mask;
+
+ MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num), val);
+
+ val = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num));
+ val = (val | mask) & mp->xirq_mask;
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), val);
+
+ rtems_interrupt_enable(l);
+}
+
+static inline uint32_t
+mveth_disable_irqs(struct mveth_private *mp, uint32_t mask)
+{
+rtems_interrupt_level l;
+uint32_t val,xval,tmp;
+ rtems_interrupt_disable(l);
+
+ val = MV_READ(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num));
+ tmp = ( (val & ~mask) | MV643XX_ETH_IRQ_EXT_ENA ) & mp->irq_mask;
+ MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num), tmp);
+
+ xval = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num));
+ tmp = (xval & ~mask) & mp->xirq_mask;
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), tmp);
+
+ rtems_interrupt_enable(l);
+
+ return (val | xval);
+}
+
+/* This should be safe even w/o turning off interrupts if multiple
+ * threads ack different bits in the cause register (and ignore
+ * other ones) since writing 'ones' into the cause register doesn't
+ * 'stick'.
+ */
+
+static inline uint32_t
+mveth_ack_irqs(struct mveth_private *mp, uint32_t mask)
+{
+register uint32_t x,xe,p;
+
+ p = mp->port_num;
+ /* Get cause */
+ x = MV_READ(MV643XX_ETH_INTERRUPT_CAUSE_R(p));
+
+ /* Ack interrupts filtering the ones we're interested in */
+
+ /* Note: EXT_IRQ bit clears by itself if EXT interrupts are cleared */
+ MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(p), ~ (x & mp->irq_mask & mask));
+
+ /* linux driver tests 1<<1 as a summary bit for extended interrupts;
+ * the mv64360 seems to use 1<<19 for that purpose; for the moment,
+ * I just check both.
+ * Update: link status irq (1<<16 in xe) doesn't set (1<<19) in x!
+ */
+ if ( 1 /* x & 2 */ )
+ {
+ xe = MV_READ(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(p));
+
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(p), ~ (xe & mp->xirq_mask & mask));
+ } else {
+ xe = 0;
+ }
+#ifdef MVETH_TESTING
+ if ( ((x & MV643XX_ETH_ALL_IRQS) & ~MV643XX_ETH_KNOWN_IRQS)
+ || ((xe & MV643XX_ETH_ALL_EXT_IRQS) & ~MV643XX_ETH_KNOWN_EXT_IRQS) ) {
+ fprintf(stderr, "Unknown IRQs detected; leaving all disabled for debugging:\n");
+ fprintf(stderr, "Cause reg was 0x%08x, ext cause 0x%08x\n", x, xe);
+ mp->irq_mask = 0;
+ mp->xirq_mask = 0;
+ }
+#endif
+ /* luckily, the extended and 'normal' interrupts we use don't overlap so
+ * we can just OR them into a single word
+ */
+ return (xe & mp->xirq_mask) | (x & mp->irq_mask);
+}
+
+static void mveth_isr(rtems_irq_hdl_param arg)
+{
+unsigned unit = (unsigned)arg;
+ mveth_disable_irqs(&theMvEths[unit].pvt, -1);
+ theMvEths[unit].pvt.stats.irqs++;
+ rtems_bsdnet_event_send( theMvEths[unit].pvt.tid, 1<<unit );
+}
+
+static void mveth_isr_1(rtems_irq_hdl_param arg)
+{
+unsigned unit = (unsigned)arg;
+struct mveth_private *mp = &theMvEths[unit].pvt;
+
+ mp->stats.irqs++;
+ mp->isr(mp->isr_arg);
+}
+
+static void
+mveth_clear_mib_counters(struct mveth_private *mp)
+{
+register int i;
+register uint32_t b;
+ /* reading the counters resets them */
+ b = MV643XX_ETH_MIB_COUNTERS(mp->port_num);
+ for (i=0; i< MV643XX_ETH_NUM_MIB_COUNTERS; i++, b+=4)
+ (void)MV_READ(b);
+}
+
+/* Reading a MIB register also clears it. Hence we read the lo
+ * register first, then the hi one. Correct reading is guaranteed since
+ * the 'lo' register cannot overflow after it is read since it had
+ * been reset to 0.
+ */
+static unsigned long long
+read_long_mib_counter(int port_num, int idx)
+{
+unsigned long lo;
+unsigned long long hi;
+ lo = MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
+ idx++;
+ hi = MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
+ return (hi<<32) | lo;
+}
+
+static inline unsigned long
+read_mib_counter(int port_num, int idx)
+{
+ return MV_READ(MV643XX_ETH_MIB_COUNTERS(port_num)+(idx<<2));
+}
+
+
+/* write ethernet address from buffer to hardware (need to change unicast filter after this) */
+static void
+mveth_write_eaddr(struct mveth_private *mp, unsigned char *eaddr)
+{
+int i;
+uint32_t x;
+
+ /* build hi word */
+ for (i=4,x=0; i; i--, eaddr++) {
+ x = (x<<8) | *eaddr;
+ }
+ MV_WRITE(MV643XX_ETH_MAC_ADDR_HI(mp->port_num), x);
+
+ /* build lo word */
+ for (i=2,x=0; i; i--, eaddr++) {
+ x = (x<<8) | *eaddr;
+ }
+ MV_WRITE(MV643XX_ETH_MAC_ADDR_LO(mp->port_num), x);
+}
+
+/* PHY/MII Interface
+ *
+ * Read/write a PHY register;
+ *
+ * NOTE: The SMI register is shared among the three devices.
+ * Protection is provided by the global networking semaphore.
+ * If non-bsd drivers are running on a subset of IFs proper
+ * locking of all shared registers must be implemented!
+ */
+STATIC unsigned
+mveth_mii_read(struct mveth_private *mp, unsigned addr)
+{
+unsigned v;
+unsigned wc = 0;
+
+ addr &= 0x1f;
+
+ /* wait until not busy */
+ do {
+ v = MV_READ(MV643XX_ETH_SMI_R);
+ wc++;
+ } while ( MV643XX_ETH_SMI_BUSY & v );
+
+ MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_RD );
+
+ do {
+ v = MV_READ(MV643XX_ETH_SMI_R);
+ wc++;
+ } while ( MV643XX_ETH_SMI_BUSY & v );
+
+ if (wc>0xffff)
+ wc = 0xffff;
+ return (wc<<16) | (v & 0xffff);
+}
+
+STATIC unsigned
+mveth_mii_write(struct mveth_private *mp, unsigned addr, unsigned v)
+{
+unsigned wc = 0;
+
+ addr &= 0x1f;
+ v &= 0xffff;
+
+ /* busywait is ugly but not preventing ISRs or high priority tasks from
+ * preempting us
+ */
+
+ /* wait until not busy */
+ while ( MV643XX_ETH_SMI_BUSY & MV_READ(MV643XX_ETH_SMI_R) )
+ wc++ /* wait */;
+
+ MV_WRITE(MV643XX_ETH_SMI_R, (addr <<21 ) | (mp->phy<<16) | MV643XX_ETH_SMI_OP_WR | v );
+
+ return wc;
+}
+
+/* MID-LAYER SUPPORT ROUTINES */
+
+/* Start TX if descriptors are exhausted */
+static __inline__ void
+mveth_start_tx(struct mveth_private *mp)
+{
+uint32_t running;
+ if ( mp->avail <= 0 ) {
+ running = MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num));
+ if ( ! (running & MV643XX_ETH_TX_START(0)) ) {
+ MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+ }
+ }
+}
+
+/* Stop TX and wait for the command queues to stop and the fifo to drain */
+static uint32_t
+mveth_stop_tx(int port)
+{
+uint32_t active_q;
+
+ active_q = (MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port)) & MV643XX_ETH_TX_ANY_RUNNING);
+
+ if ( active_q ) {
+ /* Halt TX and wait for activity to stop */
+ MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port), MV643XX_ETH_TX_STOP_ALL);
+ while ( MV643XX_ETH_TX_ANY_RUNNING & MV_READ(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(port)) )
+ /* poll-wait */;
+ /* Wait for Tx FIFO to drain */
+ while ( ! (MV643XX_ETH_PORT_STATUS_R(port) & MV643XX_ETH_PORT_STATUS_TX_FIFO_EMPTY) )
+ /* poll-wait */;
+ }
+
+ return active_q;
+}
+
+/* update serial port settings from current link status */
+static void
+mveth_update_serial_port(struct mveth_private *mp, int media)
+{
+int port = mp->port_num;
+uint32_t old, new;
+
+ new = old = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(port));
+
+ /* mask speed and duplex settings */
+ new &= ~( MV643XX_ETH_SET_GMII_SPEED_1000
+ | MV643XX_ETH_SET_MII_SPEED_100
+ | MV643XX_ETH_SET_FULL_DUPLEX );
+
+ if ( IFM_FDX & media )
+ new |= MV643XX_ETH_SET_FULL_DUPLEX;
+
+ switch ( IFM_SUBTYPE(media) ) {
+ default: /* treat as 10 */
+ break;
+ case IFM_100_TX:
+ new |= MV643XX_ETH_SET_MII_SPEED_100;
+ break;
+ case IFM_1000_T:
+ new |= MV643XX_ETH_SET_GMII_SPEED_1000;
+ break;
+ }
+
+ if ( new != old ) {
+ if ( ! (MV643XX_ETH_SERIAL_PORT_ENBL & new) ) {
+ /* just write */
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+ } else {
+ uint32_t were_running;
+
+ were_running = mveth_stop_tx(port);
+
+ old &= ~MV643XX_ETH_SERIAL_PORT_ENBL;
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), old);
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+ /* linux driver writes twice... */
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(port), new);
+
+ if ( were_running ) {
+ MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+ }
+ }
+ }
+}
+
+/* Clear multicast filters */
+void
+BSP_mve_mcast_filter_clear(struct mveth_private *mp)
+{
+int i;
+register uint32_t s,o;
+uint32_t v = mp->promisc ? 0x01010101 : 0x00000000;
+ s = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
+ o = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
+ for (i=0; i<MV643XX_ETH_NUM_MCAST_ENTRIES; i++) {
+ MV_WRITE(s,v);
+ MV_WRITE(o,v);
+ s+=4;
+ o+=4;
+ }
+ for (i=0; i<sizeof(mp->mc_refcnt.specl)/sizeof(mp->mc_refcnt.specl[0]); i++) {
+ mp->mc_refcnt.specl[i] = 0;
+ mp->mc_refcnt.other[i] = 0;
+ }
+}
+
+void
+BSP_mve_mcast_filter_accept_all(struct mveth_private *mp)
+{
+int i;
+register uint32_t s,o;
+ s = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
+ o = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
+ for (i=0; i<MV643XX_ETH_NUM_MCAST_ENTRIES; i++) {
+ MV_WRITE(s,0x01010101);
+ MV_WRITE(o,0x01010101);
+ s+=4;
+ o+=4;
+ /* Not clear what we should do with the reference count.
+ * For now just increment it.
+ */
+ for (i=0; i<sizeof(mp->mc_refcnt.specl)/sizeof(mp->mc_refcnt.specl[0]); i++) {
+ mp->mc_refcnt.specl[i]++;
+ mp->mc_refcnt.other[i]++;
+ }
+ }
+}
+
+static void add_entry(uint32_t off, uint8_t hash, Mc_Refcnt *refcnt)
+{
+uint32_t val;
+uint32_t slot = hash & 0xfc;
+
+ if ( 0 == (*refcnt)[hash]++ ) {
+ val = MV_READ(off+slot) | ( 1 << ((hash&3)<<3) );
+ MV_WRITE(off+slot, val);
+ }
+}
+
+static void del_entry(uint32_t off, uint8_t hash, Mc_Refcnt *refcnt)
+{
+uint32_t val;
+uint32_t slot = hash & 0xfc;
+
+ if ( (*refcnt)[hash] > 0 && 0 == --(*refcnt)[hash] ) {
+ val = MV_READ(off+slot) & ~( 1 << ((hash&3)<<3) );
+ MV_WRITE(off+slot, val);
+ }
+}
+
+void
+BSP_mve_mcast_filter_accept_add(struct mveth_private *mp, unsigned char *enaddr)
+{
+uint32_t hash;
+static const char spec[]={0x01,0x00,0x5e,0x00,0x00};
+static const char bcst[]={0xff,0xff,0xff,0xff,0xff,0xff};
+uint32_t tabl;
+Mc_Refcnt *refcnt;
+
+ if ( ! (0x01 & enaddr[0]) ) {
+ /* not a multicast address; ignore */
+ return;
+ }
+
+ if ( 0 == memcmp(enaddr, bcst, sizeof(bcst)) ) {
+ /* broadcast address; ignore */
+ return;
+ }
+
+ if ( 0 == memcmp(enaddr, spec, sizeof(spec)) ) {
+ hash = enaddr[5];
+ tabl = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
+ refcnt = &mp->mc_refcnt.specl;
+ } else {
+ uint32_t test, mask;
+ int i;
+ /* algorithm used by linux driver */
+ for ( hash=0, i=0; i<6; i++ ) {
+ hash = (hash ^ enaddr[i]) << 8;
+ for ( test=0x8000, mask=0x8380; test>0x0080; test>>=1, mask>>=1 ) {
+ if ( hash & test )
+ hash ^= mask;
+ }
+ }
+ tabl = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
+ refcnt = &mp->mc_refcnt.other;
+ }
+ add_entry(tabl, hash, refcnt);
+}
+
+void
+BSP_mve_mcast_filter_accept_del(struct mveth_private *mp, unsigned char *enaddr)
+{
+uint32_t hash;
+static const char spec[]={0x01,0x00,0x5e,0x00,0x00};
+static const char bcst[]={0xff,0xff,0xff,0xff,0xff,0xff};
+uint32_t tabl;
+Mc_Refcnt *refcnt;
+
+ if ( ! (0x01 & enaddr[0]) ) {
+ /* not a multicast address; ignore */
+ return;
+ }
+
+ if ( 0 == memcmp(enaddr, bcst, sizeof(bcst)) ) {
+ /* broadcast address; ignore */
+ return;
+ }
+
+ if ( 0 == memcmp(enaddr, spec, sizeof(spec)) ) {
+ hash = enaddr[5];
+ tabl = MV643XX_ETH_DA_FILTER_SPECL_MCAST_TBL(mp->port_num);
+ refcnt = &mp->mc_refcnt.specl;
+ } else {
+ uint32_t test, mask;
+ int i;
+ /* algorithm used by linux driver */
+ for ( hash=0, i=0; i<6; i++ ) {
+ hash = (hash ^ enaddr[i]) << 8;
+ for ( test=0x8000, mask=0x8380; test>0x0080; test>>=1, mask>>=1 ) {
+ if ( hash & test )
+ hash ^= mask;
+ }
+ }
+ tabl = MV643XX_ETH_DA_FILTER_OTHER_MCAST_TBL(mp->port_num);
+ refcnt = &mp->mc_refcnt.other;
+ }
+ del_entry(tabl, hash, refcnt);
+}
+
+/* Clear all address filters (multi- and unicast) */
+static void
+mveth_clear_addr_filters(struct mveth_private *mp)
+{
+register int i;
+register uint32_t u;
+ u = MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num);
+ for (i=0; i<MV643XX_ETH_NUM_UNICAST_ENTRIES; i++) {
+ MV_WRITE(u,0);
+ u+=4;
+ }
+ BSP_mve_mcast_filter_clear(mp);
+}
+
+/* Setup unicast filter for a given MAC address (least significant nibble) */
+static void
+mveth_ucfilter(struct mveth_private *mp, unsigned char mac_lsbyte, int accept)
+{
+unsigned nib, slot, bit;
+uint32_t val;
+ /* compute slot in table */
+ nib = mac_lsbyte & 0xf; /* strip nibble */
+ slot = nib & ~3; /* (nibble/4)*4 */
+ bit = (nib & 3)<<3; /* 8*(nibble % 4) */
+ val = MV_READ(MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num) + slot);
+ if ( accept ) {
+ val |= 0x01 << bit;
+ } else {
+ val &= 0x0e << bit;
+ }
+ MV_WRITE(MV643XX_ETH_DA_FILTER_UNICAST_TBL(mp->port_num) + slot, val);
+}
+
+#if defined( ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM ) && 0
+/* Currently unused; small unaligned buffers seem to be rare
+ * so we just use memcpy()...
+ */
+
+/* memcpy for 0..7 bytes; arranged so that gcc
+ * optimizes for powerpc...
+ */
+
+static inline void memcpy8(void *to, void *fr, unsigned x)
+{
+register uint8_t *d = to, *s = fro;
+
+ d+=l; s+=l;
+ if ( l & 1 ) {
+ *--d=*--s;
+ }
+ if ( l & 2 ) {
+ /* pre-decrementing causes gcc to use auto-decrementing
+ * PPC instructions (lhzu rx, -2(ry))
+ */
+ d-=2; s-=2;
+ /* use memcpy; don't cast to short -- accessing
+ * misaligned data as short is not portable
+ * (but it works on PPC).
+ */
+ __builtin_memcpy(d,s,2);
+ }
+ if ( l & 4 ) {
+ d-=4; s-=4;
+ /* see above */
+ __builtin_memcpy(d,s,4);
+ }
+}
+#endif
+
+/* Assign values (buffer + user data) to a tx descriptor slot */
+static int
+mveth_assign_desc(MvEthTxDesc d, struct mbuf *m, unsigned long extra)
+{
+int rval = (d->byte_cnt = m->m_len);
+
+#ifdef MVETH_TESTING
+ assert( !d->mb );
+ assert( m->m_len );
+#endif
+
+ /* set CRC on all descriptors; seems to be necessary */
+ d->cmd_sts = extra | (TDESC_GEN_CRC | TDESC_ZERO_PAD);
+
+#ifdef ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
+ /* The buffer must be 64bit aligned if the payload is <8 (??) */
+ if ( rval < 8 && ((mtod(m, uintptr_t)) & 7) ) {
+ d->buf_ptr = CPUADDR2ENET( d->workaround );
+ memcpy((void*)d->workaround, mtod(m, void*), rval);
+ } else
+#endif
+ {
+ d->buf_ptr = CPUADDR2ENET( mtod(m, unsigned long) );
+ }
+ d->l4i_chk = 0;
+ return rval;
+}
+
+static int
+mveth_assign_desc_raw(MvEthTxDesc d, void *buf, int len, unsigned long extra)
+{
+int rval = (d->byte_cnt = len);
+
+#ifdef MVETH_TESTING
+ assert( !d->u_buf );
+ assert( len );
+#endif
+
+ /* set CRC on all descriptors; seems to be necessary */
+ d->cmd_sts = extra | (TDESC_GEN_CRC | TDESC_ZERO_PAD);
+
+#ifdef ENABLE_TX_WORKAROUND_8_BYTE_PROBLEM
+ /* The buffer must be 64bit aligned if the payload is <8 (??) */
+ if ( rval < 8 && ( ((uintptr_t)buf) & 7) ) {
+ d->buf_ptr = CPUADDR2ENET( d->workaround );
+ memcpy((void*)d->workaround, buf, rval);
+ } else
+#endif
+ {
+ d->buf_ptr = CPUADDR2ENET( (unsigned long)buf );
+ }
+ d->l4i_chk = 0;
+ return rval;
+}
+
+/*
+ * Ring Initialization
+ *
+ * ENDIAN ASSUMPTION: DMA engine matches CPU endianness (???)
+ *
+ * Linux driver discriminates __LITTLE and __BIG endian for re-arranging
+ * the u16 fields in the descriptor structs. However, no endian conversion
+ * is done on the individual fields (SDMA byte swapping is disabled on LE).
+ */
+
+STATIC int
+mveth_init_rx_desc_ring(struct mveth_private *mp)
+{
+int i,sz;
+MvEthRxDesc d;
+uintptr_t baddr;
+
+ memset((void*)mp->rx_ring, 0, sizeof(*mp->rx_ring)*mp->rbuf_count);
+
+ mp->rx_desc_dma = CPUADDR2ENET(mp->rx_ring);
+
+ for ( i=0, d = mp->rx_ring; i<mp->rbuf_count; i++, d++ ) {
+ d->u_buf = mp->alloc_rxbuf(&sz, &baddr);
+ assert( d->u_buf );
+
+#ifndef ENABLE_HW_SNOOPING
+ /* could reduce the area to max. ethernet packet size */
+ INVAL_BUF(baddr, sz);
+#endif
+
+ d->buf_size = sz;
+ d->byte_cnt = 0;
+ d->cmd_sts = RDESC_DMA_OWNED | RDESC_INT_ENA;
+ d->next = mp->rx_ring + (i+1) % mp->rbuf_count;
+
+ d->buf_ptr = CPUADDR2ENET( baddr );
+ d->next_desc_ptr = CPUADDR2ENET(d->next);
+ FLUSH_DESC(d);
+ }
+ FLUSH_BARRIER();
+
+ mp->d_rx_t = mp->rx_ring;
+
+ /* point the chip to the start of the ring */
+ MV_WRITE(MV643XX_ETH_RX_Q0_CURRENT_DESC_PTR(mp->port_num),mp->rx_desc_dma);
+
+
+ return i;
+}
+
+STATIC int
+mveth_init_tx_desc_ring(struct mveth_private *mp)
+{
+int i;
+MvEthTxDesc d;
+
+ memset((void*)mp->tx_ring, 0, sizeof(*mp->tx_ring)*mp->xbuf_count);
+
+ /* DMA and CPU live in the same address space (rtems) */
+ mp->tx_desc_dma = CPUADDR2ENET(mp->tx_ring);
+ mp->avail = TX_AVAILABLE_RING_SIZE(mp);
+
+ for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++,d++ ) {
+ d->l4i_chk = 0;
+ d->byte_cnt = 0;
+ d->cmd_sts = 0;
+ d->buf_ptr = 0;
+
+ d->next = mp->tx_ring + (i+1) % mp->xbuf_count;
+ d->next_desc_ptr = CPUADDR2ENET(d->next);
+ FLUSH_DESC(d);
+ }
+ FLUSH_BARRIER();
+
+ mp->d_tx_h = mp->d_tx_t = mp->tx_ring;
+
+ /* point the chip to the start of the ring */
+ MV_WRITE(MV643XX_ETH_TX_Q0_CURRENT_DESC_PTR(mp->port_num),mp->tx_desc_dma);
+
+ return i;
+}
+
+/* PUBLIC LOW-LEVEL DRIVER ACCESS */
+
+static struct mveth_private *
+mve_setup_internal(
+ int unit,
+ rtems_id tid,
+ void (*isr)(void*isr_arg),
+ void *isr_arg,
+ void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred),
+ void *cleanup_txbuf_arg,
+ void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+ void *consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+
+{
+struct mveth_private *mp;
+struct ifnet *ifp;
+int InstallISRSuccessful;
+
+ if ( unit <= 0 || unit > MV643XXETH_NUM_DRIVER_SLOTS ) {
+ printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, MV643XXETH_NUM_DRIVER_SLOTS);
+ return 0;
+ }
+ ifp = &theMvEths[unit-1].arpcom.ac_if;
+ if ( ifp->if_init ) {
+ if ( ifp->if_init ) {
+ printk(DRVNAME": instance %i already attached.\n", unit);
+ return 0;
+ }
+ }
+
+ if ( rx_ring_size < 0 && tx_ring_size < 0 )
+ return 0;
+
+ if ( MV_64360 != BSP_getDiscoveryVersion(0) ) {
+ printk(DRVNAME": not mv64360 chip\n");
+ return 0;
+ }
+
+ /* lazy init of mutex (non thread-safe! - we assume 1st initialization is single-threaded) */
+ if ( ! mveth_mtx ) {
+ rtems_status_code sc;
+ sc = rtems_semaphore_create(
+ rtems_build_name('m','v','e','X'),
+ 1,
+ RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY | RTEMS_DEFAULT_ATTRIBUTES,
+ 0,
+ &mveth_mtx);
+ if ( RTEMS_SUCCESSFUL != sc ) {
+ rtems_error(sc,DRVNAME": creating mutex\n");
+ rtems_panic("unable to proceed\n");
+ }
+ }
+
+ mp = &theMvEths[unit-1].pvt;
+
+ memset(mp, 0, sizeof(*mp));
+
+ mp->port_num = unit-1;
+ mp->phy = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*mp->port_num)) & 0x1f;
+
+ mp->tid = tid;
+ mp->isr = isr;
+ mp->isr_arg = isr_arg;
+
+ mp->cleanup_txbuf = cleanup_txbuf;
+ mp->cleanup_txbuf_arg = cleanup_txbuf_arg;
+ mp->alloc_rxbuf = alloc_rxbuf;
+ mp->consume_rxbuf = consume_rxbuf;
+ mp->consume_rxbuf_arg = consume_rxbuf_arg;
+
+ mp->rbuf_count = rx_ring_size ? rx_ring_size : MV643XX_RX_RING_SIZE;
+ mp->xbuf_count = tx_ring_size ? tx_ring_size : MV643XX_TX_RING_SIZE;
+
+ if ( mp->xbuf_count > 0 )
+ mp->xbuf_count += TX_NUM_TAG_SLOTS;
+
+ if ( mp->rbuf_count < 0 )
+ mp->rbuf_count = 0;
+ if ( mp->xbuf_count < 0 )
+ mp->xbuf_count = 0;
+
+ /* allocate ring area; add 1 entry -- room for alignment */
+ assert( !mp->ring_area );
+ mp->ring_area = malloc(
+ sizeof(*mp->ring_area) *
+ (mp->rbuf_count + mp->xbuf_count + 1),
+ M_DEVBUF,
+ M_WAIT );
+ assert( mp->ring_area );
+
+ BSP_mve_stop_hw(mp);
+
+ if ( irq_mask ) {
+ irq_data[mp->port_num].hdl = tid ? mveth_isr : mveth_isr_1;
+ InstallISRSuccessful = BSP_install_rtems_irq_handler( &irq_data[mp->port_num] );
+ assert( InstallISRSuccessful );
+ }
+
+ /* mark as used */
+ ifp->if_init = (void*)(-1);
+
+ if ( rx_ring_size < 0 )
+ irq_mask &= ~ MV643XX_ETH_IRQ_RX_DONE;
+ if ( tx_ring_size < 0 )
+ irq_mask &= ~ MV643XX_ETH_EXT_IRQ_TX_DONE;
+
+ mp->irq_mask = (irq_mask & MV643XX_ETH_IRQ_RX_DONE);
+ if ( (irq_mask &= (MV643XX_ETH_EXT_IRQ_TX_DONE | MV643XX_ETH_EXT_IRQ_LINK_CHG)) ) {
+ mp->irq_mask |= MV643XX_ETH_IRQ_EXT_ENA;
+ mp->xirq_mask = irq_mask;
+ } else {
+ mp->xirq_mask = 0;
+ }
+
+ return mp;
+}
+
+struct mveth_private *
+BSP_mve_setup(
+ int unit,
+ rtems_id tid,
+ void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred),
+ void *cleanup_txbuf_arg,
+ void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+ void *consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+{
+ if ( irq_mask && 0 == tid ) {
+ printk(DRVNAME": must supply a TID if irq_msk not zero\n");
+ return 0;
+ }
+
+ return mve_setup_internal(
+ unit,
+ tid,
+ 0, 0,
+ cleanup_txbuf, cleanup_txbuf_arg,
+ alloc_rxbuf,
+ consume_rxbuf, consume_rxbuf_arg,
+ rx_ring_size, tx_ring_size,
+ irq_mask);
+}
+
+struct mveth_private *
+BSP_mve_setup_1(
+ int unit,
+ void (*isr)(void *isr_arg),
+ void *isr_arg,
+ void (*cleanup_txbuf)(void *user_buf, void *closure, int error_on_tx_occurred),
+ void *cleanup_txbuf_arg,
+ void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *closure, int len),
+ void *consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+{
+ if ( irq_mask && 0 == isr ) {
+ printk(DRVNAME": must supply an ISR if irq_msk not zero\n");
+ return 0;
+ }
+
+ return mve_setup_internal(
+ unit,
+ 0,
+ isr, isr_arg,
+ cleanup_txbuf, cleanup_txbuf_arg,
+ alloc_rxbuf,
+ consume_rxbuf, consume_rxbuf_arg,
+ rx_ring_size, tx_ring_size,
+ irq_mask);
+}
+
+rtems_id
+BSP_mve_get_tid(struct mveth_private *mp)
+{
+ return mp->tid;
+}
+
+int
+BSP_mve_detach(struct mveth_private *mp)
+{
+int unit = mp->port_num;
+ BSP_mve_stop_hw(mp);
+ if ( mp->irq_mask || mp->xirq_mask ) {
+ if ( !BSP_remove_rtems_irq_handler( &irq_data[mp->port_num] ) )
+ return -1;
+ }
+ free( (void*)mp->ring_area, M_DEVBUF );
+ memset(mp, 0, sizeof(*mp));
+ __asm__ __volatile__("":::"memory");
+ /* mark as unused */
+ theMvEths[unit].arpcom.ac_if.if_init = 0;
+ return 0;
+}
+
+/* MAIN RX-TX ROUTINES
+ *
+ * BSP_mve_swipe_tx(): descriptor scavenger; releases mbufs
+ * BSP_mve_send_buf(): xfer mbufs from IF to chip
+ * BSP_mve_swipe_rx(): enqueue received mbufs to interface
+ * allocate new ones and yield them to the
+ * chip.
+ */
+
+/* clean up the TX ring freeing up buffers */
+int
+BSP_mve_swipe_tx(struct mveth_private *mp)
+{
+int rval = 0;
+register MvEthTxDesc d;
+
+ for ( d = mp->d_tx_t; d->buf_ptr; d = NEXT_TXD(d) ) {
+
+ INVAL_DESC(d);
+
+ if ( (TDESC_DMA_OWNED & d->cmd_sts)
+ && (uint32_t)d == MV_READ(MV643XX_ETH_CURRENT_SERVED_TX_DESC(mp->port_num)) )
+ break;
+
+ /* d->u_buf is only set on the last descriptor in a chain;
+ * we only count errors in the last descriptor;
+ */
+ if ( d->u_buf ) {
+ mp->cleanup_txbuf(d->u_buf, mp->cleanup_txbuf_arg, (d->cmd_sts & TDESC_ERROR) ? 1 : 0);
+ d->u_buf = 0;
+ }
+
+ d->buf_ptr = 0;
+
+ rval++;
+ }
+ mp->d_tx_t = d;
+ mp->avail += rval;
+
+ return rval;
+}
+
+/* allocate a new cluster and copy an existing chain there;
+ * old chain is released...
+ */
+static struct mbuf *
+repackage_chain(struct mbuf *m_head)
+{
+struct mbuf *m;
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+
+ if ( !m ) {
+ goto bail;
+ }
+
+ MCLGET(m, M_DONTWAIT);
+
+ if ( !(M_EXT & m->m_flags) ) {
+ m_freem(m);
+ m = 0;
+ goto bail;
+ }
+
+ m_copydata(m_head, 0, MCLBYTES, mtod(m, caddr_t));
+ m->m_pkthdr.len = m->m_len = m_head->m_pkthdr.len;
+
+bail:
+ m_freem(m_head);
+ return m;
+}
+
+/* Enqueue a mbuf chain or a raw data buffer for transmission;
+ * RETURN: #bytes sent or -1 if there are not enough descriptors
+ *
+ * If 'len' is <=0 then 'm_head' is assumed to point to a mbuf chain.
+ * OTOH, a raw data packet may be send (non-BSD driver) by pointing
+ * m_head to the start of the data and passing 'len' > 0.
+ *
+ * Comments: software cache-flushing incurs a penalty if the
+ * packet cannot be queued since it is flushed anyways.
+ * The algorithm is slightly more efficient in the normal
+ * case, though.
+ */
+int
+BSP_mve_send_buf(struct mveth_private *mp, void *m_head, void *data_p, int len)
+{
+int rval;
+register MvEthTxDesc l,d,h;
+register struct mbuf *m1;
+int nmbs;
+int ismbuf = (len <= 0);
+
+/* Only way to get here is when we discover that the mbuf chain
+ * is too long for the tx ring
+ */
+startover:
+
+ rval = 0;
+
+#ifdef MVETH_TESTING
+ assert(m_head);
+#endif
+
+ /* if no descriptor is available; try to wipe the queue */
+ if ( (mp->avail < 1) && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
+ /* Maybe TX is stalled and needs to be restarted */
+ mveth_start_tx(mp);
+ return -1;
+ }
+
+ h = mp->d_tx_h;
+
+#ifdef MVETH_TESTING
+ assert( !h->buf_ptr );
+ assert( !h->mb );
+#endif
+
+ if ( ! (m1 = m_head) )
+ return 0;
+
+ if ( ismbuf ) {
+ /* find first mbuf with actual data */
+ while ( 0 == m1->m_len ) {
+ if ( ! (m1 = m1->m_next) ) {
+ /* end reached and still no data to send ?? */
+ m_freem(m_head);
+ return 0;
+ }
+ }
+ }
+
+ /* Don't use the first descriptor yet because BSP_mve_swipe_tx()
+ * needs mp->d_tx_h->buf_ptr == NULL as a marker. Hence, we
+ * start with the second mbuf and fill the first descriptor
+ * last.
+ */
+
+ l = h;
+ d = NEXT_TXD(h);
+
+ mp->avail--;
+
+ nmbs = 1;
+ if ( ismbuf ) {
+ register struct mbuf *m;
+ for ( m=m1->m_next; m; m=m->m_next ) {
+ if ( 0 == m->m_len )
+ continue; /* skip empty mbufs */
+
+ nmbs++;
+
+ if ( mp->avail < 1 && MVETH_CLEAN_ON_SEND(mp)<=0 ) {
+ /* Maybe TX was stalled - try to restart */
+ mveth_start_tx(mp);
+
+ /* not enough descriptors; cleanup...
+ * the first slot was never used, so we start
+ * at mp->d_tx_h->next;
+ */
+ for ( l = NEXT_TXD(h); l!=d; l=NEXT_TXD(l) ) {
+#ifdef MVETH_TESTING
+ assert( l->mb == 0 );
+#endif
+ l->buf_ptr = 0;
+ l->cmd_sts = 0;
+ mp->avail++;
+ }
+ mp->avail++;
+ if ( nmbs > TX_AVAILABLE_RING_SIZE(mp) ) {
+ /* this chain will never fit into the ring */
+ if ( nmbs > mp->stats.maxchain )
+ mp->stats.maxchain = nmbs;
+ mp->stats.repack++;
+ if ( ! (m_head = repackage_chain(m_head)) ) {
+ /* no cluster available */
+ mp->stats.odrops++;
+ return 0;
+ }
+ goto startover;
+ }
+ return -1;
+ }
+
+ mp->avail--;
+
+#ifdef MVETH_TESTING
+ assert( d != h );
+ assert( !d->buf_ptr );
+#endif
+
+ /* fill this slot */
+ rval += mveth_assign_desc(d, m, TDESC_DMA_OWNED);
+
+ FLUSH_BUF(mtod(m, uint32_t), m->m_len);
+
+ l = d;
+ d = NEXT_TXD(d);
+
+ FLUSH_DESC(l);
+ }
+
+ /* fill first slot - don't release to DMA yet */
+ rval += mveth_assign_desc(h, m1, TDESC_FRST);
+
+
+ FLUSH_BUF(mtod(m1, uint32_t), m1->m_len);
+
+ } else {
+ /* fill first slot with raw buffer - don't release to DMA yet */
+ rval += mveth_assign_desc_raw(h, data_p, len, TDESC_FRST);
+
+ FLUSH_BUF( (uint32_t)data_p, len);
+ }
+
+ /* tag last slot; this covers the case where 1st==last */
+ l->cmd_sts |= TDESC_LAST | TDESC_INT_ENA;
+ /* mbuf goes into last desc */
+ l->u_buf = m_head;
+
+
+ FLUSH_DESC(l);
+
+ /* Tag end; make sure chip doesn't try to read ahead of here! */
+ l->next->cmd_sts = 0;
+ FLUSH_DESC(l->next);
+
+#ifdef MVETH_DEBUG_TX_DUMP
+ if ( (mveth_tx_dump & (1<<mp->port_num)) ) {
+ int ll,kk;
+ if ( ismbuf ) {
+ struct mbuf *m;
+ for ( kk=0, m=m_head; m; m=m->m_next) {
+ for ( ll=0; ll<m->m_len; ll++ ) {
+ printf("%02X ",*(mtod(m,char*) + ll));
+ if ( ((++kk)&0xf) == 0 )
+ printf("\n");
+ }
+ }
+ } else {
+ for ( ll=0; ll<len; ) {
+ printf("%02X ",*((char*)data_p + ll));
+ if ( ((++ll)&0xf) == 0 )
+ printf("\n");
+ }
+ }
+ printf("\n");
+ }
+#endif
+
+ membarrier();
+
+ /* turn over the whole chain by flipping ownership of the first desc */
+ h->cmd_sts |= TDESC_DMA_OWNED;
+
+ FLUSH_DESC(h);
+
+ membarrier();
+
+ /* notify the device */
+ MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+
+ /* Update softc */
+ mp->stats.packet++;
+ if ( nmbs > mp->stats.maxchain )
+ mp->stats.maxchain = nmbs;
+
+ /* remember new head */
+ mp->d_tx_h = d;
+
+ return rval; /* #bytes sent */
+}
+
+int
+BSP_mve_send_buf_raw(
+ struct mveth_private *mp,
+ void *head_p,
+ int h_len,
+ void *data_p,
+ int d_len)
+{
+int rval;
+register MvEthTxDesc l,d,h;
+int needed;
+void *frst_buf;
+int frst_len;
+
+ rval = 0;
+
+#ifdef MVETH_TESTING
+ assert(header || data);
+#endif
+
+ needed = head_p && data_p ? 2 : 1;
+
+ /* if no descriptor is available; try to wipe the queue */
+ if ( ( mp->avail < needed )
+ && ( MVETH_CLEAN_ON_SEND(mp) <= 0 || mp->avail < needed ) ) {
+ /* Maybe TX was stalled and needs a restart */
+ mveth_start_tx(mp);
+ return -1;
+ }
+
+ h = mp->d_tx_h;
+
+#ifdef MVETH_TESTING
+ assert( !h->buf_ptr );
+ assert( !h->mb );
+#endif
+
+ /* find the 'first' user buffer */
+ if ( (frst_buf = head_p) ) {
+ frst_len = h_len;
+ } else {
+ frst_buf = data_p;
+ frst_len = d_len;
+ }
+
+ /* Don't use the first descriptor yet because BSP_mve_swipe_tx()
+ * needs mp->d_tx_h->buf_ptr == NULL as a marker. Hence, we
+ * start with the second (optional) slot and fill the first
+ * descriptor last.
+ */
+
+ l = h;
+ d = NEXT_TXD(h);
+
+ mp->avail--;
+
+ if ( needed > 1 ) {
+ mp->avail--;
+#ifdef MVETH_TESTING
+ assert( d != h );
+ assert( !d->buf_ptr );
+#endif
+ rval += mveth_assign_desc_raw(d, data_p, d_len, TDESC_DMA_OWNED);
+ FLUSH_BUF( (uint32_t)data_p, d_len );
+ d->u_buf = data_p;
+
+ l = d;
+ d = NEXT_TXD(d);
+
+ FLUSH_DESC(l);
+ }
+
+ /* fill first slot with raw buffer - don't release to DMA yet */
+ rval += mveth_assign_desc_raw(h, frst_buf, frst_len, TDESC_FRST);
+
+ FLUSH_BUF( (uint32_t)frst_buf, frst_len);
+
+ /* tag last slot; this covers the case where 1st==last */
+ l->cmd_sts |= TDESC_LAST | TDESC_INT_ENA;
+
+ /* first buffer of 'chain' goes into last desc */
+ l->u_buf = frst_buf;
+
+ FLUSH_DESC(l);
+
+ /* Tag end; make sure chip doesn't try to read ahead of here! */
+ l->next->cmd_sts = 0;
+ FLUSH_DESC(l->next);
+
+ membarrier();
+
+ /* turn over the whole chain by flipping ownership of the first desc */
+ h->cmd_sts |= TDESC_DMA_OWNED;
+
+ FLUSH_DESC(h);
+
+ membarrier();
+
+ /* notify the device */
+ MV_WRITE(MV643XX_ETH_TRANSMIT_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_TX_START(0));
+
+ /* Update softc */
+ mp->stats.packet++;
+ if ( needed > mp->stats.maxchain )
+ mp->stats.maxchain = needed;
+
+ /* remember new head */
+ mp->d_tx_h = d;
+
+ return rval; /* #bytes sent */
+}
+
+/* send received buffers upwards and replace them
+ * with freshly allocated ones;
+ * ASSUMPTION: buffer length NEVER changes and is set
+ * when the ring is initialized.
+ * TS 20060727: not sure if this assumption is still necessary - I believe it isn't.
+ */
+
+int
+BSP_mve_swipe_rx(struct mveth_private *mp)
+{
+int rval = 0, err;
+register MvEthRxDesc d;
+void *newbuf;
+int sz;
+uintptr_t baddr;
+
+ for ( d = mp->d_rx_t; ! (INVAL_DESC(d), (RDESC_DMA_OWNED & d->cmd_sts)); d=NEXT_RXD(d) ) {
+
+#ifdef MVETH_TESTING
+ assert(d->u_buf);
+#endif
+
+ err = (RDESC_ERROR & d->cmd_sts);
+
+ if ( err || !(newbuf = mp->alloc_rxbuf(&sz, &baddr)) ) {
+ /* drop packet and recycle buffer */
+ newbuf = d->u_buf;
+ mp->consume_rxbuf(0, mp->consume_rxbuf_arg, err ? -1 : 0);
+ } else {
+#ifdef MVETH_TESTING
+ assert( d->byte_cnt > 0 );
+#endif
+ mp->consume_rxbuf(d->u_buf, mp->consume_rxbuf_arg, d->byte_cnt);
+
+#ifndef ENABLE_HW_SNOOPING
+ /* could reduce the area to max. ethernet packet size */
+ INVAL_BUF(baddr, sz);
+#endif
+ d->u_buf = newbuf;
+ d->buf_ptr = CPUADDR2ENET(baddr);
+ d->buf_size = sz;
+ FLUSH_DESC(d);
+ }
+
+ membarrier();
+
+ d->cmd_sts = RDESC_DMA_OWNED | RDESC_INT_ENA;
+
+ FLUSH_DESC(d);
+
+ rval++;
+ }
+ MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_START(0));
+ mp->d_rx_t = d;
+ return rval;
+}
+
+/* Stop hardware and clean out the rings */
+void
+BSP_mve_stop_hw(struct mveth_private *mp)
+{
+MvEthTxDesc d;
+MvEthRxDesc r;
+int i;
+
+ mveth_disable_irqs(mp, -1);
+
+ mveth_stop_tx(mp->port_num);
+
+ /* cleanup TX rings */
+ if (mp->d_tx_t) { /* maybe ring isn't initialized yet */
+ for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++, d++ ) {
+ /* should be safe to clear ownership */
+ d->cmd_sts &= ~TDESC_DMA_OWNED;
+ FLUSH_DESC(d);
+ }
+ FLUSH_BARRIER();
+
+ BSP_mve_swipe_tx(mp);
+
+#ifdef MVETH_TESTING
+ assert( mp->d_tx_h == mp->d_tx_t );
+ for ( i=0, d=mp->tx_ring; i<mp->xbuf_count; i++, d++ ) {
+ assert( !d->buf_ptr );
+ }
+#endif
+ }
+
+ MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_STOP_ALL);
+ while ( MV643XX_ETH_RX_ANY_RUNNING & MV_READ(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num)) )
+ /* poll-wait */;
+
+ /* stop serial port */
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num),
+ MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num))
+ & ~( MV643XX_ETH_SERIAL_PORT_ENBL | MV643XX_ETH_FORCE_LINK_FAIL_DISABLE | MV643XX_ETH_FORCE_LINK_PASS)
+ );
+
+ /* clear pending interrupts */
+ MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(mp->port_num), 0);
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(mp->port_num), 0);
+
+ /* cleanup RX rings */
+ if ( mp->rx_ring ) {
+ for ( i=0, r=mp->rx_ring; i<mp->rbuf_count; i++, r++ ) {
+ /* should be OK to clear ownership flag */
+ r->cmd_sts = 0;
+ FLUSH_DESC(r);
+ mp->consume_rxbuf(r->u_buf, mp->consume_rxbuf_arg, 0);
+ r->u_buf = 0;
+ }
+ FLUSH_BARRIER();
+ }
+
+
+}
+
+uint32_t mveth_serial_ctrl_config_val = MVETH_SERIAL_CTRL_CONFIG_VAL;
+
+/* Fire up the low-level driver
+ *
+ * - make sure hardware is halted
+ * - enable cache snooping
+ * - clear address filters
+ * - clear mib counters
+ * - reset phy
+ * - initialize (or reinitialize) descriptor rings
+ * - check that the firmware has set up a reasonable mac address.
+ * - generate unicast filter entry for our mac address
+ * - write register config values to the chip
+ * - start hardware (serial port and SDMA)
+ */
+
+void
+BSP_mve_init_hw(struct mveth_private *mp, int promisc, unsigned char *enaddr)
+{
+int i;
+uint32_t v;
+static int inited = 0;
+
+#ifdef MVETH_DEBUG
+ printk(DRVNAME"%i: Entering BSP_mve_init_hw()\n", mp->port_num+1);
+#endif
+
+ /* since enable/disable IRQ routine only operate on select bitsets
+ * we must make sure everything is masked initially.
+ */
+ MV_WRITE(MV643XX_ETH_INTERRUPT_ENBL_R(mp->port_num), 0);
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_ENBL_R(mp->port_num), 0);
+
+ BSP_mve_stop_hw(mp);
+
+ memset(&mp->stats, 0, sizeof(mp->stats));
+
+ mp->promisc = promisc;
+
+ /* MotLoad has cache snooping disabled on the ENET2MEM windows.
+ * Some comments in (linux) indicate that there are errata
+ * which cause problems which would be a real bummer.
+ * We try it anyways...
+ */
+ if ( !inited ) {
+ unsigned long disbl, bar;
+ inited = 1; /* FIXME: non-thread safe lazy init */
+ disbl = MV_READ(MV643XX_ETH_BAR_ENBL_R);
+ /* disable all 6 windows */
+ MV_WRITE(MV643XX_ETH_BAR_ENBL_R, MV643XX_ETH_BAR_DISBL_ALL);
+ /* set WB snooping on enabled bars */
+ for ( i=0; i<MV643XX_ETH_NUM_BARS*8; i+=8 ) {
+ if ( (bar = MV_READ(MV643XX_ETH_BAR_0 + i)) && MV_READ(MV643XX_ETH_SIZE_R_0 + i) ) {
+#ifdef ENABLE_HW_SNOOPING
+ MV_WRITE(MV643XX_ETH_BAR_0 + i, bar | MV64360_ENET2MEM_SNOOP_WB);
+#else
+ MV_WRITE(MV643XX_ETH_BAR_0 + i, bar & ~MV64360_ENET2MEM_SNOOP_MSK);
+#endif
+ /* read back to flush fifo [linux comment] */
+ (void)MV_READ(MV643XX_ETH_BAR_0 + i);
+ }
+ }
+ /* restore/re-enable */
+ MV_WRITE(MV643XX_ETH_BAR_ENBL_R, disbl);
+ }
+
+ mveth_clear_mib_counters(mp);
+ mveth_clear_addr_filters(mp);
+
+/* Just leave it alone...
+ reset_phy();
+*/
+
+ if ( mp->rbuf_count > 0 ) {
+ mp->rx_ring = (MvEthRxDesc)MV643XX_ALIGN(mp->ring_area, RING_ALIGNMENT);
+ mveth_init_rx_desc_ring(mp);
+ }
+
+ if ( mp->xbuf_count > 0 ) {
+ mp->tx_ring = (MvEthTxDesc)mp->rx_ring + mp->rbuf_count;
+ mveth_init_tx_desc_ring(mp);
+ }
+
+ if ( enaddr ) {
+ /* set ethernet address from arpcom struct */
+#ifdef MVETH_DEBUG
+ printk(DRVNAME"%i: Writing MAC addr ", mp->port_num+1);
+ for (i=5; i>=0; i--) {
+ printk("%02X%c", enaddr[i], i?':':'\n');
+ }
+#endif
+ mveth_write_eaddr(mp, enaddr);
+ }
+
+ /* set mac address and unicast filter */
+
+ {
+ uint32_t machi, maclo;
+ maclo = MV_READ(MV643XX_ETH_MAC_ADDR_LO(mp->port_num));
+ machi = MV_READ(MV643XX_ETH_MAC_ADDR_HI(mp->port_num));
+ /* ASSUME: firmware has set the mac address for us
+ * - if assertion fails, we have to do more work...
+ */
+ assert( maclo && machi && maclo != 0xffffffff && machi != 0xffffffff );
+ mveth_ucfilter(mp, maclo&0xff, 1/* accept */);
+ }
+
+ /* port, serial and sdma configuration */
+ v = MVETH_PORT_CONFIG_VAL;
+ if ( promisc ) {
+ /* multicast filters were already set up to
+ * accept everything (mveth_clear_addr_filters())
+ */
+ v |= MV643XX_ETH_UNICAST_PROMISC_MODE;
+ } else {
+ v &= ~MV643XX_ETH_UNICAST_PROMISC_MODE;
+ }
+ MV_WRITE(MV643XX_ETH_PORT_CONFIG_R(mp->port_num),
+ v);
+ MV_WRITE(MV643XX_ETH_PORT_CONFIG_XTEND_R(mp->port_num),
+ MVETH_PORT_XTEND_CONFIG_VAL);
+
+ v = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num));
+ v &= ~(MVETH_SERIAL_CTRL_CONFIG_MSK);
+ v |= mveth_serial_ctrl_config_val;
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num), v);
+
+ i = IFM_MAKEWORD(0, 0, 0, 0);
+ if ( 0 == BSP_mve_media_ioctl(mp, SIOCGIFMEDIA, &i) ) {
+ if ( (IFM_LINK_OK & i) ) {
+ mveth_update_serial_port(mp, i);
+ }
+ }
+
+ /* enable serial port */
+ v = MV_READ(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num));
+ MV_WRITE(MV643XX_ETH_SERIAL_CONTROL_R(mp->port_num),
+ v | MV643XX_ETH_SERIAL_PORT_ENBL);
+
+#ifndef __BIG_ENDIAN__
+#error "byte swapping needs to be disabled for little endian machines"
+#endif
+ MV_WRITE(MV643XX_ETH_SDMA_CONFIG_R(mp->port_num), MVETH_SDMA_CONFIG_VAL);
+
+ /* allow short frames */
+ MV_WRITE(MV643XX_ETH_RX_MIN_FRAME_SIZE_R(mp->port_num), MVETH_MIN_FRAMSZ_CONFIG_VAL);
+
+ MV_WRITE(MV643XX_ETH_INTERRUPT_CAUSE_R(mp->port_num), 0);
+ MV_WRITE(MV643XX_ETH_INTERRUPT_EXTEND_CAUSE_R(mp->port_num), 0);
+ /* TODO: set irq coalescing */
+
+ /* enable Rx */
+ if ( mp->rbuf_count > 0 ) {
+ MV_WRITE(MV643XX_ETH_RECEIVE_QUEUE_COMMAND_R(mp->port_num), MV643XX_ETH_RX_START(0));
+ }
+
+ mveth_enable_irqs(mp, -1);
+
+#ifdef MVETH_DEBUG
+ printk(DRVNAME"%i: Leaving BSP_mve_init_hw()\n", mp->port_num+1);
+#endif
+}
+
+/* read ethernet address from hw to buffer */
+void
+BSP_mve_read_eaddr(struct mveth_private *mp, unsigned char *oeaddr)
+{
+int i;
+uint32_t x;
+unsigned char buf[6], *eaddr;
+
+ eaddr = oeaddr ? oeaddr : buf;
+
+ eaddr += 5;
+ x = MV_READ(MV643XX_ETH_MAC_ADDR_LO(mp->port_num));
+
+ /* lo word */
+ for (i=2; i; i--, eaddr--) {
+ *eaddr = (unsigned char)(x & 0xff);
+ x>>=8;
+ }
+
+ x = MV_READ(MV643XX_ETH_MAC_ADDR_HI(mp->port_num));
+ /* hi word */
+ for (i=4; i; i--, eaddr--) {
+ *eaddr = (unsigned char)(x & 0xff);
+ x>>=8;
+ }
+
+ if ( !oeaddr ) {
+ printf("%02X",buf[0]);
+ for (i=1; i<sizeof(buf); i++)
+ printf(":%02X",buf[i]);
+ printf("\n");
+ }
+}
+
+int
+BSP_mve_media_ioctl(struct mveth_private *mp, int cmd, int *parg)
+{
+int rval;
+ /* alias cmd == 0,1 */
+ switch ( cmd ) {
+ case 0: cmd = SIOCGIFMEDIA;
+ break;
+ case 1: cmd = SIOCSIFMEDIA;
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ break;
+ default: return -1;
+ }
+ REGLOCK();
+ rval = rtems_mii_ioctl(&mveth_mdio, mp, cmd, parg);
+ REGUNLOCK();
+ return rval;
+}
+
+void
+BSP_mve_enable_irqs(struct mveth_private *mp)
+{
+ mveth_enable_irqs(mp, -1);
+}
+
+void
+BSP_mve_disable_irqs(struct mveth_private *mp)
+{
+ mveth_disable_irqs(mp, -1);
+}
+
+uint32_t
+BSP_mve_ack_irqs(struct mveth_private *mp)
+{
+ return mveth_ack_irqs(mp, -1);
+}
+
+
+void
+BSP_mve_enable_irq_mask(struct mveth_private *mp, uint32_t mask)
+{
+ mveth_enable_irqs(mp, mask);
+}
+
+uint32_t
+BSP_mve_disable_irq_mask(struct mveth_private *mp, uint32_t mask)
+{
+ return mveth_disable_irqs(mp, mask);
+}
+
+uint32_t
+BSP_mve_ack_irq_mask(struct mveth_private *mp, uint32_t mask)
+{
+ return mveth_ack_irqs(mp, mask);
+}
+
+int
+BSP_mve_ack_link_chg(struct mveth_private *mp, int *pmedia)
+{
+int media = IFM_MAKEWORD(0,0,0,0);
+
+ if ( 0 == BSP_mve_media_ioctl(mp, SIOCGIFMEDIA, &media)) {
+ if ( IFM_LINK_OK & media ) {
+ mveth_update_serial_port(mp, media);
+ /* If TX stalled because there was no buffer then whack it */
+ mveth_start_tx(mp);
+ }
+ if ( pmedia )
+ *pmedia = media;
+ return 0;
+ }
+ return -1;
+}
+
+/* BSDNET SUPPORT/GLUE ROUTINES */
+
+static void
+mveth_set_filters(struct ifnet *ifp);
+
+STATIC void
+mveth_stop(struct mveth_softc *sc)
+{
+ BSP_mve_stop_hw(&sc->pvt);
+ sc->arpcom.ac_if.if_timer = 0;
+}
+
+/* allocate a mbuf for RX with a properly aligned data buffer
+ * RETURNS 0 if allocation fails
+ */
+static void *
+alloc_mbuf_rx(int *psz, uintptr_t *paddr)
+{
+struct mbuf *m;
+unsigned long l,o;
+
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if ( !m )
+ return 0;
+ MCLGET(m, M_DONTWAIT);
+ if ( ! (m->m_flags & M_EXT) ) {
+ m_freem(m);
+ return 0;
+ }
+
+ o = mtod(m, unsigned long);
+ l = MV643XX_ALIGN(o, RX_BUF_ALIGNMENT) - o;
+
+ /* align start of buffer */
+ m->m_data += l;
+
+ /* reduced length */
+ l = MCLBYTES - l;
+
+ m->m_len = m->m_pkthdr.len = l;
+ *psz = m->m_len;
+ *paddr = mtod(m, uintptr_t);
+
+ return (void*) m;
+}
+
+static void consume_rx_mbuf(void *buf, void *arg, int len)
+{
+struct ifnet *ifp = arg;
+struct mbuf *m = buf;
+
+ if ( len <= 0 ) {
+ ifp->if_iqdrops++;
+ if ( len < 0 ) {
+ ifp->if_ierrors++;
+ }
+ if ( m )
+ m_freem(m);
+ } else {
+ struct ether_header *eh;
+
+ eh = (struct ether_header *)(mtod(m, unsigned long) + ETH_RX_OFFSET);
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header) - ETH_RX_OFFSET - ETH_CRC_LEN;
+ m->m_data += sizeof(struct ether_header) + ETH_RX_OFFSET;
+ m->m_pkthdr.rcvif = ifp;
+
+ ifp->if_ipackets++;
+ ifp->if_ibytes += m->m_pkthdr.len;
+
+ if (0) {
+ /* Low-level debugging */
+ int i;
+ for (i=0; i<13; i++) {
+ printf("%02X:",((char*)eh)[i]);
+ }
+ printf("%02X\n",((char*)eh)[i]);
+ for (i=0; i<m->m_len; i++) {
+ if ( !(i&15) )
+ printf("\n");
+ printf("0x%02x ",mtod(m,char*)[i]);
+ }
+ printf("\n");
+ }
+
+ if (0) {
+ /* Low-level debugging/testing without bsd stack */
+ m_freem(m);
+ } else {
+ /* send buffer upwards */
+ ether_input(ifp, eh, m);
+ }
+ }
+}
+
+static void release_tx_mbuf(void *buf, void *arg, int err)
+{
+struct ifnet *ifp = arg;
+struct mbuf *mb = buf;
+
+ if ( err ) {
+ ifp->if_oerrors++;
+ } else {
+ ifp->if_opackets++;
+ }
+ ifp->if_obytes += mb->m_pkthdr.len;
+ m_freem(mb);
+}
+
+static void
+dump_update_stats(struct mveth_private *mp, FILE *f)
+{
+int p = mp->port_num;
+int idx;
+uint32_t v;
+
+ if ( !f )
+ f = stdout;
+
+ fprintf(f, DRVNAME"%i Statistics:\n", mp->port_num + 1);
+ fprintf(f, " # IRQS: %i\n", mp->stats.irqs);
+ fprintf(f, " Max. mbuf chain length: %i\n", mp->stats.maxchain);
+ fprintf(f, " # repacketed: %i\n", mp->stats.repack);
+ fprintf(f, " # packets: %i\n", mp->stats.packet);
+ fprintf(f, "MIB Counters:\n");
+ for ( idx = MV643XX_ETH_MIB_GOOD_OCTS_RCVD_LO>>2;
+ idx < MV643XX_ETH_NUM_MIB_COUNTERS;
+ idx++ ) {
+ switch ( idx ) {
+ case MV643XX_ETH_MIB_GOOD_OCTS_RCVD_LO>>2:
+ mp->stats.mib.good_octs_rcvd += read_long_mib_counter(p, idx);
+ fprintf(f, mibfmt[idx], mp->stats.mib.good_octs_rcvd);
+ idx++;
+ break;
+
+ case MV643XX_ETH_MIB_GOOD_OCTS_SENT_LO>>2:
+ mp->stats.mib.good_octs_sent += read_long_mib_counter(p, idx);
+ fprintf(f, mibfmt[idx], mp->stats.mib.good_octs_sent);
+ idx++;
+ break;
+
+ default:
+ v = ((uint32_t*)&mp->stats.mib)[idx] += read_mib_counter(p, idx);
+ fprintf(f, mibfmt[idx], v);
+ break;
+ }
+ }
+ fprintf(f, "\n");
+}
+
+void
+BSP_mve_dump_stats(struct mveth_private *mp, FILE *f)
+{
+ dump_update_stats(mp, f);
+}
+
+/* BSDNET DRIVER CALLBACKS */
+
+static void
+mveth_init(void *arg)
+{
+struct mveth_softc *sc = arg;
+struct ifnet *ifp = &sc->arpcom.ac_if;
+int media;
+
+ BSP_mve_init_hw(&sc->pvt, ifp->if_flags & IFF_PROMISC, sc->arpcom.ac_enaddr);
+
+ media = IFM_MAKEWORD(0, 0, 0, 0);
+ if ( 0 == BSP_mve_media_ioctl(&sc->pvt, SIOCGIFMEDIA, &media) ) {
+ if ( (IFM_LINK_OK & media) ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ } else {
+ ifp->if_flags |= IFF_OACTIVE;
+ }
+ }
+
+ /* if promiscuous then there is no need to change */
+ if ( ! (ifp->if_flags & IFF_PROMISC) )
+ mveth_set_filters(ifp);
+
+ ifp->if_flags |= IFF_RUNNING;
+ sc->arpcom.ac_if.if_timer = 0;
+}
+
+/* bsdnet driver entry to start transmission */
+static void
+mveth_start(struct ifnet *ifp)
+{
+struct mveth_softc *sc = ifp->if_softc;
+struct mbuf *m = 0;
+
+ while ( ifp->if_snd.ifq_head ) {
+ IF_DEQUEUE( &ifp->if_snd, m );
+ if ( BSP_mve_send_buf(&sc->pvt, m, 0, 0) < 0 ) {
+ IF_PREPEND( &ifp->if_snd, m);
+ ifp->if_flags |= IFF_OACTIVE;
+ break;
+ }
+ /* need to do this really only once
+ * but it's cheaper this way.
+ */
+ ifp->if_timer = 2*IFNET_SLOWHZ;
+ }
+}
+
+/* bsdnet driver entry; */
+static void
+mveth_watchdog(struct ifnet *ifp)
+{
+struct mveth_softc *sc = ifp->if_softc;
+
+ ifp->if_oerrors++;
+ printk(DRVNAME"%i: watchdog timeout; resetting\n", ifp->if_unit);
+
+ mveth_init(sc);
+ mveth_start(ifp);
+}
+
+static void
+mveth_set_filters(struct ifnet *ifp)
+{
+struct mveth_softc *sc = ifp->if_softc;
+uint32_t v;
+
+ v = MV_READ(MV643XX_ETH_PORT_CONFIG_R(sc->pvt.port_num));
+ if ( ifp->if_flags & IFF_PROMISC )
+ v |= MV643XX_ETH_UNICAST_PROMISC_MODE;
+ else
+ v &= ~MV643XX_ETH_UNICAST_PROMISC_MODE;
+ MV_WRITE(MV643XX_ETH_PORT_CONFIG_R(sc->pvt.port_num), v);
+
+ if ( ifp->if_flags & (IFF_PROMISC | IFF_ALLMULTI) ) {
+ BSP_mve_mcast_filter_accept_all(&sc->pvt);
+ } else {
+ struct ether_multi *enm;
+ struct ether_multistep step;
+
+ BSP_mve_mcast_filter_clear( &sc->pvt );
+
+ ETHER_FIRST_MULTI(step, (struct arpcom *)ifp, enm);
+
+ while ( enm ) {
+ if ( memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN) )
+ assert( !"Should never get here; IFF_ALLMULTI should be set!" );
+
+ BSP_mve_mcast_filter_accept_add(&sc->pvt, enm->enm_addrlo);
+
+ ETHER_NEXT_MULTI(step, enm);
+ }
+ }
+}
+
+/* bsdnet driver ioctl entry */
+static int
+mveth_ioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data)
+{
+struct mveth_softc *sc = ifp->if_softc;
+struct ifreq *ifr = (struct ifreq *)data;
+int error = 0;
+int f;
+
+ switch ( cmd ) {
+ case SIOCSIFFLAGS:
+ f = ifp->if_flags;
+ if ( f & IFF_UP ) {
+ if ( ! ( f & IFF_RUNNING ) ) {
+ mveth_init(sc);
+ } else {
+ if ( (f & IFF_PROMISC) != (sc->bsd.oif_flags & IFF_PROMISC) ) {
+ /* Note: in all other scenarios the 'promisc' flag
+ * in the low-level driver [which affects the way
+ * the multicast filter is setup: accept none vs.
+ * accept all in promisc mode] is eventually
+ * set when the IF is brought up...
+ */
+ sc->pvt.promisc = (f & IFF_PROMISC);
+
+ mveth_set_filters(ifp);
+ }
+ /* FIXME: other flag changes are ignored/unimplemented */
+ }
+ } else {
+ if ( f & IFF_RUNNING ) {
+ mveth_stop(sc);
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+ }
+ }
+ sc->bsd.oif_flags = ifp->if_flags;
+ break;
+
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ error = BSP_mve_media_ioctl(&sc->pvt, cmd, &ifr->ifr_media);
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ error = (cmd == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &sc->arpcom)
+ : ether_delmulti(ifr, &sc->arpcom);
+
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING) {
+ mveth_set_filters(ifp);
+ }
+ error = 0;
+ }
+ break;
+
+
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ dump_update_stats(&sc->pvt, stdout);
+ break;
+
+ default:
+ error = ether_ioctl(ifp, cmd, data);
+ break;
+ }
+
+ return error;
+}
+
+/* DRIVER TASK */
+
+/* Daemon task does all the 'interrupt' work */
+static void mveth_daemon(void *arg)
+{
+struct mveth_softc *sc;
+struct ifnet *ifp;
+rtems_event_set evs;
+ for (;;) {
+ rtems_bsdnet_event_receive( 7, RTEMS_WAIT | RTEMS_EVENT_ANY, RTEMS_NO_TIMEOUT, &evs );
+ evs &= 7;
+ for ( sc = theMvEths; evs; evs>>=1, sc++ ) {
+ if ( (evs & 1) ) {
+ register uint32_t x;
+
+ ifp = &sc->arpcom.ac_if;
+
+ if ( !(ifp->if_flags & IFF_UP) ) {
+ mveth_stop(sc);
+ ifp->if_flags &= ~(IFF_UP|IFF_RUNNING);
+ continue;
+ }
+
+ if ( !(ifp->if_flags & IFF_RUNNING) ) {
+ /* event could have been pending at the time hw was stopped;
+ * just ignore...
+ */
+ continue;
+ }
+
+ x = mveth_ack_irqs(&sc->pvt, -1);
+
+ if ( MV643XX_ETH_EXT_IRQ_LINK_CHG & x ) {
+ /* phy status changed */
+ int media;
+
+ if ( 0 == BSP_mve_ack_link_chg(&sc->pvt, &media) ) {
+ if ( IFM_LINK_OK & media ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ mveth_start(ifp);
+ } else {
+ /* stop sending */
+ ifp->if_flags |= IFF_OACTIVE;
+ }
+ }
+ }
+ /* free tx chain */
+ if ( (MV643XX_ETH_EXT_IRQ_TX_DONE & x) && BSP_mve_swipe_tx(&sc->pvt) ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ if ( TX_AVAILABLE_RING_SIZE(&sc->pvt) == sc->pvt.avail )
+ ifp->if_timer = 0;
+ mveth_start(ifp);
+ }
+ if ( (MV643XX_ETH_IRQ_RX_DONE & x) )
+ BSP_mve_swipe_rx(&sc->pvt);
+
+ mveth_enable_irqs(&sc->pvt, -1);
+ }
+ }
+ }
+}
+
+#ifdef MVETH_DETACH_HACK
+static int mveth_detach(struct mveth_softc *sc);
+#endif
+
+
+/* PUBLIC RTEMS BSDNET ATTACH FUNCTION */
+int
+rtems_mve_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+char *unitName;
+int unit,i,cfgUnits;
+struct mveth_softc *sc;
+struct ifnet *ifp;
+
+ unit = rtems_bsdnet_parse_driver_name(ifcfg, &unitName);
+ if ( unit <= 0 || unit > MV643XXETH_NUM_DRIVER_SLOTS ) {
+ printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, MV643XXETH_NUM_DRIVER_SLOTS);
+ return 1;
+ }
+
+ sc = &theMvEths[unit-1];
+ ifp = &sc->arpcom.ac_if;
+ sc->pvt.port_num = unit-1;
+ sc->pvt.phy = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*sc->pvt.port_num)) & 0x1f;
+
+ if ( attaching ) {
+ if ( ifp->if_init ) {
+ printk(DRVNAME": instance %i already attached.\n", unit);
+ return -1;
+ }
+
+ for ( i=cfgUnits = 0; i<MV643XXETH_NUM_DRIVER_SLOTS; i++ ) {
+ if ( theMvEths[i].arpcom.ac_if.if_init )
+ cfgUnits++;
+ }
+ cfgUnits++; /* this new one */
+
+ /* lazy init of TID should still be thread-safe because we are protected
+ * by the global networking semaphore..
+ */
+ if ( !mveth_tid ) {
+ /* newproc uses the 1st 4 chars of name string to build an rtems name */
+ mveth_tid = rtems_bsdnet_newproc("MVEd", 4096, mveth_daemon, 0);
+ }
+
+ if ( !BSP_mve_setup( unit,
+ mveth_tid,
+ release_tx_mbuf, ifp,
+ alloc_mbuf_rx,
+ consume_rx_mbuf, ifp,
+ ifcfg->rbuf_count,
+ ifcfg->xbuf_count,
+ BSP_MVE_IRQ_TX | BSP_MVE_IRQ_RX | BSP_MVE_IRQ_LINK) ) {
+ return -1;
+ }
+
+ if ( nmbclusters < sc->pvt.rbuf_count * cfgUnits + 60 /* arbitrary */ ) {
+ printk(DRVNAME"%i: (mv643xx ethernet) Your application has not enough mbuf clusters\n", unit);
+ printk( " configured for this driver.\n");
+ return -1;
+ }
+
+ if ( ifcfg->hardware_address ) {
+ memcpy(sc->arpcom.ac_enaddr, ifcfg->hardware_address, ETHER_ADDR_LEN);
+ } else {
+ /* read back from hardware assuming that MotLoad already had set it up */
+ BSP_mve_read_eaddr(&sc->pvt, sc->arpcom.ac_enaddr);
+ }
+
+ ifp->if_softc = sc;
+ ifp->if_unit = unit;
+ ifp->if_name = unitName;
+
+ ifp->if_mtu = ifcfg->mtu ? ifcfg->mtu : ETHERMTU;
+
+ ifp->if_init = mveth_init;
+ ifp->if_ioctl = mveth_ioctl;
+ ifp->if_start = mveth_start;
+ ifp->if_output = ether_output;
+ /*
+ * While nonzero, the 'if->if_timer' is decremented
+ * (by the networking code) at a rate of IFNET_SLOWHZ (1hz) and 'if_watchdog'
+ * is called when it expires.
+ * If either of those fields is 0 the feature is disabled.
+ */
+ ifp->if_watchdog = mveth_watchdog;
+ ifp->if_timer = 0;
+
+ sc->bsd.oif_flags = /* ... */
+ ifp->if_flags = IFF_BROADCAST | IFF_MULTICAST | IFF_SIMPLEX;
+
+ /*
+ * if unset, this set to 10Mbps by ether_ifattach; seems to be unused by bsdnet stack;
+ * could be updated along with phy speed, though...
+ ifp->if_baudrate = 10000000;
+ */
+
+ /* NOTE: ether_output drops packets if ifq_len >= ifq_maxlen
+ * but this is the packet count, not the fragment count!
+ ifp->if_snd.ifq_maxlen = sc->pvt.xbuf_count;
+ */
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+#ifdef MVETH_DETACH_HACK
+ if ( !ifp->if_addrlist ) /* do only the first time [reattach hack] */
+#endif
+ {
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ }
+
+ } else {
+#ifdef MVETH_DETACH_HACK
+ if ( !ifp->if_init ) {
+ printk(DRVNAME": instance %i not attached.\n", unit);
+ return -1;
+ }
+ return mveth_detach(sc);
+#else
+ printk(DRVNAME": interface detaching not implemented\n");
+ return -1;
+#endif
+ }
+
+ return 0;
+}
+
+/* EARLY PHY ACCESS */
+static int
+mveth_early_init(int idx)
+{
+ if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
+ return -1;
+
+ /* determine the phy */
+ theMvEths[idx].pvt.phy = (MV_READ(MV643XX_ETH_PHY_ADDR_R) >> (5*idx)) & 0x1f;
+ return 0;
+}
+
+static int
+mveth_early_read_phy(int idx, unsigned reg)
+{
+int rval;
+
+ if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
+ return -1;
+
+ rval = mveth_mii_read(&theMvEths[idx].pvt, reg);
+ return rval < 0 ? rval : rval & 0xffff;
+}
+
+static int
+mveth_early_write_phy(int idx, unsigned reg, unsigned val)
+{
+ if ( idx < 0 || idx >= MV643XXETH_NUM_DRIVER_SLOTS )
+ return -1;
+
+ mveth_mii_write(&theMvEths[idx].pvt, reg, val);
+ return 0;
+}
+
+rtems_bsdnet_early_link_check_ops
+rtems_mve_early_link_check_ops = {
+ init: mveth_early_init,
+ read_phy: mveth_early_read_phy,
+ write_phy: mveth_early_write_phy,
+ name: DRVNAME,
+ num_slots: MAX_NUM_SLOTS
+};
+
+/* DEBUGGING */
+
+#ifdef MVETH_DEBUG
+/* Display/dump descriptor rings */
+
+int
+mveth_dring(struct mveth_softc *sc)
+{
+int i;
+if (1) {
+MvEthRxDesc pr;
+printf("RX:\n");
+
+ for (i=0, pr=sc->pvt.rx_ring; i<sc->pvt.rbuf_count; i++, pr++) {
+#ifndef ENABLE_HW_SNOOPING
+ /* can't just invalidate the descriptor - if it contains
+ * data that hasn't been flushed yet, we create an inconsistency...
+ */
+ rtems_bsdnet_semaphore_obtain();
+ INVAL_DESC(pr);
+#endif
+ printf("cnt: 0x%04x, size: 0x%04x, stat: 0x%08x, next: 0x%08x, buf: 0x%08x\n",
+ pr->byte_cnt, pr->buf_size, pr->cmd_sts, (uint32_t)pr->next_desc_ptr, pr->buf_ptr);
+
+#ifndef ENABLE_HW_SNOOPING
+ rtems_bsdnet_semaphore_release();
+#endif
+ }
+}
+if (1) {
+MvEthTxDesc pt;
+printf("TX:\n");
+ for (i=0, pt=sc->pvt.tx_ring; i<sc->pvt.xbuf_count; i++, pt++) {
+#ifndef ENABLE_HW_SNOOPING
+ rtems_bsdnet_semaphore_obtain();
+ INVAL_DESC(pt);
+#endif
+ printf("cnt: 0x%04x, stat: 0x%08x, next: 0x%08x, buf: 0x%08x, mb: 0x%08x\n",
+ pt->byte_cnt, pt->cmd_sts, (uint32_t)pt->next_desc_ptr, pt->buf_ptr,
+ (uint32_t)pt->mb);
+
+#ifndef ENABLE_HW_SNOOPING
+ rtems_bsdnet_semaphore_release();
+#endif
+ }
+}
+ return 0;
+}
+
+#endif
+
+/* DETACH HACK DETAILS */
+
+#ifdef MVETH_DETACH_HACK
+int
+_cexpModuleFinalize(void *mh)
+{
+int i;
+ for ( i=0; i<MV643XXETH_NUM_DRIVER_SLOTS; i++ ) {
+ if ( theMvEths[i].arpcom.ac_if.if_init ) {
+ printf("Interface %i still attached; refuse to unload\n", i+1);
+ return -1;
+ }
+ }
+ /* delete task; since there are no attached interfaces, it should block
+ * for events and hence not hold the semaphore or other resources...
+ */
+ rtems_task_delete(mveth_tid);
+ return 0;
+}
+
+/* ugly hack to allow unloading/reloading the driver core.
+ * needed because rtems' bsdnet release doesn't implement
+ * if_detach(). Therefore, we bring the interface down but
+ * keep the device record alive...
+ */
+static void
+ether_ifdetach_pvt(struct ifnet *ifp)
+{
+ ifp->if_flags = 0;
+ ifp->if_ioctl = 0;
+ ifp->if_start = 0;
+ ifp->if_watchdog = 0;
+ ifp->if_init = 0;
+}
+
+static int
+mveth_detach(struct mveth_softc *sc)
+{
+struct ifnet *ifp = &sc->arpcom.ac_if;
+ if ( ifp->if_init ) {
+ if ( ifp->if_flags & (IFF_UP | IFF_RUNNING) ) {
+ printf(DRVNAME"%i: refuse to detach; interface still up\n",sc->pvt.port_num+1);
+ return -1;
+ }
+ mveth_stop(sc);
+/* not implemented in BSDnet/RTEMS (yet) but declared in header */
+#define ether_ifdetach ether_ifdetach_pvt
+ ether_ifdetach(ifp);
+ }
+ free( (void*)sc->pvt.ring_area, M_DEVBUF );
+ sc->pvt.ring_area = 0;
+ sc->pvt.tx_ring = 0;
+ sc->pvt.rx_ring = 0;
+ sc->pvt.d_tx_t = sc->pvt.d_tx_h = 0;
+ sc->pvt.d_rx_t = 0;
+ sc->pvt.avail = 0;
+ /* may fail if ISR was not installed yet */
+ BSP_remove_rtems_irq_handler( &irq_data[sc->pvt.port_num] );
+ return 0;
+}
+
+#ifdef MVETH_DEBUG
+struct rtems_bsdnet_ifconfig mveth_dbg_config = {
+ name: DRVNAME"1",
+ attach: rtems_mve_attach,
+ ip_address: "192.168.2.10", /* not used by rtems_bsdnet_attach */
+ ip_netmask: "255.255.255.0", /* not used by rtems_bsdnet_attach */
+ hardware_address: 0, /* (void *) */
+ ignore_broadcast: 0, /* TODO driver should honour this */
+ mtu: 0,
+ rbuf_count: 0, /* TODO driver should honour this */
+ xbuf_count: 0, /* TODO driver should honour this */
+};
+#endif
+#endif
diff --git a/bsps/powerpc/beatnik/net/if_mve/mve_smallbuf_tst.c b/bsps/powerpc/beatnik/net/if_mve/mve_smallbuf_tst.c
new file mode 100644
index 0000000..721ade3
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_mve/mve_smallbuf_tst.c
@@ -0,0 +1,145 @@
+#include <rtems.h>
+#include <bsp.h>
+#include <bsp/if_mve_pub.h>
+#include <stdlib.h>
+#include <stdio.h>
+
+/* Demo for the mv64360 ethernet quirk:
+ *
+ * $$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+ * $$ buffer segments < 8 bytes must be aligned $$
+ * $$ to 8 bytes but larger segments are not $$
+ * $$ sensitive to alignment. $$
+ * $$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$
+ *
+ * How to use:
+ *
+ * Init MVE driver on (unused) unit 2:
+ *
+ * mve = mvtst_init(2)
+ *
+ * data = { 1,2,3,4,5,6,7,8,9,0xa,0xb, ... }
+ *
+ * Alloc 2-element mbuf chain (1st holds an
+ * ethernet header which is > 8bytes so we can't
+ * test this with only 1 mbuf. The 2nd mbuf holds
+ * a small fragment of data).
+ *
+ * mb = mvtst_getbuf(mve)
+ *
+ * Copy data into aligned area inside 2nd mbuf,
+ * (so that you can see if the chip starts using
+ * the aligned area rather than the unaligned
+ * buffer pointer). Point mbuf's data pointer
+ * at 'off'set from the aligned area:
+ *
+ * mvtst_putbuf(mb, data, len, offset)
+ *
+ * Send chain off:
+ *
+ * BSP_mve_send_buf(mve, mb, 0, 0)
+ *
+ * Watch raw data:
+ *
+ * tcpdump -XX -vv -s0 ether host <my-ether-addr>
+ *
+ * E.g, if offset = 1, len = 2 then we would like
+ * to see
+ *
+ * GOOD:
+ * < 14 header bytes > 0x02, 0x03
+
+ * but if the chip starts DMA at aligned address
+ * we see instead
+ * BAD:
+ * < 14 header bytes > 0x01, 0x02
+ */
+
+static inline void *rmalloc(size_t l) { return malloc(l); }
+static inline void rfree(void *p) { return free(p); }
+
+#define _KERNEL
+#include <sys/param.h>
+#include <sys/mbuf.h>
+
+static void
+cleanup_buf(void *u_b, void *closure, int error)
+{
+rtems_bsdnet_semaphore_obtain();
+ m_freem((struct mbuf*)u_b);
+rtems_bsdnet_semaphore_release();
+}
+
+struct mbuf *mvtst_getbuf(struct mveth_private *mp)
+{
+struct mbuf *m,*n;
+
+ if ( !mp ) {
+ printf("need driver ptr arg\n");
+ return 0;
+ }
+rtems_bsdnet_semaphore_obtain();
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ MGET(n, M_DONTWAIT, MT_DATA);
+ m->m_next = n;
+rtems_bsdnet_semaphore_release();
+ /* Ethernet header */
+ memset( mtod(m, unsigned char*), 0xff, 6);
+ BSP_mve_read_eaddr(mp, mtod(m, unsigned char*) + 6);
+ /* Arbitrary; setting to IP but we don't bother
+ * to setup a real IP header. We just watch the
+ * raw packet contents...
+ */
+ mtod(m, unsigned char*)[12] = 0x08;
+ mtod(m, unsigned char*)[13] = 0x00;
+ m->m_pkthdr.len = m->m_len = 14;
+ n->m_len = 0;
+ return m;
+}
+
+int
+mvtst_putbuf(struct mbuf *m, void *data, int len, int off)
+{
+int i;
+ if ( m ) {
+ m->m_pkthdr.len += len;
+ if ( ( m= m->m_next ) ) {
+ m->m_len = len;
+ memcpy(mtod(m, void*), data, 32);
+ m->m_data += off;
+ printf("m.dat: 0x%08x, m.data: 0x%08x\n", m->m_dat, m->m_data);
+ for ( i=0; i< 16; i++ ) {
+ printf(" %02x,",mtod(m, unsigned char*)[i]);
+ }
+ printf("\n");
+ }
+ }
+
+ return 0;
+}
+
+static void *alloc_rxbuf(int *p_size, unsigned long *paddr)
+{
+ return *(void**)paddr = rmalloc((*p_size = 1800));
+}
+
+static void consume_buf(void *buf, void *closure, int len)
+{
+ rfree(buf);
+}
+
+void *
+mvtst_init(int unit)
+{
+struct mveth_private *mp;
+ mp = BSP_mve_setup(
+ unit, 0,
+ cleanup_buf, 0,
+ alloc_rxbuf,
+ consume_buf, 0,
+ 10, 10,
+ 0);
+ if ( mp )
+ BSP_mve_init_hw(mp, 0, 0);
+ return mp;
+}
diff --git a/bsps/powerpc/beatnik/net/if_mve/testing.c b/bsps/powerpc/beatnik/net/if_mve/testing.c
new file mode 100644
index 0000000..a1233bd
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/if_mve/testing.c
@@ -0,0 +1,324 @@
+#ifndef KERNEL
+#define KERNEL
+#endif
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet_internal.h>
+#include <bsp.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+
+#include "mv64340_eth_ll.h"
+
+#include <string.h>
+#include <assert.h>
+
+#include <netinet/in.h>
+#include <stdio.h>
+
+#define RX_SPACING 1
+#define TX_SPACING 1
+
+#define RX_RING_SIZE (MV64340_RX_QUEUE_SIZE*RX_SPACING)
+#define TX_RING_SIZE (MV64340_TX_QUEUE_SIZE*TX_SPACING)
+
+
+struct eth_rx_desc rx_ring[RX_RING_SIZE] __attribute__((aligned(32)));
+struct eth_rx_desc rx_ring[RX_RING_SIZE] = {{0},};
+
+struct eth_tx_desc tx_ring[TX_RING_SIZE] __attribute__((aligned(32)));
+struct eth_tx_desc tx_ring[TX_RING_SIZE] = {{0},};
+
+/* packet buffers */
+char rx_buf[MV64340_RX_QUEUE_SIZE][2048] __attribute__((aligned(8)));
+char rx_buf[MV64340_RX_QUEUE_SIZE][2048];
+
+char tx_buf[MV64340_RX_QUEUE_SIZE][2048] __attribute__((aligned(8)));
+char tx_buf[MV64340_RX_QUEUE_SIZE][2048];
+
+char BcHeader[22] = {
+ 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, /* dst */
+ 0x00, 0x01, 0xaf, 0x13, 0xb5, 0x3e, /* src */
+ 00, 00, /* len */
+ 0xAA, /* dsap */
+ 0xAA, /* ssap */
+ 0x03, /* ctrl */
+ 0x08, 0x00, 0x56, /* snap_org [stanford] */
+ 0x80, 0x5b, /* snap_type (stanford kernel) */
+};
+
+struct mv64340_private mveth = {
+ port_num: 0,
+ port_mac_addr: {0x00,0x01,0xAF,0x13,0xB5,0x3C},
+ /* port_config .. tx_resource_err are set by port_init */
+ 0
+};
+
+struct pkt_info p0,p1;
+
+static inline void rx_stopq(int port)
+{
+ MV_WRITE(MV64340_ETH_RECEIVE_QUEUE_COMMAND_REG(port), 0x0000ff00);
+}
+
+static inline void tx_stopq(int port)
+{
+ MV_WRITE(MV64340_ETH_TRANSMIT_QUEUE_COMMAND_REG(port), 0x0000ff00);
+}
+
+#define MV64360_ENET2MEM_SNOOP_NONE 0x0000
+#define MV64360_ENET2MEM_SNOOP_WT 0x1000
+#define MV64360_ENET2MEM_SNOOP_WB 0x2000
+
+#if 0
+int
+mveth_init(struct mv64340_private *mp)
+{
+int i;
+ mp->p_rx_desc_area = rx_ring;
+ mp->p_tx_desc_area = tx_ring;
+
+ rx_stopq(mp->port_num);
+ tx_stopq(mp->port_num);
+
+ /* MotLoad has cache snooping disabled on the ENET2MEM windows.
+ * Some comments in (linux) indicate that there are errata
+ * which cause problems which is a real bummer.
+ * We try it anyways...
+ */
+ {
+ unsigned long disbl, bar;
+ disbl = MV_READ(MV64340_ETH_BASE_ADDR_ENABLE_REG);
+ /* disable all 6 windows */
+ MV_WRITE(MV64340_ETH_BASE_ADDR_ENABLE_REG, 0x3f);
+ /* set WB snooping */
+ for ( i=0; i<6*8; i+=8 ) {
+ if ( (bar = MV_READ(MV64340_ETH_BAR_0 + i)) && MV_READ(MV64340_ETH_SIZE_REG_0 + i) ) {
+ MV_WRITE(MV64340_ETH_BAR_0 + i, bar | MV64360_ENET2MEM_SNOOP_WB);
+ /* read back to flush fifo [linux comment] */
+ (void)MV_READ(MV64340_ETH_BAR_0 + i);
+ }
+ }
+ /* restore/re-enable */
+ MV_WRITE(MV64340_ETH_BASE_ADDR_ENABLE_REG, disbl);
+ }
+
+ eth_port_init(mp);
+
+ sleep(1);
+
+ mveth_init_tx_desc_ring(mp);
+ mveth_init_rx_desc_ring(mp);
+#if 0
+ for ( i = 0; i<MV64340_RX_QUEUE_SIZE; i++ ) {
+ p0.byte_cnt = sizeof(rx_buf[0]);
+ p0.buf_ptr = (dma_addr_t)rx_buf[i];
+ p0.return_info = (void*)i;
+ /* other fields are not used by ll driver */
+ assert ( ETH_OK == eth_rx_return_buff(mp,&p0) );
+ }
+ memset(&p0, 0, sizeof(p0));
+#endif
+
+ return eth_port_start(mp);
+}
+#endif
+
+void
+mveth_stop(struct mv64340_private *mp)
+{
+extern void mveth_stop_hw();
+ rtems_bsdnet_semaphore_obtain();
+ mveth_stop_hw(mp);
+ rtems_bsdnet_semaphore_release();
+}
+
+extern int mveth_send_mbuf();
+extern int mveth_swipe_tx();
+
+int
+mveth_tx(struct mv64340_private *mp, char *data, int len, int nbufs)
+{
+int rval = -1,l;
+char *p;
+struct mbuf *m;
+char *emsg = 0;
+
+ rtems_bsdnet_semaphore_obtain();
+ MGETHDR(m, M_WAIT, MT_DATA);
+ if ( !m ) {
+ emsg="Unable to allocate header\n";
+ goto bail;
+ }
+ MCLGET(m, M_WAIT);
+ if ( !(m->m_flags & M_EXT) ) {
+ m_freem(m);
+ emsg="Unable to allocate cluster\n";
+ goto bail;
+ }
+ p = mtod(m, char *);
+ l = 0;
+ switch (nbufs) {
+ case 3:
+ default:
+ emsg="nbufs arg must be 1..3\n";
+ goto bail;
+
+ case 1:
+ l += sizeof(BcHeader);
+ memcpy(p, &BcHeader, sizeof(BcHeader));
+ p += sizeof(BcHeader);
+
+ case 2:
+ memcpy(p,data,len);
+ l += len;
+ m->m_len = m->m_pkthdr.len = l;
+ if ( 2 == nbufs ) {
+ M_PREPEND(m, sizeof (BcHeader), M_WAIT);
+ if (!m) {
+ emsg = "Unable to prepend\n";
+ goto bail;
+ }
+ p = mtod(m, char*);
+ memcpy(p,&BcHeader,sizeof(BcHeader));
+ l += sizeof(BcHeader);
+ }
+ break;
+ }
+ *(short*)(mtod(m, char*) + 12) = htons(l-14);
+ rval = mveth_send_mbuf(mp,m);
+
+bail:
+ rtems_bsdnet_semaphore_release();
+ if (emsg)
+ printf(emsg);
+
+#if 0
+ /*
+ * Add local net header. If no space in first mbuf,
+ * allocate another.
+ */
+ M_PREPEND(m, sizeof (struct ether_header), M_DONTWAIT);
+ if (m == 0)
+ senderr(ENOBUFS);
+ eh = mtod(m, struct ether_header *);
+ (void)memcpy(&eh->ether_type, &type,
+ sizeof(eh->ether_type));
+ (void)memcpy(eh->ether_dhost, edst, sizeof (edst));
+ (void)memcpy(eh->ether_shost, ac->ac_enaddr,
+ sizeof(eh->ether_shost));
+#endif
+ return rval;
+}
+
+int
+mveth_protected(int (*p)(struct mv64340_private*), struct mv64340_private *mp)
+{
+int rval;
+ rtems_bsdnet_semaphore_obtain();
+ rval = p(mp);
+ rtems_bsdnet_semaphore_release();
+ return rval;
+}
+
+int
+mveth_rx(struct mv64340_private *mp)
+{
+extern int mveth_swipe_rx();
+ return mveth_protected(mveth_swipe_rx,mp);
+}
+
+int
+mveth_reclaim(struct mv64340_private *mp)
+{
+extern int mveth_swipe_tx();
+ return mveth_protected(mveth_swipe_tx,mp);
+}
+
+
+int preth(FILE *f, char *p)
+{
+int i;
+ for (i=0; i<4; i++)
+ fprintf(f,"%02X:",p[i]);
+ fprintf(f,"%02X",p[i]);
+ return 6;
+}
+
+char *errcode2str(st)
+{
+char *rval;
+ switch(st) {
+ case ETH_OK:
+ rval = "OK";
+ break;
+ case ETH_ERROR:
+ rval = "Fundamental error.";
+ break;
+ case ETH_RETRY:
+ rval = "Could not process request. Try later.";
+ break;
+ case ETH_END_OF_JOB:
+ rval = "Ring has nothing to process.";
+ break;
+ case ETH_QUEUE_FULL:
+ rval = "Ring resource error.";
+ break;
+ case ETH_QUEUE_LAST_RESOURCE:
+ rval = "Ring resources about to exhaust.";
+ break;
+ default:
+ rval = "UNKNOWN"; break;
+ }
+ return rval;
+}
+
+
+#if 0
+int
+mveth_rx(struct mv64340_private *mp)
+{
+int st;
+struct pkt_info p;
+ if ( ETH_OK != (st=eth_port_receive(mp, &p)) ) {
+ fprintf(stderr,"receive: %s\n", errcode2str(st));
+ return -1;
+ }
+ printf("%i bytes received from ", p.byte_cnt);
+ preth(stdout,(char*)p.buf_ptr+6);
+ printf(" (desc. stat: 0x%08x)\n", p.cmd_sts);
+
+ p.byte_cnt = sizeof(rx_buf[0]);
+ p.buf_ptr -= RX_BUF_OFFSET;
+ if ( ETH_OK != (st=eth_rx_return_buff(mp,&p) ) ) {
+ fprintf(stderr,"returning buffer: %s\n", errcode2str(st));
+ return -1;
+ }
+ return 0;
+}
+#endif
+
+int
+dring()
+{
+int i;
+if (1) {
+struct eth_rx_desc *pr;
+printf("RX:\n");
+ for (i=0, pr=rx_ring; i<RX_RING_SIZE; i+=RX_SPACING, pr+=RX_SPACING) {
+ dcbi(pr);
+ printf("cnt: 0x%04x, size: 0x%04x, stat: 0x%08x, next: 0x%08x, buf: 0x%08x\n",
+ pr->byte_cnt, pr->buf_size, pr->cmd_sts, pr->next_desc_ptr, pr->buf_ptr);
+ }
+}
+if (1) {
+struct eth_tx_desc *pt;
+printf("TX:\n");
+ for (i=0, pt=tx_ring; i<TX_RING_SIZE; i+=TX_SPACING, pt+=TX_SPACING) {
+ dcbi(pt);
+ printf("cnt: 0x%04x, stat: 0x%08x, next: 0x%08x, buf: 0x%08x\n",
+ pt->byte_cnt, pt->cmd_sts, pt->next_desc_ptr, pt->buf_ptr);
+ }
+}
+ return 0;
+}
diff --git a/bsps/powerpc/beatnik/net/porting/LICENSE b/bsps/powerpc/beatnik/net/porting/LICENSE
new file mode 100644
index 0000000..62b91ab
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/LICENSE
@@ -0,0 +1,51 @@
+/* NOTE: The terms described in this LICENSE file apply only to the
+ * files created by the author (see below). Consult individual
+ * file headers for more details. Some files were ported from
+ * netbsd and/or freebsd and are covered by the respective
+ * file header copyright notices.
+ */
+
+/*
+ * Authorship
+ * ----------
+ * This software ('RTEMS-portability wrappers for BSD network drivers') was
+ * created by Till Straumann <strauman@slac.stanford.edu>, 2005-2007,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * The 'RTEMS-portability wrappers for BSD network drivers' software was produced by
+ * the Stanford Linear Accelerator Center, Stanford University,
+ * under Contract DE-AC03-76SFO0515 with the Department of Energy.
+ *
+ * Government disclaimer of liability
+ * ----------------------------------
+ * Neither the United States nor the United States Department of Energy,
+ * nor any of their employees, makes any warranty, express or implied, or
+ * assumes any legal liability or responsibility for the accuracy,
+ * completeness, or usefulness of any data, apparatus, product, or process
+ * disclosed, or represents that its use would not infringe privately owned
+ * rights.
+ *
+ * Stanford disclaimer of liability
+ * --------------------------------
+ * Stanford University makes no representations or warranties, express or
+ * implied, nor assumes any liability for the use of this software.
+ *
+ * Stanford disclaimer of copyright
+ * --------------------------------
+ * Stanford University, owner of the copyright, hereby disclaims its
+ * copyright and all other rights in this software. Hence, anyone may
+ * freely use it for any purpose without restriction.
+ *
+ * Maintenance of notices
+ * ----------------------
+ * In the interest of clarity regarding the origin and status of this
+ * SLAC software, this and all the preceding Stanford University notices
+ * are to remain affixed to any copy or derivative of this software made
+ * or distributed by the recipient and are to be affixed to any copy of
+ * software made or distributed by the recipient that contains a copy or
+ * derivative of this software.
+ *
+ * ------------------ SLAC Software Notices, Set 4 OTT.002a, 2004 FEB 03
+ */
diff --git a/bsps/powerpc/beatnik/net/porting/Makefile.template b/bsps/powerpc/beatnik/net/porting/Makefile.template
new file mode 100644
index 0000000..3c5d6e3
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/Makefile.template
@@ -0,0 +1,84 @@
+#
+# Makefile.lib,v 1.5 2000/06/12 15:00:14 joel Exp
+#
+# Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+# License: see LICENSE file.
+#
+# Templates/Makefile.lib
+# Template library Makefile
+#
+
+LIBNAME=libif_XXX.a # XXX- your library names goes here
+LIB=${ARCH}/${LIBNAME}
+
+# C and C++ source names, if any, go here -- minus the .c or .cc
+C_PIECES=if_XXX if_XXX_rtems
+C_FILES=$(C_PIECES:%=%.c)
+C_O_FILES=$(C_PIECES:%=${ARCH}/%.o)
+
+CC_PIECES=
+CC_FILES=$(CC_PIECES:%=%.cc)
+CC_O_FILES=$(CC_PIECES:%=${ARCH}/%.o)
+
+H_FILES=
+
+# Assembly source names, if any, go here -- minus the .S
+S_PIECES=
+S_FILES=$(S_PIECES:%=%.S)
+S_O_FILES=$(S_FILES:%.S=${ARCH}/%.o)
+
+SRCS=$(C_FILES) $(CC_FILES) $(H_FILES) $(S_FILES)
+OBJS=$(C_O_FILES) $(CC_O_FILES) $(S_O_FILES)
+
+include $(RTEMS_MAKEFILE_PATH)/Makefile.inc
+
+include $(RTEMS_CUSTOM)
+include $(RTEMS_ROOT)/make/lib.cfg
+
+#
+# Add local stuff here using +=
+#
+
+#DEFINES += -DHAVE_LIBBSPEXT -DDEBUG_MODULAR
+CPPFLAGS += -I. -Ilibchip -Iporting
+# bsdnet newproc generated daemon is non-FP;
+# prevent optimizer from generating FP instructions
+CFLAGS += -Wno-unused-variable -msoft-float
+
+#
+# Add your list of files to delete here. The config files
+# already know how to delete some stuff, so you may want
+# to just run 'make clean' first to see what gets missed.
+# 'make clobber' already includes 'make clean'
+#
+
+CLEAN_ADDITIONS +=
+CLOBBER_ADDITIONS +=
+
+all: ${ARCH} $(SRCS) $(LIB)
+
+$(LIB): ${OBJS}
+ $(make-library)
+
+ifndef RTEMS_SITE_INSTALLDIR
+RTEMS_SITE_INSTALLDIR = $(PROJECT_RELEASE)
+endif
+
+${RTEMS_SITE_INSTALLDIR}/include \
+${RTEMS_SITE_INSTALLDIR}/lib \
+${RTEMS_SITE_INSTALLDIR}/bin \
+${RTEMS_SITE_INSTALLDIR}/$(RTEMS_BSP)/include \
+${RTEMS_SITE_INSTALLDIR}/$(RTEMS_BSP)/lib \
+${RTEMS_SITE_INSTALLDIR}/$(RTEMS_BSP)/bin :
+ test -d $@ || mkdir -p $@
+
+# Install the library, appending _g or _p as appropriate.
+# for include files, just use $(INSTALL_CHANGE)
+#
+# NOTES:
+# - BSP specific libraries, headers etc. should be installed to
+# $RTEMS_SITE_INSTALLDIR)/$(RTEMS_BSP)/lib
+#
+
+install: all $(RTEMS_SITE_INSTALLDIR)/lib
+ $(INSTALL_VARIANT) -m 644 ${LIB} ${RTEMS_SITE_INSTALLDIR}/lib
diff --git a/bsps/powerpc/beatnik/net/porting/README b/bsps/powerpc/beatnik/net/porting/README
new file mode 100644
index 0000000..b262d77
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/README
@@ -0,0 +1,104 @@
+Templates to help porting freebsd networking drivers
+to rtems (focus on i386 and powerpc) using a 'quick and dirty'
+approach.
+This is not an elegant piece of software -- be warned.
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+Usage:
+
+ A obtain the freebsd driver source. It usually is made
+ up of a
+ if_XXX.c -- core driver
+ if_XXXreg.h -- core header
+ if_XXXvar.h -- some have it, some don't
+ if_XXX_<bus>.c -- glue to integrate the core
+ driver with different environments
+ (such as pccard, pci, ...). There
+ are several of these.
+
+ Note that you might have to get an older version
+ as some structures and interfaces may have undergone
+ significant changes since the bsd/networking version that
+ was ported to rtems.
+
+ B Copy the Makefile and rtemscompat_defs.h templates to the
+ driver source dir and edit them.
+
+ C Edit if_XXXreg.h and comment all unneeded fields from the
+ 'softc' structure declaration with
+
+ #ifndef __rtems__
+ #endif
+
+ In particular, the bushandle field (as defined in rtemscompat_defs.h)
+ above, see comments in the template) must be re-declared:
+
+ #ifndef __rtems__
+ bus_space_handle_t XXX_bhandle;
+ #else
+ unsigned XXX_bhandle;
+ unsigned char irq_no;
+ unsigned char b,d,f; /* PCI tuple; needed for PCI only */
+ rtems_id tid; /* driver task id */
+ #endif
+
+ Later, the compilation attempts will help identifying
+ fields that need to be removed.
+
+ I like the #ifdef __rtems__ construct as it minimizes changes
+ to the source thus making merging updated driver versions easier.
+
+ D Edit if_XXX.c; at the very top, include the lines
+
+ #ifdef __rtems__
+ #include <rtemscompat.h>
+ #endif
+
+ use the #ifndef __rtems__ #endif construct to comment
+ unneeded / unsupported inclusion of headers and code pieces.
+
+ - inclusion of net/if_media.h must usually be mapped to
+ libchip/if_media.h
+
+ comment all vm, machine, bus, mii etc. related headers.
+
+ - replace inclusion of if_XXXreg.h by
+
+ #include "if_XXXreg.h"
+ #include <rtemscompat1.h>
+
+ - work through the if_XXX.c and if_XXXreg.h files commenting
+ stuff until if_XXX.c compiles. This might involve hacking
+ the helper headers.
+
+ - pay attention to endian issues; things may need to be fixed!
+
+ - at the top where the freebsd 'methods' and the like are
+ commented, add a definition of the driver methods for RTEMS:
+
+ #ifdef __rtems__
+ net_drv_tbl_t METHODS = {
+ n_probe : XXX_probe,
+ n_attach : XXX_attach,
+ n_detach : XXX_detach, /* optional; */
+ n_intr : XXX_intr, /* freebsd ISR; executed from daemon under RTEMS */
+ };
+ #endif
+
+ - make sure all the if_xxx methods are set; in particular,
+ set
+ sc->if_output = ether_output;
+
+ - on input:
+ you can use DO_ETHER_INPUT_SKIPPING_ETHER_HEADER() macro
+ -- if you don't MAKE SURE THE RECEIVING INTERFACE IS SET
+ in the mbuf packet header!!!
+
+ E create 'rtems_<chip>_setup()' to probe for devices and
+ set the softc struct's base address, interrupt line and
+ bus/dev/fun triple (PCI only).
+ For PCI devices, a generic setup routine already comes with
+ porting/if_xxx_rtems.c -> nothing needs to be written!
diff --git a/bsps/powerpc/beatnik/net/porting/if_xxx.modini.c b/bsps/powerpc/beatnik/net/porting/if_xxx.modini.c
new file mode 100644
index 0000000..1abad7d
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/if_xxx.modini.c
@@ -0,0 +1,34 @@
+#include <rtems.h>
+#include <porting/rtemscompat.h>
+
+/* CEXP module initialization/finalization */
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+void
+_cexpModuleInitialize(void *unused)
+{
+extern void NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringup)(char *);
+ METHODSPTR = &METHODS;
+/*
+#ifdef DEBUG
+ NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringup)("192.168.2.13/255.255.255.0");
+#endif
+*/
+}
+
+int
+_cexpModuleFinalize(void *unused)
+{
+#ifdef DEBUG
+extern int NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringdown)();
+ if (NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringdown)())
+ return -1;
+ METHODSPTR = 0;
+ return 0;
+#else
+ return -1;
+#endif
+}
diff --git a/bsps/powerpc/beatnik/net/porting/if_xxx_rtems.c b/bsps/powerpc/beatnik/net/porting/if_xxx_rtems.c
new file mode 100644
index 0000000..a0d459f
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/if_xxx_rtems.c
@@ -0,0 +1,500 @@
+#include "rtemscompat.h"
+
+/* Template for driver task, setup and attach routines. To be instantiated
+ * by defining the relevant symbols in header files.
+ */
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+#include <rtems/irq.h>
+
+#include <stdio.h>
+#include <string.h>
+#include <inttypes.h>
+
+#include <sys/cdefs.h>
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/kernel.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+#include <net/if_arp.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <net/if_media.h>
+
+#ifdef IF_REG_HEADER
+#include IF_REG_HEADER
+#endif
+#ifdef IF_VAR_HEADER
+#include IF_VAR_HEADER
+#endif
+
+#include "rtemscompat1.h"
+
+#define EX_EVENT RTEMS_EVENT_1
+#undef IRQ_AT_8259
+
+NETDEV_DECL = { /*[0]:*/{ /* softc: */ { /* arpcom: */{ /* ac_if: */ { 0 }}}}};
+
+static void net_daemon(void *arg);
+
+#ifdef HAVE_LIBBSPEXT
+#include <bsp/bspExt.h>
+static void the_net_isr(void *);
+#else
+static void noop(const rtems_irq_connect_data *unused) {}
+static int noop1(const rtems_irq_connect_data *unused) { return 0;}
+#if ISMINVERSION(4,6,99)
+static void the_net_isr(rtems_irq_hdl_param);
+#else
+static void the_net_isr();
+#if NETDRIVER_SLOTS > 1
+#error only one instance supported (stupid IRQ API)
+#else
+static struct NET_SOFTC *thesc;
+#endif
+#endif
+#endif
+
+#if defined(NETDRIVER_PCI)
+/* Public setup routine for PCI devices;
+ * TODO: currently doesn't work for subsystem vendor/id , i.e.
+ * devices behind a standard PCI interface...
+ */
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_pci_setup)(int inst);
+#endif
+
+static unsigned
+NET_EMBEMB(,NETDRIVER_PREFIX,_net_driver_ticks_per_sec) = 0;
+
+/* other drivers may already have this created */
+extern unsigned net_driver_ticks_per_sec
+__attribute__((weak, alias(NET_STRSTR(NETDRIVER_PREFIX)"_net_driver_ticks_per_sec") ));
+
+#ifdef DEBUG_MODULAR
+net_drv_tbl_t * volatile METHODSPTR = 0;
+#endif
+
+
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_attach)
+ (struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ int error = 0;
+ device_t dev = net_dev_get(config);
+ struct NET_SOFTC *sc;
+ struct ifnet *ifp;
+#ifndef HAVE_LIBBSPEXT
+ rtems_irq_connect_data irq_data = {
+ 0,
+ the_net_isr,
+#if ISMINVERSION(4,6,99)
+ 0,
+#endif
+ noop,
+ noop,
+ noop1 };
+#endif
+
+ if ( !dev )
+ return 1;
+
+ if ( !dev->d_softc.NET_SOFTC_BHANDLE_FIELD ) {
+#if defined(NETDRIVER_PCI)
+ device_printf(dev,NETDRIVER" unit not configured; executing setup...");
+ /* setup should really be performed prior to attaching.
+ * Wipe the device; setup and re-obtain the device...
+ */
+ memset(dev,0,sizeof(*dev));
+ error = NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_pci_setup)(-1);
+ /* re-obtain the device */
+ dev = net_dev_get(config);
+ if ( !dev ) {
+ printk("Unable to re-assign device structure???\n");
+ return 1;
+ }
+ if (error <= 0) {
+ device_printf(dev,NETDRIVER" FAILED; unable to attach interface, sorry\n");
+ return 1;
+ }
+ device_printf(dev,"success\n");
+#else
+ device_printf(dev,NETDRIVER" unit not configured; use 'rtems_"NETDRIVER"_setup()'\n");
+ return 1;
+#endif
+ }
+
+ if ( !net_driver_ticks_per_sec )
+ net_driver_ticks_per_sec = rtems_clock_get_ticks_per_second();
+
+ sc = device_get_softc( dev );
+ ifp = &sc->arpcom.ac_if;
+
+#ifdef DEBUG_MODULAR
+ if (!METHODSPTR) {
+ device_printf(dev,NETDRIVER": method pointer not set\n");
+ return -1;
+ }
+#endif
+
+ if ( attaching ) {
+ if ( ifp->if_init ) {
+ device_printf(dev,NETDRIVER" Driver already attached.\n");
+ return -1;
+ }
+ if ( config->hardware_address ) {
+ /* use configured MAC address */
+ memcpy(sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ } else {
+#ifdef NET_READ_MAC_ADDR
+ NET_READ_MAC_ADDR(sc);
+#endif
+ }
+ if ( METHODSPTR->n_attach(dev) ) {
+ device_printf(dev,NETDRIVER"_attach() failed\n");
+ return -1;
+ }
+ } else {
+ if ( !ifp->if_init ) {
+ device_printf(dev,NETDRIVER" Driver not attached.\n");
+ return -1;
+ }
+ if ( METHODSPTR->n_detach ) {
+ if ( METHODSPTR->n_detach(dev) ) {
+ device_printf(dev,NETDRIVER"_detach() failed\n");
+ return -1;
+ }
+ } else {
+ device_printf(dev,NETDRIVER"_detach() not implemented\n");
+ return -1;
+ }
+ }
+
+
+ if ( !sc->tid )
+ sc->tid = rtems_bsdnet_newproc(NETDRIVER"d", 4096, net_daemon, sc);
+
+ if (attaching) {
+#ifdef DEBUG
+ printf("Installing IRQ # %i\n",sc->irq_no);
+#endif
+#ifdef HAVE_LIBBSPEXT
+ if ( bspExtInstallSharedISR(sc->irq_no, the_net_isr, sc, 0) )
+#else
+ /* BSP dependent :-( */
+ irq_data.name = sc->irq_no;
+#if ISMINVERSION(4,6,99)
+ irq_data.handle = (rtems_irq_hdl_param)sc;
+#else
+ thesc = sc;
+#endif
+ if ( ! BSP_install_rtems_irq_handler( &irq_data ) )
+#endif
+ {
+ fprintf(stderr,NETDRIVER": unable to install ISR\n");
+ error = -1;
+ }
+ } else {
+ if ( sc->irq_no ) {
+#ifdef DEBUG
+ printf("Removing IRQ # %i\n",sc->irq_no);
+#endif
+#ifdef HAVE_LIBBSPEXT
+ if (bspExtRemoveSharedISR(sc->irq_no, the_net_isr, sc))
+#else
+ /* BSP dependent :-( */
+ irq_data.name = sc->irq_no;
+#if ISMINVERSION(4,6,99)
+ irq_data.handle = (rtems_irq_hdl_param)sc;
+#endif
+ if ( ! BSP_remove_rtems_irq_handler( &irq_data ) )
+#endif
+ {
+ fprintf(stderr,NETDRIVER": unable to uninstall ISR\n");
+ error = -1;
+ }
+ }
+ }
+ return error;
+}
+
+static void
+the_net_isr(
+#ifdef HAVE_LIBBSPEXT
+void *thesc
+#elif ISMINVERSION(4,6,99)
+rtems_irq_hdl_param thesc
+#endif
+)
+{
+struct NET_SOFTC *sc = thesc;
+
+ /* disable interrupts */
+ NET_DISABLE_IRQS(sc);
+
+ rtems_bsdnet_event_send( sc->tid, EX_EVENT );
+}
+
+static void net_daemon(void *arg)
+{
+struct NET_SOFTC *sc = arg;
+rtems_event_set evs;
+
+ for (;;) {
+ rtems_bsdnet_event_receive(
+ EX_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &evs);
+
+ METHODSPTR->n_intr(sc);
+
+ /* re-enable interrupts */
+ NET_ENABLE_IRQS(sc);
+ }
+}
+
+static struct NET_SOFTC *
+net_drv_check_unit(int unit)
+{
+ unit--;
+ if ( unit < 0 || unit >= NETDRIVER_SLOTS ) {
+ fprintf(stderr,"Invalid unit # %i (not in %i..%i)\n", unit+1, 1, NETDRIVER_SLOTS);
+ return 0;
+ }
+
+ if ( THEDEVS[unit].d_name ) {
+ fprintf(stderr,"Unit %i already set up\n", unit+1);
+ return 0;
+ }
+
+ memset( &THEDEVS[unit], 0, sizeof(THEDEVS[0]) );
+
+ return &THEDEVS[unit].d_softc;
+}
+
+struct rtems_bsdnet_ifconfig NET_EMBEMB(NETDRIVER_PREFIX,_dbg,_config) = {
+ NETDRIVER"1",
+ NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_attach),
+ 0
+};
+
+#ifdef DEBUG
+void
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringup)(char *ipaddr)
+{
+short flags;
+struct sockaddr_in addr;
+char *mask;
+
+
+ if (!ipaddr) {
+ printf("Need an ip[/mask] argument (dot notation)\n");
+ return;
+ }
+
+ ipaddr = strdup(ipaddr);
+
+ if ( (mask = strchr(ipaddr,'/')) ) {
+ *mask++=0;
+ } else {
+ mask = "255.255.255.0";
+ }
+
+#if defined(NETDRIVER_PCI)
+ /* this fails if already setup */
+ NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_pci_setup)(-1);
+#endif
+ rtems_bsdnet_attach(&NET_EMBEMB(NETDRIVER_PREFIX,_dbg,_config));
+
+ flags = IFF_UP /*| IFF_PROMISC*/;
+ if ( rtems_bsdnet_ifconfig(NETDRIVER"1",SIOCSIFFLAGS,&flags) < 0 ) {
+ printf("Can't bring '"NETDRIVER"1' up\n");
+ goto cleanup;
+ }
+ memset(&addr,0,sizeof(addr));
+ addr.sin_len = sizeof(addr);
+ addr.sin_family = AF_INET;
+ addr.sin_addr.s_addr = inet_addr(mask);
+ if ( rtems_bsdnet_ifconfig(NETDRIVER"1",SIOCSIFNETMASK,&addr) < 0 ) {
+ printf("Unable to set netmask on '"NETDRIVER"1'\n");
+ goto cleanup;
+ }
+ addr.sin_addr.s_addr = inet_addr(ipaddr);
+ if ( rtems_bsdnet_ifconfig(NETDRIVER"1",SIOCSIFADDR,&addr) < 0 ) {
+ printf("Unable to set address on '"NETDRIVER"1'\n");
+ goto cleanup;
+ }
+cleanup:
+ the_real_free (ipaddr);
+}
+
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_bringdown)()
+{
+short flags;
+ flags = 0;
+ if ( rtems_bsdnet_ifconfig(NETDRIVER"1",SIOCSIFFLAGS,&flags) < 0 ) {
+ printf("Can't bring '"NETDRIVER"1' down\n");
+ return -1;
+ }
+
+ rtems_bsdnet_detach(&NET_EMBEMB(NETDRIVER_PREFIX,_dbg,_config));
+ return 0;
+}
+#endif
+
+
+#if defined(NETDRIVER_PCI) && !defined(NETDRIVER_OWN_SETUP)
+/* Public setup routine for PCI devices;
+ * TODO: currently doesn't work for subsystem vendor/id , i.e.
+ * devices behind a standard PCI interface...
+ * passing 'inst' > only sets-up the 'inst'th card; passing
+ * 'inst' == 0 sets-up all matching cards.
+ */
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_pci_setup)(int inst)
+{
+unsigned b,d,f,i,isio,unit;
+rtemscompat_32_t base;
+unsigned short cmd,id;
+unsigned char h;
+struct NET_SOFTC *sc;
+unsigned try[] = { PCI_BASE_ADDRESS_0, PCI_BASE_ADDRESS_1, 0 };
+
+#ifdef DEBUG_MODULAR
+ if ( !METHODSPTR ) {
+ fprintf(stderr,NETDRIVER": Methods pointer not set\n");
+ return -1;
+ }
+#endif
+
+ /* 0 can be reached when looking for the desired instance */
+ if ( 0 == inst )
+ inst = -1;
+
+#ifdef HAVE_LIBBSPEXT
+ /* make sure it's initialized */
+ bspExtInit();
+#endif
+
+ /* scan PCI for supported devices */
+ for ( b=0, sc=0, unit=0; b<pci_bus_count(); b++ ) {
+ for ( d=0; d<PCI_MAX_DEVICES; d++ ) {
+ pci_read_config_word(b,d,0,PCI_VENDOR_ID,&id);
+ if ( 0xffff == id )
+ continue; /* empty slot */
+
+ pci_read_config_byte(b,d,0,PCI_HEADER_TYPE,&h);
+ h = h&0x80 ? PCI_MAX_FUNCTIONS : 1; /* multifunction device ? */
+
+ for ( f=0; f<h; f++ ) {
+ if ( !sc && !(sc=net_drv_check_unit(unit+1))) {
+ fprintf(stderr,"Not enough driver slots; stop looking for more devices...\n");
+ return unit;
+ }
+ pci_read_config_word(b,d,f,PCI_VENDOR_ID,&id);
+ if ( 0xffff == id )
+ continue; /* empty slot */
+
+ pci_read_config_word(b,d,f,PCI_CLASS_DEVICE,&id);
+ if ( PCI_CLASS_NETWORK_ETHERNET != id )
+ continue; /* only look at ethernet devices */
+
+ sc->b = b;
+ sc->d = d;
+ sc->f = f;
+
+ for ( i=0, base=0, isio=0; try[i]; i++ ) {
+ pci_read_config_dword(b,d,f,try[i],&base);
+ if ( base ) {
+ if ( (isio = (PCI_BASE_ADDRESS_SPACE_IO == (base & PCI_BASE_ADDRESS_SPACE )) ) ) {
+#ifdef NET_CHIP_PORT_IO
+ base &= PCI_BASE_ADDRESS_IO_MASK;
+ sc->NET_SOFTC_BHANDLE_FIELD = PCI_IO_2LOCAL(base,b);
+#ifdef DEBUG
+ printf("Found PCI I/O Base 0x%08x\n", (unsigned)base);
+#endif
+#else
+ base = 0;
+ continue;
+#endif
+ } else {
+#ifdef NET_CHIP_MEM_IO
+ base &= PCI_BASE_ADDRESS_MEM_MASK;
+ sc->NET_SOFTC_BHANDLE_FIELD = PCI2LOCAL(base,b);
+#ifdef DEBUG
+ printf("Found PCI MEM Base 0x%08x\n", (unsigned)base);
+#endif
+#else
+ base = 0;
+ continue;
+#endif
+ }
+ break;
+ }
+ }
+ if ( !base ) {
+#ifdef DEBUG
+ fprintf(stderr, NETDRIVER": (warning) Neither PCI base address 0 nor 1 are configured; skipping bus %i, slot %i, fn %i...\n",b,d,f);
+#endif
+ continue;
+ }
+
+ if ( 0 == METHODSPTR->n_probe(&THEDEVS[unit]) && (inst < 0 || !--inst) ) {
+ pci_read_config_word(b,d,f,PCI_COMMAND,&cmd);
+ pci_write_config_word(b,d,f,PCI_COMMAND,
+ cmd | (isio ? PCI_COMMAND_IO : PCI_COMMAND_MEMORY) | PCI_COMMAND_MASTER );
+ pci_read_config_byte(b,d,f,PCI_INTERRUPT_LINE,&sc->irq_no);
+ printf(NETDRIVER": card found @PCI[%s] 0x%08x (local 0x%08x), IRQ %i\n",
+ (isio ? "io" : "mem"), (unsigned)base, sc->NET_SOFTC_BHANDLE_FIELD, sc->irq_no);
+
+ sc = 0; /* need to allocate a new slot */
+ unit++;
+
+ if ( 0 == inst ) {
+ /* found desired instance */
+ goto terminated;
+ }
+ }
+ }
+ }
+ }
+
+terminated:
+ return unit;
+}
+#else
+
+/* simple skeleton
+int
+NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_setup)(
+ int unit,
+ void *base_addr,
+ int irq_no)
+{
+struct NET_SOFTC *sc;
+ if ( !(sc=net_drv_check_unit(unit)) ) {
+ fprintf(stderr,"Bad unit number -- (not enought driver slots?)\n");
+ return 0;
+ }
+ sc->NET_SOFTC_BHANDLE_FIELD = base_addr;
+ if ( 0 == METHODSPTR->n_probe(&THEDEVS[unit-1]) ) {
+ sc->irq_no = irq_no;
+ printf(NETDRIVER": Unit %i set up\n", unit);
+ return unit;
+ }
+ return 0;
+}
+*/
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/porting/pcireg.h b/bsps/powerpc/beatnik/net/porting/pcireg.h
new file mode 100644
index 0000000..8487f5b
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/pcireg.h
@@ -0,0 +1,405 @@
+/*-
+ * Copyright (c) 1997, Stefan Esser <se@freebsd.org>
+ * 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 unmodified, 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.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR 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.
+ *
+ * $FreeBSD: /repoman/r/ncvs/src/sys/dev/pci/pcireg.h,v 1.39.4.3 2005/04/02 05:03:34 jmg Exp $
+ *
+ */
+
+/*
+ * PCIM_xxx: mask to locate subfield in register
+ * PCIR_xxx: config register offset
+ * PCIC_xxx: device class
+ * PCIS_xxx: device subclass
+ * PCIP_xxx: device programming interface
+ * PCIV_xxx: PCI vendor ID (only required to fixup ancient devices)
+ * PCID_xxx: device ID
+ * PCIY_xxx: capability identification number
+ */
+
+/* some PCI bus constants */
+
+#define PCI_BUSMAX 255
+#define PCI_SLOTMAX 31
+#define PCI_FUNCMAX 7
+#define PCI_REGMAX 255
+#define PCI_MAXHDRTYPE 2
+
+/* PCI config header registers for all devices */
+
+#define PCIR_DEVVENDOR 0x00
+#define PCIR_VENDOR 0x00
+#define PCIR_DEVICE 0x02
+#define PCIR_COMMAND 0x04
+#define PCIM_CMD_PORTEN 0x0001
+#define PCIM_CMD_MEMEN 0x0002
+#define PCIM_CMD_BUSMASTEREN 0x0004
+#define PCIM_CMD_SPECIALEN 0x0008
+#define PCIM_CMD_MWRICEN 0x0010
+#define PCIM_CMD_PERRESPEN 0x0040
+#define PCIM_CMD_SERRESPEN 0x0100
+#define PCIM_CMD_BACKTOBACK 0x0200
+#define PCIR_STATUS 0x06
+#define PCIM_STATUS_CAPPRESENT 0x0010
+#define PCIM_STATUS_66CAPABLE 0x0020
+#define PCIM_STATUS_BACKTOBACK 0x0080
+#define PCIM_STATUS_PERRREPORT 0x0100
+#define PCIM_STATUS_SEL_FAST 0x0000
+#define PCIM_STATUS_SEL_MEDIMUM 0x0200
+#define PCIM_STATUS_SEL_SLOW 0x0400
+#define PCIM_STATUS_SEL_MASK 0x0600
+#define PCIM_STATUS_STABORT 0x0800
+#define PCIM_STATUS_RTABORT 0x1000
+#define PCIM_STATUS_RMABORT 0x2000
+#define PCIM_STATUS_SERR 0x4000
+#define PCIM_STATUS_PERR 0x8000
+#define PCIR_REVID 0x08
+#define PCIR_PROGIF 0x09
+#define PCIR_SUBCLASS 0x0a
+#define PCIR_CLASS 0x0b
+#define PCIR_CACHELNSZ 0x0c
+#define PCIR_LATTIMER 0x0d
+#define PCIR_HDRTYPE 0x0e
+#ifndef BURN_BRIDGES
+#define PCIR_HEADERTYPE PCIR_HDRTYPE
+#endif
+#define PCIM_HDRTYPE 0x7f
+#define PCIM_HDRTYPE_NORMAL 0x00
+#define PCIM_HDRTYPE_BRIDGE 0x01
+#define PCIM_HDRTYPE_CARDBUS 0x02
+#define PCIM_MFDEV 0x80
+#define PCIR_BIST 0x0f
+
+/* Capability Identification Numbers */
+
+#define PCIY_PMG 0x01 /* PCI Power Management */
+#define PCIY_AGP 0x02 /* AGP */
+#define PCIY_VPD 0x03 /* Vital Product Data */
+#define PCIY_SLOTID 0x04 /* Slot Identification */
+#define PCIY_MSI 0x05 /* Message Signaled Interrupts */
+#define PCIY_CHSWP 0x06 /* CompactPCI Hot Swap */
+#define PCIY_PCIX 0x07 /* PCI-X */
+#define PCIY_HT 0x08 /* HyperTransport */
+#define PCIY_VENDOR 0x09 /* Vendor Unique */
+#define PCIY_DEBUG 0x0a /* Debug port */
+#define PCIY_CRES 0x0b /* CompactPCI central resource control */
+#define PCIY_HOTPLUG 0x0c /* PCI Hot-Plug */
+#define PCIY_AGP8X 0x0e /* AGP 8x */
+#define PCIY_SECDEV 0x0f /* Secure Device */
+#define PCIY_EXPRESS 0x10 /* PCI Express */
+#define PCIY_MSIX 0x11 /* MSI-X */
+
+/* config registers for header type 0 devices */
+
+#define PCIR_BARS 0x10
+#define PCIR_BAR(x) (PCIR_BARS + (x) * 4)
+#ifndef BURN_BRIDGES
+#define PCIR_MAPS PCIR_BARS
+#endif
+#define PCIR_CARDBUSCIS 0x28
+#define PCIR_SUBVEND_0 0x2c
+#define PCIR_SUBDEV_0 0x2e
+#define PCIR_BIOS 0x30
+#define PCIM_BIOS_ENABLE 0x01
+#define PCIR_CAP_PTR 0x34
+#define PCIR_INTLINE 0x3c
+#define PCIR_INTPIN 0x3d
+#define PCIR_MINGNT 0x3e
+#define PCIR_MAXLAT 0x3f
+
+/* config registers for header type 1 (PCI-to-PCI bridge) devices */
+
+#define PCIR_SECSTAT_1 0x1e
+
+#define PCIR_PRIBUS_1 0x18
+#define PCIR_SECBUS_1 0x19
+#define PCIR_SUBBUS_1 0x1a
+#define PCIR_SECLAT_1 0x1b
+
+#define PCIR_IOBASEL_1 0x1c
+#define PCIR_IOLIMITL_1 0x1d
+#define PCIR_IOBASEH_1 0x30
+#define PCIR_IOLIMITH_1 0x32
+#define PCIM_BRIO_16 0x0
+#define PCIM_BRIO_32 0x1
+#define PCIM_BRIO_MASK 0xf
+
+#define PCIR_MEMBASE_1 0x20
+#define PCIR_MEMLIMIT_1 0x22
+
+#define PCIR_PMBASEL_1 0x24
+#define PCIR_PMLIMITL_1 0x26
+#define PCIR_PMBASEH_1 0x28
+#define PCIR_PMLIMITH_1 0x2c
+
+#define PCIR_BRIDGECTL_1 0x3e
+
+#define PCIR_SUBVEND_1 0x34
+#define PCIR_SUBDEV_1 0x36
+
+/* config registers for header type 2 (CardBus) devices */
+
+#define PCIR_SECSTAT_2 0x16
+
+#define PCIR_PRIBUS_2 0x18
+#define PCIR_SECBUS_2 0x19
+#define PCIR_SUBBUS_2 0x1a
+#define PCIR_SECLAT_2 0x1b
+
+#define PCIR_MEMBASE0_2 0x1c
+#define PCIR_MEMLIMIT0_2 0x20
+#define PCIR_MEMBASE1_2 0x24
+#define PCIR_MEMLIMIT1_2 0x28
+#define PCIR_IOBASE0_2 0x2c
+#define PCIR_IOLIMIT0_2 0x30
+#define PCIR_IOBASE1_2 0x34
+#define PCIR_IOLIMIT1_2 0x38
+
+#define PCIR_BRIDGECTL_2 0x3e
+
+#define PCIR_SUBVEND_2 0x40
+#define PCIR_SUBDEV_2 0x42
+
+#define PCIR_PCCARDIF_2 0x44
+
+/* PCI device class, subclass and programming interface definitions */
+
+#define PCIC_OLD 0x00
+#define PCIS_OLD_NONVGA 0x00
+#define PCIS_OLD_VGA 0x01
+
+#define PCIC_STORAGE 0x01
+#define PCIS_STORAGE_SCSI 0x00
+#define PCIS_STORAGE_IDE 0x01
+#define PCIP_STORAGE_IDE_MODEPRIM 0x01
+#define PCIP_STORAGE_IDE_PROGINDPRIM 0x02
+#define PCIP_STORAGE_IDE_MODESEC 0x04
+#define PCIP_STORAGE_IDE_PROGINDSEC 0x08
+#define PCIP_STORAGE_IDE_MASTERDEV 0x80
+#define PCIS_STORAGE_FLOPPY 0x02
+#define PCIS_STORAGE_IPI 0x03
+#define PCIS_STORAGE_RAID 0x04
+#define PCIS_STORAGE_OTHER 0x80
+
+#define PCIC_NETWORK 0x02
+#define PCIS_NETWORK_ETHERNET 0x00
+#define PCIS_NETWORK_TOKENRING 0x01
+#define PCIS_NETWORK_FDDI 0x02
+#define PCIS_NETWORK_ATM 0x03
+#define PCIS_NETWORK_ISDN 0x04
+#define PCIS_NETWORK_OTHER 0x80
+
+#define PCIC_DISPLAY 0x03
+#define PCIS_DISPLAY_VGA 0x00
+#define PCIS_DISPLAY_XGA 0x01
+#define PCIS_DISPLAY_3D 0x02
+#define PCIS_DISPLAY_OTHER 0x80
+
+#define PCIC_MULTIMEDIA 0x04
+#define PCIS_MULTIMEDIA_VIDEO 0x00
+#define PCIS_MULTIMEDIA_AUDIO 0x01
+#define PCIS_MULTIMEDIA_TELE 0x02
+#define PCIS_MULTIMEDIA_OTHER 0x80
+
+#define PCIC_MEMORY 0x05
+#define PCIS_MEMORY_RAM 0x00
+#define PCIS_MEMORY_FLASH 0x01
+#define PCIS_MEMORY_OTHER 0x80
+
+#define PCIC_BRIDGE 0x06
+#define PCIS_BRIDGE_HOST 0x00
+#define PCIS_BRIDGE_ISA 0x01
+#define PCIS_BRIDGE_EISA 0x02
+#define PCIS_BRIDGE_MCA 0x03
+#define PCIS_BRIDGE_PCI 0x04
+#define PCIS_BRIDGE_PCMCIA 0x05
+#define PCIS_BRIDGE_NUBUS 0x06
+#define PCIS_BRIDGE_CARDBUS 0x07
+#define PCIS_BRIDGE_RACEWAY 0x08
+#define PCIS_BRIDGE_OTHER 0x80
+
+#define PCIC_SIMPLECOMM 0x07
+#define PCIS_SIMPLECOMM_UART 0x00
+#define PCIP_SIMPLECOMM_UART_16550A 0x02
+#define PCIS_SIMPLECOMM_PAR 0x01
+#define PCIS_SIMPLECOMM_MULSER 0x02
+#define PCIS_SIMPLECOMM_MODEM 0x03
+#define PCIS_SIMPLECOMM_OTHER 0x80
+
+#define PCIC_BASEPERIPH 0x08
+#define PCIS_BASEPERIPH_PIC 0x00
+#define PCIS_BASEPERIPH_DMA 0x01
+#define PCIS_BASEPERIPH_TIMER 0x02
+#define PCIS_BASEPERIPH_RTC 0x03
+#define PCIS_BASEPERIPH_PCIHOT 0x04
+#define PCIS_BASEPERIPH_OTHER 0x80
+
+#define PCIC_INPUTDEV 0x09
+#define PCIS_INPUTDEV_KEYBOARD 0x00
+#define PCIS_INPUTDEV_DIGITIZER 0x01
+#define PCIS_INPUTDEV_MOUSE 0x02
+#define PCIS_INPUTDEV_SCANNER 0x03
+#define PCIS_INPUTDEV_GAMEPORT 0x04
+#define PCIS_INPUTDEV_OTHER 0x80
+
+#define PCIC_DOCKING 0x0a
+#define PCIS_DOCKING_GENERIC 0x00
+#define PCIS_DOCKING_OTHER 0x80
+
+#define PCIC_PROCESSOR 0x0b
+#define PCIS_PROCESSOR_386 0x00
+#define PCIS_PROCESSOR_486 0x01
+#define PCIS_PROCESSOR_PENTIUM 0x02
+#define PCIS_PROCESSOR_ALPHA 0x10
+#define PCIS_PROCESSOR_POWERPC 0x20
+#define PCIS_PROCESSOR_MIPS 0x30
+#define PCIS_PROCESSOR_COPROC 0x40
+
+#define PCIC_SERIALBUS 0x0c
+#define PCIS_SERIALBUS_FW 0x00
+#define PCIS_SERIALBUS_ACCESS 0x01
+#define PCIS_SERIALBUS_SSA 0x02
+#define PCIS_SERIALBUS_USB 0x03
+#define PCIP_SERIALBUS_USB_UHCI 0x00
+#define PCIP_SERIALBUS_USB_OHCI 0x10
+#define PCIP_SERIALBUS_USB_EHCI 0x20
+#define PCIS_SERIALBUS_FC 0x04
+#define PCIS_SERIALBUS_SMBUS 0x05
+
+#define PCIC_WIRELESS 0x0d
+#define PCIS_WIRELESS_IRDA 0x00
+#define PCIS_WIRELESS_IR 0x01
+#define PCIS_WIRELESS_RF 0x10
+#define PCIS_WIRELESS_OTHER 0x80
+
+#define PCIC_INTELLIIO 0x0e
+#define PCIS_INTELLIIO_I2O 0x00
+
+#define PCIC_SATCOM 0x0f
+#define PCIS_SATCOM_TV 0x01
+#define PCIS_SATCOM_AUDIO 0x02
+#define PCIS_SATCOM_VOICE 0x03
+#define PCIS_SATCOM_DATA 0x04
+
+#define PCIC_CRYPTO 0x10
+#define PCIS_CRYPTO_NETCOMP 0x00
+#define PCIS_CRYPTO_ENTERTAIN 0x10
+#define PCIS_CRYPTO_OTHER 0x80
+
+#define PCIC_DASP 0x11
+#define PCIS_DASP_DPIO 0x00
+#define PCIS_DASP_OTHER 0x80
+
+#define PCIC_OTHER 0xff
+
+/* PCI power manangement */
+
+#define PCIR_POWER_CAP 0x2
+#define PCIM_PCAP_SPEC 0x0007
+#define PCIM_PCAP_PMEREQCLK 0x0008
+#define PCIM_PCAP_PMEREQPWR 0x0010
+#define PCIM_PCAP_DEVSPECINIT 0x0020
+#define PCIM_PCAP_DYNCLOCK 0x0040
+#define PCIM_PCAP_SECCLOCK 0x00c0
+#define PCIM_PCAP_CLOCKMASK 0x00c0
+#define PCIM_PCAP_REQFULLCLOCK 0x0100
+#define PCIM_PCAP_D1SUPP 0x0200
+#define PCIM_PCAP_D2SUPP 0x0400
+#define PCIM_PCAP_D0PME 0x1000
+#define PCIM_PCAP_D1PME 0x2000
+#define PCIM_PCAP_D2PME 0x4000
+
+#define PCIR_POWER_STATUS 0x4
+#define PCIM_PSTAT_D0 0x0000
+#define PCIM_PSTAT_D1 0x0001
+#define PCIM_PSTAT_D2 0x0002
+#define PCIM_PSTAT_D3 0x0003
+#define PCIM_PSTAT_DMASK 0x0003
+#define PCIM_PSTAT_REPENABLE 0x0010
+#define PCIM_PSTAT_PMEENABLE 0x0100
+#define PCIM_PSTAT_D0POWER 0x0000
+#define PCIM_PSTAT_D1POWER 0x0200
+#define PCIM_PSTAT_D2POWER 0x0400
+#define PCIM_PSTAT_D3POWER 0x0600
+#define PCIM_PSTAT_D0HEAT 0x0800
+#define PCIM_PSTAT_D1HEAT 0x1000
+#define PCIM_PSTAT_D2HEAT 0x1200
+#define PCIM_PSTAT_D3HEAT 0x1400
+#define PCIM_PSTAT_DATAUNKN 0x0000
+#define PCIM_PSTAT_DATADIV10 0x2000
+#define PCIM_PSTAT_DATADIV100 0x4000
+#define PCIM_PSTAT_DATADIV1000 0x6000
+#define PCIM_PSTAT_DATADIVMASK 0x6000
+#define PCIM_PSTAT_PME 0x8000
+
+#define PCIR_POWER_PMCSR 0x6
+#define PCIM_PMCSR_DCLOCK 0x10
+#define PCIM_PMCSR_B2SUPP 0x20
+#define PCIM_BMCSR_B3SUPP 0x40
+#define PCIM_BMCSR_BPCE 0x80
+
+#define PCIR_POWER_DATA 0x7
+
+/* PCI Message Signalled Interrupts (MSI) */
+#define PCIR_MSI_CTRL 0x2
+#define PCIM_MSICTRL_VECTOR 0x0100
+#define PCIM_MSICTRL_64BIT 0x0080
+#define PCIM_MSICTRL_MME_MASK 0x0070
+#define PCIM_MSICTRL_MME_1 0x0000
+#define PCIM_MSICTRL_MME_2 0x0010
+#define PCIM_MSICTRL_MME_4 0x0020
+#define PCIM_MSICTRL_MME_8 0x0030
+#define PCIM_MSICTRL_MME_16 0x0040
+#define PCIM_MSICTRL_MME_32 0x0050
+#define PCIM_MSICTRL_MMC_MASK 0x000E
+#define PCIM_MSICTRL_MMC_1 0x0000
+#define PCIM_MSICTRL_MMC_2 0x0002
+#define PCIM_MSICTRL_MMC_4 0x0004
+#define PCIM_MSICTRL_MMC_8 0x0006
+#define PCIM_MSICTRL_MMC_16 0x0008
+#define PCIM_MSICTRL_MMC_32 0x000A
+#define PCIM_MSICTRL_MSI_ENABLE 0x0001
+#define PCIR_MSI_ADDR 0x4
+#define PCIR_MSI_ADDR_HIGH 0x8
+#define PCIR_MSI_DATA 0x8
+#define PCIR_MSI_DATA_64BIT 0xc
+#define PCIR_MSI_MASK 0x10
+#define PCIR_MSI_PENDING 0x14
+
+/* PCI-X definitions */
+#define PCIXR_COMMAND 0x96
+#define PCIXR_DEVADDR 0x98
+#define PCIXM_DEVADDR_FNUM 0x0003 /* Function Number */
+#define PCIXM_DEVADDR_DNUM 0x00F8 /* Device Number */
+#define PCIXM_DEVADDR_BNUM 0xFF00 /* Bus Number */
+#define PCIXR_STATUS 0x9A
+#define PCIXM_STATUS_64BIT 0x0001 /* Active 64bit connection to device. */
+#define PCIXM_STATUS_133CAP 0x0002 /* Device is 133MHz capable */
+#define PCIXM_STATUS_SCDISC 0x0004 /* Split Completion Discarded */
+#define PCIXM_STATUS_UNEXPSC 0x0008 /* Unexpected Split Completion */
+#define PCIXM_STATUS_CMPLEXDEV 0x0010 /* Device Complexity (set == bridge) */
+#define PCIXM_STATUS_MAXMRDBC 0x0060 /* Maximum Burst Read Count */
+#define PCIXM_STATUS_MAXSPLITS 0x0380 /* Maximum Split Transactions */
+#define PCIXM_STATUS_MAXCRDS 0x1C00 /* Maximum Cumulative Read Size */
+#define PCIXM_STATUS_RCVDSCEM 0x2000 /* Received a Split Comp w/Error msg */
diff --git a/bsps/powerpc/beatnik/net/porting/rtemscompat.h b/bsps/powerpc/beatnik/net/porting/rtemscompat.h
new file mode 100644
index 0000000..5a4bb6b
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/rtemscompat.h
@@ -0,0 +1,454 @@
+#ifndef RTEMS_COMPAT_BSD_NET_H
+#define RTEMS_COMPAT_BSD_NET_H
+
+/* BSD -> rtems wrappers; stuff that must be defined
+ * prior to including most BSD headers
+ */
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+#include <rtems.h>
+#include <sys/errno.h>
+#include <sys/types.h>
+
+#include <stdlib.h>
+
+/* Check for RTEMS version; true if >= ma.mi.re */
+#define ISMINVERSION(ma,mi,re) \
+ ( __RTEMS_MAJOR__ > (ma) \
+ || (__RTEMS_MAJOR__ == (ma) && __RTEMS_MINOR__ > (mi)) \
+ || (__RTEMS_MAJOR__ == (ma) && __RTEMS_MINOR__ == (mi) && __RTEMS_REVISION__ >= (re)) \
+ )
+
+/* 'align' ARG is evaluated more than once */
+#define _DO_ALIGN(addr, align) (((uint32_t)(addr) + (align) - 1) & ~((align)-1))
+
+
+/* malloc/free are redefined :-( */
+static inline void *the_real_malloc(size_t n)
+{
+ return malloc(n);
+}
+
+static inline void the_real_free(void *p)
+{
+ return free(p);
+}
+
+#include <machine/rtems-bsd-kernel-space.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_bsdnet_internal.h>
+#ifdef __i386__
+#include <libcpu/cpu.h>
+#elif defined(__PPC__)
+#include <libcpu/io.h>
+#else
+#error "dunno what IO ops to use on this architecture"
+#endif
+#include <rtems/bspIo.h>
+
+#define NET_EMB(x,y,z) x ## y ## z
+#define NET_EMBEMB(x,y,z) NET_EMB(x,y,z)
+
+#define NET_STR(arg) #arg
+#define NET_STRSTR(arg) NET_STR(arg)
+
+#define NET_SOFTC NET_EMBEMB(,NETDRIVER_PREFIX,_softc)
+
+#define METHODS NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_methods)
+extern struct _net_drv_tbl METHODS;
+
+#ifdef DEBUG_MODULAR
+#define METHODSPTR NET_EMBEMB(rtems_,NETDRIVER_PREFIX,_methods_p)
+extern struct _net_drv_tbl *volatile METHODSPTR;
+#else
+#define METHODSPTR (&METHODS)
+#endif
+
+#if defined(__LITTLE_ENDIAN__) || (__i386__)
+static inline uint16_t htole16(uint16_t v) { return v; }
+static inline uint32_t htole32(uint32_t v) { return v; }
+static inline uint64_t htole64(uint64_t v) { return v; }
+static inline uint16_t le16toh(uint16_t v) { return v; }
+static inline uint32_t le32toh(uint32_t v) { return v; }
+static inline uint64_t le64toh(uint64_t v) { return v; }
+#elif defined(__BIG_ENDIAN__)
+#ifdef __PPC__
+#include <libcpu/byteorder.h>
+
+/* Different RTEMS versions use different types
+ * for 32-bit (unsigned vs. unsigned long which
+ * always cause gcc warnings and possible alias
+ * violations, sigh).
+ */
+
+#if ISMINVERSION(4,8,0)
+typedef uint32_t rtemscompat_32_t;
+#else
+typedef unsigned rtemscompat_32_t;
+#endif
+
+static inline uint16_t
+htole16(uint16_t v)
+{
+uint16_t rval;
+ st_le16(&rval,v);
+ return rval;
+}
+
+static inline uint16_t
+le16toh(uint16_t v)
+{
+ return ld_le16((unsigned short*)&v);
+}
+
+static inline uint32_t
+htole32(uint32_t v)
+{
+rtemscompat_32_t rval;
+ st_le32(&rval,v);
+ return rval;
+}
+
+static inline uint32_t
+le32toh(uint32_t v)
+{
+rtemscompat_32_t vv = v;
+ return ld_le32(&vv);
+}
+
+/* Compiler generated floating point instructions for this
+ * and rtems_bsdnet_newproc()-generated tasks are non-FP
+ * :-(
+ */
+static inline uint64_t
+htole64(uint64_t v)
+{
+union {
+ rtemscompat_32_t tmp[2];
+ uint64_t rval;
+} u;
+
+ st_le32( &u.tmp[0], (unsigned)(v&0xffffffff) );
+ st_le32( &u.tmp[1], (unsigned)((v>>32)&0xffffffff) );
+
+ return u.rval;
+}
+
+#else
+#error "need htoleXX() implementation for this CPU arch"
+#endif
+
+#else
+#error "Unknown CPU endianness"
+#endif
+
+
+
+#ifdef __PPC__
+#define _out_byte(a,v) out_8((volatile uint8_t*)(a),(v))
+#define _inp_byte(a) in_8((volatile uint8_t*)(a))
+#ifdef NET_CHIP_LE
+#define _out_word(a,v) out_le16((volatile uint16_t*)(a),(v))
+#define _out_long(a,v) out_le32((volatile uint32_t *)(a),(v))
+#define _inp_word(a) in_le16((volatile uint16_t*)(a))
+#define _inp_long(a) in_le32((volatile uint32_t *)(a))
+#elif defined(NET_CHIP_BE)
+#define _out_word(a,v) out_be16((volatile uint16_t*)(a),(v))
+#define _out_long(a,v) out_be32((volatile uint32_t *)(a),(v))
+#define _inp_word(a) in_be16((volatile uint16_t*)(a))
+#define _inp_long(a) in_be32((volatile uint32_t *)(a))
+#else
+#error rtemscompat_defs.h must define either NET_CHIP_LE or NET_CHIP_BE
+#endif
+static inline void wrle32(unsigned *a, unsigned v)
+{
+ asm volatile("stwbrx %1,0,%2":"=m"(*a):"r"(v),"r"(a));
+}
+static inline unsigned rdle32(unsigned *a)
+{
+ asm volatile("lwbrx %0,0,%0":"=r"(a):"0"(a),"m"(*a));
+ return (unsigned)a;
+}
+static inline void orle32(unsigned *a,unsigned v) { wrle32(a, rdle32(a) | v); }
+static inline void anle32(unsigned *a,unsigned v) { wrle32(a, rdle32(a) & v); }
+
+static inline void wrle16(unsigned short *a, unsigned short v)
+{
+ asm volatile("sthbrx %1,0,%2":"=m"(*a):"r"(v),"r"(a));
+}
+static inline unsigned short rdle16(unsigned short *a)
+{
+ asm volatile("lhbrx %0,0,%0":"=r"(a):"0"(a),"m"(*a));
+ return (unsigned short)(unsigned)a;
+}
+static inline void orle16(unsigned short *a,unsigned short v) { wrle16(a, rdle16(a) | v); }
+static inline void anle16(unsigned short *a,unsigned short v) { wrle16(a, rdle16(a) & v); }
+#endif
+
+#ifdef __i386__
+#ifdef NET_CHIP_BE
+#error dunno how to output BE data
+#endif
+
+static inline void wrle32(volatile unsigned *p, unsigned v) { *p = v; }
+static inline void orle32(volatile unsigned *p, unsigned v) { *p |= v; }
+static inline void anle32(volatile unsigned *p, unsigned v) { *p &= v; }
+static inline unsigned rdle32(volatile unsigned *p) { return *p; }
+
+static inline void wrle16(volatile unsigned short *p, unsigned short v) { *p = v; }
+static inline void orle16(volatile unsigned short *p, unsigned short v) { *p |= v; }
+static inline void anle16(volatile unsigned short *p, unsigned short v) { *p &= v; }
+static inline unsigned short rdle16(volatile unsigned short *p) { return *p; }
+
+#ifdef NET_CHIP_MEM_IO
+
+#ifdef __i386__
+static inline void _out_byte(unsigned a, unsigned char v) { *(volatile unsigned char*)a = v; }
+static inline unsigned char _inp_byte(unsigned a) { return *(volatile unsigned char*)a; }
+#ifdef NET_CHIP_LE
+static inline void _out_word(unsigned a, unsigned short v) { *(volatile unsigned short*)a = v; }
+static inline unsigned short _inp_word(unsigned a) { return *(volatile unsigned short*)a; }
+static inline void _out_long(unsigned a, unsigned v) { *(volatile unsigned *)a = v; }
+static inline unsigned _inp_long(unsigned a) { return *(volatile unsigned *)a; }
+#elif defined(NET_CHIP_BE)
+#error "BE memory IO not implemented for i386 yet"
+#else
+#error rtemscompat_defs.h must define either NET_CHIP_LE or NET_CHIP_BE
+#endif
+#else
+
+#error "Memory IO not implemented for this CPU architecture yet"
+
+#endif
+#elif defined(NET_CHIP_PORT_IO)
+#define _out_byte(addr,val) outport_byte((addr),(val))
+#define _out_word(addr,val) outport_word((addr),(val))
+#define _out_long(addr,val) outport_long((addr),(val))
+
+static inline u_int8_t _inp_byte(volatile unsigned char *a)
+{
+register u_int8_t rval;
+ inport_byte((unsigned short)(unsigned)a,rval);
+ return rval;
+}
+static inline u_int16_t _inp_word(volatile unsigned short *a)
+{
+register u_int16_t rval;
+ inport_word((unsigned short)(unsigned)a,rval);
+ return rval;
+}
+static inline u_int32_t _inp_long(volatile unsigned *a)
+{
+register u_int32_t rval;
+ inport_long((unsigned short)(unsigned)a,rval);
+ return rval;
+}
+#else
+#error either NET_CHIP_MEM_IO or NET_CHIP_PORT_IO must be defined
+#endif
+#endif
+
+#ifndef __FBSDID
+#define __FBSDID(arg)
+#endif
+
+#define device_printf(device,format,args...) printk(format,## args)
+
+static inline u_int8_t bus_space_do_read_1(u_long handle, unsigned reg)
+{
+ return _inp_byte((volatile unsigned char*)((handle)+(reg)));
+}
+
+static inline u_int16_t bus_space_do_read_2(u_long handle, unsigned reg)
+{
+ return _inp_word((volatile unsigned short*)((handle)+(reg)));
+}
+
+static inline u_int32_t bus_space_do_read_4(u_long handle, unsigned reg)
+{
+ return _inp_long((volatile unsigned *)((handle)+(reg)));
+}
+
+#define bus_space_read_1(tag,handle,reg) bus_space_do_read_1((handle),(reg))
+#define bus_space_read_2(tag,handle,reg) bus_space_do_read_2((handle),(reg))
+#define bus_space_read_4(tag,handle,reg) bus_space_do_read_4((handle),(reg))
+
+static inline void bus_space_do_write_multi_1(u_long handle, unsigned reg, unsigned char *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++) _out_byte( (handle) + (reg), (addr)[i]);
+}
+
+static inline void bus_space_do_write_multi_2(u_long handle, unsigned reg, unsigned short *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++) _out_word( (handle) + (reg), (addr)[i]);
+}
+
+static inline void bus_space_do_write_multi_4(u_long handle, unsigned reg, unsigned long *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++) _out_long( (handle) + (reg), (addr)[i]);
+}
+
+
+#define bus_space_write_multi_1(tag, handle, reg, addr, cnt) \
+ bus_space_do_write_multi_1(handle, reg, addr, cnt)
+#define bus_space_write_multi_2(tag, handle, reg, addr, cnt) \
+ bus_space_do_write_multi_2(handle, reg, addr, cnt)
+#define bus_space_write_multi_4(tag, handle, reg, addr, cnt) \
+ bus_space_do_write_multi_4(handle, reg, addr, cnt)
+
+static inline void bus_space_do_read_multi_1(u_long handle, unsigned reg, unsigned char *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++)
+ (addr)[i] = _inp_byte((volatile unsigned char*)((handle)+(reg)));
+}
+
+static inline void bus_space_do_read_multi_2(u_long handle, unsigned reg, unsigned short *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++)
+ (addr)[i] = _inp_word((volatile unsigned short*)((handle)+(reg)));
+}
+
+static inline void bus_space_do_read_multi_4(u_long handle, unsigned reg, unsigned long *addr, int cnt)
+{
+ int i; for (i=0; i<cnt; i++)
+ (addr)[i] = _inp_long((volatile unsigned *)((handle)+(reg)));
+}
+
+#define bus_space_read_multi_1(tag, handle, reg, addr, cnt) \
+ bus_space_do_read_multi_1(handle, reg, addr, cnt)
+#define bus_space_read_multi_2(tag, handle, reg, addr, cnt) \
+ bus_space_do_read_multi_2(handle, reg, addr, cnt)
+#define bus_space_read_multi_4(tag, handle, reg, addr, cnt) \
+ bus_space_do_read_multi_4(handle, reg, addr, cnt)
+
+
+
+#define bus_space_write_1(tag, handle, reg, val) \
+ do { _out_byte( (handle) + (reg), (val)); } while (0)
+
+#define bus_space_write_2(tag, handle, reg, val) \
+ do { _out_word( (handle) + (reg), (val)); } while (0)
+
+#define bus_space_write_4(tag, handle, reg, val) \
+ do { _out_long( (handle) + (reg), (val)); } while (0)
+
+#define BPF_MTAP(a,b) do { } while (0)
+
+extern unsigned net_driver_ticks_per_sec;
+
+#ifdef __PPC__
+/* PPC has a timebase - based delay */
+#define DELAY(n) do { \
+ if ( (n) > 10000 ) \
+ rtems_task_wake_after((((n)*net_driver_ticks_per_sec)/1000000) + 1); \
+ else \
+ rtems_bsp_delay(n); \
+ } while (0)
+#else
+#warning "Have no good usec delay implementation"
+#define DELAY(n) do { \
+ rtems_task_wake_after((((n)*net_driver_ticks_per_sec)/1000000) + 1); \
+ } while (0)
+#endif
+
+
+#define IRQ_LOCKED(code) \
+ do { unsigned long _xtre_irq_flags; \
+ rtems_interrupt_disable(_xtre_irq_flags); \
+ do { code } while(0); \
+ rtems_interrupt_enable(_xtre_irq_flags); \
+ } while (0)
+
+typedef void (driver_intr_t)(void *);
+
+#define if_xname if_name
+
+/* need to replace those with LOCAL2PCI() and make sure the bus handle is initialized
+ * (on most BSPs we get away with PCI_DRAM_OFFSET [no bus handle needed at all]
+ */
+#ifndef PCI_DRAM_OFFSET
+#define PCI_DRAM_OFFSET 0
+#endif
+
+#ifndef PCI_MEM_BASE
+#define PCI_MEM_BASE 0
+#endif
+
+#define kvtop(a) ((unsigned long)(a) + PCI_DRAM_OFFSET)
+#define vtophys(a) ((unsigned long)(a) + PCI_DRAM_OFFSET)
+
+#define PCI2LOCAL(a,bus) ((unsigned long)(a) + PCI_MEM_BASE)
+
+#ifdef PCI0_IO_BASE /* special mvme5500 hack :-( */
+#define PCI_IO_2LOCAL(a,bus) ((unsigned long)(a) + PCI0_IO_BASE)
+#elif defined(PCI_IO_BASE)
+#define PCI_IO_2LOCAL(a,bus) ((unsigned long)(a) + PCI_IO_BASE)
+#elif defined(_IO_BASE)
+#define PCI_IO_2LOCAL(a,bus) ((unsigned long)(a) + _IO_BASE)
+#else
+#warning "Unable to determine base address of PCI IO space; using ZERO"
+#define PCI_IO_2LOCAL(a,bus) ((unsigned long)(a))
+#endif
+
+#define if_printf(if,fmt,args...) printf("%s:"fmt,(if)->if_name,args)
+
+#ifndef BUS_PROBE_DEFAULT
+#define BUS_PROBE_DEFAULT 0
+#endif
+
+static inline void *
+contigmalloc(
+ unsigned long size,
+ int type,
+ int flags,
+ unsigned long lo,
+ unsigned long hi,
+ unsigned long align,
+ unsigned long bound)
+{
+void *ptr = rtems_bsdnet_malloc(size + sizeof(ptr) + align-1, type, flags);
+char *rval = 0;
+ if ( ptr ) {
+ unsigned tmp = (unsigned)ptr + align - 1;
+ tmp -= tmp % align;
+ rval = (char*)tmp;
+ /* save backlink */
+ *(void**)(rval+size) = ptr;
+ }
+ return rval;
+}
+
+static inline void
+contigfree(void *ptr, size_t size, int type)
+{
+ rtems_bsdnet_free( *(void**)((unsigned)ptr + size), type);
+}
+
+/* callout stuff */
+#define callout_init(args...) do {} while (0);
+#define callout_reset(args...) do {} while (0);
+#define callout_stop(args...) do {} while (0);
+
+#define IFQ_DRV_IS_EMPTY(q) (0 == (q)->ifq_head)
+#define IFQ_DRV_DEQUEUE(q,m) IF_DEQUEUE((q),(m))
+#define IFQ_DRV_PREPEND(q,m) IF_PREPEND((q),(m))
+
+#define DO_ETHER_INPUT_SKIPPING_ETHER_HEADER(ifp,m) \
+ { struct ether_header *eh; \
+ eh = mtod(m, struct ether_header*); \
+ m->m_data += sizeof(struct ether_header); \
+ m->m_len -= sizeof(struct ether_header); \
+ m->m_pkthdr.len -= sizeof(struct ether_header); \
+ m->m_pkthdr.rcvif = ifp; \
+ ether_input(ifp, eh, m); \
+ } while (0)
+
+
+#ifndef __KERNEL_RCSID
+#define __KERNEL_RCSID(arg...)
+#endif
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/porting/rtemscompat1.h b/bsps/powerpc/beatnik/net/porting/rtemscompat1.h
new file mode 100644
index 0000000..cee1652
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/rtemscompat1.h
@@ -0,0 +1,219 @@
+#ifndef RTEMS_COMPAT1_BSD_NET_H
+#define RTEMS_COMPAT1_BSD_NET_H
+
+/* BSD -> RTEMS conversion wrappers; stuff that must be defined
+ * after most BSD headers are included.
+ */
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+typedef struct device {
+ struct NET_SOFTC d_softc; /* MUST BE FIRST FIELD */
+ char *d_name;
+ char *d_desc;
+ int d_unit;
+ int flags;
+ /* pointer to ifconfig only valid during excution of
+ * the n_attach/n_detach methods (see below)
+ */
+ struct rtems_bsdnet_ifconfig *d_ifconfig;
+} netdev_t;
+
+#define THEDEVS NET_EMBEMB(the_,NETDRIVER_PREFIX,_devs)
+#define NETDEV_DECL netdev_t THEDEVS[NETDRIVER_SLOTS]
+
+extern NETDEV_DECL;
+
+typedef struct _net_drv_tbl {
+ int (*n_probe)(device_t);
+ int (*n_attach)(device_t);
+ int (*n_detach)(device_t);
+ void (*n_intr)(void *);
+} net_drv_tbl_t;
+
+static inline netdev_t *
+net_dev_get(struct rtems_bsdnet_ifconfig *config)
+{
+ int unitNo;
+ char *unitName;
+
+ unitNo = rtems_bsdnet_parse_driver_name(config, &unitName);
+ if ( unitNo < 0 )
+ return 0;
+
+ if ( unitNo <=0 || unitNo > NETDRIVER_SLOTS ) {
+ device_printf(dev, "Bad "NETDRIVER" unit number.\n");
+ return 0;
+ }
+
+ if ( THEDEVS[unitNo-1].d_unit && THEDEVS[unitNo-1].d_unit != unitNo ) {
+ device_printf(dev, "Unit # mismatch !!??\n");
+ return 0;
+ }
+
+ THEDEVS[unitNo-1].d_unit = unitNo;
+ THEDEVS[unitNo-1].d_name = unitName;
+ THEDEVS[unitNo-1].d_ifconfig = config;
+
+ return &THEDEVS[unitNo - 1];
+}
+
+/* kludge; that's why softc needs to be first */
+static inline netdev_t *
+softc_get_device(struct NET_SOFTC *sc)
+{
+ return (netdev_t *)sc;
+}
+
+static inline struct NET_SOFTC *
+device_get_softc(netdev_t *dev)
+{ return &dev->d_softc; }
+
+static inline int
+device_get_unit(netdev_t *dev)
+{ return dev->d_unit; }
+
+static inline char *
+device_get_name(netdev_t *dev)
+{ return dev->d_name; }
+
+static inline void
+if_initname(struct ifnet *ifp, char *name, int unit)
+{
+ ifp->if_name = name;
+ ifp->if_unit = unit;
+}
+
+static inline void
+device_set_desc(netdev_t *dev, char *str)
+{
+ dev->d_desc = str;
+}
+
+static inline void
+device_set_desc_copy(netdev_t *dev, char *str)
+{
+ dev->d_desc = strdup(str);
+}
+
+
+static inline int
+device_is_attached(netdev_t *dev)
+{
+ return dev->d_softc.arpcom.ac_if.if_addrlist && dev->d_softc.arpcom.ac_if.if_init;
+}
+
+#ifdef NETDRIVER_PCI
+#include NETDRIVER_PCI
+#include "pcireg.h"
+
+static inline unsigned
+pci_read_config(device_t dev, unsigned addr, unsigned width)
+{
+rtemscompat_32_t d;
+unsigned short s;
+unsigned char b;
+struct NET_SOFTC *sc = device_get_softc(dev);
+ switch (width) {
+ case 1: pci_read_config_byte(sc->b, sc->d, sc->f, addr, &b);
+ return b;
+ case 2: pci_read_config_word(sc->b, sc->d, sc->f, addr, &s);
+ return s;
+ case 4: pci_read_config_dword(sc->b, sc->d, sc->f, addr, &d);
+ return d;
+ default:
+ break;
+ }
+ return 0xdeadbeef;
+}
+
+static inline void
+pci_write_config(device_t dev, unsigned addr, unsigned width, unsigned val)
+{
+struct NET_SOFTC *sc = device_get_softc(dev);
+ switch (width) {
+ case 1: pci_write_config_byte(sc->b, sc->d, sc->f, addr, val);
+ return ;
+ case 2: pci_write_config_word(sc->b, sc->d, sc->f, addr, val);
+ return ;
+ case 4: pci_write_config_dword(sc->b, sc->d, sc->f, addr, val);
+ return ;
+ default:
+ break;
+ }
+}
+
+
+static inline unsigned short
+pci_get_vendor(device_t dev)
+{
+ return pci_read_config(dev, PCIR_VENDOR, 2);
+}
+
+static inline unsigned short
+pci_get_device(device_t dev)
+{
+ return pci_read_config(dev, PCIR_DEVICE, 2);
+}
+
+static inline unsigned short
+pci_get_subvendor(device_t dev)
+{
+ return pci_read_config(dev, PCIR_SUBVEND_0, 2);
+}
+
+static inline unsigned short
+pci_get_subdevice(device_t dev)
+{
+ return pci_read_config(dev, PCIR_SUBDEV_0, 2);
+}
+
+
+static inline void
+pci_enable_busmaster(device_t dev)
+{
+ pci_write_config(
+ dev,
+ PCIR_COMMAND,
+ 2,
+ pci_read_config(dev, PCIR_COMMAND, 2)
+ | PCIM_CMD_BUSMASTEREN);
+}
+
+#define mtx_init(a,b,c,d) do {} while(0)
+#define mtx_initialized(ma) (1)
+#define mtx_destroy(ma) do {} while(0)
+#define mtx_lock(a) do {} while(0)
+#define mtx_unlock(a) do {} while(0)
+#define mtx_assert(a,b) do {} while(0)
+
+#define callout_handle_init(x) do {} while (0)
+#define untimeout(a...) do {} while (0)
+
+#if !ISMINVERSION(4,6,99)
+#define pci_bus_count BusCountPCI
+#endif
+
+#endif
+
+/* Ugly hack to allow unloading/reloading the driver core.
+ * Needed because rtems' bsdnet release doesn't implement
+ * if_detach(). Therefore, we bring the interface down but
+ * keep the device record alive...
+ */
+static inline void
+__ether_ifdetach(struct ifnet *ifp)
+{
+ ifp->if_flags = 0;
+ ifp->if_ioctl = 0;
+ ifp->if_start = 0;
+ ifp->if_watchdog = 0;
+ ifp->if_init = 0;
+}
+
+#endif
diff --git a/bsps/powerpc/beatnik/net/porting/rtemscompat_defs.h.template b/bsps/powerpc/beatnik/net/porting/rtemscompat_defs.h.template
new file mode 100644
index 0000000..5dc8d1e
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/porting/rtemscompat_defs.h.template
@@ -0,0 +1,97 @@
+#ifndef RTEMS_COMPAT_DEFS_H
+#define RTEMS_COMPAT_DEFS_H
+
+/* Symbol definitions for a particular driver */
+
+/* Copyright: Till Straumann <strauman@slac.stanford.edu>, 2005;
+ * License: see LICENSE file.
+ */
+
+/* Number of device instances the driver should support
+ * - may be limited to 1 depending on IRQ API
+ * (braindamaged PC586 and powerpc)
+ */
+#define NETDRIVER_SLOTS 1
+/* String name to print with error messages */
+#define NETDRIVER "PCN"
+/* Name snippet used to make global symbols unique to this driver */
+#define NETDRIVER_PREFIX pcn
+
+/* Define according to endianness of the *ethernet*chip*
+ * (not the CPU - most probably are LE)
+ * This must be either NET_CHIP_LE or NET_CHIP_BE
+ */
+
+#define NET_CHIP_LE
+#undef NET_CHIP_BE
+
+/* Define either NET_CHIP_MEM_IO or NET_CHIP_PORT_IO,
+ * depending whether the CPU sees it in memory address space
+ * or (e.g. x86) uses special I/O instructions.
+ */
+#define NET_CHIP_MEM_IO
+#undef NET_CHIP_PORT_IO
+
+/* The name of the hijacked 'bus handle' field in the softc
+ * structure. We use this field to store the chip's base address.
+ */
+#define NET_SOFTC_BHANDLE_FIELD pcn_bhandle
+
+/* define the names of the 'if_XXXreg.h' and 'if_XXXvar.h' headers
+ * (only if present, i.e., if the BSDNET driver has no respective
+ * header, leave this undefined).
+ *
+ */
+#undef IF_REG_HEADER <if_XXXreg.h>
+#undef IF_VAR_HEADER <if_XXXvar.h>
+
+/* define if a pci device */
+#define NETDRIVER_PCI <bsp/pci.h>
+
+/* Macros to disable and enable interrupts, respectively.
+ * The 'disable' macro is expanded in the ISR, the 'enable'
+ * macro is expanded in the driver task.
+ * The global network semaphore usually provides mutex
+ * protection of the device registers.
+ * Special care must be taken when coding the 'disable' macro,
+ * however to MAKE SURE THERE ARE NO OTHER SIDE EFFECTS such
+ * as:
+ * - macro must not clear any status flags
+ * - macro must save/restore any context information
+ * (e.g., a address register pointer or a bank switch register)
+ *
+ * ARGUMENT: the macro arg is a pointer to the driver's 'softc' structure
+ */
+
+/* Here EXAMPLES for the pcnet chip which addresses registers indirectly
+ * through a 'address-pointer' (RAP) and 'data-port' (RDP) register pair:
+#define NET_DISABLE_IRQS(sc) do { \
+ unsigned rap = CSR_READ_4((sc),PCN_IO32_RAP); \
+ unsigned val; \
+ CSR_WRITE_4((sc),PCN_IO32_RAP,PCN_CSR_CSR); \
+ val = CSR_READ_4((sc),PCN_IO32_RDP); \
+ CSR_WRITE_4((sc), PCN_IO32_RDP, val & ~(CSR0_INT_STATUS_MASK | PCN_CSR_INTEN)); \
+ CSR_WRITE_4((sc), PCN_IO32_RAP, rap); \
+ } while (0)
+
+#define NET_ENABLE_IRQS(sc) do { \
+ unsigned flags,val; \
+ rtems_interrupt_disable(flags); \
+ CSR_WRITE_4((sc),PCN_IO32_RAP,PCN_CSR_CSR); \
+ val = CSR_READ_4((sc),PCN_IO32_RDP); \
+ CSR_WRITE_4((sc), PCN_IO32_RDP, (val & ~CSR0_INT_STATUS_MASK) | PCN_CSR_INTEN); \
+ rtems_interrupt_enable(flags); \
+ } while (0)
+*/
+
+/* Driver may provide a macro/function to copy the hardware address
+ * from the device into 'softc.arpcom'.
+ * If this is undefined, the driver must to the copy itself.
+ * Preferrably, it should check soft.arpcom.ac_enaddr for all
+ * zeros and leave it alone if it is nonzero, i.e., write it
+ * to the hardware.
+#define NET_READ_MAC_ADDR(sc)
+ */
+
+#define KASSERT(a...) do {} while (0)
+#endif
diff --git a/bsps/powerpc/beatnik/net/support/bsp_attach.c b/bsps/powerpc/beatnik/net/support/bsp_attach.c
new file mode 100644
index 0000000..30329d9
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/support/bsp_attach.c
@@ -0,0 +1,468 @@
+/* BSP specific wrapper for rtems_bsdnet_attach(). This wrapper
+ * dispatches to the correct driver attach routine depending on
+ * the board type, boot parameters, link status etc.
+ *
+ * Also, it performs board-specific setup of driver parameters
+ * (such as ethernet address, base addresses and the like)
+ */
+
+/*
+ * Authorship
+ * ----------
+ * This software ('beatnik' RTEMS BSP for MVME6100 and MVME5500) was
+ * created by Till Straumann <strauman@slac.stanford.edu>, 2005-2007,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * The 'beatnik' BSP was produced by
+ * the Stanford Linear Accelerator Center, Stanford University,
+ * under Contract DE-AC03-76SFO0515 with the Department of Energy.
+ *
+ * Government disclaimer of liability
+ * ----------------------------------
+ * Neither the United States nor the United States Department of Energy,
+ * nor any of their employees, makes any warranty, express or implied, or
+ * assumes any legal liability or responsibility for the accuracy,
+ * completeness, or usefulness of any data, apparatus, product, or process
+ * disclosed, or represents that its use would not infringe privately owned
+ * rights.
+ *
+ * Stanford disclaimer of liability
+ * --------------------------------
+ * Stanford University makes no representations or warranties, express or
+ * implied, nor assumes any liability for the use of this software.
+ *
+ * Stanford disclaimer of copyright
+ * --------------------------------
+ * Stanford University, owner of the copyright, hereby disclaims its
+ * copyright and all other rights in this software. Hence, anyone may
+ * freely use it for any purpose without restriction.
+ *
+ * Maintenance of notices
+ * ----------------------
+ * In the interest of clarity regarding the origin and status of this
+ * SLAC software, this and all the preceding Stanford University notices
+ * are to remain affixed to any copy or derivative of this software made
+ * or distributed by the recipient and are to be affixed to any copy of
+ * software made or distributed by the recipient that contains a copy or
+ * derivative of this software.
+ *
+ * ------------------ SLAC Software Notices, Set 4 OTT.002a, 2004 FEB 03
+ */
+
+#include <unistd.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <bsp/pci.h>
+
+#include <bsp/early_enet_link_status.h>
+
+#include <bsp/if_mve_pub.h>
+#include <bsp/if_gfe_pub.h>
+#include <bsp/if_em_pub.h>
+
+#include <stdio.h>
+#include <string.h>
+#include <assert.h>
+
+#define IS_6100() (MVME6100 == BSP_getBoardType())
+#define IS_5500() (MVME5500 == BSP_getBoardType())
+
+static int bsp_gfe_attach(struct rtems_bsdnet_ifconfig *, int);
+static int mvme5500_em_attach (struct rtems_bsdnet_ifconfig *, int);
+static int mvme5500_em_find_onboard_unit(void);
+
+char BSP_auto_network_driver_name[20] = {0,};
+
+static BSP_NetIFDescRec mvme6100_netifs[] = {
+ {
+ name: "mve1",
+ description: "MV64360 built-in 10/100/1000 Ethernet 1",
+ attach_fn: rtems_mve_attach
+ },
+ {
+ name: "mve2",
+ description: "MV64360 built-in 10/100/1000 Ethernet 2",
+ attach_fn: rtems_mve_attach
+ },
+ {
+ name: 0,
+ }
+};
+
+static BSP_NetIFDescRec mvme5500_netifs[] = {
+ {
+ name: "em1",
+ description: "Intel 82544 on-board 10/100/1000 Ethernet (port 1)",
+ attach_fn: mvme5500_em_attach,
+ },
+ {
+ name: "gfe1",
+ description: "GT64260 built-in 10/100 Ethernet (port 2)",
+ attach_fn: bsp_gfe_attach,
+ },
+ {
+ name: 0,
+ }
+};
+
+
+/* wrap the 'gfe' and 'em' attach functions.
+ * RATIONALE: 'rtems_gfe_attach()' and 'rtems_em_attach()' are
+ * *chip* specific functions. However, they require
+ * some *board* specific parameter setup prior to
+ * being attached which is what these wrappers do...
+ */
+
+static unsigned em_info[];
+
+static int scan4irqLine(int bus, int dev, int fn, void *uarg)
+{
+unsigned char byte;
+unsigned short word;
+int i;
+
+ /* count the number of 82544 we find */
+ pci_read_config_word(bus, dev, fn, PCI_VENDOR_ID, &word);
+ if ( 0x8086 != word )
+ return 0;
+
+ pci_read_config_word(bus, dev, fn, PCI_DEVICE_ID, &word);
+ for ( i = 0; em_info[i]; i++ ) {
+ if ( em_info[i] == word )
+ break;
+ }
+
+ if ( !em_info[i] )
+ return 0;
+
+ /* found a candidate; bump unit number */
+ (*(int *)uarg)++;
+
+ pci_read_config_byte(bus, dev, fn, PCI_INTERRUPT_LINE, &byte);
+
+ /* On the mvme5500 the 82544 is hooked to GPP IRQ 20 */
+
+ return ( BSP_IRQ_GPP_0 + 20 == byte ) ? 1 : 0;
+}
+
+/* Setup only once */
+static void
+onboard_em_setup_once(void)
+{
+static char done = 0;
+
+ /* If scanning didn't do anything, passing 0 will setup all interfaces */
+ if ( !done
+ && rtems_em_pci_setup( mvme5500_em_find_onboard_unit() > 0 ) ) {
+ done=1;
+ }
+}
+
+static void
+onboard_gfe_setup_once(void)
+{
+static char done = 0;
+
+ /* must setup HW address -- note that the label on the
+ * board indicates that the gfe is the second interface
+ * but motLoad etc. interprets the order actually
+ * the other way round...
+ */
+ if ( !done
+ && rtems_gfe_setup( 1, BSP_enetAddr0, BSP_MV64x60_BASE ) > 0 ) {
+ done=1;
+ }
+}
+
+
+/* Find the unit number of the on-board 82544 (even if there is another one
+ * plugged into PMC...
+ *
+ * RETURNS: unit # (>0) or zero if nothing at all was found. (New board rev.
+ * with the 82544 hooked to a different IRQ line, new PCI device ID,
+ * ...)
+ */
+static int
+mvme5500_em_find_onboard_unit(void)
+{
+int unit = 0;
+void *h;
+ /* Determine the on-board 'em' adapter; we know it's interrupt line :-) */
+ for ( h=0; (h=BSP_pciScan(h, scan4irqLine, &unit)); )
+ /* nothing else to do */;
+ return h ? unit : 0;
+}
+
+static int
+mvme5500_em_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+ if ( attaching ) {
+ onboard_em_setup_once();
+
+ /* Make sure there is no conflict in MAC address -- see below
+ * why we 'swap' the addresses. (We actually don't but swap the
+ * order of the interfaces so they match the label.)
+ */
+ if ( !ifcfg->hardware_address )
+ ifcfg->hardware_address = BSP_enetAddr1;
+ }
+
+ return rtems_em_attach(ifcfg, attaching);
+}
+
+static int
+bsp_gfe_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+ if ( attaching ) {
+ onboard_gfe_setup_once();
+ }
+ return rtems_gfe_attach(ifcfg, attaching);
+}
+
+BSP_NetIFDesc
+BSP_availableNetIFs(void)
+{
+ if ( IS_6100() )
+ return mvme6100_netifs;
+ if ( IS_5500() )
+ return mvme5500_netifs;
+
+ fprintf(stderr,"BSP_availableNetIFs() -- productIdent not set? unable to identify board type\n");
+
+ return 0;
+}
+
+typedef int (*read_op_t)(int,unsigned);
+typedef int (*write_op_t)(int,unsigned,unsigned);
+
+struct poll_job {
+ read_op_t rdop;
+ write_op_t wrop;
+ int unit;
+};
+
+static int
+check_phys(struct poll_job *job)
+{
+struct poll_job *j;
+int rval = -2;
+ for ( j=job; j->rdop; j++ ) {
+ unsigned w;
+ w = j->rdop(j->unit, 1/*status*/);
+ if ( 0x04 & w ) /* active link */
+ return j-job;
+ if ( !(0x20 & w) ) /* aneg not done */
+ rval = -1;
+ }
+ return rval;
+}
+
+/* check a number of phys
+ * RETURNS: -1 if at least one is still busy
+ * -2 if all are terminated but no link is found
+ * >=0 index of first IF with a live link
+ */
+static int
+poll_phys(struct poll_job *job)
+{
+int rval;
+struct poll_job *j = job;
+int retry = 4;
+
+ /* see if we already have a link */
+ if ( (rval=check_phys(job)) < 0 ) {
+ /* no - start negotiation */
+ for ( j = job; j->rdop; j++ ) {
+ j->wrop(j->unit, 0/* ctrl */, 0x1200 /* start aneg */);
+ }
+
+ do {
+ sleep(1);
+ } while ( -1 == (rval = check_phys(job)) && retry-- );
+ }
+
+ return rval;
+}
+
+
+/* note that detaching is not supported by the current version of the BSD stack */
+int
+BSP_auto_enet_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+int i = -1;
+BSP_NetIFDesc d = BSP_availableNetIFs();
+struct poll_job job[3];
+
+ if ( !d )
+ return -1;
+
+ /* If they pass a name, find the attach fn */
+ if ( ifcfg->name && RTEMS_BSP_NETWORK_DRIVER_NAME != ifcfg->name && attaching ) {
+ for (i = 0; d[i].name; i++ ) {
+ if ( !strcmp(d[i].name, ifcfg->name) ) {
+ ifcfg->attach = d[i].attach_fn;
+ break;
+ }
+ }
+ if ( !d[i].name ) {
+ fprintf(stderr,"WARNING: have no '%s' interface - using default\n", ifcfg->name);
+ ifcfg->name = 0;
+ }
+ }
+
+ if ( !ifcfg->name || ifcfg->name == RTEMS_BSP_NETWORK_DRIVER_NAME ) {
+ /* automatically choose and attach an interface */
+ if ( RTEMS_BSP_NETWORK_DRIVER_NAME[0] ) {
+ fprintf(stderr,
+ "Configuration error: 'auto' network if already chosen (%s)\n",
+ RTEMS_BSP_NETWORK_DRIVER_NAME);
+ return -1;
+ }
+ if ( IS_6100() ) {
+#define ops rtems_mve_early_link_check_ops
+ assert(ops.num_slots >= 2);
+ ops.init(0);
+ ops.init(1);
+ job[0].rdop = ops.read_phy;
+ job[0].wrop = ops.write_phy;
+ job[0].unit = 0;
+ job[1].rdop = ops.read_phy;
+ job[1].wrop = ops.write_phy;
+ job[1].unit = 1;
+#undef ops
+ } else if ( IS_5500() ) {
+#define opsgfe rtems_gfe_early_link_check_ops
+#define opsem rtems_em_early_link_check_ops
+ assert(opsgfe.num_slots >= 1);
+ onboard_gfe_setup_once();
+ opsgfe.init(0);
+ assert(opsem.num_slots >= 1);
+ onboard_em_setup_once();
+ opsem.init(0);
+ job[0].rdop = opsem.read_phy;
+ job[0].wrop = opsem.write_phy;
+ job[0].unit = 0;
+ job[1].rdop = opsgfe.read_phy;
+ job[1].wrop = opsgfe.write_phy;
+ job[1].unit = 0;
+#undef opsgfe
+#undef opsem
+ }
+ job[2].rdop = 0; /* tag end */
+ i = poll_phys(job);
+ if ( i >= 0 ) {
+ printf("L");
+ } else {
+ i = 0;
+ printf("No l");
+ }
+ printf("ink detected; attaching %s\n",d[i].name);
+
+ /* set attach function and IF name */
+ ifcfg->attach = d[i].attach_fn;
+ ifcfg->name = RTEMS_BSP_NETWORK_DRIVER_NAME;
+ strcpy(RTEMS_BSP_NETWORK_DRIVER_NAME, d[i].name);
+ }
+ return ifcfg->attach(ifcfg, attaching);
+}
+
+/* from 'em' */
+
+/* PCI Device IDs */
+#define E1000_DEV_ID_82542 0x1000
+#define E1000_DEV_ID_82543GC_FIBER 0x1001
+#define E1000_DEV_ID_82543GC_COPPER 0x1004
+#define E1000_DEV_ID_82544EI_COPPER 0x1008
+#define E1000_DEV_ID_82544EI_FIBER 0x1009
+#define E1000_DEV_ID_82544GC_COPPER 0x100C
+#define E1000_DEV_ID_82544GC_LOM 0x100D
+#define E1000_DEV_ID_82540EM 0x100E
+#define E1000_DEV_ID_82541ER_LOM 0x1014
+#define E1000_DEV_ID_82540EM_LOM 0x1015
+#define E1000_DEV_ID_82540EP_LOM 0x1016
+#define E1000_DEV_ID_82540EP 0x1017
+#define E1000_DEV_ID_82540EP_LP 0x101E
+#define E1000_DEV_ID_82545EM_COPPER 0x100F
+#define E1000_DEV_ID_82545EM_FIBER 0x1011
+#define E1000_DEV_ID_82545GM_COPPER 0x1026
+#define E1000_DEV_ID_82545GM_FIBER 0x1027
+#define E1000_DEV_ID_82545GM_SERDES 0x1028
+#define E1000_DEV_ID_82546EB_COPPER 0x1010
+#define E1000_DEV_ID_82546EB_FIBER 0x1012
+#define E1000_DEV_ID_82546EB_QUAD_COPPER 0x101D
+#define E1000_DEV_ID_82541EI 0x1013
+#define E1000_DEV_ID_82541EI_MOBILE 0x1018
+#define E1000_DEV_ID_82541ER 0x1078
+#define E1000_DEV_ID_82547GI 0x1075
+#define E1000_DEV_ID_82541GI 0x1076
+#define E1000_DEV_ID_82541GI_MOBILE 0x1077
+#define E1000_DEV_ID_82541GI_LF 0x107C
+#define E1000_DEV_ID_82546GB_COPPER 0x1079
+#define E1000_DEV_ID_82546GB_FIBER 0x107A
+#define E1000_DEV_ID_82546GB_SERDES 0x107B
+#define E1000_DEV_ID_82546GB_PCIE 0x108A
+#define E1000_DEV_ID_82547EI 0x1019
+#define E1000_DEV_ID_82547EI_MOBILE 0x101A
+#define E1000_DEV_ID_82573E 0x108B
+#define E1000_DEV_ID_82573E_IAMT 0x108C
+
+#define E1000_DEV_ID_82546GB_QUAD_COPPER 0x1099
+
+static unsigned em_info[] =
+{
+ /* Intel(R) PRO/1000 Network Connection */
+ E1000_DEV_ID_82540EM,
+ E1000_DEV_ID_82540EM_LOM,
+ E1000_DEV_ID_82540EP,
+ E1000_DEV_ID_82540EP_LOM,
+ E1000_DEV_ID_82540EP_LP,
+
+ E1000_DEV_ID_82541EI,
+ E1000_DEV_ID_82541ER,
+ E1000_DEV_ID_82541ER_LOM,
+ E1000_DEV_ID_82541EI_MOBILE,
+ E1000_DEV_ID_82541GI,
+ E1000_DEV_ID_82541GI_LF,
+ E1000_DEV_ID_82541GI_MOBILE,
+
+ E1000_DEV_ID_82542,
+
+ E1000_DEV_ID_82543GC_FIBER,
+ E1000_DEV_ID_82543GC_COPPER,
+
+ E1000_DEV_ID_82544EI_COPPER,
+ E1000_DEV_ID_82544EI_FIBER,
+ E1000_DEV_ID_82544GC_COPPER,
+ E1000_DEV_ID_82544GC_LOM,
+
+ E1000_DEV_ID_82545EM_COPPER,
+ E1000_DEV_ID_82545EM_FIBER,
+ E1000_DEV_ID_82545GM_COPPER,
+ E1000_DEV_ID_82545GM_FIBER,
+ E1000_DEV_ID_82545GM_SERDES,
+
+ E1000_DEV_ID_82546EB_COPPER,
+ E1000_DEV_ID_82546EB_FIBER,
+ E1000_DEV_ID_82546EB_QUAD_COPPER,
+ E1000_DEV_ID_82546GB_COPPER,
+ E1000_DEV_ID_82546GB_FIBER,
+ E1000_DEV_ID_82546GB_SERDES,
+ E1000_DEV_ID_82546GB_PCIE,
+ E1000_DEV_ID_82546GB_QUAD_COPPER,
+
+ E1000_DEV_ID_82547EI,
+ E1000_DEV_ID_82547EI_MOBILE,
+ E1000_DEV_ID_82547GI,
+
+ E1000_DEV_ID_82573E,
+ E1000_DEV_ID_82573E_IAMT,
+
+ /* required last entry */
+ 0,
+};
diff --git a/bsps/powerpc/beatnik/net/support/early_link_status.c b/bsps/powerpc/beatnik/net/support/early_link_status.c
new file mode 100644
index 0000000..271f970
--- /dev/null
+++ b/bsps/powerpc/beatnik/net/support/early_link_status.c
@@ -0,0 +1,40 @@
+#include <rtems.h>
+#include <bsp/early_enet_link_status.h>
+#include <rtems/bspIo.h>
+
+/* T. Straumann, 2005; see ../../LICENSE */
+
+static const char *ename = ": rtems_em_early_check_link_status() - ";
+
+int
+BSP_early_check_link_status(int unit, rtems_bsdnet_early_link_check_ops *ops)
+{
+int status;
+
+ unit--;
+ if ( unit < 0 || unit >= ops->num_slots ) {
+ printk("%s%sinvalid unit # %i (not in %i..%i)\n",
+ ops->name, ename, unit+1, 1, ops->num_slots);
+ return -1;
+ }
+
+ if ( !ops->initialized ) {
+ if ( ops->init(unit) ) {
+ printk("%s%sFAILURE to init hardware\n",ops->name, ename);
+ return -1;
+ }
+ /* Start autoneg */
+ if ( ops->write_phy(unit, 0, 0x1200) ) {
+ printk("%s%sFAILURE to start autonegotiation\n",ops->name, ename);
+ return -1;
+ }
+ /* Dont wait here; the caller can do this on various interfaces
+ * and wait herself.
+ */
+ ops->initialized = 1;
+ }
+ if ( (status = ops->read_phy(unit, 1)) < 0 ) {
+ printk("%s%sFAILURE to read phy status\n", ops->name, ename);
+ }
+ return status;
+}
diff --git a/bsps/powerpc/gen5200/net/network.c b/bsps/powerpc/gen5200/net/network.c
new file mode 100644
index 0000000..a18ab48
--- /dev/null
+++ b/bsps/powerpc/gen5200/net/network.c
@@ -0,0 +1,1580 @@
+/*===============================================================*\
+| Project: RTEMS generic MPC5200 BSP |
++-----------------------------------------------------------------+
+| Partially based on the code references which are named below. |
+| Adaptions, modifications, enhancements and any recent parts of |
+| the code are: |
+| Copyright (c) 2005 |
+| Embedded Brains GmbH |
+| Obere Lagerstr. 30 |
+| D-82178 Puchheim |
+| Germany |
+| rtems@embedded-brains.de |
++-----------------------------------------------------------------+
+| The license and distribution terms for this file may be |
+| found in the file LICENSE in this distribution or at |
+| |
+| http://www.rtems.org/license/LICENSE. |
+| |
++-----------------------------------------------------------------+
+| this file contains the networking driver |
+\*===============================================================*/
+/*
+ * RTEMS/TCPIP driver for MPC5200 FEC Ethernet
+ *
+ * Modified for Motorola MPC5200 by Thomas Doerfler, <Thomas.Doerfler@imd-systems.de>
+ * COPYRIGHT (c) 2003, IMD
+ *
+ * Modified for Motorola IceCube (mgt5100) by Peter Rasmussen <prasmus@ipr-engineering.de>
+ * COPYRIGHT (c) 2003, IPR Engineering
+ *
+ * Parts of code are also under property of Driver Information Systems and based
+ * on Motorola Proprietary Information.
+ * COPYRIGHT (c) 2002 MOTOROLA INC.
+ *
+ * Modified for MPC860 by Jay Monkman (jmonkman@frasca.com)
+ *
+ * This supports Ethernet on either SCC1 or the FEC of the MPC860T.
+ * Right now, we only do 10 Mbps, even with the FEC. The function
+ * rtems_enet_driver_attach determines which one to use. Currently,
+ * only one may be used at a time.
+ *
+ * Based on the MC68360 network driver by
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ *
+ * This supports ethernet on SCC1. Right now, we only do 10 Mbps.
+ *
+ * Modifications by Darlene Stewart <Darlene.Stewart@iit.nrc.ca>
+ * and Charles-Antoine Gauthier <charles.gauthier@iit.nrc.ca>
+ * Copyright (c) 1999, National Research Council of Canada
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+#include <stdio.h>
+#include <inttypes.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <bsp/mpc5200.h>
+#include <net/if_var.h>
+#include <errno.h>
+
+#include <bsp/bestcomm/include/ppctypes.h>
+#include <bsp/bestcomm/dma_image.h>
+#include <bsp/bestcomm/bestcomm_glue.h>
+#include <bsp/bestcomm/bestcomm_api.h>
+#include <bsp/bestcomm/task_api/bestcomm_cntrl.h>
+#include <bsp/bestcomm/task_api/tasksetup_bdtable.h>
+
+/* #define ETH_DEBUG */
+
+#define FEC_BD_LAST TASK_BD_TFD
+#define FEC_BD_INT TASK_BD_INT
+#define FEC_BD_READY SDMA_BD_MASK_READY
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 64
+#define TX_BUF_COUNT 64
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+#define FEC_EVENT RTEMS_EVENT_0
+
+/* Task number assignment */
+#define FEC_RECV_TASK_NO TASK_FEC_RX
+#define FEC_XMIT_TASK_NO TASK_FEC_TX
+
+
+/* BD and parameters are stored in SRAM(refer to sdma.h) */
+#define MPC5200_FEC_BD_BASE ETH_BD_BASE
+
+/* FEC transmit watermark settings */
+#define MPC5200_FEC_X_WMRK_64 0x0 /* or 0x1 */
+#define MPC5200_FEC_X_WMRK_128 0x2
+#define MPC5200_FEC_X_WMRK_192 0x3
+
+/* RBD bits definitions */
+#define MPC5200_FEC_RBD_EMPTY 0x8000 /* Buffer is empty */
+#define MPC5200_FEC_RBD_WRAP 0x2000 /* Last BD in ring */
+#define MPC5200_FEC_RBD_INT 0x1000 /* Interrupt */
+#define MPC5200_FEC_RBD_LAST 0x0800 /* Buffer is last in frame(useless) */
+#define MPC5200_FEC_RBD_MISS 0x0100 /* Miss bit for prom mode */
+#define MPC5200_FEC_RBD_BC 0x0080 /* The received frame is broadcast frame */
+#define MPC5200_FEC_RBD_MC 0x0040 /* The received frame is multicast frame */
+#define MPC5200_FEC_RBD_LG 0x0020 /* Frame length violation */
+#define MPC5200_FEC_RBD_NO 0x0010 /* Nonoctet align frame */
+#define MPC5200_FEC_RBD_SH 0x0008 /* Short frame, FEC does not support SH and this bit is always cleared */
+#define MPC5200_FEC_RBD_CR 0x0004 /* CRC error */
+#define MPC5200_FEC_RBD_OV 0x0002 /* Receive FIFO overrun */
+#define MPC5200_FEC_RBD_TR 0x0001 /* The receive frame is truncated */
+#define MPC5200_FEC_RBD_ERR (MPC5200_FEC_RBD_LG | \
+ MPC5200_FEC_RBD_NO | \
+ MPC5200_FEC_RBD_CR | \
+ MPC5200_FEC_RBD_OV | \
+ MPC5200_FEC_RBD_TR)
+
+/* TBD bits definitions */
+#define MPC5200_FEC_TBD_READY 0x8000 /* Buffer is ready */
+#define MPC5200_FEC_TBD_WRAP 0x2000 /* Last BD in ring */
+#define MPC5200_FEC_TBD_INT 0x1000 /* Interrupt */
+#define MPC5200_FEC_TBD_LAST 0x0800 /* Buffer is last in frame */
+#define MPC5200_FEC_TBD_TC 0x0400 /* Transmit the CRC */
+#define MPC5200_FEC_TBD_ABC 0x0200 /* Append bad CRC */
+
+/* MII-related definitios */
+#define MPC5200_FEC_MII_DATA_ST 0x40000000 /* Start of frame delimiter */
+#define MPC5200_FEC_MII_DATA_OP_RD 0x20000000 /* Perform a read operation */
+#define MPC5200_FEC_MII_DATA_OP_WR 0x10000000 /* Perform a write operation */
+#define MPC5200_FEC_MII_DATA_PA_MSK 0x0f800000 /* PHY Address field mask */
+#define MPC5200_FEC_MII_DATA_RA_MSK 0x007c0000 /* PHY Register field mask */
+#define MPC5200_FEC_MII_DATA_TA 0x00020000 /* Turnaround */
+#define MPC5200_FEC_MII_DATA_DATAMSK 0x0000fff /* PHY data field */
+
+#define MPC5200_FEC_MII_DATA_RA_SHIFT 0x12 /* MII Register address bits */
+#define MPC5200_FEC_MII_DATA_PA_SHIFT 0x17 /* MII PHY address bits */
+
+#define FEC_INTR_MASK_USED \
+(FEC_INTR_LCEN |FEC_INTR_CRLEN |\
+ FEC_INTR_XFUNEN|FEC_INTR_XFERREN|FEC_INTR_RFERREN)
+
+typedef enum {
+ FEC_STATE_RESTART_0,
+ FEC_STATE_RESTART_1,
+ FEC_STATE_NORMAL,
+} mpc5200_fec_state;
+
+/*
+ * Device data
+ */
+typedef struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ mpc5200_fec_state state;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ unsigned long rxInterrupts;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxBadCRC;
+ unsigned long rxFIFOError;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txLateCollision;
+ unsigned long txUnderrun;
+ unsigned long txFIFOError;
+ unsigned long txMisaligned;
+ unsigned long rxNotFirst;
+ unsigned long txRetryLimit;
+
+ struct rtems_mdio_info mdio;
+ int phyAddr;
+ bool phyInitialized;
+} mpc5200_fec_context;
+
+static mpc5200_fec_context enet_driver[NIFACES];
+
+static void mpc5200_fec_send_event(rtems_id task)
+{
+ rtems_bsdnet_event_send(task, FEC_EVENT);
+}
+
+static void mpc5200_fec_wait_for_event(void)
+{
+ rtems_event_set out;
+ rtems_bsdnet_event_receive(
+ FEC_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &out
+ );
+}
+
+static void mpc5200_fec_stop_dma(void)
+{
+ TaskStop(FEC_RECV_TASK_NO);
+ TaskStop(FEC_XMIT_TASK_NO);
+}
+
+static void mpc5200_fec_request_restart(mpc5200_fec_context *self)
+{
+ self->state = FEC_STATE_RESTART_0;
+ mpc5200_fec_send_event(self->txDaemonTid);
+ mpc5200_fec_send_event(self->rxDaemonTid);
+}
+
+static void mpc5200_fec_start_dma_and_controller(void)
+{
+ TaskStart(FEC_RECV_TASK_NO, 1, FEC_RECV_TASK_NO, 1);
+ TaskStart(FEC_XMIT_TASK_NO, 1, FEC_XMIT_TASK_NO, 1);
+
+ mpc5200.ecntrl |= FEC_ECNTRL_OE | FEC_ECNTRL_EN;
+}
+
+/*
+ * Function: MPC5200_eth_addr_filter_set
+ *
+ * Description: Set individual address filter for unicast address and
+ * set physical address registers.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mpc5200_eth_addr_filter_set(mpc5200_fec_context *self) {
+ unsigned char *mac;
+ unsigned char currByte; /* byte for which to compute the CRC */
+ int byte; /* loop - counter */
+ int bit; /* loop - counter */
+ unsigned long crc = 0xffffffff; /* initial value */
+
+ /*
+ * Get the mac address of ethernet controller
+ */
+ mac = (unsigned char *)(&self->arpcom.ac_enaddr);
+
+ /*
+ * 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)
+ {
+
+ mpc5200.iaddr1 = (1 << (crc - 32));
+ mpc5200.iaddr2 = 0;
+
+ }
+ else
+ {
+
+ mpc5200.iaddr1 = 0;
+ mpc5200.iaddr2 = (1 << crc);
+
+ }
+
+ /*
+ * Set physical address
+ */
+ mpc5200.paddr1 = (mac[0] << 24) + (mac[1] << 16) + (mac[2] << 8) + mac[3];
+ mpc5200.paddr2 = (mac[4] << 24) + (mac[5] << 16) + 0x8808;
+
+ }
+
+static int mpc5200_eth_mii_transfer(
+ int phyAddr,
+ unsigned regAddr,
+ uint32_t data
+)
+{
+ int timeout = 0xffff;
+
+ mpc5200.ievent = FEC_INTR_MII;
+
+ mpc5200.mii_data = MPC5200_FEC_MII_DATA_ST
+ | MPC5200_FEC_MII_DATA_TA
+ | (phyAddr << MPC5200_FEC_MII_DATA_PA_SHIFT)
+ | (regAddr << MPC5200_FEC_MII_DATA_RA_SHIFT)
+ | data;
+
+ while (timeout > 0 && (mpc5200.ievent & FEC_INTR_MII) == 0) {
+ --timeout;
+ }
+
+ return timeout > 0 ? 0 : -1;
+}
+
+/* FIXME: Make this static, this needs a fix in an application */
+int mpc5200_eth_mii_read(
+ int phyAddr,
+ void *arg,
+ unsigned regAddr,
+ uint32_t *retVal
+)
+{
+ int rv = mpc5200_eth_mii_transfer(
+ phyAddr,
+ regAddr,
+ MPC5200_FEC_MII_DATA_OP_RD
+ );
+
+ *retVal = mpc5200.mii_data & 0xffff;
+
+ return rv;
+}
+
+static int mpc5200_eth_mii_write(
+ int phyAddr,
+ void *arg,
+ unsigned regAddr,
+ uint32_t data
+)
+{
+ return mpc5200_eth_mii_transfer(
+ phyAddr,
+ regAddr,
+ MPC5200_FEC_MII_DATA_OP_WR | data
+ );
+}
+
+
+/*
+ * Reset a running ethernet driver including the hardware FIFOs and the FEC.
+ */
+static void mpc5200_fec_reset(mpc5200_fec_context *self)
+{
+ volatile int delay;
+ /*
+ * Clear FIFO status registers
+ */
+ mpc5200.rfifo_status &= FEC_FIFO_STAT_ERROR;
+ mpc5200.tfifo_status &= FEC_FIFO_STAT_ERROR;
+
+ /*
+ * reset the FIFOs
+ */
+ mpc5200.reset_cntrl = 0x03000000;
+
+ for (delay = 0;delay < 16*4;delay++) {};
+
+ mpc5200.reset_cntrl = 0x01000000;
+
+ /*
+ * Issue a reset command to the FEC chip
+ */
+ mpc5200.ecntrl |= FEC_ECNTRL_RESET;
+
+ /*
+ * wait at least 16 clock cycles
+ */
+ for (delay = 0;delay < 16*4;delay++) {};
+}
+
+
+/*
+ * Function: mpc5200_fec_off
+ *
+ * Description: Stop the FEC and disable the ethernet SmartComm tasks.
+ * This function "turns off" the driver.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mpc5200_fec_off(mpc5200_fec_context *self)
+ {
+ int counter = 0xffff;
+
+
+#if defined(ETH_DEBUG)
+ uint32_t phyStatus;
+ int i;
+
+ for(i = 0; i < 9; i++)
+ {
+
+ mpc5200_eth_mii_read(self->phyAddr, self, i, &phyStatus);
+ printf ("Mii reg %d: 0x%04" PRIx32 "\r\n", i, phyStatus);
+
+ }
+
+ for(i = 16; i < 21; i++)
+ {
+
+ mpc5200_eth_mii_read(self->phyAddr, self, i, &phyStatus);
+ printf ("Mii reg %d: 0x%04" PRIx32 "\r\n", i, phyStatus);
+
+ }
+#endif /* ETH_DEBUG */
+
+ /*
+ * block FEC chip interrupts
+ */
+ mpc5200.imask = 0;
+
+ /*
+ * issue graceful stop command to the FEC transmitter if necessary
+ */
+ mpc5200.x_cntrl |= FEC_XCNTRL_GTS;
+
+ /*
+ * wait for graceful stop to register
+ * FIXME: add rtems_task_wake_after here, if it takes to long
+ */
+ while((counter--) && (!(mpc5200.ievent & FEC_INTR_GRA)));
+
+ mpc5200_fec_stop_dma();
+
+ /*
+ * Disable transmit / receive interrupts
+ */
+ bestcomm_glue_irq_disable(FEC_XMIT_TASK_NO);
+ bestcomm_glue_irq_disable(FEC_RECV_TASK_NO);
+
+ /*
+ * Disable the Ethernet Controller
+ */
+ mpc5200.ecntrl &= ~(FEC_ECNTRL_OE | FEC_ECNTRL_EN);
+}
+
+/*
+ * MPC5200 FEC interrupt handler
+ */
+static void mpc5200_fec_irq_handler(rtems_irq_hdl_param handle)
+{
+ mpc5200_fec_context *self = (mpc5200_fec_context *) handle;
+ volatile uint32_t ievent;
+
+ ievent = mpc5200.ievent;
+
+ mpc5200.ievent = ievent;
+ /*
+ * check errors, update statistics
+ */
+ if (ievent & FEC_INTR_LATE_COL) {
+ self->txLateCollision++;
+ }
+ if (ievent & FEC_INTR_COL_RETRY) {
+ self->txRetryLimit++;
+ }
+ if (ievent & FEC_INTR_XFIFO_UN) {
+ self->txUnderrun++;
+ }
+ if (ievent & FEC_INTR_XFIFO_ERR) {
+ self->txFIFOError++;
+ }
+ if (ievent & FEC_INTR_RFIFO_ERR) {
+ self->rxFIFOError++;
+ }
+ /*
+ * fatal error occurred?
+ */
+ if (ievent & (FEC_INTR_XFIFO_ERR | FEC_INTR_RFIFO_ERR)) {
+ mpc5200.imask &= ~(FEC_INTR_XFERREN | FEC_INTR_RFERREN);
+ mpc5200_fec_request_restart(self);
+ }
+}
+
+static void mpc5200_smartcomm_rx_irq_handler(void *arg)
+{
+ mpc5200_fec_context *self = arg;
+
+ ++self->rxInterrupts;
+ mpc5200_fec_send_event(self->rxDaemonTid);
+ SDMA_CLEAR_IEVENT(&mpc5200.sdma.IntPend, FEC_RECV_TASK_NO);
+ bestcomm_glue_irq_disable(FEC_RECV_TASK_NO);
+}
+
+static void mpc5200_smartcomm_tx_irq_handler(void *arg)
+{
+ mpc5200_fec_context *self = arg;
+
+ ++self->txInterrupts;
+ mpc5200_fec_send_event(self->txDaemonTid);
+ SDMA_CLEAR_IEVENT(&mpc5200.sdma.IntPend, FEC_XMIT_TASK_NO);
+ bestcomm_glue_irq_disable(FEC_XMIT_TASK_NO);
+}
+
+static void mpc5200_fec_init_mib(mpc5200_fec_context *self)
+{
+ memset(RTEMS_DEVOLATILE(uint8_t *, &mpc5200.RES [0]), 0, 0x2e4);
+ mpc5200.mib_control = 0x40000000;
+}
+
+/*
+ * Function: mpc5200_fec_initialize_hardware
+ *
+ * Description: Configure the MPC5200 FEC registers and enable the
+ * SmartComm tasks. This function "turns on" the driver.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mpc5200_fec_initialize_hardware(mpc5200_fec_context *self)
+{
+ /* We want at most 2.5MHz */
+ uint32_t div = 2 * 2500000;
+ uint32_t mii_speed = (IPB_CLOCK + div - 1) / div;
+
+ /*
+ * Reset mpc5200 FEC
+ */
+ mpc5200_fec_reset(self);
+ mpc5200_fec_init_mib(self);
+
+ /*
+ * Clear FEC-Lite interrupt event register (IEVENT)
+ */
+ mpc5200.ievent = FEC_INTR_CLEAR_ALL;
+
+ /*
+ * Set interrupt mask register
+ */
+ mpc5200.imask = FEC_INTR_MASK_USED;
+ /*
+ * Set FEC-Lite receive control register (R_CNTRL)
+ * frame length=1518, MII mode for 18-wire-transceiver
+ */
+ mpc5200.r_cntrl = ((ETHER_MAX_LEN << FEC_RCNTRL_MAX_FL_SHIFT)
+ | FEC_RCNTRL_FCE
+ | FEC_RCNTRL_MII_MODE);
+
+ /*
+ * Set FEC-Lite transmit control register (X_CNTRL)
+ * full-duplex, heartbeat disabled
+ */
+ mpc5200.x_cntrl = FEC_XCNTRL_FDEN;
+
+
+
+ /*
+ * Set MII_SPEED = IPB clock / (2 * mii_speed))
+ * and do not drop the Preamble.
+ */
+ mpc5200.mii_speed = mii_speed << 1;
+
+ /*
+ * Set Opcode/Pause Duration Register
+ */
+ mpc5200.op_pause = 0x00010020;
+
+ /*
+ * Set Rx FIFO alarm and granularity value
+ */
+ mpc5200.rfifo_cntrl = (FEC_FIFO_CNTRL_FRAME
+ | (0x7 << FEC_FIFO_CNTRL_GR_SHIFT));
+ mpc5200.rfifo_alarm = 0x0000030c;
+
+ /*
+ * Set Tx FIFO granularity value
+ */
+ mpc5200.tfifo_cntrl = (FEC_FIFO_CNTRL_FRAME
+ | (0x7 << FEC_FIFO_CNTRL_GR_SHIFT));
+
+ /*
+ * Set transmit fifo watermark register (X_WMRK), default = 64
+ */
+ mpc5200.tfifo_alarm = 0x00000100; /* 256 bytes */
+ mpc5200.x_wmrk = FEC_XWMRK_256; /* 256 bytes */
+
+ /*
+ * Set individual address filter for unicast address
+ * and set physical address registers.
+ */
+ mpc5200_eth_addr_filter_set(self);
+
+ /*
+ * Set multicast address filter
+ */
+ mpc5200.gaddr1 = 0x00000000;
+ mpc5200.gaddr2 = 0x00000000;
+
+ /*
+ * enable CRC in finite state machine register
+ */
+ mpc5200.xmit_fsm = FEC_FSM_CRC | FEC_FSM_ENFSM;
+}
+
+ /*
+ * Initialize PHY(LXT971A):
+ *
+ * Generally, on power up, the LXT971A reads its configuration
+ * pins to check for forced operation, If not cofigured for
+ * forced operation, it uses auto-negotiation/parallel detection
+ * to automatically determine line operating conditions.
+ * If the PHY device on the other side of the link supports
+ * auto-negotiation, the LXT971A auto-negotiates with it
+ * using Fast Link Pulse(FLP) Bursts. If the PHY partner does not
+ * support auto-negotiation, the LXT971A automatically detects
+ * the presence of either link pulses(10Mbps PHY) or Idle
+ * symbols(100Mbps) and sets its operating conditions accordingly.
+ *
+ * When auto-negotiation is controlled by software, the following
+ * steps are recommended.
+ *
+ * Note:
+ * The physical address is dependent on hardware configuration.
+ *
+ * Returns: void
+ *
+ * Notes:
+ *
+ */
+static void mpc5200_fec_initialize_phy(mpc5200_fec_context *self)
+{
+ if (self->phyInitialized) {
+ return;
+ } else {
+ self->phyInitialized = true;
+ }
+
+ /*
+ * Reset PHY, then delay 300ns
+ */
+ mpc5200_eth_mii_write(self->phyAddr, self, 0x0, 0x8000);
+
+ rtems_task_wake_after(2);
+
+ /* MII100 */
+
+ /*
+ * Set the auto-negotiation advertisement register bits
+ */
+ mpc5200_eth_mii_write(self->phyAddr, self, 0x4, 0x01e1);
+
+ /*
+ * Set MDIO bit 0.12 = 1(&& bit 0.9=1?) to enable auto-negotiation
+ */
+ mpc5200_eth_mii_write(self->phyAddr, self, 0x0, 0x1200);
+
+ /*
+ * Wait for AN completion
+ */
+#if 0
+ int timeout = 0x100;
+ uint32_t phyStatus;
+ do
+ {
+
+ rtems_task_wake_after(2);
+
+ if((timeout--) == 0)
+ {
+
+#if defined(ETH_DEBUG)
+ printf ("MPC5200FEC PHY auto neg failed." "\r\n");
+#endif
+
+ }
+
+ if(mpc5200_eth_mii_read(self->phyAddr, self, 0x1, &phyStatus) != true)
+ {
+
+#if defined(ETH_DEBUG)
+ printf ("MPC5200FEC PHY auto neg failed: 0x%04" PRIx32 ".\r\n", phyStatus);
+#endif
+
+ return;
+
+ }
+
+ } while((phyStatus & 0x0020) != 0x0020);
+
+#endif
+#if ETH_PROMISCOUS_MODE
+ mpc5200.r_cntrl |= 0x00000008; /* set to promiscous mode */
+#endif
+
+#if ETH_LOOP_MODE
+ mpc5200.r_cntrl |= 0x00000001; /* set to loop mode */
+#endif
+
+#if defined(ETH_DEBUG)
+ int i;
+ uint32_t phyStatus;
+ /*
+ * Print PHY registers after initialization.
+ */
+ for(i = 0; i < 9; i++)
+ {
+
+ mpc5200_eth_mii_read(self->phyAddr, self, i, &phyStatus);
+ printf ("Mii reg %d: 0x%04" PRIx32 "\r\n", i, phyStatus);
+
+ }
+
+ for(i = 16; i < 21; i++)
+ {
+
+ mpc5200_eth_mii_read(self->phyAddr, self, i, &phyStatus);
+ printf ("Mii reg %d: 0x%04" PRIx32 "\r\n", i, phyStatus);
+
+ }
+#endif /* ETH_DEBUG */
+
+ }
+
+static void mpc5200_fec_restart(mpc5200_fec_context *self, rtems_id otherDaemon)
+{
+ if (self->state == FEC_STATE_RESTART_1) {
+ mpc5200_fec_initialize_hardware(self);
+ mpc5200_fec_initialize_phy(self);
+ mpc5200_fec_start_dma_and_controller();
+ self->state = FEC_STATE_NORMAL;
+ } else {
+ self->state = FEC_STATE_RESTART_1;
+ }
+
+ mpc5200_fec_send_event(otherDaemon);
+ while (self->state != FEC_STATE_NORMAL) {
+ mpc5200_fec_wait_for_event();
+ }
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void mpc5200_fec_tx_start(struct ifnet *ifp)
+ {
+
+ mpc5200_fec_context *self = ifp->if_softc;
+
+ ifp->if_flags |= IFF_OACTIVE;
+
+ mpc5200_fec_send_event(self->txDaemonTid);
+
+ }
+
+static TaskBD1_t *mpc5200_fec_init_tx_dma(int bdCount, struct mbuf **mbufs)
+{
+ TaskSetupParamSet_t param = {
+ .NumBD = bdCount,
+ .Size = {
+ .MaxBuf = ETHER_MAX_LEN
+ },
+ .Initiator = 0,
+ .StartAddrSrc = 0,
+ .IncrSrc = sizeof(uint32_t),
+ .SzSrc = sizeof(uint32_t),
+ .StartAddrDst = (uint32) &mpc5200.tfifo_data,
+ .IncrDst = 0,
+ .SzDst = sizeof(uint32_t)
+ };
+ int bdIndex = 0;
+
+ TaskSetup(FEC_XMIT_TASK_NO, &param);
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ mbufs [bdIndex] = NULL;
+ }
+
+ return (TaskBD1_t *) TaskGetBDRing(FEC_XMIT_TASK_NO);
+}
+
+#if 0
+static void mpc5200_fec_requeue_and_discard_tx_frames(
+ int bdIndex,
+ int bdCount,
+ TaskBD1_t *bdRing,
+ struct mbuf **mbufs
+)
+{
+ int bdStop = bdIndex;
+ struct mbuf *previous = NULL;
+
+ do {
+ struct mbuf *current = NULL;
+ uint32 status = 0;
+ TaskBD1_t *bd = NULL;
+
+ if (bdIndex > 1) {
+ --bdIndex;
+ } else {
+ bdIndex = bdCount - 1;
+ }
+
+ current = mbufs [bdIndex];
+ mbufs [bdIndex] = NULL;
+
+ status = bdRing [bdIndex].Status;
+ bdRing [bdIndex].Status = 0;
+
+ if (current != NULL) {
+ if ((status & FEC_BD_LAST) != 0) {
+ if (previous != NULL) {
+ IF_PREPEND(&ifp->if_snd, previous);
+ }
+ }
+ } else {
+ break;
+ }
+
+ previous = current;
+ } while (bdIndex != bdStop);
+}
+#endif
+
+static void mpc5200_fec_discard_tx_frames(
+ int bdCount,
+ struct mbuf **mbufs
+)
+{
+ int bdIndex = 0;
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ struct mbuf *m = mbufs [bdIndex];
+
+ if (m != NULL) {
+ mbufs [bdIndex] = NULL;
+ m_free(m);
+ }
+ }
+}
+
+static void mpc5200_fec_reset_tx_dma(
+ int bdCount,
+ TaskBD1_t *bdRing,
+ struct mbuf **mbufs,
+ struct mbuf *m
+)
+{
+ TaskStop(FEC_XMIT_TASK_NO);
+ TaskBDReset(FEC_XMIT_TASK_NO);
+ mpc5200_fec_discard_tx_frames(bdCount, mbufs);
+ while (m != NULL) {
+ m = m_free(m);
+ }
+}
+
+static struct mbuf *mpc5200_fec_next_fragment(
+ struct ifnet *ifp,
+ struct mbuf *m,
+ bool *isFirst
+)
+{
+ struct mbuf *n = NULL;
+
+ *isFirst = false;
+
+ while (true) {
+ if (m == NULL) {
+ IF_DEQUEUE(&ifp->if_snd, m);
+
+ if (m != NULL) {
+ *isFirst = true;
+ } else {
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ return NULL;
+ }
+ }
+
+ if (m->m_len > 0) {
+ break;
+ } else {
+ m = m_free(m);
+ }
+ }
+
+ n = m->m_next;
+ while (n != NULL && n->m_len <= 0) {
+ n = m_free(n);
+ }
+ m->m_next = n;
+
+ return m;
+}
+
+static bool mpc5200_fec_transmit(
+ struct ifnet *ifp,
+ int bdCount,
+ TaskBD1_t *bdRing,
+ struct mbuf **mbufs,
+ int *bdIndexPtr,
+ struct mbuf **mPtr,
+ TaskBD1_t **firstPtr
+)
+{
+ bool bdShortage = false;
+ int bdIndex = *bdIndexPtr;
+ struct mbuf *m = *mPtr;
+ TaskBD1_t *first = *firstPtr;
+
+ while (true) {
+ TaskBD1_t *bd = &bdRing [bdIndex];
+
+ if (bd->Status == 0) {
+ struct mbuf *done = mbufs [bdIndex];
+ bool isFirst = false;
+
+ if (done != NULL) {
+ m_free(done);
+ mbufs [bdIndex] = NULL;
+ }
+
+ m = mpc5200_fec_next_fragment(ifp, m, &isFirst);
+ if (m != NULL) {
+ uint32 status = (uint32) m->m_len;
+
+ mbufs [bdIndex] = m;
+
+ rtems_cache_flush_multiple_data_lines(mtod(m, void *), m->m_len);
+
+ if (isFirst) {
+ first = bd;
+ } else {
+ status |= FEC_BD_READY;
+ }
+
+ bd->DataPtr [0] = mtod(m, uint32);
+
+ if (m->m_next != NULL) {
+ bd->Status = status;
+ } else {
+ bd->Status = status | FEC_BD_INT | FEC_BD_LAST;
+ first->Status |= FEC_BD_READY;
+ SDMA_TASK_ENABLE(SDMA_TCR, FEC_XMIT_TASK_NO);
+ }
+
+ m = m->m_next;
+ } else {
+ break;
+ }
+ } else {
+ bdShortage = true;
+ break;
+ }
+
+ if (bdIndex < bdCount - 1) {
+ ++bdIndex;
+ } else {
+ bdIndex = 0;
+ }
+ }
+
+ *bdIndexPtr = bdIndex;
+ *mPtr = m;
+ *firstPtr = first;
+
+ return bdShortage;
+}
+
+static void mpc5200_fec_tx_daemon(void *arg)
+{
+ mpc5200_fec_context *self = arg;
+ struct ifnet *ifp = &self->arpcom.ac_if;
+ int bdIndex = 0;
+ int bdCount = self->txBdCount;
+ struct mbuf **mbufs = &self->txMbuf [0];
+ struct mbuf *m = NULL;
+ TaskBD1_t *bdRing = mpc5200_fec_init_tx_dma(bdCount, mbufs);
+ TaskBD1_t *first = NULL;
+ bool bdShortage = false;
+
+ while (true) {
+ if (bdShortage) {
+ bestcomm_glue_irq_enable(FEC_XMIT_TASK_NO);
+ }
+ mpc5200_fec_wait_for_event();
+
+ if (self->state != FEC_STATE_NORMAL) {
+ mpc5200_fec_reset_tx_dma(bdCount, bdRing, mbufs, m);
+ mpc5200_fec_restart(self, self->rxDaemonTid);
+ bdIndex = 0;
+ m = NULL;
+ first = NULL;
+ }
+
+ bdShortage = mpc5200_fec_transmit(
+ ifp,
+ bdCount,
+ bdRing,
+ mbufs,
+ &bdIndex,
+ &m,
+ &first
+ );
+ }
+}
+
+static struct mbuf *mpc5200_fec_add_mbuf(struct ifnet *ifp, TaskBD1_t *bd)
+{
+ struct mbuf *m = NULL;
+
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+
+ /* XXX: The dcbi operation does not work properly */
+ rtems_cache_flush_multiple_data_lines(mtod(m, void *), ETHER_MAX_LEN);
+
+ bd->DataPtr [0] = mtod(m, uint32);
+ bd->Status = ETHER_MAX_LEN | FEC_BD_READY;
+
+ return m;
+}
+
+static TaskBD1_t *mpc5200_fec_init_rx_dma(
+ struct ifnet *ifp,
+ int bdCount,
+ struct mbuf **mbufs
+)
+{
+ TaskSetupParamSet_t param = {
+ .NumBD = bdCount,
+ .Size = {
+ .MaxBuf = ETHER_MAX_LEN
+ },
+ .Initiator = 0,
+ .StartAddrSrc = (uint32) &mpc5200.rfifo_data,
+ .IncrSrc = 0,
+ .SzSrc = sizeof(uint32_t),
+ .StartAddrDst = 0,
+ .IncrDst = sizeof(uint32_t),
+ .SzDst = sizeof(uint32_t)
+ };
+ TaskBD1_t *bdRing = NULL;
+ int bdIndex = 0;
+
+ TaskSetup(FEC_RECV_TASK_NO, &param);
+ bdRing = (TaskBD1_t *) TaskGetBDRing(FEC_RECV_TASK_NO);
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ mbufs [bdIndex] = mpc5200_fec_add_mbuf(ifp, &bdRing [bdIndex]);
+ }
+
+ return bdRing;
+}
+
+static void mpc5200_fec_reset_rx_dma(int bdCount, TaskBD1_t *bdRing)
+{
+ int bdIndex = 0;
+
+ TaskStop(FEC_RECV_TASK_NO);
+ TaskBDReset(FEC_RECV_TASK_NO);
+
+ for (bdIndex = 0; bdIndex < bdCount; ++bdIndex) {
+ bdRing [bdIndex].Status = ETHER_MAX_LEN | FEC_BD_READY;
+ }
+}
+
+static int mpc5200_fec_ether_input(
+ struct ifnet *ifp,
+ int bdIndex,
+ int bdCount,
+ TaskBD1_t *bdRing,
+ struct mbuf **mbufs
+)
+{
+ while (true) {
+ TaskBD1_t *bd = &bdRing [bdIndex];
+ struct mbuf *m = mbufs [bdIndex];
+ uint32 status = 0;
+ int len = 0;
+ struct ether_header *eh = NULL;
+
+ SDMA_CLEAR_IEVENT(&mpc5200.sdma.IntPend, FEC_RECV_TASK_NO);
+ status = bd->Status;
+
+ if ((status & FEC_BD_READY) != 0) {
+ break;
+ }
+
+ eh = mtod(m, struct ether_header *);
+
+ len = (status & 0xffff) - ETHER_HDR_LEN - ETHER_CRC_LEN;
+ m->m_len = len;
+ m->m_pkthdr.len = len;
+ m->m_data = mtod(m, char *) + ETHER_HDR_LEN;
+
+ ether_input(ifp, eh, m);
+
+ mbufs [bdIndex] = mpc5200_fec_add_mbuf(ifp, bd);
+
+ if (bdIndex < bdCount - 1) {
+ ++bdIndex;
+ } else {
+ bdIndex = 0;
+ }
+ }
+
+ return bdIndex;
+}
+
+static void mpc5200_fec_rx_daemon(void *arg)
+{
+ mpc5200_fec_context *self = arg;
+ struct ifnet *ifp = &self->arpcom.ac_if;
+ int bdIndex = 0;
+ int bdCount = self->rxBdCount;
+ struct mbuf **mbufs = &self->rxMbuf [0];
+ TaskBD1_t *bdRing = mpc5200_fec_init_rx_dma(ifp, bdCount, mbufs);
+
+ while (true) {
+ bestcomm_glue_irq_enable(FEC_RECV_TASK_NO);
+ mpc5200_fec_wait_for_event();
+
+ bdIndex = mpc5200_fec_ether_input(ifp, bdIndex, bdCount, bdRing, mbufs);
+
+ if (self->state != FEC_STATE_NORMAL) {
+ mpc5200_fec_reset_rx_dma(bdCount, bdRing);
+ mpc5200_fec_restart(self, self->txDaemonTid);
+ bdIndex = 0;
+ }
+ }
+}
+
+/*
+ * Initialize and start the device
+ */
+static void mpc5200_fec_init(void *arg)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ mpc5200_fec_context *self = (mpc5200_fec_context *)arg;
+ struct ifnet *ifp = &self->arpcom.ac_if;
+
+ if(self->txDaemonTid == 0)
+ {
+ size_t rxMbufTableSize = self->rxBdCount * sizeof(*self->rxMbuf);
+ size_t txMbufTableSize = self->txBdCount * sizeof(*self->txMbuf);
+
+ /*
+ * Allocate a set of mbuf pointers
+ */
+ self->rxMbuf = malloc(rxMbufTableSize, M_MBUF, M_NOWAIT);
+ self->txMbuf = malloc(txMbufTableSize, M_MBUF, M_NOWAIT);
+
+ if(!self->rxMbuf || !self->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ /*
+ * DMA setup
+ */
+ bestcomm_glue_init();
+ mpc5200.sdma.ipr [0] = 4; /* always initiator */
+ mpc5200.sdma.ipr [3] = 6; /* eth rx initiator */
+ mpc5200.sdma.ipr [4] = 5; /* eth tx initiator */
+
+ /*
+ * Set up interrupts
+ */
+ bestcomm_glue_irq_install(FEC_RECV_TASK_NO,
+ mpc5200_smartcomm_rx_irq_handler,
+ self);
+ bestcomm_glue_irq_install(FEC_XMIT_TASK_NO,
+ mpc5200_smartcomm_tx_irq_handler,
+ self);
+ sc = rtems_interrupt_handler_install(
+ BSP_SIU_IRQ_ETH,
+ "FEC",
+ RTEMS_INTERRUPT_UNIQUE,
+ mpc5200_fec_irq_handler,
+ self
+ );
+ if(sc != RTEMS_SUCCESSFUL) {
+ rtems_panic ("Can't attach MPC5x00 FEX interrupt handler\n");
+ }
+
+ /*
+ * Start driver tasks
+ */
+ self->txDaemonTid = rtems_bsdnet_newproc("FEtx", 4096, mpc5200_fec_tx_daemon, self);
+ self->rxDaemonTid = rtems_bsdnet_newproc("FErx", 4096, mpc5200_fec_rx_daemon, self);
+ }
+
+ mpc5200_fec_request_restart(self);
+
+ /*
+ * Set flags appropriately
+ */
+ if(ifp->if_flags & IFF_PROMISC)
+ mpc5200.r_cntrl |= 0x08;
+ else
+ mpc5200.r_cntrl &= ~0x08;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+}
+
+static void enet_stats (mpc5200_fec_context *self)
+{
+ if (self->phyAddr >= 0) {
+ struct ifnet *ifp = &self->arpcom.ac_if;
+ int media = IFM_MAKEWORD(0, 0, 0, self->phyAddr);
+ int rv = (*ifp->if_ioctl)(ifp, SIOCGIFMEDIA, (caddr_t) &media);
+
+ if (rv == 0) {
+ rtems_ifmedia2str(media, NULL, 0);
+ printf ("\n");
+ } else {
+ printf ("PHY communication error\n");
+ }
+ }
+ printf (" Rx Interrupts:%-8lu", self->rxInterrupts);
+ printf (" Rx Not First:%-8lu", self->rxNotFirst);
+ printf (" Rx Not Last:%-8lu\n", self->rxNotLast);
+ printf (" Rx Giant:%-8lu", self->rxGiant);
+ printf (" Rx Non-octet:%-8lu", self->rxNonOctet);
+ printf (" Rx Bad CRC:%-8lu\n", self->rxBadCRC);
+ printf (" Rx FIFO Error:%-8lu", self->rxFIFOError);
+ printf (" Rx Collision:%-8lu", self->rxCollision);
+
+ printf (" Tx Interrupts:%-8lu\n", self->txInterrupts);
+ printf (" Tx Deferred:%-8lu", self->txDeferred);
+ printf (" Tx Late Collision:%-8lu", self->txLateCollision);
+ printf (" Tx Retransmit Limit:%-8lu\n", self->txRetryLimit);
+ printf (" Tx Underrun:%-8lu", self->txUnderrun);
+ printf (" Tx FIFO Error:%-8lu", self->txFIFOError);
+ printf (" Tx Misaligned:%-8lu\n", self->txMisaligned);
+}
+
+static int32_t mpc5200_fec_setMultiFilter(struct ifnet *ifp)
+{
+ /*mpc5200_fec_context *self = ifp->if_softc; */
+ /* XXX anything to do? */
+ return 0;
+}
+
+
+/*
+ * Driver ioctl handler
+ */
+static int mpc5200_fec_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+ {
+ mpc5200_fec_context *self = ifp->if_softc;
+ int error = 0;
+
+ switch(command)
+ {
+
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+
+ ether_ioctl(ifp, command, data);
+
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI: {
+ struct ifreq* ifr = (struct ifreq*) data;
+ error = (command == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &self->arpcom)
+ : ether_delmulti(ifr, &self->arpcom);
+
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING)
+ error = mpc5200_fec_setMultiFilter(ifp);
+ else
+ error = 0;
+ }
+ break;
+ }
+
+ case SIOCSIFFLAGS:
+
+ switch(ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+
+ case IFF_RUNNING:
+
+ mpc5200_fec_off(self);
+
+ break;
+
+ case IFF_UP:
+
+ mpc5200_fec_init(self);
+
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+
+ mpc5200_fec_off(self);
+ mpc5200_fec_init(self);
+
+ break;
+
+ default:
+ break;
+
+ }
+
+ break;
+
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ error = rtems_mii_ioctl(&self->mdio, self, command, (int *) data);
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+
+ enet_stats(self);
+
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+
+ error = EINVAL;
+
+ break;
+
+ }
+
+ return error;
+
+ }
+
+
+/*
+ * Attach the MPC5200 fec driver to the system
+ */
+static int rtems_mpc5200_fec_driver_attach(struct rtems_bsdnet_ifconfig *config)
+ {
+ mpc5200_fec_context *self;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+
+ /*
+ * Parse driver name
+ */
+ if((unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES))
+ {
+
+ printf ("Bad FEC unit number.\n");
+ return 0;
+
+ }
+
+ self = &enet_driver[unitNumber - 1];
+ ifp = &self->arpcom.ac_if;
+
+ if(ifp->if_softc != NULL)
+ {
+
+ printf ("Driver already in use.\n");
+ return 0;
+
+ }
+
+ self->mdio.mdio_r = mpc5200_eth_mii_read;
+ self->mdio.mdio_w = mpc5200_eth_mii_write;
+
+ /*
+ * Process options
+ */
+#if NVRAM_CONFIGURE == 1
+
+ /* Configure from NVRAM */
+ if(addr = nvram->ipaddr)
+ {
+
+ /* We have a non-zero entry, copy the value */
+ if(pAddr = malloc(INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT))
+ config->ip_address = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1);
+ else
+ rtems_panic("Can't allocate ip_address buffer!\n");
+
+ }
+
+ if(addr = nvram->netmask)
+ {
+
+ /* We have a non-zero entry, copy the value */
+ if (pAddr = malloc (INET_ADDR_MAX_BUF_SIZE, 0, M_NOWAIT))
+ config->ip_netmask = (char *)inet_ntop(AF_INET, &addr, pAddr, INET_ADDR_MAX_BUF_SIZE -1);
+ else
+ rtems_panic("Can't allocate ip_netmask buffer!\n");
+
+ }
+
+ /* Ethernet address requires special handling -- it must be copied into
+ * the arpcom struct. The following if construct serves only to give the
+ * User Area NVRAM parameter the highest priority.
+ *
+ * If the ethernet address is specified in NVRAM, go ahead and copy it.
+ * (ETHER_ADDR_LEN = 6 bytes).
+ */
+ if(nvram->enaddr[0] || nvram->enaddr[1] || nvram->enaddr[2])
+ {
+
+ /* Anything in the first three bytes indicates a non-zero entry, copy value */
+ memcpy((void *)self->arpcom.ac_enaddr, &nvram->enaddr, ETHER_ADDR_LEN);
+
+ }
+ else
+ if(config->hardware_address)
+ {
+
+ /* There is no entry in NVRAM, but there is in the ifconfig struct, so use it. */
+ memcpy((void *)self->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+ else
+ {
+ /* There is no ethernet address provided, so it could be read
+ * from the Ethernet protocol block of SCC1 in DPRAM.
+ */
+ rtems_panic("No Ethernet address specified!\n");
+ }
+
+#else /* NVRAM_CONFIGURE != 1 */
+
+ if(config->hardware_address)
+ {
+
+ memcpy(self->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ }
+ else
+ {
+
+ /* There is no ethernet address provided, so it could be read
+ * from the Ethernet protocol block of SCC1 in DPRAM.
+ */
+ rtems_panic("No Ethernet address specified!\n");
+
+ }
+
+#endif /* NVRAM_CONFIGURE != 1 */
+#ifdef HAS_UBOOT
+ if ((self->arpcom.ac_enaddr[0] == 0) &&
+ (self->arpcom.ac_enaddr[1] == 0) &&
+ (self->arpcom.ac_enaddr[2] == 0)) {
+ memcpy(
+ (void *)self->arpcom.ac_enaddr,
+ bsp_uboot_board_info.bi_enetaddr,
+ ETHER_ADDR_LEN
+ );
+ }
+#endif
+ if(config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+
+ if(config->rbuf_count)
+ self->rxBdCount = config->rbuf_count;
+ else
+ self->rxBdCount = RX_BUF_COUNT;
+
+ if(config->xbuf_count)
+ self->txBdCount = config->xbuf_count;
+ else
+ self->txBdCount = TX_BUF_COUNT;
+
+ self->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = self;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = mpc5200_fec_init;
+ ifp->if_ioctl = mpc5200_fec_ioctl;
+ ifp->if_start = mpc5200_fec_tx_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_MULTICAST;
+ /*ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;*/
+
+ if(ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach(ifp);
+
+ ether_ifattach(ifp);
+
+ return 1;
+ }
+
+
+int rtems_mpc5200_fec_driver_attach_detach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ if (attaching) {
+ return rtems_mpc5200_fec_driver_attach(config);
+ }
+ else {
+ return 0;
+ }
+}
+
+
diff --git a/bsps/powerpc/gen83xx/net/network.c b/bsps/powerpc/gen83xx/net/network.c
new file mode 100644
index 0000000..0426717
--- /dev/null
+++ b/bsps/powerpc/gen83xx/net/network.c
@@ -0,0 +1,255 @@
+/*===============================================================*\
+| Project: RTEMS support for MPC83xx |
++-----------------------------------------------------------------+
+| Copyright (c) 2007 |
+| Embedded Brains GmbH |
+| Obere Lagerstr. 30 |
+| D-82178 Puchheim |
+| Germany |
+| rtems@embedded-brains.de |
++-----------------------------------------------------------------+
+| The license and distribution terms for this file may be |
+| found in the file LICENSE in this distribution or at |
+| |
+| http://www.rtems.org/license/LICENSE. |
+| |
++-----------------------------------------------------------------+
+| this file contains the board specific portion |
+| of the network interface driver |
+\*===============================================================*/
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_bsdnet_internal.h>
+#include <bsp.h>
+#include <bsp/tsec.h>
+#include <bsp/u-boot.h>
+#include <mpc83xx/mpc83xx.h>
+#include <string.h>
+#include <libcpu/spr.h>
+
+#if MPC83XX_CHIP_TYPE / 10 != 830
+
+#define TSEC_IFMODE_RGMII 0
+#define TSEC_IFMODE_GMII 1
+
+#if defined( MPC83XX_BOARD_MPC8313ERDB)
+
+#define TSEC_IFMODE TSEC_IFMODE_RGMII
+
+#elif defined( MPC83XX_BOARD_MPC8349EAMDS)
+
+#define TSEC_IFMODE TSEC_IFMODE_GMII
+
+#elif defined( MPC83XX_BOARD_HSC_CM01)
+
+#define TSEC_IFMODE TSEC_IFMODE_RGMII
+
+#else
+
+#warning No TSEC configuration available
+
+#endif
+
+/* System Version Register */
+#define SVR 286
+SPR_RO( SVR)
+
+/* Processor Version Register */
+SPR_RO( PPC_PVR)
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+int BSP_tsec_attach
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| attach or detach the driver |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ struct rtems_bsdnet_ifconfig *config, /* interface configuration */
+ int attaching /* 0 = detach, else attach */
+)
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| 1, if success |
+\*=========================================================================*/
+{
+ tsec_config tsec_cfg;
+ int unitNumber;
+ char *unitName;
+ uint32_t svr = _read_SVR();
+ uint32_t pvr = _read_PPC_PVR();
+
+ memset(&tsec_cfg, 0, sizeof(tsec_cfg));
+ config->drv_ctrl = &tsec_cfg;
+
+ /*
+ * Parse driver name
+ */
+ if((unitNumber = rtems_bsdnet_parse_driver_name(config, &unitName)) < 0) {
+ return 0;
+ }
+
+ tsec_cfg.reg_ptr = &mpc83xx.tsec [unitNumber - 1];
+ tsec_cfg.mdio_ptr = &mpc83xx.tsec [0];
+
+ if (attaching) {
+#if (TSEC_IFMODE==TSEC_IFMODE_GMII)
+#if !defined(MPC83XX_BOARD_HSC_CM01)
+
+ /*
+ * do not change system I/O configuration registers on HSC board
+ * because should initialize from RCW
+ */
+
+
+ if (unitNumber == 1) {
+ /*
+ * init system I/O configuration registers
+ * to ensure proper pin functions
+ */
+ mpc83xx.syscon.sicrh = mpc83xx.syscon.sicrh & ~0x1F800000;
+ /*
+ * init port registers (GPIO2DIR) for TSEC1
+ */
+ mpc83xx.gpio[1].gpdir = ((mpc83xx.gpio[1].gpdir & ~0x00000FFF)
+ | 0x0000001f);
+ }
+ if (unitNumber == 2) {
+ /*
+ * init system I/O configuration registers
+ * to ensure proper pin functions
+ */
+ mpc83xx.syscon.sicrh = mpc83xx.syscon.sicrh & ~0x007f8000;
+ /*
+ * init port registers (GPIO2DIR) for TSEC2
+ */
+ mpc83xx.gpio[0].gpdir = ((mpc83xx.gpio[0].gpdir & ~0x000FFFFF)
+ | 0x00087881);
+ }
+#endif /* !defined(MPC83XX_BOARD_HSC_CM01) */
+#endif
+#if (TSEC_IFMODE==TSEC_IFMODE_RGMII)
+
+ /*
+ * Nothing special needed for TSEC1 operation
+ */
+#endif
+ }
+ /*
+ * add MAC address into config->hardware_adderss
+ * FIXME: get the real address we need
+ */
+ if (config->hardware_address == NULL) {
+#if !defined(HAS_UBOOT)
+ static char hw_addr [TSEC_COUNT][6];
+ volatile tsec_registers *reg_ptr = tsec_cfg.reg_ptr;
+
+ /* read MAC address from hardware register */
+ /* we expect it htere from the boot loader */
+ config->hardware_address = hw_addr[unitNumber-1];
+
+ hw_addr[unitNumber-1][5] = (reg_ptr->macstnaddr[0] >> 24) & 0xff;
+ hw_addr[unitNumber-1][4] = (reg_ptr->macstnaddr[0] >> 16) & 0xff;
+ hw_addr[unitNumber-1][3] = (reg_ptr->macstnaddr[0] >> 8) & 0xff;
+ hw_addr[unitNumber-1][2] = (reg_ptr->macstnaddr[0] >> 0) & 0xff;
+ hw_addr[unitNumber-1][1] = (reg_ptr->macstnaddr[1] >> 24) & 0xff;
+ hw_addr[unitNumber-1][0] = (reg_ptr->macstnaddr[1] >> 16) & 0xff;
+#endif
+
+#if defined(HAS_UBOOT)
+ switch (unitNumber) {
+ case 1:
+ config->hardware_address = bsp_uboot_board_info.bi_enetaddr;
+ break;
+
+#ifdef CONFIG_HAS_ETH1
+ case 2:
+ config->hardware_address = bsp_uboot_board_info.bi_enet1addr;
+ break;
+#endif /* CONFIG_HAS_ETH1 */
+
+#ifdef CONFIG_HAS_ETH2
+ case 3:
+ config->hardware_address = bsp_uboot_board_info.bi_enet2addr;
+ break;
+#endif /* CONFIG_HAS_ETH2 */
+
+#ifdef CONFIG_HAS_ETH3
+ case 4:
+ config->hardware_address = bsp_uboot_board_info.bi_enet3addr;
+ break;
+#endif /* CONFIG_HAS_ETH3 */
+
+ default:
+ return 0;
+ }
+
+#endif /* HAS_UBOOT */
+
+ }
+ /*
+ * set interrupt number for given interface
+ */
+ config->irno = (unsigned) (
+ unitNumber == 1
+ ? BSP_IPIC_IRQ_TSEC1_TX
+ : BSP_IPIC_IRQ_TSEC2_TX
+ );
+
+ if (svr == 0x80b00010 && pvr == 0x80850010) {
+ /*
+ * This is a special case for MPC8313ERDB with silicon revision 1. Look in
+ * "MPC8313ECE Rev. 3, 3/2008" errata for "IPIC 1".
+ */
+ if (unitNumber == 1) {
+ tsec_cfg.irq_num_tx = 37;
+ tsec_cfg.irq_num_rx = 36;
+ tsec_cfg.irq_num_err = 35;
+ } else if (unitNumber == 2) {
+ tsec_cfg.irq_num_tx = 34;
+ tsec_cfg.irq_num_rx = 33;
+ tsec_cfg.irq_num_err = 32;
+ } else {
+ return 0;
+ }
+ } else {
+ rtems_irq_number irno = unitNumber == 1 ?
+ BSP_IPIC_IRQ_TSEC1_TX : BSP_IPIC_IRQ_TSEC2_TX;
+
+ /* get base interrupt number (for Tx irq, Rx=base+1,Err=base+2) */
+ tsec_cfg.irq_num_tx = irno + 0;
+ tsec_cfg.irq_num_rx = irno + 1;
+ tsec_cfg.irq_num_err = irno + 2;
+ }
+
+ /*
+ * XXX: Although most hardware builders will assign the PHY addresses
+ * like this, this should be more configurable
+ */
+#ifdef MPC83XX_BOARD_MPC8313ERDB
+ if (unitNumber == 2) {
+ tsec_cfg.phy_default = 4;
+ } else {
+ /* TODO */
+ return 0;
+ }
+#else /* MPC83XX_BOARD_MPC8313ERDB */
+ tsec_cfg.phy_default = unitNumber-1;
+#endif /* MPC83XX_BOARD_MPC8313ERDB */
+
+ tsec_cfg.unit_number = unitNumber;
+ tsec_cfg.unit_name = unitName;
+
+ /*
+ * call attach function of board independent driver
+ */
+ return tsec_driver_attach_detach(config, attaching);
+}
+
+#endif /* MPC83XX_CHIP_TYPE / 10 != 830 */
diff --git a/bsps/powerpc/haleakala/net/network.c b/bsps/powerpc/haleakala/net/network.c
new file mode 100644
index 0000000..4148125
--- /dev/null
+++ b/bsps/powerpc/haleakala/net/network.c
@@ -0,0 +1,1249 @@
+/*
+ * network.c
+ * RTEMS_490
+ *
+ * Created by Michael Hamel on 18/11/08.
+ *
+ * This code is for the PPC405EX, 405EXr on the Haleakala board with an
+ * 88E1111 PHY.
+ * Its has some adaptations for the 405GP, and 405GPr (untested).
+ *
+ * It should handle dual interfaces correctly, but has not been tested.
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+#include <rtems/score/assert.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+
+#include <netinet/if_ether.h>
+#include <bsp/irq.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+#include <ppc4xx/ppc405gp.h>
+#include <ppc4xx/ppc405ex.h>
+
+#define qDebug /* General printf debugging */
+/* #define qMultiDebug */ /* Debugging for the multicast hardware filter */
+
+/*---------------------------- Hardware definitions -------------------------- */
+
+/* PHY addresses for Kilauea & Haleakala; defined by hardware */
+enum {
+ kPHY0 = 1,
+ kPHY1 = 2,
+ kMaxEMACs = 2
+};
+
+enum {
+ kMaxRxBuffers = 256,
+ kNXmtDescriptors = 256, /* May as well use all of them */
+ kNoXmtBusy = 666 /* Arbitrary flag value outside 0..kNXmtDescriptors */
+};
+
+
+/*----------------------- Local variables for the driver -------------------------- */
+
+typedef struct MALDescriptor {
+ uint16_t ctrlBits;
+ uint16_t adrDataSize; /* 4 bits of high address, 12 bits of length */
+ uint8_t* ptr;
+} MALDescriptor;
+
+typedef struct EMACLocals {
+ struct arpcom arpcom;
+
+ /* Pointer to memory-mapped hardware */
+ volatile EthernetRegisters_GP* EMAC;
+
+ /* Transmit and receive task references */
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+ int nRxBuffers;
+ int xmtFreeIndex;
+ int xmtBusyIndex;
+ MALDescriptor* xmtDescTable;
+ MALDescriptor* rcvDescTable;
+
+ struct mbuf* rxMBufs[kMaxRxBuffers];
+ struct mbuf* txMBufs[kNXmtDescriptors];
+
+ int phyAddr, /* PHY address */
+ phyState, /* Last link state */
+ phyOUI, /* Cached PHY type info */
+ phyModel,
+ phyRev;
+
+ /* Statistics */
+ uint32_t rxInterrupts;
+ uint32_t rxOverrun;
+ uint32_t rxRunt;
+ uint32_t rxBadCRC;
+ uint32_t rxNonOctet;
+ uint32_t rxGiant;
+
+ uint32_t txInterrupts;
+
+ uint32_t txLostCarrier;
+ uint32_t txDeferred;
+ uint32_t txOneCollision;
+ uint32_t txMultiCollision;
+ uint32_t txTooManyCollision;
+ uint32_t txLateCollision;
+ uint32_t txUnderrun;
+ uint32_t txPoorSignal;
+} EMACLocals;
+
+
+EMACLocals gEmacs[kMaxEMACs];
+
+int ppc405_emac_phy_adapt(EMACLocals* ep);
+
+/*----------------------------------- Globals --------------------------------------*/
+
+/*
+ Pointers to the buffer descriptor tables used by the MAL. Tricky because they are both
+ read and written to by the MAL, which is unaware of the CPU data cache. As four 8-byte
+ descriptors fit into a single cache line this makes managing them in cached memory difficult.
+ Best solution is to label them as uncached using the MMU. This code assumes an appropriate
+ sized block stating at _enet_bdesc_base has been reserved by linkcmds and has been set up
+ with uncached MMU attrributes in bspstart.c */
+
+LINKER_SYMBOL(_enet_bdesc_start); /* start of buffer descriptor space, from linkcmds */
+LINKER_SYMBOL(_enet_bdesc_end); /* top limit, from linkcmds */
+
+static MALDescriptor* gTx0Descs = NULL;
+static MALDescriptor* gRx0Descs = NULL;
+static MALDescriptor* gTx1Descs = NULL;
+static MALDescriptor* gRx1Descs = NULL;
+
+/*------------------------------------------------------------*/
+
+
+/*
+ * RTEMS event used by interrupt handler to signal driver tasks.
+ * This must not be any of the events used by the network task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+#define _sync __asm__ volatile ("sync\n"::)
+
+#define kCacheLineMask (PPC_CACHE_ALIGNMENT - 1)
+
+
+/*----------------------- IRQ handler glue -----------------------*/
+
+static void InstallIRQHandler(rtems_irq_number id,
+ rtems_irq_hdl handler,
+ rtems_irq_enable turnOn,
+ rtems_irq_disable turnOff)
+{
+ rtems_irq_connect_data params;
+
+ params.name = id;
+ params.hdl = handler;
+ params.on = turnOn;
+ params.off = turnOff;
+ params.isOn = NULL;
+ params.handle = NULL;
+ if (! BSP_install_rtems_irq_handler(&params))
+ rtems_panic ("Can't install interrupt handler");
+}
+
+static void
+NoAction(const rtems_irq_connect_data* unused)
+{
+ /* printf("NoAction %d\n",unused->name); */
+}
+
+
+/*------------------------ PHY interface -------------------------- */
+/* This code recognises and works with the 88E1111 only. Other PHYs
+ will require appropriate adaptations to this code */
+
+enum {
+ kPHYControl = 0,
+ kPHYReset = 0x8000,
+ kPHYStatus = 1,
+ kPHYLinkStatus = 0x0004,
+ kPHYID1 = 2,
+ kPHYID2 = 3,
+ kPHYAutoNegExp = 6,
+ kPHY1000BaseTCtl = 9,
+ kPHYExtStatus = 15,
+
+ /* 88E1111 identification */
+ kMarvellOUI = 0x5043,
+ k88E1111Part = 0x0C,
+
+ /* 88E1111 register addresses */
+ k8PHYSpecStatus = 17,
+ k8PHYSpeedShift = 14,
+ k8PHYDuplex = 0x2000,
+ k8PHYResolved = 0x0800,
+ k8PHYLinkUp = 0x0400,
+ k8IntStatus = 19,
+ k8IntEnable = 18,
+ k8AutoNegComplete = 0x0800,
+ k8LinkStateChanged = 0x0400,
+ k8ExtCtlReg = 20,
+ k8RcvTimingDelay = 0x0080,
+ k8XmtTimingDelay = 0x0002,
+ k8XmtEnable = 0x0001,
+ k8LEDCtlReg = 24,
+ k8ExtStatusReg = 27,
+};
+
+
+static uint16_t ReadPHY(EMACLocals* ep, uint8_t reg)
+{
+ int n = 0;
+ uint32_t t;
+
+ reg &= 0x1F;
+
+ /* 405EX-specific! */
+ while ((ep->EMAC->STAcontrol & keSTARun) != 0)
+ { ; }
+ ep->EMAC->STAcontrol = keSTADirectRd + (ep->phyAddr<<5) + reg;
+ ep->EMAC->STAcontrol |= keSTARun;
+ /* Wait for the read to complete, should take ~25usec */
+ do {
+ t = ep->EMAC->STAcontrol;
+ if (++n > 200000)
+ rtems_panic("PHY read timed out");
+ } while ((t & keSTARun) != 0);
+
+ if (t & kSTAErr)
+ rtems_panic("PHY read failed");
+ return t >> 16;
+}
+
+static void WritePHY(EMACLocals* ep, uint8_t reg, uint16_t value)
+{
+
+ reg &= 0x1F;
+
+ /* 405EX-specific */
+ while ((ep->EMAC->STAcontrol & keSTARun) != 0)
+ { ; }
+ ep->EMAC->STAcontrol = (value<<16) | keSTADirectWr | (ep->phyAddr<<5) | reg;
+ ep->EMAC->STAcontrol |= keSTARun;
+}
+
+static void ResetPHY(EMACLocals* ep)
+{
+ int n;
+
+ n = ReadPHY(ep, kPHYControl);
+ n |= kPHYReset;
+ WritePHY(ep, kPHYControl, n);
+ do {
+ rtems_task_wake_after( (rtems_bsdnet_ticks_per_second/20) + 1 );
+ n = ReadPHY(ep, kPHYControl);
+ } while ((n & kPHYReset)!=0);
+}
+
+enum {
+ kELinkUp = 0x80,
+ kELinkFullDuplex = 0x40,
+ kELinkSpeed10 = 0,
+ kELinkSpeed100 = 1,
+ kELinkSpeed1000 = 2,
+ kELinkSpeedMask = 3
+};
+
+static int GetPHYLinkState(EMACLocals* ep)
+/* Return link state (up/speed/duplex) as a set of flags */
+{
+ int state, result;
+
+ /* if (ep->phyOUI==kMarvellOUI) */
+ result = 0;
+ state = ReadPHY(ep,k8PHYSpecStatus);
+ if ((state & k8PHYLinkUp) && (state & k8PHYResolved)) {
+ result |= kELinkUp;
+ if (state & k8PHYDuplex) result |= kELinkFullDuplex;
+ result |= ((state >> k8PHYSpeedShift) & 3);
+ }
+ return result;
+}
+
+/*---------------------- PHY setup ------------------------*/
+
+
+static void InitPHY(EMACLocals* ep)
+{
+ int id,id2,n;
+
+ id = ReadPHY(ep,kPHYID1);
+ id2 = ReadPHY(ep,kPHYID2);
+ ep->phyOUI = (id<<6) + (id2>>10);
+ ep->phyModel = (id2>>4) & 0x1F;
+ ep->phyRev = id2 & 0xF;
+
+ #ifdef qDebug
+ printf("PHY %d maker $%X model %d revision %d\n",ep->phyAddr,ep->phyOUI,ep->phyModel,ep->phyRev);
+ #endif
+
+ /* Test for PHYs that we understand; insert new PHY types initialisation here */
+ if (ep->phyOUI == kMarvellOUI || ep->phyModel == k88E1111Part) {
+ /* 88E111-specific: Enable RxTx timing control, enable transmitter */
+ n = ReadPHY(ep, k8ExtCtlReg);
+ n |= k8RcvTimingDelay + k8XmtTimingDelay + k8XmtEnable;
+ WritePHY(ep, k8ExtCtlReg, n);
+
+ /* Set LED mode; Haleakala has LINK10 and TX LEDs only. Set up to do 100/1000 and link up/active*/
+ WritePHY(ep, k8LEDCtlReg, 0x4109);
+
+ /* Need to do a reset after fiddling with registers*/
+ ResetPHY(ep);
+ } else
+ rtems_panic("Unknown PHY type");
+}
+
+
+/*--------------------- Interrupt handlers for the MAL ----------------------------- */
+
+static void
+MALTXDone_handler(rtems_irq_hdl_param param)
+{
+ int n;
+
+ n = PPC_DEVICE_CONTROL_REGISTER(MAL0_TXEOBISR);
+ if (n & kMALChannel0) {
+ gEmacs[0].txInterrupts++;
+ rtems_event_send (gEmacs[0].txDaemonTid, INTERRUPT_EVENT);
+ }
+ if (n & kMALChannel1) {
+ gEmacs[1].txInterrupts++;
+ rtems_event_send (gEmacs[1].txDaemonTid, INTERRUPT_EVENT);
+ }
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXEOBISR,n);
+}
+
+static void
+MALRXDone_handler (rtems_irq_hdl_param param)
+{
+ int n;
+
+ n = PPC_DEVICE_CONTROL_REGISTER(MAL0_RXEOBISR);
+ if (n & kMALChannel0) {
+ gEmacs[0].rxInterrupts++;
+ rtems_event_send (gEmacs[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+ if (n & kMALChannel1) {
+ gEmacs[1].rxInterrupts++;
+ rtems_event_send (gEmacs[1].rxDaemonTid, INTERRUPT_EVENT);
+ }
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXEOBISR,n); /* Write back to clear interrupt */
+}
+
+/* These handlers are useful for debugging, but we don't actually need to process these interrupts */
+
+static void
+MALErr_handler (rtems_irq_hdl_param param)
+{
+ uint32_t errCause;
+
+ errCause = PPC_DEVICE_CONTROL_REGISTER(MAL0_ESR);
+ /* Clear the error */
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_ESR,errCause);
+}
+
+static void
+EMAC0Err_handler (rtems_irq_hdl_param param)
+{
+ uint32_t errCause;
+
+ errCause = gEmacs[0].EMAC->intStatus;
+ /* Clear error by writing back */
+ gEmacs[0].EMAC->intStatus = errCause;
+}
+
+static void
+EMAC1Err_handler (rtems_irq_hdl_param param)
+{
+ uint32_t errCause;
+
+ errCause = gEmacs[1].EMAC->intStatus;
+ /* Clear error by writing back */
+ gEmacs[1].EMAC->intStatus = errCause;
+}
+
+
+/*--------------------- Low-level hardware initialisation ----------------------------- */
+
+
+
+static void
+mal_initialise(void)
+{
+ uint32_t bdescbase;
+ int nBytes, ntables;
+
+ /*------------------- Initialise the MAL for both channels ---------------------- */
+
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_CFG,kMALReset);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCARR, kMALChannel0 | kMALChannel1);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCARR, kMALChannel0 | kMALChannel1);
+
+ /* Acquire MAL interrupts */
+ InstallIRQHandler(BSP_UIC_MALTXEOB, MALTXDone_handler, NoAction, NoAction);
+ InstallIRQHandler(BSP_UIC_MALRXEOB, MALRXDone_handler, NoAction, NoAction);
+ InstallIRQHandler(BSP_UIC_MALSERR, MALErr_handler, NoAction, NoAction);
+
+ /* Set up the buffer descriptor tables */
+ bdescbase = (uint32_t)(_enet_bdesc_start);
+ nBytes = sizeof(MALDescriptor) * 256;
+ ntables = 4;
+ if (get_ppc_cpu_type() != PPC_405EX) {
+ /* The 405GP/GPr requires table bases to be 4K-aligned and can use two tx channels on one EMAC */
+ nBytes = (nBytes + 0x0FFF) & ~0x0FFF;
+ bdescbase = (bdescbase + 0x0FFF) & ~0x0FFF;
+ ntables = 3;
+ }
+
+ /* printf("Buffer descriptors at $%X..$%X, code from $%X\n",bdescbase, bdescbase + nBytes*ntables - 1,(uint32_t)&_text_start); */
+
+ /* Check that we have been given enough space and the buffers don't run past the enet_bdesc_end address */
+ if (bdescbase + nBytes*ntables > (uint32_t)_enet_bdesc_end)
+ rtems_panic("Ethernet descriptor space insufficient!");
+
+ gTx0Descs = (MALDescriptor*)bdescbase;
+ gTx1Descs = (MALDescriptor*)(bdescbase + nBytes);
+ gRx0Descs = (MALDescriptor*)(bdescbase + nBytes*2);
+ /* Clear the buffer descriptor tables */
+ memset(gTx0Descs, 0, sizeof(MALDescriptor)*256);
+ memset(gTx1Descs, 0, sizeof(MALDescriptor)*256);
+ memset(gRx0Descs, 0, sizeof(MALDescriptor)*256);
+ if (get_ppc_cpu_type() == PPC_405EX) {
+ gRx1Descs = (MALDescriptor*)(bdescbase + nBytes*3);
+ memset(gRx1Descs, 0, sizeof(MALDescriptor)*256);
+ }
+
+ /* Set up the MAL registers */
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCTP0R,gTx0Descs);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCTP1R,gTx1Descs);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCTP0R,gRx0Descs);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RCBS0, (MCLBYTES-16)>>4); /* The hardware writes directly to the mbuf clusters, so it can write MCLBYTES */
+ if (get_ppc_cpu_type() == PPC_405EX) {
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_CFG,kMALMedHiPriority + keMALRdMaxBurst32 + keMALWrMedHiPriority + keMALWrMaxBurst32 +
+ kMALLocksOPB + kMALLocksErrs + kMALCanBurst);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCTP1R,gRx1Descs);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RCBS1, (MCLBYTES-16)>>4);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_IER,0xF7); /* Enable all MAL interrupts */
+ } else {
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_CFG,kMALMedHiPriority + kMALLocksOPB + kMALLocksErrs + kMALCanBurst + kMALLatency8);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_IER,0x1F); /* Enable all MAL interrupts */
+ }
+}
+
+
+
+#ifdef qDebug
+static void printaddr(uint8_t* enetaddr)
+{
+ printf("%02X.%02X.%02X.%02X.%02X.%02X",enetaddr[0],enetaddr[1],enetaddr[2],enetaddr[3],enetaddr[4],enetaddr[5]);
+}
+#endif
+
+static bool gMALInited = FALSE;
+
+static void
+ppc405_emac_initialize_hardware(EMACLocals* ep)
+{
+
+ int n,mfr;
+ int unitnum = ep->arpcom.ac_if.if_unit;
+
+ if (get_ppc_cpu_type() == PPC_405EX) {
+ /* PPC405EX: configure the RGMII bridge and clocks */
+ RGMIIRegisters* rgmp = (RGMIIRegisters*)RGMIIAddress;
+ rgmp->FER = 0x00080055; /* Both EMACs RGMII */
+ rgmp->SSR = 0x00000044; /* Both EMACs 1000Mbps */
+ /* Configure the TX clock to be external */
+ mfsdr(SDR0_MFR,mfr);
+ mfr &= ~0x0C000000; /* Switches both PHYs */
+ mtsdr(SDR0_MFR,mfr);
+ }
+
+ /* Reset the EMAC */
+ n = 0;
+ ep->EMAC->mode0 = kEMACSoftRst;
+ while ((ep->EMAC->mode0 & kEMACSoftRst) != 0)
+ n++; /* Wait for it to complete */
+
+ /* Set up so we can talk to the PHY */
+ ep->EMAC->mode1 = keEMACIPHYAddr4 | keEMACOPB100MHz;
+
+ /* Initialise the PHY */
+ InitPHY(ep);
+
+ /* Initialise the MAL (once only) */
+ if ( ! gMALInited) {
+ mal_initialise();
+ gMALInited = TRUE;
+ }
+
+ /* Set up IRQ handlers and enable the MAL channels for this port */
+ if (unitnum==0) {
+ ep->xmtDescTable = gTx0Descs;
+ ep->rcvDescTable = gRx0Descs;
+ InstallIRQHandler(BSP_UIC_EMAC0, EMAC0Err_handler, NoAction, NoAction);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCASR,kMALChannel0);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCASR,kMALChannel0);
+ } else {
+ ep->xmtDescTable = gTx1Descs;
+ ep->rcvDescTable = gRx1Descs;
+ InstallIRQHandler(BSP_UIC_EMAC1, EMAC1Err_handler, NoAction, NoAction);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCASR,kMALChannel1);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCASR,kMALChannel1);
+ }
+
+ /* The rest of the EMAC initialisation is done in emac_phy_adapt
+ when we know what the characteristics of the link are */
+}
+
+
+/* EMAC second stage initialisation; talks to the PHY to find out how to do it.
+ Resets the EMAC if the PHY parameters need to be changed */
+
+int ppc405_emac_phy_adapt(EMACLocals* ep)
+{
+ int linkState = GetPHYLinkState(ep);
+ int spd;
+
+ if ((linkState & kELinkUp) && (linkState != ep->phyState)) {
+ /* Reset the EMAC and set registers according to PHY state */
+ int i,n = 0;
+ uint32_t mode, rmode;
+
+ ep->EMAC->mode0 = kEMACSoftRst;
+ while ((ep->EMAC->mode0 & kEMACSoftRst) != 0)
+ n++; /* Wait for it to complete */
+ spd = linkState & kELinkSpeedMask;
+ mode = (spd<<22) | kgEMACTx0Multi;
+ if (get_ppc_cpu_type() == PPC_405EX)
+ mode |= (keEMAC16KRxFIFO | keEMAC16KTxFIFO | keEMACIPHYAddr4 | keEMACOPB100MHz );
+ else
+ mode |= (kgEMAC4KRxFIFO | kgEMAC2KTxFIFO);
+ if (linkState & kELinkFullDuplex)
+ mode |= kEMACFullDuplex + kEMACDoFlowControl;
+ if ( (linkState & kELinkFullDuplex) || (spd > kELinkSpeed10) )
+ mode |= kEMACIgnoreSQE;
+
+
+ if (spd==kELinkSpeed1000) {
+ /* Gigabit, so we support jumbo frames. Take appropriate measures: adjust the if_mtu */
+ /* Note that we do this here because changing it later doesn't work very well : see
+ the SIOCSIFMTU discussion below */
+ struct ifnet* ifp = &ep->arpcom.ac_if;
+ ifp->if_mtu = ETHERMTU_JUMBO;
+ mode |= keEMACJumbo;
+ }
+
+
+ ep->phyState = linkState;
+ ep->EMAC->mode1 = mode;
+
+ /* Install 48-bit hardware address that we have been given */
+ ep->EMAC->addrHi = (ep->arpcom.ac_enaddr[0]<<8) + ep->arpcom.ac_enaddr[1];
+ ep->EMAC->addrLo = (ep->arpcom.ac_enaddr[2]<<24) + (ep->arpcom.ac_enaddr[3]<<16)
+ + (ep->arpcom.ac_enaddr[4]<<8) + (ep->arpcom.ac_enaddr[5] );
+
+ /* Set receive mode appropriately */
+ rmode = kEMACStripPadding + kEMACStripFCS + kEMACBrcastRcv;
+
+ if (ep->arpcom.ac_if.if_flags & IFF_PROMISC) rmode |= kEMACPromiscRcv;
+ else rmode |= kEMACIndivRcv;
+ if (get_ppc_cpu_type() == PPC_405EX)
+ rmode |= keEMACRxFIFOAFMax;
+ if ((ep->arpcom.ac_if.if_flags & IFF_ALLMULTI) != 0)
+ rmode |= kEMACPromMultRcv;
+ else if ((ep->arpcom.ac_if.if_flags & IFF_MULTICAST) != 0)
+ rmode |= kEMACMultcastRcv;
+
+ ep->EMAC->rcvMode = rmode;
+
+ if (get_ppc_cpu_type() == PPC_405EX)
+ for (i=0; i<8; i++)
+ ep->EMAC->e_groupHash[i] = 0;
+ else
+ for (i=0; i<4; i++)
+ ep->EMAC->g_groupHash[i] = 0;
+
+ if (get_ppc_cpu_type() == PPC_405EX) {
+ /* Rcv low watermark, must be < mode1 Rcv FIFO size and > MAL burst length (default 64x4 bytes), 16-byte units
+ High watermark must be > low and < RcvFIFO size */
+ ep->EMAC->rcvWatermarks = (16<<22) + (768<<6);
+ /* Xmt low request must be >= 17 FIFO entries, Xmt urgent must be > low */
+ ep->EMAC->xmtMode1 = (17<<27) + (68<<14); /* TLR = 17, TUR = 68 */
+ /* Xmt partial packet request threshold */
+ ep->EMAC->xmtReqThreshold = ((1000>>2)-1) << 24; /* TRTR[TRT] = 1000 FIFO entries */
+ } else {
+ ep->EMAC->rcvWatermarks = (15<<24) + (32<<8);
+ ep->EMAC->xmtReqThreshold = ((1448>>6)-1) << 26; /* TRT = 1024b */
+ ep->EMAC->xmtMode1 = 0x40200000; /* TLR = 8w=32b, TUR=32w=128b */
+ }
+
+ ep->EMAC->IPGap = 8;
+
+ /* Want EMAC interrupts for error logging & statistics */
+ ep->EMAC->intEnable = kEMACIOverrun + kEMACIPause + kEMACIBadPkt + kEMACIRuntPkt + kEMACIShortEvt
+ + kEMACIAlignErr + kEMACIBadFCS + kEMACIOverSize + kEMACILLCRange + kEMACISQEErr
+ + kEMACITxErr;
+
+ /* Start it running */
+ ep->EMAC->mode0 = kEMACRxEnable + kEMACTxEnable;
+ return 0;
+ } else
+ return -1;
+}
+
+
+static void
+ppc405_emac_disable(EMACLocals* ep)
+/* Disable the EMAC channels so we stop running and processing interrupts */
+{
+ ep->EMAC->mode0 = 0;
+}
+
+static void
+ppc405_emac_startxmt(EMACLocals* ep)
+/* Start the transmitter: set TMR0[GNP] */
+{
+ ep->EMAC->xmtMode0 = kEMACNewPacket0 + 7; /* *** TFAE value for EX */
+}
+
+static void ppc405_emac_watchdog(struct ifnet* ifp)
+/* Called if a transmit stalls or when the interface is down. Check the PHY
+ until we get a valid link */
+{
+ EMACLocals* ep = ifp->if_softc;
+
+ if (ppc405_emac_phy_adapt(ep)==0) {
+ ep->arpcom.ac_if.if_flags |= IFF_RUNNING;
+ ifp->if_timer = 0; /* No longer needed */
+ } else
+ ifp->if_timer = 1; /* reschedule, once a second */
+}
+
+
+
+/*----------------------- The transmit daemon/task -------------------------- */
+
+
+static void
+FreeTxDescriptors(EMACLocals* ep)
+/* Make descriptors and mbufs at xmtBusyIndex available for re-use if the packet that they */
+/* point at has all gone */
+{
+ uint16_t scan, status;
+
+ if (ep->xmtBusyIndex != kNoXmtBusy) {
+ scan = ep->xmtBusyIndex;
+ while (TRUE) {
+ /* Scan forward through the descriptors */
+ status = ep->xmtDescTable[scan].ctrlBits;
+ if (++scan >= kNXmtDescriptors)
+ scan = 0;
+ /* If we find a ready (i.e not-yet-sent) descriptor, stop */
+ if ((status & kMALTxReady) != 0)
+ break;
+ /* If we find a last descriptor, we can free all the buffers up to and including it */
+ if ((status & kMALLast) != 0) {
+ /* End of packet and it has been sent or abandoned; advance xmtBusyIndex to */
+ /* the next buffer and free buffers. */
+ if ((status & kEMACErrMask) != 0) {
+ /* Transmit error of some kind */
+
+ if ((status & kEMACDeferred) != 0)
+ ep->txDeferred++;
+ if ((status & kEMACLostCarrier) != 0)
+ ep->txLostCarrier++; /* *** Perhaps more serious reaction needed... */
+
+ if ((status & kEMACLateColl) != 0)
+ ep->txLateCollision++;
+ if ((status & kEMACOneColl) != 0)
+ ep->txOneCollision++;
+ if ((status & kEMACMultColl) != 0)
+ ep->txMultiCollision++;
+ if ((status & kEMACCollFail) != 0)
+ ep->txTooManyCollision++;
+
+ if ((status & kEMACSQEFail) != 0)
+ ep->txPoorSignal++;
+ if ((status & kEMACUnderrun) != 0)
+ ep->txUnderrun++;
+ }
+ while (ep->xmtBusyIndex != scan) {
+ m_free(ep->txMBufs[ep->xmtBusyIndex]);
+ if (++ep->xmtBusyIndex >= kNXmtDescriptors) ep->xmtBusyIndex = 0;
+ }
+ if (ep->xmtBusyIndex == ep->xmtFreeIndex) {
+ /* Nothing is busy */
+ ep->xmtBusyIndex = kNoXmtBusy;
+ break;
+ }
+ }
+ }
+ }
+}
+
+
+static void
+SendPacket (EMACLocals* ep, struct ifnet *ifp, struct mbuf *m)
+/* Given a chain of mbufs, set up a transmit description and fire it off */
+{
+ int nAdded, index, lastidx = -1, totalbytes;
+ uint16_t status;
+ struct mbuf* lastAdded;
+
+ nAdded = 0;
+ totalbytes = 0;
+ lastAdded = NULL;
+ index = ep->xmtFreeIndex;
+
+ /* Go through the chain of mbufs setting up descriptors for each */
+ while (m != NULL) {
+
+ if (m->m_len == 0) {
+ /* Can be empty: dispose and unlink from chain */
+ m = m_free(m);
+ if (lastAdded!=NULL) lastAdded->m_next = m;
+ } else {
+ /* Make sure the mbuf has been written to memory */
+ rtems_cache_flush_multiple_data_lines(mtod (m, void *), m->m_len);
+ /* If there are no descriptors available wait until there are */
+ while (index == ep->xmtBusyIndex) {
+ rtems_event_set events;
+ ifp->if_timer = 2;
+ /* Then check for free descriptors, followed by: */
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT, RTEMS_WAIT | RTEMS_EVENT_ANY, RTEMS_NO_TIMEOUT, &events);
+ FreeTxDescriptors(ep);
+ }
+
+ /* Fill in a descriptor for this mbuf and record it */
+ ep->txMBufs[index] = m;
+ ep->xmtDescTable[index].ptr = mtod (m, void *);
+ ep->xmtDescTable[index].adrDataSize = m->m_len;
+ /* Fill in ctrlBits as we go but don't mark the first one as ready yet */
+ status = kEMACGenFCS + kEMACGenPad + kEMACRepSrcAddr;
+ if (nAdded > 0)
+ status |= kMALTxReady;
+ if (index==kNXmtDescriptors-1)
+ status |= kMALWrap;
+ ep->xmtDescTable[index].ctrlBits = status;
+ lastidx = index;
+
+ totalbytes += m->m_len;
+ lastAdded = m;
+ m = m->m_next;
+ nAdded++;
+
+ index += 1;
+ if (index==kNXmtDescriptors)
+ index = 0;
+
+ if (nAdded==kNXmtDescriptors)
+ rtems_fatal_error_occurred(RTEMS_INTERNAL_ERROR); /* This is impossible, of course... */
+ }
+ }
+
+ _Assert( lastidx != -1 );
+
+ if (nAdded > 0) {
+ /* Done and we added some buffers */
+ /* Label the last buffer and ask for an interrupt */
+ ep->xmtDescTable[lastidx].ctrlBits |= kMALLast + kMALInterrupt;
+ /* Finally set the ready bit on the first buffer */
+ ep->xmtDescTable[ep->xmtFreeIndex].ctrlBits |= kMALTxReady;
+ /* Make sure this has been written */
+ _sync;
+ if (ep->xmtBusyIndex == kNoXmtBusy)
+ ep->xmtBusyIndex = ep->xmtFreeIndex;
+ ep->xmtFreeIndex = index;
+ /* Poke the EMAC to get it started (which may not be needed if its already running */
+ ppc405_emac_startxmt(ep);
+ ifp->if_timer = 2;
+ }
+}
+
+static void
+ppc405_emac_txDaemon (void* param)
+{
+ EMACLocals* ep = param;
+ struct ifnet *ifp = &ep->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ ep->xmtFreeIndex = 0;
+ ep->xmtBusyIndex = kNoXmtBusy;
+ while (TRUE) {
+ /* Wait for someone wanting to transmit */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT | INTERRUPT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ if (events & INTERRUPT_EVENT)
+ ifp->if_timer = 0;
+ /* Grab packets and send until empty */
+ /* Note that this doesn't (at the time of writing, RTEMS 4.9.1), ever get asked to send more than
+ one header mbuf and one data mbuf cluster, regardless of the MTU. This is because sosend() in the FreeBSD
+ stack only passes one mbuf at a time across to tcp_send, which immediately sends it */
+ while (TRUE) {
+ FreeTxDescriptors(ep);
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (m == NULL)
+ break;
+ SendPacket (ep, ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*----------------------- The receive daemon/task -------------------------- */
+
+static void
+MakeRxBuffer(EMACLocals* ep, int index)
+{
+ struct mbuf* m;
+
+ /* Allocate an mbuf, wait if necessary, label as dynamic data, start of record */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ /* Allocate a cluster buffer to this mbuf, waiting if necessary */
+ MCLGET (m, M_WAIT);
+ /* Set up reference to the interface the packet will be received on */
+ m->m_pkthdr.rcvif = &ep->arpcom.ac_if;
+ ep->rxMBufs[index] = m;
+ ep->rcvDescTable[index].ptr = mtod (m, uint8_t*);
+ ep->rcvDescTable[index].adrDataSize = 0x0EEE; /* Precaution */
+ if (index==ep->nRxBuffers-1)
+ ep->rcvDescTable[index].ctrlBits = kMALRxEmpty + kMALInterrupt + kMALWrap;
+ else
+ ep->rcvDescTable[index].ctrlBits = kMALRxEmpty + kMALInterrupt;
+}
+
+
+
+static void
+ppc405_emac_rxDaemon (void* param)
+{
+ EMACLocals* ep = param;
+ int index,n,mdex;
+ struct mbuf* m;
+ struct mbuf* mstart = NULL;
+ struct mbuf* mlast = NULL;
+ struct ifnet* ifp;
+ struct ether_header* eh = NULL;
+ rtems_event_set events;
+
+ /* Startup : allocate a bunch of receive buffers and point the descriptor table entries at them */
+ ifp = &ep->arpcom.ac_if;
+ index = 0;
+ while (index < ep->nRxBuffers) {
+ MakeRxBuffer(ep,index);
+ index += 1;
+ }
+ index = 0;
+ mdex = 0;
+
+ /* Loop waiting for frames to arrive */
+ while (TRUE) {
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ while ((ep->rcvDescTable[index].ctrlBits & kMALRxEmpty) == 0) {
+ /* Got a frame */
+ uint16_t flags = ep->rcvDescTable[index].ctrlBits;
+ if ((flags & kEMACErrMask) != 0) {
+ /* It has errors. Update statistics */
+ if ((flags & kEMACOverrun) != 0)
+ ep->rxOverrun++;
+ if ((flags & kEMACRuntPkt) != 0)
+ ep->rxRunt++;
+ if ((flags & kEMACBadFCS) != 0)
+ ep->rxBadCRC++;
+ if ((flags & kEMACAlignErr) != 0)
+ ep->rxNonOctet++;
+ if ((flags & kEMACPktLong) != 0)
+ ep->rxGiant++;
+ /* and reset descriptor to empty */
+
+ /* No need to get new mbufs, just reset */
+ ep->rcvDescTable[index].adrDataSize = 0x0EEE;
+ if (index==ep->nRxBuffers-1)
+ ep->rcvDescTable[index].ctrlBits = kMALRxEmpty + kMALInterrupt + kMALWrap;
+ else
+ ep->rcvDescTable[index].ctrlBits = kMALRxEmpty + kMALInterrupt;
+
+ } else {
+ /* Seems to be OK. Invalidate cache over the size we received */
+ n = ep->rcvDescTable[index].adrDataSize & 0x0FFF;
+ m = ep->rxMBufs[index];
+ rtems_cache_invalidate_multiple_data_lines(m->m_data, (n + kCacheLineMask) & ~kCacheLineMask);
+
+ /* Consider copying small packets out of the cluster into m_pktdat to save clusters? */
+ m->m_len = n;
+
+ /* Jumbo packets will span multiple mbufs; chain them together and submit when we get the last one */
+ if (flags & kMALRxFirst) {
+ /* First mbuf in the packet */
+ if (mstart!=NULL)
+ rtems_panic("first, no last");
+
+ /* Adjust the mbuf pointers to skip the header and set eh to point to it */
+ m->m_len -= sizeof(struct ether_header);
+ m->m_pkthdr.len = m->m_len;
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ mstart = m;
+ mlast = m;
+ mdex = index;
+ } else {
+ /* Chain onto mstart: add length to pkthdr.len */
+ if (mstart == NULL)
+ rtems_panic("last, no first");
+
+ mstart->m_pkthdr.len += n;
+ m->m_flags &= ~M_PKTHDR;
+ mlast->m_next = m;
+ mlast = m;
+ }
+
+ if (flags & kMALLast) {
+ /* Last mbuf in the packet: pass base of the chain to a higher level */
+ ether_input (ifp, eh, mstart);
+
+ /* ether_input took the chain, set up new mbufs in the slots we used */
+ mdex -= 1;
+ do {
+ if (++mdex==ep->nRxBuffers) mdex = 0;
+ MakeRxBuffer(ep,mdex);
+ } while (mdex != index);
+ mstart = NULL;
+ mlast = NULL;
+ eh = NULL;
+ }
+ }
+ index += 1;
+ if (index == ep->nRxBuffers) index = 0;
+ }
+ }
+}
+
+/*----------- Vectored routines called through the driver struct ------------------ */
+
+static void ppc405_emac_init (void* p)
+/* Initialise the hardware, create and start the transmit and receive tasks */
+{
+ char txName[] = "ETx0";
+ char rxName[] = "ERx0";
+
+ EMACLocals* ep = (EMACLocals*)p;
+ if (ep->txDaemonTid == 0) {
+ ppc405_emac_initialize_hardware(ep);
+ rxName[3] += ep->phyAddr;
+ ep->rxDaemonTid = rtems_bsdnet_newproc (rxName, 4096, ppc405_emac_rxDaemon, ep);
+ txName[3] += ep->phyAddr;
+ ep->txDaemonTid = rtems_bsdnet_newproc (txName, 4096, ppc405_emac_txDaemon, ep);
+ }
+ /* Only set IFF_RUNNING if the PHY is ready. If not set the watchdog timer running so we check it */
+ if ( GetPHYLinkState(ep) & kELinkUp )
+ ep->arpcom.ac_if.if_flags |= IFF_RUNNING;
+ else
+ ep->arpcom.ac_if.if_timer = 1;
+}
+
+static void ppc405_emac_start(struct ifnet *ifp)
+/* Send a packet: send an event to the transmit task, waking it up */
+{
+ EMACLocals* ep = ifp->if_softc;
+ rtems_event_send (ep->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void ppc405_emac_stop (EMACLocals* ep)
+{
+ uint32_t mask;
+
+ mask = 0x80000000 >> ep->arpcom.ac_if.if_unit;
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_TXCARR,mask);
+ PPC_SET_DEVICE_CONTROL_REGISTER(MAL0_RXCARR,mask);
+ ppc405_emac_disable(ep);
+ /* *** delete daemons, or do they exit themselves? */
+ ep->arpcom.ac_if.if_flags &= ~IFF_RUNNING;
+}
+
+#ifdef qDebug
+static void ppc405_emac_stats (EMACLocals* ep)
+{
+
+ printf (" Rx Interrupts:%-8lu", ep->rxInterrupts);
+ printf (" Giant:%-8lu", ep->rxGiant);
+ printf (" Runt:%-8lu\n", ep->rxRunt);
+ printf (" Non-octet:%-8lu", ep->rxNonOctet);
+ printf (" Bad CRC:%-8lu", ep->rxBadCRC);
+ printf (" Overrun:%-8lu\n", ep->rxOverrun);
+
+ printf (" Tx Interrupts:%-8lu", ep->txInterrupts);
+ printf (" Long deferral:%-8lu", ep->txDeferred);
+ printf (" No Carrier:%-8lu\n", ep->txLostCarrier);
+ printf (" Late collision:%-8lu", ep->txLateCollision);
+ printf (" One collision:%-8lu", ep->txOneCollision);
+ printf (" Many collisions:%-8lu\n", ep->txMultiCollision);
+ printf ("Excess collisions:%-8lu", ep->txTooManyCollision);
+ printf (" Underrun:%-8lu", ep->txUnderrun);
+ printf (" Poor signal:%-8lu\n", ep->txPoorSignal);
+}
+#endif
+
+static int UpdateMulticast(EMACLocals* ep)
+{
+ /* Traverse list of multicast addresses and update hardware hash filter. This is just a work-reduction */
+ /* step; the filter uses a hash of the hardware address and therefore doesn't catch all unwanted packets */
+ /* We have to do other checks in software. */
+ /* 405GP/GPr has 4x16-bit hash registers, 405EX/EXr has 8x32-bit */
+
+ struct ether_multi* enm;
+ struct ether_multistep step;
+ uint32_t hash;
+
+ #ifdef qMultiDebug
+ printf("\nMulticast etheraddrs:\n");
+ #endif
+
+ ETHER_FIRST_MULTI(step, &ep->arpcom, enm);
+ while (enm != NULL) {
+
+ /* *** Doesn't implement ranges */
+
+ hash = ether_crc32_be( (uint8_t*)&enm->enm_addrlo, sizeof(enm->enm_addrlo) );
+ if (get_ppc_cpu_type() == PPC_405EX) {
+ hash >>= 24; /* Upper 8 bits, split 3/5 */
+ /* This has been experimentally verified against the hardware */
+ ep->EMAC->e_groupHash[7-(hash>>5)] |= (1 << (hash & 0x1F));
+ } else {
+ hash >>= 26; /* Upper 6 bits, split 2/4 */
+ /* This has not been checked */
+ ep->EMAC->g_groupHash[3-(hash>>6)] |= (1 << (hash & 0xF));
+ }
+
+ #ifdef qMultiDebug
+ printf(" ");
+ printaddr(enm->enm_addrlo);
+ printf(" = bit %d",hash);
+ if (memcmp(&enm->enm_addrlo, &enm->enm_addrhi, 6) != 0) {
+ printf(" - ");
+ printaddr(enm->enm_addrhi);
+ printf(" [not supported]");
+ }
+ printf("\n");
+ #endif
+
+ ETHER_NEXT_MULTI(step, enm);
+ }
+ #ifdef qMultiDebug
+ {
+ int i;
+ printf(" Grouphash is ");
+ for (i=0; i<8; i++)
+ printf("%08X:",(int)ep->EMAC->e_groupHash[i]);
+ printf("\n");
+ }
+ #endif
+ return 0;
+}
+
+
+static int ppc405_emac_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ int error = 0;
+ EMACLocals* ep = ifp->if_softc;
+ struct ifreq* reqP = (struct ifreq *) data;
+
+ switch (command) {
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ ppc405_emac_stop(ep);
+ break;
+
+ case IFF_UP:
+ ppc405_emac_init(ep);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ ppc405_emac_stop(ep);
+ ppc405_emac_init(ep);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIOCADDMULTI: {
+ error = ether_addmulti( reqP, &ep->arpcom);
+ if (error==ENETRESET)
+ error = UpdateMulticast(ep);
+ } break;
+
+ case SIOCDELMULTI:
+ error = ether_delmulti( (struct ifreq *) data, &ep->arpcom);
+ if (error==ENETRESET)
+ error = UpdateMulticast(ep);
+ break;
+
+ case SIOCSIFMTU: {
+ /* Note that this may not do what you want; setting the interface MTU doesn't touch the route MTUs,
+ and new routes are sometimes made by cloning old ones. So this won't change the MTU to known hosts
+ and may not change the MTU to new ones either... */
+ int max;
+ if ( get_ppc_cpu_type() == PPC_405EX && (ep->EMAC->mode1 & keEMACJumbo) != 0 )
+ max = ETHER_MAX_LEN_JUMBO;
+ else
+ max = ETHER_MAX_LEN;
+ if (reqP->ifr_mtu > max - ETHER_HDR_LEN - ETHER_CRC_LEN)
+ error = EINVAL;
+ else
+ ifp->if_mtu = reqP->ifr_mtu;
+ } break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ #ifdef qDebug
+ ppc405_emac_stats(ep);
+ #endif
+ break;
+
+ default:
+ /* Not handled here, pass to generic */
+ error = ether_ioctl(ifp,command,data);
+ break;
+ }
+
+ #ifdef qDebug
+ if (error != 0)
+ printf("--- Ethernet ioctl %d failed %d\n",(int)command,error);
+ #endif
+
+ return error;
+}
+
+
+/*----------------------- External attach function --------------------------
+ *
+ * This is the one function we are required to define in here: declared in bsp.h
+ * as RTEMS_BSP_NETWORK_DRIVER_ATTACH and called from rtems_bsdnet_attach
+ *
+*/
+
+int
+rtems_emac_driver_attach(struct rtems_bsdnet_ifconfig* config, int attaching)
+{
+ int unitNumber, nUnits;
+ char* unitName;
+ struct ifnet* ifp;
+ EMACLocals* ep;
+
+ if (attaching==0) {
+ printk ("EMAC: driver cannot be detached.\n");
+ return 0;
+ }
+
+ nUnits = 1;
+ if (get_ppc_cpu_type()==PPC_405EX && get_ppc_cpu_revision() > 0x1474)
+ nUnits = 2; /* PPC405EX has two interfaces, EXr has one */
+
+ unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName);
+ if (unitNumber < 0 || unitNumber > nUnits-1) {
+ printk ("EMAC: bad unit number %d.\n",unitNumber);
+ return 0;
+ }
+
+ ep = &gEmacs[unitNumber];
+
+ if (get_ppc_cpu_type()==PPC_405EX) {
+ if (unitNumber==0) ep->EMAC = (EthernetRegisters_EX*)EMAC0EXAddress;
+ else ep->EMAC = (EthernetRegisters_GP*)EMAC1EXAddress;
+ } else
+ ep->EMAC = (EthernetRegisters_GP*)EMAC0GPAddress;
+
+ ifp = &ep->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printk ("EMAC: driver already in use.\n");
+ return 0;
+ }
+ ifp->if_softc = ep;
+
+ if (config->hardware_address == 0)
+ rtems_panic("No Ethernet MAC address specified!");
+ memcpy (ep->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ ifp->if_name = unitName;
+ ifp->if_unit = unitNumber;
+
+ if (config->mtu != 0)
+ ifp->if_mtu = config->mtu;
+ else
+ ifp->if_mtu = ETHERMTU; /* May be adjusted later by ppc405_emac_phy_adapt() */
+
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ ifp->if_init = &ppc405_emac_init;
+ ifp->if_ioctl = ppc405_emac_ioctl;
+ ifp->if_start = ppc405_emac_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = ppc405_emac_watchdog;
+ ifp->if_timer = 0;
+
+ if (config->rbuf_count != 0) {
+ if (config->rbuf_count > 256) ep->nRxBuffers = 256;
+ else ep->nRxBuffers = config->rbuf_count;
+ } else
+ ep->nRxBuffers = nmbclusters/2;
+
+ ep->phyAddr = unitNumber+1;
+ ep->phyState = 0;
+
+ #ifdef qDebug
+ printf("\n Setting up EMAC %d of %d\n",unitNumber+1,nUnits);
+ printf(" MAC address is ");
+ printaddr(ep->arpcom.ac_enaddr);
+ printf(" MHLEN = %d, MINCLSIZE = %d MCLBYTES = %d\n",MHLEN,MINCLSIZE,MCLBYTES);
+ printf(" ticks/sec = %d, usec/tick = %d\n", rtems_bsdnet_ticks_per_second, rtems_bsdnet_microseconds_per_tick);
+ #endif
+
+ if_attach (ifp);
+ ether_ifattach (ifp);
+
+ return 1;
+}
+
diff --git a/bsps/powerpc/mpc55xxevb/net/if_smc.c b/bsps/powerpc/mpc55xxevb/net/if_smc.c
new file mode 100644
index 0000000..995bf0b
--- /dev/null
+++ b/bsps/powerpc/mpc55xxevb/net/if_smc.c
@@ -0,0 +1,161 @@
+#include <bsp.h>
+
+#ifdef HAS_SMC91111
+
+#include <mpc55xx/mpc55xx.h>
+#include <mpc55xx/regs.h>
+
+#include <rtems.h>
+
+#include <bsp/irq.h>
+#include <rtems/bspIo.h>
+#include <libcpu/powerpc-utility.h>
+
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdarg.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/irq-extension.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <libchip/smc91111exp.h>
+
+
+
+/* The SMC91111 on the MPC5554SOM is IRQ2.
+ */
+#define SMC91111_BASE_ADDR (void*)0x22000300
+#define SMC91111_BASE_IRQ MPC55XX_IRQ_SIU_EXTERNAL_2
+#define SMC91111_BASE_PIO 4
+
+extern void lan91cxx_interrupt_handler(void *arg);
+
+static const union SIU_EISR_tag clear_eisr_2 = {.B.EIF2 = 1};
+
+static void rtems_smc91111_interrupt_wrapper(void *arg)
+{
+ /* Clear external interrupt status */
+
+ SIU.EISR = clear_eisr_2;
+
+ lan91cxx_interrupt_handler(arg);
+}
+
+scmv91111_configuration_t mpc5554_scmv91111_configuration = {
+ SMC91111_BASE_ADDR, /* base address */
+ SMC91111_BASE_IRQ, /* vector number */
+ SMC91111_BASE_PIO, /* XXX: What's this? */
+ 100, /* 100b */
+ 1, /* fulldx */
+ 1, /* autoneg */
+ "SMC91111",
+ RTEMS_INTERRUPT_UNIQUE,
+ rtems_smc91111_interrupt_wrapper,
+ (void *)0
+};
+
+/*
+ * Attach an SMC91111 driver to the system
+ */
+int rtems_smc91111_driver_attach_mpc5554(struct rtems_bsdnet_ifconfig *config)
+{
+ /* Configure IRQ2 (GPIO pin 211) is set up properly:
+ * Secondary, Alternate, Input.
+ */
+ static const union SIU_PCR_tag irq_input_pcr = {
+ .B.PA = 2, /* Alternate function 1 */
+ .B.OBE = 0,
+ .B.IBE = 1, /* Input Buffer Enable */
+ .B.DSC = 0,
+ .B.ODE = 0,
+ .B.HYS = 1,
+ .B.SRC = 3, /* Maximum slew rate */
+ .B.WPE = 0, /* Disable weak pullup/pulldown */
+ .B.WPS = 1 /* Specify weak pullup? But it isn't enabled! */
+ };
+
+ union SIU_ORER_tag orer = MPC55XX_ZERO_FLAGS;
+ union SIU_DIRER_tag direr = MPC55XX_ZERO_FLAGS;
+ union SIU_IREER_tag ireer = MPC55XX_ZERO_FLAGS;
+ union SIU_IFEER_tag ifeer = MPC55XX_ZERO_FLAGS;
+ union SIU_IDFR_tag idfr = MPC55XX_ZERO_FLAGS;
+ union SIU_DIRSR_tag dirsr = MPC55XX_ZERO_FLAGS;
+ rtems_interrupt_level level;
+
+#define MPC55XX_EBI_CS_2_BR 0x22000003
+#define MPC55XX_EBI_CS_2_OR 0xff000010
+#if MPC55XX_EBI_CS_2_BR
+ static const union SIU_PCR_tag primary_50pf_weak_pullup = { /* 0x4c3 */
+ .B.PA = 1,
+ .B.DSC = 3,
+ .B.WPE = 1,
+ .B.WPS = 1
+ };
+ EBI.CS[2].BR.R = MPC55XX_EBI_CS_2_BR;
+ EBI.CS[2].OR.R = MPC55XX_EBI_CS_2_OR;
+ SIU.PCR[2] = primary_50pf_weak_pullup;
+#endif
+
+ SIU.PCR[211] = irq_input_pcr;
+
+ /* XXX These should be using bit set and bit clear instructions */
+
+ /* DMA/Interrupt Request Select */
+ rtems_interrupt_disable(level);
+ dirsr.R = SIU.DIRSR.R;
+ dirsr.B.DIRS2 = 0; /* Select interrupt not DMA */
+ SIU.DIRSR.R = dirsr.R;
+ rtems_interrupt_enable(level);
+
+ /* Overrun Request Enable */
+ rtems_interrupt_disable(level);
+ orer.R = SIU.ORER.R;
+ orer.B.ORE2 = 0; /* Disable overruns. */
+ SIU.ORER.R = orer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Rising-Edge Enable */
+ rtems_interrupt_disable(level);
+ ireer.R = SIU.IREER.R;
+ ireer.B.IREE2 = 1; /* Enable rising edge. */
+ SIU.IREER.R = ireer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Falling-Edge Enable */
+ rtems_interrupt_disable(level);
+ ifeer.R = SIU.IFEER.R;
+ ifeer.B.IFEE2 = 0; /* Disable falling edge. */
+ SIU.IFEER.R = ifeer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Digital Filter */
+ rtems_interrupt_disable(level);
+ idfr.R = SIU.IDFR.R;
+ idfr.B.DFL = 0; /* Minimal digital filter. */
+ SIU.IDFR.R = idfr.R;
+ rtems_interrupt_enable(level);
+
+ /* Clear external interrupt status */
+ SIU.EISR = clear_eisr_2;
+
+ /* DMA/Interrupt Request Enable */
+ rtems_interrupt_disable(level);
+ direr.R = SIU.DIRER.R;
+ direr.B.EIRE2 = 1; /* Enable. */
+ SIU.DIRER.R = direr.R;
+ rtems_interrupt_enable(level);
+
+ return _rtems_smc91111_driver_attach(config,&mpc5554_scmv91111_configuration);
+};
+
+#endif /* HAS_SMC91111 */
diff --git a/bsps/powerpc/mpc55xxevb/net/smsc9218i.c b/bsps/powerpc/mpc55xxevb/net/smsc9218i.c
new file mode 100644
index 0000000..d88aa8a
--- /dev/null
+++ b/bsps/powerpc/mpc55xxevb/net/smsc9218i.c
@@ -0,0 +1,2124 @@
+/**
+ * @file
+ *
+ * @ingroup RTEMSBSPsPowerPCMPC55XX
+ *
+ * @brief SMSC - LAN9218i
+ */
+
+/*
+ * Copyright (c) 2009-2012 embedded brains GmbH. All rights reserved.
+ *
+ * embedded brains GmbH
+ * Obere Lagerstr. 30
+ * 82178 Puchheim
+ * Germany
+ * <rtems@embedded-brains.de>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <rtems.h>
+
+#include <mpc55xx/regs.h>
+
+#if defined(RTEMS_NETWORKING) && defined(MPC55XX_HAS_SIU)
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <errno.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <inttypes.h>
+
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+
+#include <sys/param.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/mbuf.h>
+
+#include <net/if.h>
+#include <net/if_arp.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <netinet/in_systm.h>
+#include <netinet/ip.h>
+
+#include <mpc55xx/edma.h>
+
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <bsp/utility.h>
+#include <libcpu/powerpc-utility.h>
+#include <bsp/smsc9218i.h>
+
+#if MCLBYTES != 2048
+ #warning "unexpected MCLBYTES value"
+#endif
+
+#define ASSERT_SC(sc) assert((sc) == RTEMS_SUCCESSFUL)
+
+#define SMSC9218I_EVENT_TX RTEMS_EVENT_1
+
+#define SMSC9218I_EVENT_TX_START RTEMS_EVENT_2
+
+#define SMSC9218I_EVENT_TX_ERROR RTEMS_EVENT_3
+
+#define SMSC9218I_EVENT_RX RTEMS_EVENT_4
+
+#define SMSC9218I_EVENT_RX_ERROR RTEMS_EVENT_5
+
+#define SMSC9218I_EVENT_PHY RTEMS_EVENT_6
+
+#define SMSC9218I_EVENT_DMA RTEMS_EVENT_7
+
+#define SMSC9218I_EVENT_DMA_ERROR RTEMS_EVENT_8
+
+/* Adjust by two bytes for proper IP header alignment */
+#define SMSC9218I_RX_DATA_OFFSET 2
+
+#define SMSC9218I_RX_JOBS 32
+
+#define SMSC9218I_TX_JOBS 64
+
+/* Maximum number of fragments per frame, see manual section 3.11.3.2 */
+#define SMSC9218I_TX_FRAGMENT_MAX 86
+
+#if SMSC9218I_TX_JOBS > SMSC9218I_TX_FRAGMENT_MAX
+ #error "too many TX jobs"
+#endif
+
+#define SMSC9218I_IRQ_CFG_GLOBAL_ENABLE \
+ (SMSC9218I_IRQ_CFG_IRQ_EN | SMSC9218I_IRQ_CFG_IRQ_TYPE)
+
+#define SMSC9218I_IRQ_CFG_GLOBAL_DISABLE SMSC9218I_IRQ_CFG_IRQ_TYPE
+
+#define SMSC9218I_EDMA_RX_TCD_CDF 0x10004
+
+#define SMSC9218I_EDMA_RX_TCD_BMF 0x10003
+
+#define SMSC9218I_TCD_BMF_LINK 0x10011
+
+#define SMSC9218I_TCD_BMF_LAST 0x10003
+
+#define SMSC9218I_TCD_BMF_CLEAR 0x10000
+
+#define SMSC9218I_ERROR_INTERRUPTS \
+ (SMSC9218I_INT_TXSO \
+ | SMSC9218I_INT_RWT \
+ | SMSC9218I_INT_RXE \
+ | SMSC9218I_INT_TXE)
+
+#define SMSC9218I_UNLIKELY(x) __builtin_expect((x), 0)
+
+#ifdef DEBUG
+ #define SMSC9218I_PRINTF(...) printf(__VA_ARGS__)
+ #define SMSC9218I_PRINTK(...) printk(__VA_ARGS__)
+#else
+ #define SMSC9218I_PRINTF(...)
+ #define SMSC9218I_PRINTK(...)
+#endif
+
+typedef enum {
+ SMSC9218I_NOT_INITIALIZED,
+ SMSC9218I_CONFIGURED,
+ SMSC9218I_STARTED,
+ SMSC9218I_RUNNING
+} smsc9218i_state;
+
+static const char *const state_to_string [] = {
+ "NOT INITIALIZED",
+ "CONFIGURED",
+ "STARTED",
+ "RUNNING"
+};
+
+typedef struct {
+ struct arpcom arpcom;
+ struct rtems_mdio_info mdio;
+ smsc9218i_state state;
+ rtems_id receive_task;
+ rtems_id transmit_task;
+ edma_channel_context edma_receive;
+ edma_channel_context edma_transmit;
+ unsigned phy_interrupts;
+ unsigned received_frames;
+ unsigned receiver_errors;
+ unsigned receive_interrupts;
+ unsigned receive_dma_interrupts;
+ unsigned receive_too_long_errors;
+ unsigned receive_collision_errors;
+ unsigned receive_crc_errors;
+ unsigned receive_dma_errors;
+ unsigned receive_drop;
+ unsigned receive_watchdog_timeouts;
+ unsigned transmitted_frames;
+ unsigned transmitter_errors;
+ unsigned transmit_interrupts;
+ unsigned transmit_dma_interrupts;
+ unsigned transmit_status_overflows;
+ unsigned transmit_frame_errors;
+ unsigned transmit_dma_errors;
+} smsc9218i_driver_entry;
+
+typedef struct {
+ uint32_t a;
+ uint32_t b;
+} smsc9218i_transmit_command;
+
+typedef struct {
+ struct tcd_t command_tcd_table [SMSC9218I_TX_JOBS];
+ struct tcd_t data_tcd_table [SMSC9218I_TX_JOBS];
+ smsc9218i_transmit_command command_table [SMSC9218I_TX_JOBS];
+ struct mbuf *fragment_table [SMSC9218I_TX_JOBS];
+ struct mbuf *frame;
+ struct mbuf *next_fragment;
+ int empty_index;
+ int transfer_index;
+ int transfer_last_index;
+ int todo_index;
+ int empty;
+ int transfer;
+ int todo;
+ uint32_t frame_length;
+ uint32_t command_b;
+ uint16_t tag;
+ bool done;
+ unsigned frame_compact_count;
+} smsc9218i_transmit_job_control;
+
+typedef struct {
+ struct tcd_t tcd_table [SMSC9218I_RX_JOBS];
+ struct mbuf *mbuf_table [SMSC9218I_RX_JOBS];
+ int consume;
+ int done;
+ int produce;
+} smsc9218i_receive_job_control;
+
+static smsc9218i_receive_job_control smsc_rx_jc __attribute__((aligned (32)));
+
+static void smsc9218i_transmit_dma_done(
+ edma_channel_context *ctx,
+ uint32_t error_status
+);
+
+static void smsc9218i_receive_dma_done(
+ edma_channel_context *ctx,
+ uint32_t error_status
+);
+
+static smsc9218i_driver_entry smsc9218i_driver_data = {
+ .state = SMSC9218I_NOT_INITIALIZED,
+ .receive_task = RTEMS_ID_NONE,
+ .transmit_task = RTEMS_ID_NONE,
+ .edma_receive = {
+ .edma_tcd = EDMA_TCD_BY_CHANNEL_INDEX(SMSC9218I_EDMA_RX_CHANNEL),
+ .done = smsc9218i_receive_dma_done
+ },
+ .edma_transmit = {
+ .edma_tcd = EDMA_TCD_BY_CHANNEL_INDEX(SMSC9218I_EDMA_TX_CHANNEL),
+ .done = smsc9218i_transmit_dma_done
+ }
+};
+
+static rtems_interval smsc9218i_timeout_init(void)
+{
+ return rtems_clock_get_ticks_since_boot();
+}
+
+static bool smsc9218i_timeout_not_expired(rtems_interval start)
+{
+ rtems_interval elapsed = rtems_clock_get_ticks_since_boot() - start;
+
+ return elapsed < rtems_clock_get_ticks_per_second();
+}
+
+static bool smsc9218i_mac_wait(volatile smsc9218i_registers *regs)
+{
+ rtems_interval start = smsc9218i_timeout_init();
+ bool busy;
+
+ while (
+ (busy = (regs->mac_csr_cmd & SMSC9218I_MAC_CSR_CMD_BUSY) != 0)
+ && smsc9218i_timeout_not_expired(start)
+ ) {
+ /* Wait */
+ }
+
+ return !busy;
+}
+
+static bool smsc9218i_mac_write(
+ volatile smsc9218i_registers *regs,
+ uint32_t address,
+ uint32_t data
+)
+{
+ bool ok = smsc9218i_mac_wait(regs);
+
+ if (ok) {
+ regs->mac_csr_data = SMSC9218I_SWAP(data);
+ regs->mac_csr_cmd = SMSC9218I_MAC_CSR_CMD_BUSY
+ | SMSC9218I_MAC_CSR_CMD_ADDR(address);
+ ok = smsc9218i_mac_wait(regs);
+ }
+
+ return ok;
+}
+
+static uint32_t smsc9218i_mac_read(
+ volatile smsc9218i_registers *regs,
+ uint32_t address,
+ bool *ok_ptr
+)
+{
+ uint32_t mac_csr_data = 0;
+ bool ok = smsc9218i_mac_wait(regs);
+
+ if (ok) {
+ regs->mac_csr_cmd = SMSC9218I_MAC_CSR_CMD_BUSY
+ | SMSC9218I_MAC_CSR_CMD_READ
+ | SMSC9218I_MAC_CSR_CMD_ADDR(address);
+ ok = smsc9218i_mac_wait(regs);
+
+ if (ok) {
+ mac_csr_data = regs->mac_csr_data;
+ }
+ }
+
+ if (ok_ptr != NULL) {
+ *ok_ptr = ok;
+ }
+
+ return SMSC9218I_SWAP(mac_csr_data);
+}
+
+static bool smsc9218i_phy_wait(volatile smsc9218i_registers *regs)
+{
+ rtems_interval start = smsc9218i_timeout_init();
+ uint32_t mac_mii_acc;
+ bool busy;
+
+ do {
+ mac_mii_acc = smsc9218i_mac_read(regs, SMSC9218I_MAC_MII_ACC, NULL);
+ } while (
+ (busy = (mac_mii_acc & SMSC9218I_MAC_MII_ACC_BUSY) != 0)
+ && smsc9218i_timeout_not_expired(start)
+ );
+
+ return !busy;
+}
+
+static bool smsc9218i_phy_write(
+ volatile smsc9218i_registers *regs,
+ uint32_t address,
+ uint32_t data
+)
+{
+ bool ok = smsc9218i_phy_wait(regs);
+
+ if (ok) {
+ ok = smsc9218i_mac_write(regs, SMSC9218I_MAC_MII_DATA, data);
+
+ if (ok) {
+ ok = smsc9218i_mac_write(
+ regs,
+ SMSC9218I_MAC_MII_ACC,
+ SMSC9218I_MAC_MII_ACC_PHY_DEFAULT
+ | SMSC9218I_MAC_MII_ACC_BUSY
+ | SMSC9218I_MAC_MII_ACC_WRITE
+ | SMSC9218I_MAC_MII_ACC_ADDR(address)
+ );
+
+ if (ok) {
+ ok = smsc9218i_phy_wait(regs);
+ }
+ }
+ }
+
+ return ok;
+}
+
+static uint32_t smsc9218i_phy_read(
+ volatile smsc9218i_registers *regs,
+ uint32_t address
+)
+{
+ smsc9218i_phy_wait(regs);
+ smsc9218i_mac_write(
+ regs,
+ SMSC9218I_MAC_MII_ACC,
+ SMSC9218I_MAC_MII_ACC_PHY_DEFAULT
+ | SMSC9218I_MAC_MII_ACC_BUSY
+ | SMSC9218I_MAC_MII_ACC_ADDR(address)
+ );
+ smsc9218i_phy_wait(regs);
+ return smsc9218i_mac_read(regs, SMSC9218I_MAC_MII_DATA, NULL);
+}
+
+static bool smsc9218i_enable_promiscous_mode(
+ volatile smsc9218i_registers *regs,
+ bool enable
+)
+{
+ bool ok;
+ uint32_t mac_cr = smsc9218i_mac_read(regs, SMSC9218I_MAC_CR, &ok);
+
+ if (ok) {
+ uint32_t flags = SMSC9218I_MAC_CR_RXALL | SMSC9218I_MAC_CR_PRMS;
+
+ if (enable) {
+ mac_cr |= flags;
+ } else {
+ mac_cr &= ~flags;
+ }
+
+ ok = smsc9218i_mac_write(regs, SMSC9218I_MAC_CR, mac_cr);
+ }
+
+ return ok;
+}
+
+#if defined(DEBUG)
+static void smsc9218i_register_dump(volatile smsc9218i_registers *regs)
+{
+ uint32_t reg = 0;
+
+ reg = regs->id_rev;
+ printf(
+ "id_rev: 0x%08" PRIx32 " (ID = 0x%04" PRIx32
+ ", revision = 0x%04" PRIx32 ")\n",
+ SMSC9218I_SWAP(reg),
+ SMSC9218I_ID_REV_GET_ID(reg),
+ SMSC9218I_ID_REV_GET_REV(reg)
+ );
+
+ reg = regs->irq_cfg;
+ printf("irq_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->int_sts;
+ printf("int_sts: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->int_en;
+ printf("int_en: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->byte_test;
+ printf("byte_test: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->fifo_int;
+ printf("fifo_int: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->rx_cfg;
+ printf("rx_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->tx_cfg;
+ printf("tx_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->hw_cfg;
+ printf("hw_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->rx_dp_ctl;
+ printf("rx_dp_ctl: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->rx_fifo_inf;
+ printf(
+ "rx_fifo_inf: 0x%08" PRIx32 " (status used = %" PRIu32
+ ", data used = %" PRIu32 ")\n",
+ SMSC9218I_SWAP(reg),
+ SMSC9218I_RX_FIFO_INF_GET_SUSED(reg),
+ SMSC9218I_RX_FIFO_INF_GET_DUSED(reg)
+ );
+
+ reg = regs->tx_fifo_inf;
+ printf(
+ "tx_fifo_inf: 0x%08" PRIx32 " (status unused = %" PRIu32
+ ", free = %" PRIu32 ")\n",
+ SMSC9218I_SWAP(reg),
+ SMSC9218I_TX_FIFO_INF_GET_SUSED(reg),
+ SMSC9218I_TX_FIFO_INF_GET_FREE(reg)
+ );
+
+ reg = regs->pmt_ctrl;
+ printf("pmt_ctrl: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->gpio_cfg;
+ printf("gpio_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->gpt_cfg;
+ printf("gpt_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->gpt_cnt;
+ printf("gpt_cnt: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->word_swap;
+ printf("word_swap: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->free_run;
+ printf("free_run: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->rx_drop;
+ printf("rx_drop: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ reg = regs->afc_cfg;
+ printf("afc_cfg: 0x%08" PRIx32 "\n", SMSC9218I_SWAP(reg));
+
+ printf("mac: cr: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_CR, NULL));
+ printf("mac: addrh: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_ADDRH, NULL));
+ printf("mac: addrl: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_ADDRL, NULL));
+ printf("mac: hashh: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_HASHH, NULL));
+ printf("mac: hashl: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_HASHL, NULL));
+ printf("mac: mii_acc: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_MII_ACC, NULL));
+ printf("mac: mii_data: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_MII_DATA, NULL));
+ printf("mac: flow: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_FLOW, NULL));
+ printf("mac: vlan1: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_VLAN1, NULL));
+ printf("mac: vlan2: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_VLAN2, NULL));
+ printf("mac: wuff: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_WUFF, NULL));
+ printf("mac: wucsr: 0x%08" PRIx32 "\n", smsc9218i_mac_read(regs, SMSC9218I_MAC_WUCSR, NULL));
+
+ printf("phy: bcr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_BMCR));
+ printf("phy: bsr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_BMSR));
+ printf("phy: id1: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_PHYIDR1));
+ printf("phy: id2: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_PHYIDR2));
+ printf("phy: anar: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_ANAR));
+ printf("phy: anlpar: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_ANLPAR));
+ printf("phy: anexpr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, MII_ANER));
+ printf("phy: mcsr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_MCSR));
+ printf("phy: spmodes: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_SPMODES));
+ printf("phy: cisr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_CSIR));
+ printf("phy: isr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_ISR));
+ printf("phy: imr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_IMR));
+ printf("phy: physcsr: 0x%08" PRIx32 "\n", smsc9218i_phy_read(regs, SMSC9218I_PHY_PHYSCSR));
+}
+#endif
+
+static void smsc9218i_flush_tcd(struct tcd_t *tcd)
+{
+ ppc_data_cache_block_store(tcd);
+}
+
+static uint32_t smsc9218i_align_up(uint32_t val)
+{
+ return 4U + ((val - 1U) & ~0x3U);
+}
+
+static void smsc9218i_discard_frame(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs,
+ uint32_t rx_fifo_status,
+ uint32_t frame_length,
+ uint32_t data_length
+)
+{
+ /* Update error counters */
+ if ((rx_fifo_status & SMSC9218I_RX_STS_ERROR_TOO_LONG) != 0) {
+ ++e->receive_too_long_errors;
+ }
+ if ((rx_fifo_status & SMSC9218I_RX_STS_ERROR_COLLISION) != 0) {
+ ++e->receive_collision_errors;
+ }
+ if ((rx_fifo_status & SMSC9218I_RX_STS_ERROR_CRC) != 0) {
+ ++e->receive_crc_errors;
+ }
+
+ /* Discard frame */
+ if (frame_length > 16) {
+ /* Fast forward */
+ regs->rx_dp_ctl = SMSC9218I_RX_DP_CTRL_FFWD;
+
+ while ((regs->rx_dp_ctl & SMSC9218I_RX_DP_CTRL_FFWD) != 0) {
+ /* Wait */
+ }
+ } else {
+ uint32_t len = data_length / 4;
+ uint32_t i = 0;
+
+ /* Discard data */
+ for (i = 0; i < len; ++i) {
+ regs->rx_fifo_data;
+ }
+ }
+}
+
+static void smsc9218i_setup_receive_dma(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs,
+ smsc9218i_receive_job_control *jc
+)
+{
+ int c = jc->consume;
+ int p = jc->produce;
+ int np = (p + 1) % SMSC9218I_RX_JOBS;
+ struct tcd_t *first = &jc->tcd_table [p];
+ struct tcd_t *last = NULL;
+
+ while (np != c) {
+ uint32_t rx_fifo_inf = 0;
+ uint32_t status_used = 0;
+
+ /* Clear FIFO level status */
+ regs->int_sts = SMSC9218I_INT_RSFL;
+
+ /* Next FIFO status */
+ rx_fifo_inf = regs->rx_fifo_inf;
+ status_used = SMSC9218I_RX_FIFO_INF_GET_SUSED(rx_fifo_inf);
+
+ if (status_used > 0) {
+ uint32_t status = regs->rx_fifo_status;
+ uint32_t frame_length = SMSC9218I_RX_STS_GET_LENGTH(status);
+ uint32_t data_length = smsc9218i_align_up(
+ SMSC9218I_RX_DATA_OFFSET + frame_length
+ );
+ bool frame_ok = (status & SMSC9218I_RX_STS_ERROR) == 0;
+
+ if (frame_ok) {
+ struct mbuf *m = jc->mbuf_table [p];
+ int mbuf_length = (int) frame_length - ETHER_HDR_LEN - ETHER_CRC_LEN;
+ struct tcd_t *current = &jc->tcd_table [p];
+
+ m->m_len = mbuf_length;
+ m->m_pkthdr.len = mbuf_length;
+
+ current->NBYTES = data_length;
+ smsc9218i_flush_tcd(current);
+
+ last = current;
+ p = np;
+ np = (p + 1) % SMSC9218I_RX_JOBS;
+ } else {
+ smsc9218i_discard_frame(e, regs, status, frame_length, data_length);
+ }
+ } else {
+ break;
+ }
+ }
+
+ jc->produce = p;
+
+ if (last != NULL) {
+ volatile struct tcd_t *channel = e->edma_receive.edma_tcd;
+
+ /* Setup last TCD */
+ last->BMF.R = SMSC9218I_TCD_BMF_LAST;
+ smsc9218i_flush_tcd(last);
+ ppc_synchronize_data();
+
+ /* Start eDMA transfer */
+ channel->SADDR = first->SADDR;
+ channel->SDF.R = first->SDF.R;
+ channel->NBYTES = first->NBYTES;
+ channel->SLAST = first->SLAST;
+ channel->DADDR = first->DADDR;
+ channel->CDF.R = first->CDF.R;
+ channel->DLAST_SGA = first->DLAST_SGA;
+ channel->BMF.R = SMSC9218I_TCD_BMF_CLEAR;
+ channel->BMF.R = first->BMF.R;
+ }
+}
+
+static void smsc9218i_receive_dma_done(
+ edma_channel_context *ctx,
+ uint32_t error_status
+)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ smsc9218i_driver_entry *e = &smsc9218i_driver_data;
+ smsc9218i_receive_job_control *jc = &smsc_rx_jc;
+
+ SMSC9218I_PRINTK(
+ "edma: id = 0x%08x, error status = 0x%08x\n",
+ channel_entry->id,
+ error_status
+ );
+
+ ++e->receive_dma_interrupts;
+ if (SMSC9218I_UNLIKELY(error_status != 0)) {
+ ++e->receive_dma_errors;
+ }
+
+ sc = rtems_bsdnet_event_send(e->receive_task, SMSC9218I_EVENT_DMA);
+ ASSERT_SC(sc);
+
+ jc->done = jc->produce;
+}
+
+static void smsc9218i_transmit_dma_done(
+ edma_channel_context *ctx,
+ uint32_t error_status
+)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ smsc9218i_driver_entry *e = &smsc9218i_driver_data;
+ rtems_event_set event = error_status == 0 ?
+ SMSC9218I_EVENT_DMA : SMSC9218I_EVENT_DMA_ERROR;
+
+ SMSC9218I_PRINTK(
+ "edma: id = 0x%08x, error status = 0x%08x\n",
+ channel_entry->id,
+ error_status
+ );
+
+ ++e->transmit_dma_interrupts;
+
+ sc = rtems_bsdnet_event_send(e->transmit_task, event);
+ ASSERT_SC(sc);
+}
+
+static void smsc9218i_interrupt_handler(void *arg)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) arg;
+ volatile smsc9218i_registers *const regs = smsc9218i;
+ uint32_t int_en = regs->int_en;
+ uint32_t int_sts = regs->int_sts & int_en;
+ #ifdef DEBUG
+ uint32_t irq_cfg = regs->irq_cfg;
+ #endif
+
+ /* Get interrupt status */
+ SMSC9218I_PRINTK(
+ "interrupt: irq_cfg = 0x%08x, int_sts = 0x%08x, int_en = 0x%08x\n",
+ SMSC9218I_SWAP(irq_cfg),
+ SMSC9218I_SWAP(int_sts),
+ SMSC9218I_SWAP(int_en)
+ );
+
+ /* Disable module interrupts */
+ regs->irq_cfg = SMSC9218I_IRQ_CFG_GLOBAL_DISABLE;
+
+ /* Clear external interrupt status */
+ SIU.EISR.R = 1;
+
+ /* Clear interrupts */
+ regs->int_sts = int_sts;
+
+ /* Error interrupts */
+ if (SMSC9218I_UNLIKELY((int_sts & SMSC9218I_ERROR_INTERRUPTS) != 0)) {
+ if ((int_sts & SMSC9218I_INT_TXSO) != 0) {
+ ++e->transmit_status_overflows;
+ }
+ if ((int_sts & SMSC9218I_INT_RWT) != 0) {
+ ++e->receive_watchdog_timeouts;
+ }
+ if ((int_sts & SMSC9218I_INT_RXE) != 0) {
+ ++e->receiver_errors;
+ }
+ if ((int_sts & SMSC9218I_INT_TXE) != 0) {
+ ++e->transmitter_errors;
+ }
+ }
+
+ /* Check receive interrupts */
+ if ((int_sts & SMSC9218I_INT_RSFL) != 0) {
+ int_en &= ~SMSC9218I_INT_RSFL;
+ ++e->receive_interrupts;
+
+ sc = rtems_bsdnet_event_send(e->receive_task, SMSC9218I_EVENT_RX);
+ ASSERT_SC(sc);
+ }
+
+ /* Check PHY interrupts */
+ if (SMSC9218I_UNLIKELY((int_sts & SMSC9218I_INT_PHY) != 0)) {
+ SMSC9218I_PRINTK("interrupt: phy\n");
+ int_en &= ~SMSC9218I_INT_PHY;
+ ++e->phy_interrupts;
+ sc = rtems_bsdnet_event_send(e->receive_task, SMSC9218I_EVENT_PHY);
+ ASSERT_SC(sc);
+ }
+
+ /* Check transmit interrupts */
+ if ((int_sts & SMSC9218I_INT_TDFA) != 0) {
+ SMSC9218I_PRINTK("interrupt: transmit\n");
+ int_en &= ~SMSC9218I_INT_TDFA;
+ ++e->transmit_interrupts;
+ sc = rtems_bsdnet_event_send(e->transmit_task, SMSC9218I_EVENT_TX);
+ ASSERT_SC(sc);
+ }
+
+ /* Update interrupt enable */
+ regs->int_en = int_en;
+
+ /* Enable module interrupts */
+ regs->irq_cfg = SMSC9218I_IRQ_CFG_GLOBAL_ENABLE;
+}
+
+static void smsc9218i_enable_transmit_interrupts(
+ volatile smsc9218i_registers *regs
+)
+{
+ rtems_interrupt_level level;
+
+ rtems_interrupt_disable(level);
+ regs->int_en |= SMSC9218I_INT_TDFA;
+ rtems_interrupt_enable(level);
+}
+
+static void smsc9218i_enable_phy_interrupts(
+ volatile smsc9218i_registers *regs
+)
+{
+ rtems_interrupt_level level;
+
+ rtems_interrupt_disable(level);
+ regs->int_en |= SMSC9218I_INT_PHY;
+ rtems_interrupt_enable(level);
+}
+
+static void smsc9218i_phy_clear_interrupts(
+ volatile smsc9218i_registers *regs
+)
+{
+ smsc9218i_phy_read(regs, SMSC9218I_PHY_ISR);
+}
+
+static bool smsc9218i_media_status(smsc9218i_driver_entry *e, int *media)
+{
+ struct ifnet *ifp = &e->arpcom.ac_if;
+
+ *media = IFM_MAKEWORD(0, 0, 0, SMSC9218I_MAC_MII_ACC_PHY_DEFAULT);
+
+ return (*ifp->if_ioctl)(ifp, SIOCGIFMEDIA, (caddr_t) media) == 0;
+}
+
+static void smsc9218i_media_status_change(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs
+)
+{
+ int media = 0;
+ bool media_ok = false;
+ uint32_t mac_cr = 0;
+
+ smsc9218i_phy_clear_interrupts(regs);
+ smsc9218i_enable_phy_interrupts(regs);
+
+ media_ok = smsc9218i_media_status(e, &media);
+ mac_cr = smsc9218i_mac_read(regs, SMSC9218I_MAC_CR, NULL);
+ if (media_ok && (IFM_OPTIONS(media) & IFM_FDX) == 0) {
+ mac_cr &= ~SMSC9218I_MAC_CR_FDPX;
+ } else {
+ mac_cr |= SMSC9218I_MAC_CR_FDPX;
+ }
+ smsc9218i_mac_write(regs, SMSC9218I_MAC_CR, mac_cr);
+}
+
+static bool smsc9218i_new_mbuf(
+ struct ifnet *ifp,
+ smsc9218i_receive_job_control *jc,
+ int i,
+ struct mbuf *old_m
+)
+{
+ bool ok = false;
+ int wait = old_m != NULL ? M_DONTWAIT : M_WAIT;
+ struct mbuf *new_m = m_gethdr(wait, MT_DATA);
+ struct tcd_t *tcd = &jc->tcd_table [i];
+ char *data = NULL;
+
+ if (new_m != NULL ) {
+ new_m->m_pkthdr.rcvif = ifp;
+ MCLGET(new_m, wait);
+
+ if ((new_m->m_flags & M_EXT) != 0) {
+ ok = true;
+ } else {
+ m_free(new_m);
+ new_m = old_m;
+ }
+ } else {
+ new_m = old_m;
+ }
+
+ data = mtod(new_m, char *);
+ new_m->m_data = data + SMSC9218I_RX_DATA_OFFSET + ETHER_HDR_LEN;
+
+ jc->mbuf_table [i] = new_m;
+
+ tcd->DADDR = (uint32_t) data;
+ tcd->BMF.R = SMSC9218I_TCD_BMF_LINK;
+
+ /* FIXME: This is maybe a problem in case of a lot of small frames */
+ rtems_cache_invalidate_multiple_data_lines(
+ data,
+ SMSC9218I_RX_DATA_OFFSET + ETHER_HDR_LEN + ETHERMTU + ETHER_CRC_LEN
+ );
+
+ return ok;
+}
+
+static void smsc9218i_init_receive_jobs(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs,
+ volatile smsc9218i_registers *regs_dma,
+ smsc9218i_receive_job_control *jc
+)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ struct ifnet *ifp = &e->arpcom.ac_if;
+ int i = 0;
+
+ /* Obtain receive eDMA channel */
+ sc = mpc55xx_edma_obtain_channel(
+ &e->edma_receive,
+ MPC55XX_INTC_DEFAULT_PRIORITY
+ );
+ ASSERT_SC(sc);
+
+ for (i = 0; i < SMSC9218I_RX_JOBS; ++i) {
+ struct tcd_t *tcd = &jc->tcd_table [i];
+ struct tcd_t *next_tcd = &jc->tcd_table [(i + 1) % SMSC9218I_RX_JOBS];
+
+ tcd->SADDR = (uint32_t) &regs_dma->rx_fifo_data;
+ tcd->SDF.B.SSIZE = 0x2;
+ tcd->SDF.B.DSIZE = 0x2;
+ tcd->CDF.B.CITER = 1;
+ tcd->CDF.B.DOFF = 4;
+ tcd->DLAST_SGA = (int32_t) next_tcd;
+
+ smsc9218i_new_mbuf(ifp, jc, i, NULL);
+ }
+}
+
+static void smsc9218i_ether_input(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs,
+ smsc9218i_receive_job_control *jc
+)
+{
+ rtems_interrupt_level level;
+ struct ifnet *ifp = &e->arpcom.ac_if;
+ int c = jc->consume;
+ int d = jc->done;
+
+ while (c != d) {
+ struct mbuf *m = jc->mbuf_table [c];
+ struct ether_header *eh = (struct ether_header *)
+ (mtod(m, char *) - ETHER_HDR_LEN);
+
+ ++e->received_frames;
+ if (smsc9218i_new_mbuf(ifp, jc, c, m)) {
+ ether_input(ifp, eh, m);
+ }
+
+ c = (c + 1) % SMSC9218I_RX_JOBS;
+ }
+
+ jc->consume = c;
+
+ rtems_interrupt_disable(level);
+ /* Enabling the receive interrupts while the DMA is active leads to chaos */
+ if (c == jc->produce) {
+ regs->int_en |= SMSC9218I_INT_RSFL;
+ }
+ rtems_interrupt_enable(level);
+}
+
+static void smsc9218i_receive_task(void *arg)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ rtems_interrupt_level level;
+ smsc9218i_receive_job_control *jc = &smsc_rx_jc;
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) arg;
+ volatile smsc9218i_registers *const regs = smsc9218i;
+ volatile smsc9218i_registers *const regs_dma = smsc9218i_dma;
+ uint32_t mac_cr = 0;
+
+ smsc9218i_init_receive_jobs(e, regs, regs_dma, jc);
+
+ /* Configure receiver */
+ regs->rx_cfg = SMSC9218I_RX_CFG_END_ALIGN_4
+ | SMSC9218I_RX_CFG_DOFF(SMSC9218I_RX_DATA_OFFSET);
+
+ /* Enable MAC receiver */
+ mac_cr = smsc9218i_mac_read(regs, SMSC9218I_MAC_CR, NULL);
+ mac_cr |= SMSC9218I_MAC_CR_RXEN;
+ smsc9218i_mac_write(regs, SMSC9218I_MAC_CR, mac_cr);
+
+ /* Enable receive interrupts */
+ rtems_interrupt_disable(level);
+ regs->int_en |= SMSC9218I_INT_RSFL;
+ rtems_interrupt_enable(level);
+
+ /* Enable PHY interrupts */
+ smsc9218i_phy_write(
+ regs,
+ SMSC9218I_PHY_IMR,
+ SMSC9218I_PHY_IMR_INT4 | SMSC9218I_PHY_IMR_INT6
+ );
+ smsc9218i_enable_phy_interrupts(regs);
+
+ while (true) {
+ rtems_event_set events;
+
+ sc = rtems_bsdnet_event_receive(
+ SMSC9218I_EVENT_DMA | SMSC9218I_EVENT_PHY | SMSC9218I_EVENT_RX,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events
+ );
+ ASSERT_SC(sc);
+
+ if ((events & (SMSC9218I_EVENT_RX | SMSC9218I_EVENT_DMA)) != 0) {
+ smsc9218i_setup_receive_dma(e, regs, jc);
+ }
+
+ if ((events & SMSC9218I_EVENT_DMA) != 0) {
+ smsc9218i_ether_input(e, regs, jc);
+ }
+
+ if ((events & SMSC9218I_EVENT_PHY) != 0) {
+ smsc9218i_media_status_change(e, regs);
+ }
+ }
+}
+
+#if defined(DEBUG)
+static void smsc9218i_transmit_job_dump(
+ smsc9218i_transmit_job_control *jc,
+ const char *msg
+)
+{
+ char out [SMSC9218I_TX_JOBS + 1];
+ int c = 0;
+ int s = 0;
+
+ out [SMSC9218I_TX_JOBS] = '\0';
+
+ memset(out, '?', SMSC9218I_TX_JOBS);
+
+ c = jc->todo_index;
+ s = jc->empty;
+ while (s > 0) {
+ out [c] = 'E';
+ --s;
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ c = jc->transfer_index;
+ s = jc->todo;
+ while (s > 0) {
+ out [c] = 'T';
+ --s;
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ c = jc->empty_index;
+ s = jc->transfer;
+ while (s > 0) {
+ out [c] = 'D';
+ --s;
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ printf(
+ "tx: %s: %02u:%02u:%02u %s\n",
+ msg,
+ jc->empty,
+ jc->todo,
+ jc->transfer,
+ out
+ );
+}
+#endif /* defined(DEBUG) */
+
+static struct mbuf *smsc9218i_compact_frame(
+ smsc9218i_transmit_job_control *jc,
+ uint32_t frame_length
+)
+{
+ struct mbuf *old_m = jc->frame;
+ struct mbuf *new_m = m_gethdr(M_WAIT, MT_DATA);
+ char *data = NULL;
+
+ ++jc->frame_compact_count;
+
+ MCLGET(new_m, M_WAIT);
+ data = mtod(new_m, char *);
+
+ new_m->m_len = (int) frame_length;
+ new_m->m_pkthdr.len = (int) frame_length;
+
+ while (old_m != NULL) {
+ size_t len = (size_t) old_m->m_len;
+ memcpy(data, mtod(old_m, void *), len);
+ data += len;
+ old_m = m_free(old_m);
+ }
+
+ jc->frame = new_m;
+
+ return new_m;
+}
+
+static struct mbuf *smsc9218i_next_transmit_fragment(
+ struct ifnet *ifp,
+ smsc9218i_transmit_job_control *jc
+)
+{
+ struct mbuf *m = jc->next_fragment;
+
+ if (m != NULL) {
+ /* Next fragment is from the current frame */
+ jc->next_fragment = m->m_next;
+ } else {
+ /* Dequeue first fragment of the next frame */
+ IF_DEQUEUE(&ifp->if_snd, m);
+
+ /* Update frame head */
+ jc->frame = m;
+
+ if (m != NULL) {
+ struct mbuf *n = m;
+ struct mbuf *p = NULL;
+ uint32_t frame_length = 0;
+ unsigned fragments = 0;
+ bool tiny = false;
+
+ /* Calculate frame length and fragment number */
+ do {
+ int len = n->m_len;
+
+ if (len > 0) {
+ ++fragments;
+ frame_length += (uint32_t) len;
+ tiny = tiny || len < 4;
+
+ /* Next fragment */
+ p = n;
+ n = n->m_next;
+ } else {
+ /* Discard empty fragment and get next */
+ n = m_free(n);
+
+ /* Remove fragment from list */
+ if (p != NULL) {
+ p->m_next = n;
+ } else {
+ jc->frame = n;
+ }
+ }
+ } while (n != NULL);
+
+ if (SMSC9218I_UNLIKELY(tiny || fragments > SMSC9218I_TX_JOBS)) {
+ fragments = 1;
+ m = smsc9218i_compact_frame(jc, frame_length);
+ }
+
+ /* Set frame length */
+ jc->frame_length = frame_length;
+
+ /* Update next fragment */
+ jc->next_fragment = jc->frame->m_next;
+
+ /* Update tag */
+ ++jc->tag;
+
+ /* Command B */
+ jc->command_b = ((uint32_t) SMSC9218I_TX_B_TAG(jc->tag))
+ | SMSC9218I_TX_B_FRAME_LENGTH(jc->frame_length);
+
+ SMSC9218I_PRINTF(
+ "tx: next frame: tag = %i, frame length = %" PRIu32
+ ", fragments = %u\n",
+ jc->tag,
+ frame_length,
+ fragments
+ );
+ } else {
+ /* The transmit queue is empty, we have no next fragment */
+ jc->next_fragment = NULL;
+
+ /* Interface is now inactive */
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ /* Transmit task may wait for events */
+ jc->done = true;
+
+ SMSC9218I_PRINTF("tx: inactive\n");
+ }
+ }
+
+ return m;
+}
+
+static void smsc9218i_transmit_create_jobs(
+ smsc9218i_transmit_job_control *jc,
+ volatile smsc9218i_registers *const regs,
+ struct ifnet *ifp
+)
+{
+ int n = jc->empty;
+
+ if (n > 0) {
+ int c = jc->todo_index;
+ int i = 0;
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "create");
+ #endif
+
+ for (i = 0; i < n; ++i) {
+ struct mbuf *m = smsc9218i_next_transmit_fragment(ifp, jc);
+
+ if (m != NULL) {
+ uint32_t first = m == jc->frame ? SMSC9218I_TX_A_FIRST : 0;
+ uint32_t last = m->m_next == NULL ? SMSC9218I_TX_A_LAST : 0;
+ uint32_t fragment_length = (uint32_t) m->m_len;
+ uint32_t fragment_misalign = (uint32_t) (mtod(m, uintptr_t) % 4);
+ uint32_t data_length = fragment_misalign + fragment_length;
+ uint32_t data_misalign = data_length % 4;
+ uint32_t data = (uint32_t) (mtod(m, char *) - fragment_misalign);
+
+ /* Align data length on four byte boundary */
+ if (data_misalign > 0) {
+ data_length += 4 - data_misalign;
+ }
+
+ /* Cache flush for fragment data */
+ rtems_cache_flush_multiple_data_lines(
+ (const void *) data,
+ data_length
+ );
+
+ /* Remember fragement */
+ jc->fragment_table [c] = m;
+
+ /* Command A and B */
+ jc->command_table [c].a = SMSC9218I_TX_A_END_ALIGN_4
+ | SMSC9218I_TX_A_DOFF(fragment_misalign)
+ | SMSC9218I_TX_A_FRAGMENT_LENGTH(fragment_length)
+ | first
+ | last;
+ jc->command_table [c].b = jc->command_b;
+
+ /* Data TCD */
+ jc->data_tcd_table [c].SADDR = data;
+ jc->data_tcd_table [c].NBYTES = data_length;
+
+ SMSC9218I_PRINTF("tx: create: index = %u\n", c);
+ } else {
+ /* Nothing to do */
+ break;
+ }
+
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ /* Increment jobs to do */
+ jc->todo += i;
+
+ /* Decrement empty count */
+ jc->empty -= i;
+
+ /* Update todo index */
+ jc->todo_index = c;
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "create done");
+ #endif
+ } else {
+ /* Transmit task may wait for events */
+ jc->done = true;
+ }
+}
+
+static void smsc9218i_transmit_do_jobs(
+ smsc9218i_transmit_job_control *jc,
+ volatile smsc9218i_registers *const regs,
+ smsc9218i_driver_entry *e
+)
+{
+ if (jc->transfer == 0) {
+ uint32_t tx_fifo_inf = regs->tx_fifo_inf;
+ uint32_t data_free = SMSC9218I_TX_FIFO_INF_GET_FREE(tx_fifo_inf);
+ int c = jc->transfer_index;
+ int last_index = c;
+ int i = 0;
+ int n = jc->todo;
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "transfer");
+ #endif
+
+ for (i = 0; i < n; ++i) {
+ struct tcd_t *tcd = &jc->data_tcd_table [c];
+ uint32_t data_length = tcd->NBYTES + 14;
+
+ if (data_length <= data_free) {
+ /* Reduce free FIFO space */
+ data_free -= data_length;
+
+ /* Index of last TCD */
+ last_index = c;
+
+ /* Cache flush for data TCD */
+ smsc9218i_flush_tcd(tcd);
+ } else {
+ break;
+ }
+
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ if (i > 0) {
+ volatile struct tcd_t *channel = e->edma_transmit.edma_tcd;
+ struct tcd_t *start = &jc->command_tcd_table [jc->transfer_index];
+ struct tcd_t *last = &jc->data_tcd_table [last_index];
+
+ /* New transfer index */
+ jc->transfer_index = c;
+
+ /* New last transfer index */
+ jc->transfer_last_index = last_index;
+
+ /* Set jobs in transfer */
+ jc->transfer = i;
+
+ /* Decrement jobs to do */
+ jc->todo -= i;
+
+ /* Cache flush for command table */
+ rtems_cache_flush_multiple_data_lines(
+ jc->command_table,
+ sizeof(jc->command_table)
+ );
+
+ /* Enable interrupt for last data TCD */
+ last->BMF.R = SMSC9218I_TCD_BMF_LAST;
+ smsc9218i_flush_tcd(last);
+ ppc_synchronize_data();
+
+ /* Start eDMA transfer */
+ channel->SADDR = start->SADDR;
+ channel->SDF.R = start->SDF.R;
+ channel->NBYTES = start->NBYTES;
+ channel->SLAST = start->SLAST;
+ channel->DADDR = start->DADDR;
+ channel->CDF.R = start->CDF.R;
+ channel->DLAST_SGA = start->DLAST_SGA;
+ channel->BMF.R = SMSC9218I_TCD_BMF_CLEAR;
+ channel->BMF.R = start->BMF.R;
+
+ /* Transmit task may wait for events */
+ jc->done = true;
+ } else if (n > 0) {
+ /* We need to wait until the FIFO has more free space */
+ smsc9218i_enable_transmit_interrupts(regs);
+
+ /* Transmit task may wait for events */
+ jc->done = true;
+ }
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "transfer done");
+ #endif
+ }
+}
+
+static void smsc9218i_transmit_finish_jobs(
+ smsc9218i_transmit_job_control *jc,
+ volatile smsc9218i_registers *const regs,
+ smsc9218i_driver_entry *e,
+ rtems_event_set events
+)
+{
+ uint32_t tx_fifo_inf = regs->tx_fifo_inf;
+ uint32_t status_used = SMSC9218I_TX_FIFO_INF_GET_SUSED(tx_fifo_inf);
+ uint32_t s = 0;
+ int n = jc->transfer;
+
+ for (s = 0; s < status_used; ++s) {
+ uint32_t tx_fifo_status = regs->tx_fifo_status;
+
+ if ((tx_fifo_status & SMSC9218I_TX_STS_ERROR) == 0) {
+ ++e->transmitted_frames;
+ } else {
+ ++e->transmit_frame_errors;
+ }
+
+ SMSC9218I_PRINTF(
+ "tx: transmit status: tag = %" PRIu32 ", status = 0x%08" PRIx32 "\n",
+ SMSC9218I_TX_STS_GET_TAG(tx_fifo_status),
+ SMSC9218I_SWAP(tx_fifo_status)
+ );
+ }
+
+ if (
+ (events & (SMSC9218I_EVENT_DMA | SMSC9218I_EVENT_DMA_ERROR)) != 0
+ && n > 0
+ ) {
+ int c = jc->empty_index;
+ int i = 0;
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "finish");
+ #endif
+
+ if ((events & SMSC9218I_EVENT_DMA_ERROR) != 0) {
+ ++e->transmit_dma_errors;
+ }
+
+ /* Restore last data TCD */
+ jc->data_tcd_table [jc->transfer_last_index].BMF.R =
+ SMSC9218I_TCD_BMF_LINK;
+
+ for (i = 0; i < n; ++i) {
+ /* Free fragment buffer */
+ m_free(jc->fragment_table [c]);
+
+ c = (c + 1) % SMSC9218I_TX_JOBS;
+ }
+
+ /* Increment empty count */
+ jc->empty += n;
+
+ /* New empty index */
+ jc->empty_index = jc->transfer_index;
+
+ /* Clear jobs in transfer */
+ jc->transfer = 0;
+
+ /* Update empty index */
+ jc->empty_index = c;
+
+ #ifdef DEBUG
+ smsc9218i_transmit_job_dump(jc, "finish done");
+ #endif
+ }
+}
+
+/* FIXME */
+static smsc9218i_transmit_job_control smsc_tx_jc __attribute__((aligned (32))) = {
+ .frame = NULL,
+ .next_fragment = NULL,
+ .frame_length = 0,
+ .tag = 0,
+ .command_b = 0,
+ .done = false,
+ .empty_index = 0,
+ .transfer_index = 0,
+ .todo_index = 0,
+ .empty = SMSC9218I_TX_JOBS,
+ .transfer = 0,
+ .todo = 0
+};
+
+static void smsc9218i_transmit_task(void *arg)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ rtems_event_set events = 0;
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) arg;
+ struct ifnet *ifp = &e->arpcom.ac_if;
+ volatile smsc9218i_registers *const regs = smsc9218i;
+ volatile smsc9218i_registers *const regs_dma = smsc9218i_dma;
+ uint32_t mac_cr = 0;
+ smsc9218i_transmit_job_control *jc = &smsc_tx_jc;
+ unsigned i = 0;
+
+ SMSC9218I_PRINTF("%s\n", __func__);
+
+ /* Obtain transmit eDMA channel */
+ sc = mpc55xx_edma_obtain_channel(
+ &e->edma_transmit,
+ MPC55XX_INTC_DEFAULT_PRIORITY
+ );
+ ASSERT_SC(sc);
+
+ /* Setup transmit eDMA descriptors */
+ for (i = 0; i < SMSC9218I_TX_JOBS; ++i) {
+ unsigned ii = (i + 1) % SMSC9218I_TX_JOBS;
+ struct tcd_t tcd = EDMA_TCD_DEFAULT;
+ struct tcd_t *command_tcd = &jc->command_tcd_table [i];
+ struct tcd_t *data_tcd = &jc->data_tcd_table [i];
+ struct tcd_t *next_command_tcd = &jc->command_tcd_table [ii];
+
+ tcd.SDF.B.SSIZE = 2;
+ tcd.SDF.B.SOFF = 4;
+ tcd.SDF.B.DSIZE = 2;
+ tcd.CDF.B.CITER = 1;
+ tcd.BMF.R = SMSC9218I_TCD_BMF_LINK;
+
+ tcd.DADDR = (uint32_t) &regs_dma->tx_fifo_data;
+ tcd.DLAST_SGA = (int32_t) next_command_tcd;
+ *data_tcd = tcd;
+
+ tcd.DADDR = (uint32_t) &regs->tx_fifo_data;
+ tcd.SADDR = (uint32_t) &jc->command_table [i].a;
+ tcd.NBYTES = 8;
+ tcd.DLAST_SGA = (int32_t) data_tcd;
+ *command_tcd = tcd;
+ }
+
+ /*
+ * Cache flush for command TCD. The content of the command TCD remains
+ * invariant.
+ */
+ rtems_cache_flush_multiple_data_lines(
+ jc->command_tcd_table,
+ sizeof(jc->command_tcd_table)
+ );
+
+ /* Configure transmitter */
+ regs->tx_cfg = SMSC9218I_TX_CFG_SAO | SMSC9218I_TX_CFG_ON;
+
+ /* Enable MAC transmitter */
+ mac_cr = smsc9218i_mac_read(regs, SMSC9218I_MAC_CR, NULL) | SMSC9218I_MAC_CR_TXEN;
+ smsc9218i_mac_write(regs, SMSC9218I_MAC_CR, mac_cr);
+
+ /* Main event loop */
+ while (true) {
+ /* Wait for events */
+ sc = rtems_bsdnet_event_receive(
+ SMSC9218I_EVENT_TX
+ | SMSC9218I_EVENT_TX_START
+ | SMSC9218I_EVENT_DMA
+ | SMSC9218I_EVENT_DMA_ERROR,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events
+ );
+ ASSERT_SC(sc);
+
+ SMSC9218I_PRINTF("tx: wake up: events = 0x%08" PRIx32 "\n", events);
+
+ do {
+ jc->done = false;
+ smsc9218i_transmit_finish_jobs(jc, regs, e, events);
+ smsc9218i_transmit_create_jobs(jc, regs, ifp);
+ smsc9218i_transmit_do_jobs(jc, regs, e);
+ } while (!jc->done);
+
+ SMSC9218I_PRINTF("tx: done\n");
+ }
+
+ /* Release network semaphore */
+ rtems_bsdnet_semaphore_release();
+
+ /* Terminate self */
+ rtems_task_exit();
+}
+
+#if defined(DEBUG)
+static void smsc9218i_test_macros(void)
+{
+ unsigned i = 0;
+ unsigned byte_test = 0x87654321U;
+ unsigned val8 = 0xa5;
+ unsigned val16 = 0xa55a;
+ int r = 0;
+
+ r = SMSC9218I_SWAP(SMSC9218I_BYTE_TEST) == byte_test;
+ printf("[%i] SMSC9218I_SWAP\n", r);
+
+ for (i = 0; i < 32; ++i) {
+ r = SMSC9218I_SWAP(SMSC9218I_FLAG(i)) == (1U << i);
+ printf("[%i] flag: %u\n", r, i);
+ }
+
+ for (i = 0; i < 32; i += 8) {
+ r = SMSC9218I_SWAP(SMSC9218I_FIELD_8(val8, i)) == (val8 << i);
+ printf("[%i] field 8: %u\n", r, i);
+ }
+
+ for (i = 0; i < 32; i += 16) {
+ r = SMSC9218I_SWAP(SMSC9218I_FIELD_16(val16, i)) == (val16 << i);
+ printf("[%i] field 16: %u\n", r, i);
+ }
+
+ for (i = 0; i < 32; i += 8) {
+ r = SMSC9218I_GET_FIELD_8(SMSC9218I_BYTE_TEST, i)
+ == ((byte_test >> i) & 0xffU);
+ printf("[%i] get field 8: %u\n", r, i);
+ }
+
+ for (i = 0; i < 32; i += 16) {
+ r = SMSC9218I_GET_FIELD_16(SMSC9218I_BYTE_TEST, i)
+ == ((byte_test >> i) & 0xffffU);
+ printf("[%i] get field 16: %u\n", r, i);
+ }
+}
+#endif
+
+static bool smsc9218i_wait_for_eeprom_access(
+ volatile smsc9218i_registers *regs
+)
+{
+ rtems_interval start = smsc9218i_timeout_init();
+ bool busy;
+
+ while (
+ (busy = (regs->e2p_cmd & SMSC9218I_E2P_CMD_EPC_BUSY) != 0)
+ && smsc9218i_timeout_not_expired(start)
+ ) {
+ /* Wait */
+ }
+
+ return !busy;
+}
+
+static bool smsc9218i_get_mac_address(
+ volatile smsc9218i_registers *regs,
+ uint8_t address [6]
+)
+{
+ bool ok = false;
+
+ uint32_t low = smsc9218i_mac_read(regs, SMSC9218I_MAC_ADDRL, &ok);
+ address [0] = (uint8_t) low;
+ address [1] = (uint8_t) (low >> 8) & 0xff;
+ address [2] = (uint8_t) (low >> 16);
+ address [3] = (uint8_t) (low >> 24);
+
+ if (ok) {
+ uint32_t high = smsc9218i_mac_read(regs, SMSC9218I_MAC_ADDRH, &ok);
+ address [4] = (uint8_t) high;
+ address [5] = (uint8_t) (high >> 8);
+ }
+
+ return ok;
+}
+
+static bool smsc9218i_set_mac_address(
+ volatile smsc9218i_registers *regs,
+ const uint8_t address [6]
+)
+{
+ bool ok = smsc9218i_mac_write(
+ regs,
+ SMSC9218I_MAC_ADDRL,
+ ((uint32_t) address [3] << 24) | ((uint32_t) address [2] << 16)
+ | ((uint32_t) address [1] << 8) | (uint32_t) address [0]
+ );
+
+ if (ok) {
+ ok = smsc9218i_mac_write(
+ regs,
+ SMSC9218I_MAC_ADDRH,
+ ((uint32_t) address [5] << 8) | (uint32_t) address [4]
+ );
+ }
+
+ return ok;
+}
+
+/* Sometimes the write of the MAC address was not reliable */
+static bool smsc9218i_set_and_verify_mac_address(
+ volatile smsc9218i_registers *regs,
+ const uint8_t address [6]
+)
+{
+ bool ok = true;
+ int i;
+
+ for (i = 0; ok && i < 3; ++i) {
+ ok = smsc9218i_set_mac_address(regs, address);
+
+ if (ok) {
+ uint8_t actual_address [6];
+
+ ok = smsc9218i_get_mac_address(regs, actual_address)
+ && memcmp(address, actual_address, sizeof(actual_address)) == 0;
+ }
+ }
+
+ return ok;
+}
+
+#if defined(DEBUG)
+static void smsc9218i_mac_address_dump(volatile smsc9218i_registers *regs)
+{
+ uint8_t mac_address [6];
+ bool ok = smsc9218i_get_mac_address(regs, mac_address);
+
+ if (ok) {
+ printf(
+ "MAC address: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ mac_address [0],
+ mac_address [1],
+ mac_address [2],
+ mac_address [3],
+ mac_address [4],
+ mac_address [5]
+ );
+ } else {
+ printf("cannot read MAC address\n");
+ }
+}
+#endif
+
+static void smsc9218i_interrupt_init(
+ smsc9218i_driver_entry *e,
+ volatile smsc9218i_registers *regs
+)
+{
+#ifdef SMSC9218I_IRQ_PIN
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ union SIU_PCR_tag pcr = MPC55XX_ZERO_FLAGS;
+ union SIU_DIRER_tag direr = MPC55XX_ZERO_FLAGS;
+ union SIU_DIRSR_tag dirsr = MPC55XX_ZERO_FLAGS;
+ union SIU_ORER_tag orer = MPC55XX_ZERO_FLAGS;
+ union SIU_IREER_tag ireer = MPC55XX_ZERO_FLAGS;
+ union SIU_IFEER_tag ifeer = MPC55XX_ZERO_FLAGS;
+ union SIU_IDFR_tag idfr = MPC55XX_ZERO_FLAGS;
+ rtems_interrupt_level level;
+
+ /* Configure IRQ input pin */
+ pcr.B.PA = 2;
+ pcr.B.OBE = 0;
+ pcr.B.IBE = 1;
+#if MPC55XX_CHIP_FAMILY != 551
+ pcr.B.DSC = 0;
+#endif
+ pcr.B.ODE = 0;
+ pcr.B.HYS = 0;
+ pcr.B.SRC = 0;
+ pcr.B.WPE = 0;
+ pcr.B.WPS = 1;
+ SIU.PCR [SMSC9218I_IRQ_PIN].R = pcr.R;
+
+ /* DMA/Interrupt Request Select */
+ rtems_interrupt_disable(level);
+ dirsr.R = SIU.DIRSR.R;
+#if MPC55XX_CHIP_FAMILY != 551
+ dirsr.B.DIRS0 = 0;
+#endif
+ SIU.DIRSR.R = dirsr.R;
+ rtems_interrupt_enable(level);
+
+ /* Overrun Request Enable */
+ rtems_interrupt_disable(level);
+ orer.R = SIU.ORER.R;
+ orer.B.ORE0 = 0;
+ SIU.ORER.R = orer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Rising-Edge Enable */
+ rtems_interrupt_disable(level);
+ ireer.R = SIU.IREER.R;
+ ireer.B.IREE0 = 0;
+ SIU.IREER.R = ireer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Falling-Edge Enable */
+ rtems_interrupt_disable(level);
+ ifeer.R = SIU.IFEER.R;
+ ifeer.B.IFEE0 = 1;
+ SIU.IFEER.R = ifeer.R;
+ rtems_interrupt_enable(level);
+
+ /* IRQ Digital Filter */
+ rtems_interrupt_disable(level);
+ idfr.R = SIU.IDFR.R;
+ idfr.B.DFL = 0;
+ SIU.IDFR.R = idfr.R;
+ rtems_interrupt_enable(level);
+
+ /* Clear external interrupt status */
+ SIU.EISR.R = 1;
+
+ /* DMA/Interrupt Request Enable */
+ rtems_interrupt_disable(level);
+ direr.R = SIU.DIRER.R;
+ direr.B.EIRE0 = 1;
+ SIU.DIRER.R = direr.R;
+ rtems_interrupt_enable(level);
+
+ /* Install interrupt handler */
+ sc = rtems_interrupt_handler_install(
+ MPC55XX_IRQ_SIU_EXTERNAL_0,
+ "SMSC9218i",
+ RTEMS_INTERRUPT_UNIQUE,
+ smsc9218i_interrupt_handler,
+ e
+ );
+ ASSERT_SC(sc);
+
+ /* Enable interrupts and use push-pull driver (active low) */
+ regs->irq_cfg = SMSC9218I_IRQ_CFG_GLOBAL_ENABLE;
+
+ /* Enable error interrupts */
+ regs->int_en = SMSC9218I_ERROR_INTERRUPTS;
+#endif
+}
+
+static void smsc9218i_reset_signal(bool signal)
+{
+#ifdef SMSC9218I_RESET_PIN
+ SIU.GPDO [SMSC9218I_RESET_PIN].R = signal ? 1 : 0;
+#endif
+}
+
+static void smsc9218i_reset_signal_init(void)
+{
+#ifdef SMSC9218I_RESET_PIN
+ union SIU_PCR_tag pcr = MPC55XX_ZERO_FLAGS;
+
+ smsc9218i_reset_signal(true);
+
+ pcr.B.PA = 0;
+ pcr.B.OBE = 1;
+ pcr.B.IBE = 0;
+#if MPC55XX_CHIP_FAMILY != 551
+ pcr.B.DSC = 0;
+#endif
+ pcr.B.ODE = 0;
+ pcr.B.HYS = 0;
+ pcr.B.SRC = 0;
+ pcr.B.WPE = 1;
+ pcr.B.WPS = 1;
+
+ SIU.PCR [SMSC9218I_RESET_PIN].R = pcr.R;
+#endif
+}
+
+static bool smsc9218i_hardware_reset(volatile smsc9218i_registers *regs)
+{
+ rtems_interval start = smsc9218i_timeout_init();
+ bool not_ready;
+
+ smsc9218i_reset_signal_init();
+ smsc9218i_reset_signal(false);
+ rtems_bsp_delay(200);
+ smsc9218i_reset_signal(true);
+
+ while (
+ (not_ready = (regs->pmt_ctrl & SMSC9218I_PMT_CTRL_READY) == 0)
+ && smsc9218i_timeout_not_expired(start)
+ ) {
+ /* Wait */
+ }
+
+ return !not_ready;
+}
+
+static void smsc9218i_interface_init(void *arg)
+{
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) arg;
+ struct ifnet *ifp = &e->arpcom.ac_if;
+ volatile smsc9218i_registers *const regs = smsc9218i;
+ bool ok = true;
+
+ SMSC9218I_PRINTF("%s\n", __func__);
+
+ if (e->state == SMSC9218I_CONFIGURED) {
+ ok = smsc9218i_hardware_reset(regs);
+ if (ok) {
+ e->state = SMSC9218I_NOT_INITIALIZED;
+ }
+ }
+
+ if (e->state == SMSC9218I_NOT_INITIALIZED) {
+#if defined(DEBUG)
+ smsc9218i_register_dump(regs);
+#endif
+
+ /* Set hardware configuration */
+ regs->hw_cfg = SMSC9218I_HW_CFG_MBO | SMSC9218I_HW_CFG_TX_FIF_SZ(5);
+
+ ok = smsc9218i_wait_for_eeprom_access(regs);
+
+ if (ok) {
+ ok = smsc9218i_set_and_verify_mac_address(regs, e->arpcom.ac_enaddr);
+
+ if (ok) {
+#if defined(DEBUG)
+ smsc9218i_mac_address_dump(regs);
+#endif
+
+ /* Auto-negotiation advertisment */
+ ok = smsc9218i_phy_write(
+ regs,
+ MII_ANAR,
+ ANAR_TX_FD | ANAR_TX | ANAR_10_FD | ANAR_10 | ANAR_CSMA
+ );
+
+ if (ok) {
+#ifdef SMSC9218I_ENABLE_LED_OUTPUTS
+ regs->gpio_cfg = SMSC9218I_HW_CFG_LED_1
+ | SMSC9218I_HW_CFG_LED_2
+ | SMSC9218I_HW_CFG_LED_3;
+#endif
+
+ smsc9218i_interrupt_init(e, regs);
+
+ /* Set MAC control */
+ ok = smsc9218i_mac_write(regs, SMSC9218I_MAC_CR, SMSC9218I_MAC_CR_FDPX);
+ if (ok) {
+ /* Set FIFO interrupts */
+ regs->fifo_int = SMSC9218I_FIFO_INT_TDAL(32);
+
+ /* Clear receive drop counter */
+ regs->rx_drop;
+
+ /* Start receive task */
+ if (e->receive_task == RTEMS_ID_NONE) {
+ e->receive_task = rtems_bsdnet_newproc(
+ "ntrx",
+ 4096,
+ smsc9218i_receive_task,
+ e
+ );
+ }
+
+ /* Start transmit task */
+ if (e->transmit_task == RTEMS_ID_NONE) {
+ e->transmit_task = rtems_bsdnet_newproc(
+ "nttx",
+ 4096,
+ smsc9218i_transmit_task,
+ e
+ );
+ }
+
+ /* Change state */
+ if (e->receive_task != RTEMS_ID_NONE
+ && e->transmit_task != RTEMS_ID_NONE) {
+ e->state = SMSC9218I_STARTED;
+ }
+ }
+ }
+ }
+ }
+ }
+
+ if (e->state == SMSC9218I_STARTED) {
+ /* Enable promiscous mode */
+ ok = smsc9218i_enable_promiscous_mode(
+ regs,
+ (ifp->if_flags & IFF_PROMISC) != 0
+ );
+
+ if (ok) {
+ /* Set interface to running state */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /* Change state */
+ e->state = SMSC9218I_RUNNING;
+ }
+ }
+}
+
+static int smsc9218i_mdio_read(
+ int phy,
+ void *arg,
+ unsigned phy_reg,
+ uint32_t *val
+)
+{
+ volatile smsc9218i_registers *const regs = smsc9218i;
+
+ *val = smsc9218i_phy_read(regs, phy_reg);
+
+ return 0;
+}
+
+static int smsc9218i_mdio_write(
+ int phy,
+ void *arg,
+ unsigned phy_reg,
+ uint32_t data
+)
+{
+ volatile smsc9218i_registers *const regs = smsc9218i;
+
+ smsc9218i_phy_write(regs, phy_reg, data);
+
+ return 0;
+}
+
+static void smsc9218i_interface_stats(smsc9218i_driver_entry *e)
+{
+ volatile smsc9218i_registers *const regs = smsc9218i;
+ smsc9218i_transmit_job_control *jc = &smsc_tx_jc;
+ int media = 0;
+ bool media_ok = smsc9218i_media_status(e, &media);
+
+ if (media_ok) {
+ rtems_ifmedia2str(media, NULL, 0);
+ printf ("\n");
+ } else {
+ printf ("PHY communication error\n");
+ }
+
+ e->receive_drop += SMSC9218I_SWAP(regs->rx_drop);
+
+ printf("PHY interrupts: %u\n", e->phy_interrupts);
+ printf("received frames: %u\n", e->received_frames);
+ printf("receiver errors: %u\n", e->receiver_errors);
+ printf("receive interrupts: %u\n", e->receive_interrupts);
+ printf("receive DMA interrupts: %u\n", e->receive_dma_interrupts);
+ printf("receive to long errors: %u\n", e->receive_too_long_errors);
+ printf("receive collision errors: %u\n", e->receive_collision_errors);
+ printf("receive CRC errors: %u\n", e->receive_crc_errors);
+ printf("receive DMA errors: %u\n", e->receive_dma_errors);
+ printf("receive drops: %u\n", e->receive_drop);
+ printf("receive watchdog timeouts: %u\n", e->receive_watchdog_timeouts);
+ printf("transmitted frames: %u\n", e->transmitted_frames);
+ printf("transmitter errors: %u\n", e->transmitter_errors);
+ printf("transmit interrupts: %u\n", e->transmit_interrupts);
+ printf("transmit DMA interrupts: %u\n", e->transmit_dma_interrupts);
+ printf("transmit status overflows: %u\n", e->transmit_status_overflows);
+ printf("transmit frame errors: %u\n", e->transmit_frame_errors);
+ printf("transmit DMA errors: %u\n", e->transmit_dma_errors);
+ printf("frame compact count: %u\n", jc->frame_compact_count);
+ printf("interface state: %s\n", state_to_string [e->state]);
+}
+
+static void smsc9218i_interface_off(struct ifnet *ifp)
+{
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) ifp->if_softc;
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+
+ sc = rtems_task_suspend(e->receive_task);
+ ASSERT_SC(sc);
+
+ sc = rtems_task_suspend(e->transmit_task);
+ ASSERT_SC(sc);
+
+ /* remove interrupt handler */
+ sc = rtems_interrupt_handler_remove(
+ MPC55XX_IRQ_SIU_EXTERNAL_0,
+ smsc9218i_interrupt_handler,
+ e
+ );
+ ASSERT_SC(sc);
+
+ mpc55xx_edma_release_channel(
+ &e->edma_receive
+ );
+
+ mpc55xx_edma_release_channel(
+ &e->edma_transmit
+ );
+
+ /* set in reset state */
+ smsc9218i_reset_signal(false);
+}
+
+static int smsc9218i_interface_ioctl(
+ struct ifnet *ifp,
+ ioctl_command_t command,
+ caddr_t data
+) {
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) ifp->if_softc;
+ int rv = 0;
+
+ SMSC9218I_PRINTF("%s\n", __func__);
+
+ switch (command) {
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ rtems_mii_ioctl(&e->mdio, e, command, (int *) data);
+ break;
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+ case SIOCSIFFLAGS:
+ if (ifp->if_flags & IFF_UP) {
+ /* TODO: init */
+ } else {
+ smsc9218i_interface_off(ifp);
+ }
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ smsc9218i_interface_stats(e);
+ break;
+ default:
+ rv = EINVAL;
+ break;
+ }
+
+ return rv;
+}
+
+static void smsc9218i_interface_start(struct ifnet *ifp)
+{
+ rtems_status_code sc = RTEMS_SUCCESSFUL;
+ smsc9218i_driver_entry *e = (smsc9218i_driver_entry *) ifp->if_softc;
+
+ /* Interface is now active */
+ ifp->if_flags |= IFF_OACTIVE;
+
+ sc = rtems_bsdnet_event_send(e->transmit_task, SMSC9218I_EVENT_TX_START);
+ ASSERT_SC(sc);
+}
+
+static void smsc9218i_interface_watchdog(struct ifnet *ifp)
+{
+ SMSC9218I_PRINTF("%s\n", __func__);
+}
+
+static void smsc9218i_attach(struct rtems_bsdnet_ifconfig *config)
+{
+ smsc9218i_driver_entry *e = &smsc9218i_driver_data;
+ struct ifnet *ifp = &e->arpcom.ac_if;
+ char *unit_name = NULL;
+ int unit_number = rtems_bsdnet_parse_driver_name(config, &unit_name);
+
+ /* Check parameter */
+ assert(unit_number == 0);
+ assert(config->hardware_address != NULL);
+ assert(e->state == SMSC9218I_NOT_INITIALIZED);
+
+ /* Interrupt number */
+ config->irno = MPC55XX_IRQ_SIU_EXTERNAL_0;
+
+ /* Device control */
+ config->drv_ctrl = e;
+
+ /* Receive unit number */
+ config->rbuf_count = 0;
+
+ /* Transmit unit number */
+ config->xbuf_count = 0;
+
+ /* Copy MAC address */
+ memcpy(e->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ /* Set interface data */
+ ifp->if_softc = e;
+ ifp->if_unit = (short) unit_number;
+ ifp->if_name = unit_name;
+ ifp->if_mtu = config->mtu > 0 ? (u_long) config->mtu : ETHERMTU;
+ ifp->if_init = smsc9218i_interface_init;
+ ifp->if_ioctl = smsc9218i_interface_ioctl;
+ ifp->if_start = smsc9218i_interface_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = smsc9218i_interface_watchdog;
+ ifp->if_flags = config->ignore_broadcast ? 0 : IFF_BROADCAST;
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ ifp->if_timer = 0;
+
+ /* MDIO */
+ e->mdio.mdio_r = smsc9218i_mdio_read;
+ e->mdio.mdio_w = smsc9218i_mdio_write;
+
+ /* Change status */
+ e->state = SMSC9218I_CONFIGURED;
+
+ /* Attach the interface */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+}
+
+int smsc9218i_attach_detach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attaching
+) {
+ if (attaching) {
+ smsc9218i_attach(config);
+ } else {
+ /* TODO */
+ }
+
+ /* FIXME: Return value */
+ return 0;
+}
+
+#endif /* defined(RTEMS_NETWORKING) && defined(MPC55XX_HAS_SIU) */
diff --git a/bsps/powerpc/mpc8260ads/net/README b/bsps/powerpc/mpc8260ads/net/README
new file mode 100644
index 0000000..d572255
--- /dev/null
+++ b/bsps/powerpc/mpc8260ads/net/README
@@ -0,0 +1,55 @@
+Networking with HDLC
+====================
+
+Author: Andy Dachs <a.dachs@sstl.co.uk>
+Date: 31st August 2001
+Surrey Satellite Technology Limited
+
+
+The network support in this BSP is not Ethernet support. The
+"network" referred to here is a point to point HDLC communication link.
+The ADS board does have a 10/100 ethernet port and it would be nice to
+get support for that added.
+
+My requirement is for a WAN so I need the ability to send IP frames over
+HDLC. Ultimately this will end up as frame relay support but in the meantime
+I'm simply wrapping up the IP packet inside an HDLC frame. There is no
+addressing mechanism or mac address attached to the start of the frame.
+
+This is what is physically transmitted:
+<FLAG><IP Frame><CRC><FLAG>
+
+
+The physical link consists of four lines,
+TX DATA : Data transmitted
+TX CLOCK: Clock for transmitted data. Data source provides clock.
+RX DATA : Received data
+RX CLOCK: Clock for received data. Data sink accepts clock.
+
+To connect two entities you require a NULL modem arrangement, i.e. TX data
+and Tx clock from one end go into RX data and Rx clock on the other end.
+
+The MPC8260ADS side of the link is implemented using SCC3 in HDLC mode. The
+TX clock is generated by BRG4. The RX clock in input to the board on the CLK5
+input. I built a LVTTL to RS422 converter.
+
+The other end of the link is a Windows NT PC with WANic400 synchronous
+communication card. We bought the card from ImageStream
+(http://www.imagestream.com/WANic400.html). You also need the NT
+drivers and a cable. There are other distributors but I found these
+guys helpful - and they also do Linux drivers.
+
+The NT WANic driver has a number of modes, one of which is ethernet emulation.
+This mode is what is needed to transport IP packets in HDLC frames.
+
+In libnetworking/net you will find a file called if_hdlcsubr.c containing
+the hdlc_input and hdlc_output routines required by network.c. This file was
+created by taking out the addressing mechanisms from if_ethersubr.c in the
+same directory. There are probably neater ways to do this <any
+contributions welcome here>.
+
+
+
+
+
+
diff --git a/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.c b/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.c
new file mode 100644
index 0000000..0c9cb8a
--- /dev/null
+++ b/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.c
@@ -0,0 +1,349 @@
+/*
+ * Created from if_ethersubr.c by Andy Dachs <a.dachs@sstl.co.uk>
+ * Surrey Satellite Technology Limited (SSTL), 2001
+ * Modified (hacked) to support IP frames transmitted over HDLC. This
+ * all needs tidying up in future but it does actually work for point
+ * to point communications. I have an SDL WANic400 synchronous
+ * communications card that comes with Windows NT drivers. The drivers
+ * support a mode that they call "Ethernet Emulation". That simply
+ * puts the IP frame in an HDLC frame without any ethernet header. i.e.
+ * <HDLC Flag><IpFrame><CRC><HDLC Flag>. There is no addressing beyond
+ * the IP header information so is only suitable for point to point links
+ * with a single protocol. "At some point" I will add a Frame Relay header
+ * but at the moment I have difficulties getting the WANic card driver's
+ * Frame Relay driver to work.
+ *
+ * Copyright (c) 1982, 1989, 1993
+ * The Regents of the University of California. 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. All advertising materials mentioning features or use of this software
+ * must display the following acknowledgement:
+ * This product includes software developed by the University of
+ * California, Berkeley and its contributors.
+ * 4. Neither the name of the University nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE REGENTS 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.
+ *
+ * @(#)if_ethersubr.c 8.1 (Berkeley) 6/10/93
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+/*#include <sys/systm.h>
+#include <sys/kernel.h> */
+#include <sys/malloc.h>
+#include <sys/mbuf.h>
+#include <sys/protosw.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <errno.h>
+#include <sys/syslog.h>
+#include <sys/sysctl.h>
+
+#include <net/if.h>
+#include <net/netisr.h>
+#include <net/route.h>
+#include <net/if_llc.h>
+#include <net/if_dl.h>
+#include <net/if_types.h>
+#include <net/ethernet.h>
+
+#include <netinet/in.h>
+#include <netinet/in_var.h>
+#include <netinet/if_ether.h>
+
+#include <stdio.h>
+
+#include "if_hdlcsubr.h"
+
+/*
+u_char etherbroadcastaddr[6] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff };
+*/
+#define senderr(e) { error = (e); goto bad;}
+
+/*
+ * HDLC output routine.
+ * Just transmit the packet (hardware adds flags and CRC)
+ */
+int
+hdlc_output(ifp, m0, dst, rt0)
+ register struct ifnet *ifp;
+ struct mbuf *m0;
+ struct sockaddr *dst;
+ struct rtentry *rt0;
+{
+ short type;
+ int s, error = 0;
+#if 0
+ u_char edst[6];
+#endif
+ register struct mbuf *m = m0;
+ register struct rtentry *rt;
+ struct mbuf *mcopy = (struct mbuf *)0;
+/* register struct ether_header *eh; */
+ int off, len = m->m_pkthdr.len;
+
+/* printk( "hdlc output" ); */
+/* struct arpcom *ac = (struct arpcom *)ifp; */
+
+ if ((ifp->if_flags & (IFF_UP|IFF_RUNNING)) != (IFF_UP|IFF_RUNNING))
+ senderr(ENETDOWN);
+ rt = rt0;
+ if (rt) {
+ if ((rt->rt_flags & RTF_UP) == 0) {
+ rt0 = rt = rtalloc1(dst, 1, 0UL);
+ if (rt0)
+ rt->rt_refcnt--;
+ else
+ senderr(EHOSTUNREACH);
+ }
+ if (rt->rt_flags & RTF_GATEWAY) {
+ if (rt->rt_gwroute == 0)
+ goto lookup;
+ if (((rt = rt->rt_gwroute)->rt_flags & RTF_UP) == 0) {
+ rtfree(rt); rt = rt0;
+ lookup: rt->rt_gwroute = rtalloc1(rt->rt_gateway, 1,
+ 0UL);
+ if ((rt = rt->rt_gwroute) == 0)
+ senderr(EHOSTUNREACH);
+ }
+ }
+ if (rt->rt_flags & RTF_REJECT)
+ if (rt->rt_rmx.rmx_expire == 0 ||
+ rtems_bsdnet_seconds_since_boot() < rt->rt_rmx.rmx_expire)
+ senderr(rt == rt0 ? EHOSTDOWN : EHOSTUNREACH);
+ }
+ switch (dst->sa_family) {
+
+ case AF_INET:
+#if 0
+ if (!arpresolve(ac, rt, m, dst, edst, rt0))
+ return (0); /* if not yet resolved */
+#endif
+
+ /* If broadcasting on a simplex interface, loopback a copy */
+ if ((m->m_flags & M_BCAST) && (ifp->if_flags & IFF_SIMPLEX))
+ mcopy = m_copy(m, 0, (int)M_COPYALL);
+ off = m->m_pkthdr.len - m->m_len;
+ type = htons(ETHERTYPE_IP);
+ break;
+#if 0
+ case AF_UNSPEC:
+ eh = (struct ether_header *)dst->sa_data;
+ (void)memcpy(edst, eh->ether_dhost, sizeof (edst));
+ type = eh->ether_type;
+ break;
+#endif
+ default:
+ printf("%s%d: can't handle af%d\n", ifp->if_name, ifp->if_unit,
+ dst->sa_family);
+ senderr(EAFNOSUPPORT);
+ }
+
+ if (mcopy)
+ (void) looutput(ifp, mcopy, dst, rt);
+#if 0
+ /*
+ * Add local net header. If no space in first mbuf,
+ * allocate another.
+ */
+ M_PREPEND(m, sizeof (struct ether_header), M_DONTWAIT);
+#endif
+
+ if (m == 0)
+ senderr(ENOBUFS);
+
+#if 0
+ eh = mtod(m, struct ether_header *);
+ (void)memcpy(&eh->ether_type, &type,
+ sizeof(eh->ether_type));
+ (void)memcpy(eh->ether_dhost, edst, sizeof (edst));
+ (void)memcpy(eh->ether_shost, ac->ac_enaddr,
+ sizeof(eh->ether_shost));
+#endif
+
+ s = splimp();
+ /*
+ * Queue message on interface, and start output if interface
+ * not yet active.
+ */
+ if (IF_QFULL(&ifp->if_snd)) {
+ IF_DROP(&ifp->if_snd);
+ splx(s);
+ senderr(ENOBUFS);
+ }
+ IF_ENQUEUE(&ifp->if_snd, m);
+ if ((ifp->if_flags & IFF_OACTIVE) == 0)
+ (*ifp->if_start)(ifp);
+ splx(s);
+
+ ifp->if_obytes += len /*+ sizeof (struct ether_header)*/;
+ if (m->m_flags & M_MCAST)
+ ifp->if_omcasts++;
+ return (error);
+
+bad:
+ if (m)
+ m_freem(m);
+ return (error);
+}
+
+/*
+ * Process a received Ethernet packet;
+ * the packet is in the mbuf chain m without
+ * the ether header, which is provided separately.
+ */
+void
+hdlc_input(ifp, m)
+ struct ifnet *ifp;
+ struct mbuf *m;
+{
+ register struct ifqueue *inq;
+ int s;
+
+ struct ether_header eh;
+
+ if ((ifp->if_flags & IFF_UP) == 0) {
+ m_freem(m);
+ return;
+ }
+ ifp->if_ibytes += m->m_pkthdr.len;
+/*
+ if (memcmp((caddr_t)etherbroadcastaddr, (caddr_t)eh->ether_dhost,
+ sizeof(etherbroadcastaddr)) == 0)
+ m->m_flags |= M_BCAST;
+ else if (eh->ether_dhost[0] & 1)
+ m->m_flags |= M_MCAST;
+*/
+ if (m->m_flags & (M_BCAST|M_MCAST))
+ ifp->if_imcasts++;
+
+ /*
+ * RTEMS addition -- allow application to `tap into'
+ * the incoming packet stream.
+ */
+ if (ifp->if_tap && (*ifp->if_tap)(ifp, &eh, m)) {
+ m_freem(m);
+ return;
+ }
+
+ schednetisr(NETISR_IP);
+ inq = &ipintrq;
+
+ s = splimp();
+ if (IF_QFULL(inq)) {
+ IF_DROP(inq);
+ m_freem(m);
+ } else
+ IF_ENQUEUE(inq, m);
+ splx(s);
+}
+
+/*
+ * Perform common duties while attaching to interface list
+ */
+void
+hdlc_ifattach(ifp)
+ register struct ifnet *ifp;
+{
+ register struct ifaddr *ifa;
+ register struct sockaddr_dl *sdl;
+
+ ifp->if_type = IFT_ETHER;
+ ifp->if_addrlen = 0;
+ ifp->if_hdrlen = 0;
+ ifp->if_mtu = 2048;
+ if (ifp->if_baudrate == 0)
+ ifp->if_baudrate = 8000000;
+ for (ifa = ifp->if_addrlist; ifa; ifa = ifa->ifa_next)
+ if ((sdl = (struct sockaddr_dl *)ifa->ifa_addr) &&
+ sdl->sdl_family == AF_LINK) {
+ sdl->sdl_type = IFT_ETHER;
+ sdl->sdl_alen = ifp->if_addrlen;
+/*
+ memcpy(LLADDR(sdl),
+ (caddr_t)((struct arpcom *)ifp)->ac_enaddr,
+ ifp->if_addrlen);
+*/
+ break;
+ }
+}
+
+/* SYSCTL_NODE(_net_link, IFT_ETHER, ether, CTLFLAG_RW, 0, "Ethernet"); */
+
+int
+hdlc_ioctl(struct ifnet *ifp, int command, caddr_t data)
+{
+ struct ifaddr *ifa = (struct ifaddr *) data;
+ struct ifreq *ifr = (struct ifreq *) data;
+ int error = 0;
+
+ switch (command) {
+ case SIOCSIFADDR:
+ ifp->if_flags |= IFF_UP;
+
+ switch (ifa->ifa_addr->sa_family) {
+#if 0
+#ifdef INET
+ case AF_INET:
+ ifp->if_init(ifp->if_softc); /* before arpwhohas */
+
+ arp_ifinit((struct arpcom *)ifp, ifa);
+ break;
+#endif
+#endif
+ default:
+ ifp->if_init(ifp->if_softc);
+ break;
+ }
+ break;
+
+ case SIOCGIFADDR:
+ {
+ struct sockaddr *sa;
+
+ sa = (struct sockaddr *) & ifr->ifr_data;
+/*
+ memcpy((caddr_t) sa->sa_data,
+ ((struct arpcom *)ifp->if_softc)->ac_enaddr,
+ ETHER_ADDR_LEN);
+*/
+ }
+ break;
+
+ case SIOCSIFMTU:
+ /*
+ * Set the interface MTU.
+ */
+ if (ifr->ifr_mtu > ETHERMTU) {
+ error = EINVAL;
+ } else {
+ ifp->if_mtu = ifr->ifr_mtu;
+ }
+ break;
+ }
+ return (error);
+}
diff --git a/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.h b/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.h
new file mode 100644
index 0000000..8289c4b
--- /dev/null
+++ b/bsps/powerpc/mpc8260ads/net/if_hdlcsubr.h
@@ -0,0 +1,34 @@
+/*
+ * RTEMS/TCPIP driver for MPC8260 SCC HDLC networking
+ *
+ * Submitted by Andy Dachs <a.dachs@sstl.co.uk>
+ * (c) Surrey Satellite Technology Limited, 2001
+ *
+ * On the ADS board the ethernet interface is connected to FCC2
+ * but in my application I want TCP over HDLC (see README)
+ * so will use SCC3 as the network interface. I have other plans
+ * for the FCCs so am unlikely to add true ethernet support to
+ * this BSP. Contributions welcome!
+ *
+ * COPYRIGHT (c) 1989-1997.
+ * On-Line Applications Research Corporation (OAR).
+ *
+ * The license and distribution terms for this file may in
+ * the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+#ifndef __IF_HDLCSUBR_H
+#define __IF_HDLCSUBR_H
+
+struct ifnet;
+struct mbuf;
+struct sockaddr;
+struct rtentry;
+
+void hdlc_ifattach (struct ifnet *);
+void hdlc_input (struct ifnet *, struct mbuf *);
+int hdlc_output (struct ifnet *,
+ struct mbuf *, struct sockaddr *, struct rtentry *);
+int hdlc_ioctl (struct ifnet *, int , caddr_t );
+
+#endif
diff --git a/bsps/powerpc/mpc8260ads/net/network.c b/bsps/powerpc/mpc8260ads/net/network.c
new file mode 100644
index 0000000..31cf96a
--- /dev/null
+++ b/bsps/powerpc/mpc8260ads/net/network.c
@@ -0,0 +1,969 @@
+/*
+ * RTEMS/TCPIP driver for MPC8260 SCC
+ *
+ * Modified for MPC8260 by Andy Dachs <a.dachs@sstl.co.uk>
+ * Surrey Satellite Technology Limited
+ *
+ * On the ADS board the ethernet interface is connected to FCC2
+ * but in my application I want TCP over HDLC (see README)
+ * so will use SCC3 as the network interface. I have other plans
+ * for the FCCs so am unlikely to add true ethernet support to
+ * this BSP. Contributions welcome!
+ *
+ * Modified for MPC860 by Jay Monkman (jmonkman@frasca.com)
+ *
+ * This supports ethernet on either SCC1 or the FEC of the MPC860T.
+ * Right now, we only do 10 Mbps, even with the FEC. The function
+ * rtems_m860_enet_driver_attach determines which one to use. Currently,
+ * only one may be used at a time.
+ *
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <mpc8260.h>
+#include <mpc8260/cpm.h>
+#include <stdio.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/bspIo.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <errno.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include "if_hdlcsubr.h"
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 8
+#define TX_BD_PER_BUF 4
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+extern void m8xx_dump_brgs( void );
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+/*#define MAX_MTU_SIZE 2050*/
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+/*
+ * Per-device data
+ */
+struct m8260_hdlc_struct {
+ struct ifnet ac_if;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ m8260BufferDescriptor_t *rxBdBase;
+ m8260BufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxInterrupts;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxAbort;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxLostCarrier;
+ unsigned long txInterrupts;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+};
+static struct m8260_hdlc_struct hdlc_driver[NIFACES];
+
+static void m8xx_scc3_hdlc_on(const rtems_irq_connect_data* ptr)
+{
+}
+
+static void m8xx_scc3_hdlc_off(const rtems_irq_connect_data* ptr)
+{
+ /*
+ * Please put relevant code there
+ */
+}
+
+static int m8xx_scc3_hdlc_isOn(const rtems_irq_connect_data* ptr)
+{
+ return BSP_irq_enabled_at_cpm (ptr->name);
+}
+
+/*
+ * SCC interrupt handler
+ * TBD: Can we work out which SCC generated the interrupt from the
+ * value of v? If so we can use the same handler for multiple
+ * SCCs.
+ */
+static void
+m8xx_scc3_interrupt_handler (rtems_irq_hdl_param unused)
+{
+ /*
+ * Frame received?
+ */
+ if ((m8260.scc3.sccm & M8260_SCCE_RXF) &&
+ (m8260.scc3.scce & M8260_SCCE_RXF) ) {
+ m8260.scc3.scce = M8260_SCCE_RXF;
+/* m8260.scc3.sccm &= ~M8260_SCCE_RXF; */
+ hdlc_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send (hdlc_driver[0].rxDaemonTid, INTERRUPT_EVENT);
+/*
+ printk( "Rx " );
+*/
+ }
+
+ /*
+ * Buffer transmitted or transmitter error?
+ */
+ if ((m8260.scc3.sccm & (M8260_SCCE_TX | M8260_SCCE_TXE) ) &&
+ (m8260.scc3.scce & (M8260_SCCE_TX | M8260_SCCE_TXE) )) {
+ m8260.scc3.scce = M8260_SCCE_TX | M8260_SCCE_TXE;
+/* m8260.scc3.sccm &= ~(M8260_SCCE_TX | M8260_SCCE_TXE); */
+ hdlc_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send (hdlc_driver[0].txDaemonTid, INTERRUPT_EVENT);
+/*
+ printk( "Tx " );
+*/
+ }
+
+#if 0
+ m8260.sipnr_l = M8260_SIMASK_SCC3; /* Clear SCC3 interrupt-in-service bit */
+#endif
+}
+
+static rtems_irq_connect_data hdlcSCC3IrqData = {
+ BSP_CPM_IRQ_SCC3,
+ (rtems_irq_hdl) m8xx_scc3_interrupt_handler,
+ NULL,
+ (rtems_irq_enable) m8xx_scc3_hdlc_on,
+ (rtems_irq_disable) m8xx_scc3_hdlc_off,
+ (rtems_irq_is_enabled)m8xx_scc3_hdlc_isOn
+};
+
+/*
+ * Initialize the SCC hardware
+ * Configure I/O ports for SCC3
+ * Internal Tx clock, External Rx clock
+ */
+static void
+m8260_scc_initialize_hardware (struct m8260_hdlc_struct *sc)
+{
+ int i;
+ int brg;
+
+ rtems_status_code status;
+
+ /* RxD PB14 */
+ m8260.pparb |= 0x00020000;
+ m8260.psorb &= ~0x00020000;
+ m8260.pdirb &= ~0x00020000;
+
+ /* RxC (CLK5) PC27 */
+ m8260.pparc |= 0x00000010;
+ m8260.psorc &= ~0x00000010;
+ m8260.pdirc &= ~0x00000010;
+
+ /* TxD PD24 and TxC PD10 (BRG4) */
+ m8260.ppard |= 0x00200080;
+ m8260.psord |= 0x00200000;
+ m8260.psord &= ~0x00000080;
+ m8260.pdird |= 0x00200080;
+
+ /* External Rx Clock from CLK5 */
+ if( m8xx_get_clk( M8xx_CLK_5 ) == -1 )
+ printk( "Error allocating CLK5 for network device.\n" );
+ else
+ m8260.cmxscr |= 0x00002000;
+
+ /* Internal Tx Clock from BRG4 */
+ if( (brg = m8xx_get_brg(M8xx_BRG_4, 8000000 )) == -1 )
+ printk( "Error allocating BRG for network device\n" );
+ else
+ m8260.cmxscr |= ((unsigned)brg << 8);
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc (sc->rxBdCount * sizeof *sc->rxMbuf,
+ M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc (sc->txBdCount * sizeof *sc->txMbuf,
+ M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = m8xx_bd_allocate (sc->rxBdCount);
+ sc->txBdBase = m8xx_bd_allocate (sc->txBdCount);
+
+ m8260.scc3p.rbase = (char *)sc->rxBdBase - (char *)&m8260;
+ m8260.scc3p.tbase = (char *)sc->txBdBase - (char *)&m8260;
+
+ /*
+ * Send "Init parameters" command
+ */
+
+ m8xx_cp_execute_cmd (M8260_CR_OP_INIT_RX_TX | M8260_CR_SCC3 );
+
+ /*
+ * Set receive and transmit function codes
+ */
+ m8260.scc3p.rfcr = M8260_RFCR_MOT | M8260_RFCR_60X_BUS;
+ m8260.scc3p.tfcr = M8260_TFCR_MOT | M8260_TFCR_60X_BUS;
+
+ /*
+ * Set maximum receive buffer length
+ */
+ m8260.scc3p.mrblr = RBUF_SIZE;
+
+ m8260.scc3p.un.hdlc.c_mask = 0xF0B8;
+ m8260.scc3p.un.hdlc.c_pres = 0xFFFF;
+ m8260.scc3p.un.hdlc.disfc = 0;
+ m8260.scc3p.un.hdlc.crcec = 0;
+ m8260.scc3p.un.hdlc.abtsc = 0;
+ m8260.scc3p.un.hdlc.nmarc = 0;
+ m8260.scc3p.un.hdlc.retrc = 0;
+ m8260.scc3p.un.hdlc.rfthr = 1;
+ m8260.scc3p.un.hdlc.mflr = RBUF_SIZE;
+
+ m8260.scc3p.un.hdlc.hmask = 0x0000; /* promiscuous */
+
+ m8260.scc3p.un.hdlc.haddr1 = 0xFFFF; /* Broadcast address */
+ m8260.scc3p.un.hdlc.haddr2 = 0xFFFF; /* Station address */
+ m8260.scc3p.un.hdlc.haddr3 = 0xFFFF; /* Dummy */
+ m8260.scc3p.un.hdlc.haddr4 = 0xFFFF; /* Dummy */
+
+ /*
+ * Send "Init parameters" command
+ */
+/*
+ m8xx_cp_execute_cmd (M8260_CR_OP_INIT_RX_TX | M8260_CR_SCC3 );
+*/
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++) {
+ (sc->rxBdBase + i)->status = 0;
+ }
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ (sc->txBdBase + i)->status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ m8260.scc3.sccm = 0; /* No interrupts unmasked till necessary */
+
+ /*
+ * Clear any outstanding events
+ */
+ m8260.scc3.scce = 0xFFFF;
+
+ /*
+ * Set up interrupts
+ */
+ status = BSP_install_rtems_irq_handler (&hdlcSCC3IrqData);
+/*
+ printk( "status = %d, Success = %d\n", status, RTEMS_SUCCESSFUL );
+*/
+ if (status != 1 /*RTEMS_SUCCESSFUL*/ ) {
+ rtems_panic ("Can't attach M8260 SCC3 interrupt handler: %s\n",
+ rtems_status_text (status));
+ }
+ m8260.scc3.sccm = 0; /* No interrupts unmasked till necessary */
+
+ m8260.scc3.gsmr_h = 0;
+ m8260.scc3.gsmr_l = 0x10000000;
+ m8260.scc3.dsr = 0x7E7E; /* flag character */
+ m8260.scc3.psmr = 0x2000; /* 2 flags between Tx'd frames */
+
+/* printk("scc3 init\n" ); */
+
+ m8260.scc3.gsmr_l |= 0x00000030; /* Set ENR and ENT to enable Rx and Tx */
+
+}
+
+/*
+ * Soak up buffer descriptors that have been sent
+ * Note that a buffer descriptor can't be retired as soon as it becomes
+ * ready. The MC68360 Errata (May 96) says that, "If an Ethernet frame is
+ * made up of multiple buffers, the user should not reuse the first buffer
+ * descriptor until the last buffer descriptor of the frame has had its
+ * ready bit cleared by the CPM".
+ */
+static void
+m8260Enet_retire_tx_bd (struct m8260_hdlc_struct *sc)
+{
+ uint16_t status;
+ int i;
+ int nRetired;
+ struct mbuf *m, *n;
+
+ i = sc->txBdTail;
+ nRetired = 0;
+ while ((sc->txBdActiveCount != 0)
+ && (((status = (sc->txBdBase + i)->status) & M8260_BD_READY) == 0)) {
+ /*
+ * See if anything went wrong
+ */
+ if (status & (M8260_BD_UNDERRUN |
+ M8260_BD_CTS_LOST)) {
+ /*
+ * Check for errors which stop the transmitter.
+ */
+ if( status & M8260_BD_UNDERRUN ) {
+ hdlc_driver[0].txUnderrun++;
+
+ /*
+ * Restart the transmitter
+ */
+ /* FIXME: this should get executed only if using the SCC */
+ m8xx_cp_execute_cmd (M8260_CR_OP_RESTART_TX | M8260_CR_SCC3);
+ }
+ if (status & M8260_BD_CTS_LOST)
+ hdlc_driver[0].txLostCarrier++;
+ }
+ nRetired++;
+ if (status & M8260_BD_LAST) {
+ /*
+ * A full frame has been transmitted.
+ * Free all the associated buffer descriptors.
+ */
+ sc->txBdActiveCount -= nRetired;
+ while (nRetired) {
+ nRetired--;
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE (m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ }
+ }
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+}
+
+/*
+ * reader task
+ */
+static void
+scc_rxDaemon (void *arg)
+{
+ struct m8260_hdlc_struct *sc = (struct m8260_hdlc_struct *)arg;
+ struct ifnet *ifp = &sc->ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ m8260BufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ rxBd->status = M8260_BD_EMPTY | M8260_BD_INTERRUPT;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= M8260_BD_WRAP;
+ break;
+ }
+ }
+
+/*
+ m8260.scc3.sccm |= M8260_SCCE_RXF;
+*/
+
+ /*
+ * Input packet handling loop
+ */
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & M8260_BD_EMPTY) {
+ /*
+ * Clear old events
+ */
+
+ m8260.scc3.scce = M8260_SCCE_RXF;
+
+ /*
+ * Wait for packet
+ * Note that the buffer descriptor is checked
+ * *before* the event wait -- this catches the
+ * possibility that a packet arrived between the
+ * `if' above, and the clearing of the event register.
+ */
+ while ((status = rxBd->status) & M8260_BD_EMPTY) {
+ rtems_event_set events;
+
+ /*
+ * Unmask RXF (Full frame received) event
+ */
+ m8260.scc3.sccm |= M8260_SCCE_RXF;
+
+/* printk( "Rxdwait "); */
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+/* printk( "Rxd " ); */
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if ((status & (M8260_BD_LAST |
+ M8260_BD_FIRST_IN_FRAME |
+ M8260_BD_LONG |
+ M8260_BD_NONALIGNED |
+ M8260_BD_ABORT |
+ M8260_BD_CRC_ERROR |
+ M8260_BD_OVERRUN /*|
+ M8260_BD_CARRIER_LOST*/)) ==
+ (M8260_BD_LAST |
+ M8260_BD_FIRST_IN_FRAME ) ) {
+
+/* printk( "RxV " ); */
+
+/*
+ * Invalidate the buffer for this descriptor
+ */
+
+ rtems_cache_invalidate_multiple_data_lines((void *)rxBd->buffer, rxBd->length);
+
+ m = sc->rxMbuf[rxBdIndex];
+
+ /* strip off HDLC CRC */
+ m->m_len = m->m_pkthdr.len = rxBd->length - sizeof(uint16_t);
+
+ hdlc_input( ifp, m );
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ }
+ else {
+ printk( "RxErr[%04X,%d]", status, rxBd->length );
+ /*
+ * Something went wrong with the reception
+ */
+ if (!(status & M8260_BD_LAST))
+ sc->rxNotLast++;
+ if (!(status & M8260_BD_FIRST_IN_FRAME))
+ sc->rxNotFirst++;
+
+ if (status & M8260_BD_LONG)
+ sc->rxGiant++;
+ if (status & M8260_BD_NONALIGNED)
+ sc->rxNonOctet++;
+ if (status & M8260_BD_ABORT)
+ sc->rxAbort++;
+ if (status & M8260_BD_CRC_ERROR)
+ sc->rxBadCRC++;
+ if (status & M8260_BD_OVERRUN)
+ sc->rxOverrun++;
+ if (status & M8260_BD_CARRIER_LOST)
+ sc->rxLostCarrier++;
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & (M8260_BD_WRAP | M8260_BD_INTERRUPT)) |
+ M8260_BD_EMPTY;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+static void
+scc_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct m8260_hdlc_struct *sc = ifp->if_softc;
+ volatile m8260BufferDescriptor_t *firstTxBd, *txBd;
+ struct mbuf *l = NULL;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ m8260Enet_retire_tx_bd (sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ txBd = firstTxBd = sc->txBdBase + sc->txBdHead;
+
+/*
+ m8260.scc3.sccm |= (M8260_SCCE_TX | M8260_SCCE_TXE);
+*/
+
+ for (;;) {
+ /*
+ * Wait for buffer descriptor to become available.
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events
+ */
+ m8260.scc3.scce = M8260_SCCE_TX | M8260_SCCE_TXE;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Note that the buffer descriptors are checked
+ * *before* * entering the wait loop -- this catches
+ * the possibility that a buffer descriptor became
+ * available between the `if' above, and the clearing
+ * of the event register.
+ * This is to catch the case where the transmitter
+ * stops in the middle of a frame -- and only the
+ * last buffer descriptor in a frame can generate
+ * an interrupt.
+ */
+ m8260Enet_retire_tx_bd (sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+
+ /*
+ * Unmask TX (buffer transmitted) event
+ */
+ m8260.scc3.sccm |= (M8260_SCCE_TX | M8260_SCCE_TXE);
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ m8260Enet_retire_tx_bd (sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag till the
+ * whole packet has been readied.
+ */
+ status = nAdded ? M8260_BD_READY : 0;
+
+ /*
+ * FIXME: Why not deal with empty mbufs at at higher level?
+ * The IP fragmentation routine in ip_output
+ * can produce packet fragments with zero length.
+ * I think that ip_output should be changed to get
+ * rid of these zero-length mbufs, but for now,
+ * I'll deal with them here.
+ */
+ if (m->m_len) {
+ /*
+ * Fill in the buffer descriptor
+ */
+
+ txBd->buffer = mtod (m, void *);
+ txBd->length = m->m_len;
+
+ /*
+ * Flush the buffer for this descriptor
+ */
+
+ rtems_cache_flush_multiple_data_lines((void *)txBd->buffer, txBd->length);
+
+/* throw off the header for Ethernet Emulation mode */
+/*
+ txBd->buffer = mtod (m, void *);
+ txBd->buffer += sizeof( struct ether_header ) + 2;
+ txBd->length = m->m_len - sizeof( struct ether_header ) - 2;
+*/
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= M8260_BD_WRAP;
+ sc->txBdHead = 0;
+ }
+ l = m;
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE (m, n);
+ m = n;
+ if (l != NULL)
+ l->m_next = m;
+ }
+
+ /*
+ * Set the transmit buffer status.
+ * Break out of the loop if this mbuf is the last in the frame.
+ */
+ if (m == NULL) {
+ if (nAdded) {
+ status |= M8260_BD_LAST | M8260_BD_TX_CRC | M8260_BD_INTERRUPT;
+ txBd->status = status;
+ firstTxBd->status |= M8260_BD_READY;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ txBd = sc->txBdBase + sc->txBdHead;
+ }
+}
+
+/*
+ * Driver transmit daemon
+ */
+void
+scc_txDaemon (void *arg)
+{
+ struct m8260_hdlc_struct *sc = (struct m8260_hdlc_struct *)arg;
+ struct ifnet *ifp = &sc->ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT, RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+
+ scc_sendpacket (ifp, m);
+
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+m8260_hdlc_start (struct ifnet *ifp)
+{
+ struct m8260_hdlc_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/*
+ * Initialize and start the device
+ */
+static void
+scc_init (void *arg)
+{
+ struct m8260_hdlc_struct *sc = arg;
+ struct ifnet *ifp = &sc->ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up SCC hardware
+ */
+ m8260_scc_initialize_hardware (sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("SCtx", 4096, scc_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("SCrx", 4096, scc_rxDaemon, sc);
+
+ }
+
+#if 0
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ m8260.scc3.psmr |= 0x200;
+ else
+ m8260.scc3.psmr &= ~0x200;
+#endif
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ m8260.scc3.gsmr_l |= 0x30;
+}
+
+/*
+ * Stop the device
+ */
+static void
+scc_stop (struct m8260_hdlc_struct *sc)
+{
+ struct ifnet *ifp = &sc->ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ m8260.scc3.gsmr_l &= ~0x30;
+}
+
+/*
+ * Show interface statistics
+ */
+static void
+hdlc_stats (struct m8260_hdlc_struct *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" No Carrier:%-8lu\n", sc->rxLostCarrier);
+ printf (" Discarded:%-8lu\n", (unsigned long)m8260.scc3p.un.hdlc.disfc);
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf (" Underrun:%-8lu\n", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+/*
+ * Driver ioctl handler
+ */
+static int
+scc_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct m8260_hdlc_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ hdlc_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ scc_stop (sc);
+ break;
+
+ case IFF_UP:
+ scc_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ scc_stop (sc);
+ scc_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ hdlc_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/*
+ * Attach an SCC driver to the system
+ */
+int
+rtems_scc3_driver_attach (struct rtems_bsdnet_ifconfig *config)
+{
+ struct m8260_hdlc_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int i;
+
+ /*
+ * Find a free driver
+ */
+ for (i = 0 ; i < NIFACES ; i++) {
+ sc = &hdlc_driver[i];
+ ifp = &sc->ac_if;
+ if (ifp->if_softc == NULL)
+ break;
+ }
+ if (i >= NIFACES) {
+ printf ("Too many SCC drivers.\n");
+ return 0;
+ }
+
+#if 0
+ /*
+ * Process options
+ */
+
+ if (config->hardware_address) {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+ else {
+ sc->arpcom.ac_enaddr[0] = 0x44;
+ sc->arpcom.ac_enaddr[1] = 0x22;
+ sc->arpcom.ac_enaddr[2] = 0x33;
+ sc->arpcom.ac_enaddr[3] = 0x33;
+ sc->arpcom.ac_enaddr[4] = 0x22;
+ sc->arpcom.ac_enaddr[5] = 0x44;
+ }
+#endif
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = i + 1;
+ ifp->if_name = "eth";
+ ifp->if_mtu = mtu;
+ ifp->if_init = scc_init;
+ ifp->if_ioctl = scc_ioctl;
+ ifp->if_start = m8260_hdlc_start;
+ ifp->if_output = hdlc_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | /*IFF_PROMISC |*/ IFF_NOARP;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ hdlc_ifattach (ifp);
+ return 1;
+};
+
+int
+rtems_enet_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ return rtems_scc3_driver_attach( config );
+
+/*
+ if ((m8260.fec.mii_data & 0xffff) == 0x2000) {
+ return rtems_fec_driver_attach(config);
+ }
+ else {
+ return rtems_scc1_driver_attach(config);
+ }
+*/
+}
diff --git a/bsps/powerpc/mvme3100/net/tsec.c b/bsps/powerpc/mvme3100/net/tsec.c
new file mode 100644
index 0000000..23afbc0
--- /dev/null
+++ b/bsps/powerpc/mvme3100/net/tsec.c
@@ -0,0 +1,3208 @@
+/*
+ * Authorship
+ * ----------
+ * This software ('mvme3100' RTEMS BSP) was created by
+ *
+ * Till Straumann <strauman@slac.stanford.edu>, 2005-2007,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * The 'mvme3100' BSP was produced by
+ * the Stanford Linear Accelerator Center, Stanford University,
+ * under Contract DE-AC03-76SFO0515 with the Department of Energy.
+ *
+ * Government disclaimer of liability
+ * ----------------------------------
+ * Neither the United States nor the United States Department of Energy,
+ * nor any of their employees, makes any warranty, express or implied, or
+ * assumes any legal liability or responsibility for the accuracy,
+ * completeness, or usefulness of any data, apparatus, product, or process
+ * disclosed, or represents that its use would not infringe privately owned
+ * rights.
+ *
+ * Stanford disclaimer of liability
+ * --------------------------------
+ * Stanford University makes no representations or warranties, express or
+ * implied, nor assumes any liability for the use of this software.
+ *
+ * Stanford disclaimer of copyright
+ * --------------------------------
+ * Stanford University, owner of the copyright, hereby disclaims its
+ * copyright and all other rights in this software. Hence, anyone may
+ * freely use it for any purpose without restriction.
+ *
+ * Maintenance of notices
+ * ----------------------
+ * In the interest of clarity regarding the origin and status of this
+ * SLAC software, this and all the preceding Stanford University notices
+ * are to remain affixed to any copy or derivative of this software made
+ * or distributed by the recipient and are to be affixed to any copy of
+ * software made or distributed by the recipient that contains a copy or
+ * derivative of this software.
+ *
+ * ------------------ SLAC Software Notices, Set 4 OTT.002a, 2004 FEB 03
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+#include <rtems/error.h>
+#include <bsp/irq.h>
+#include <libcpu/byteorder.h>
+#include <inttypes.h>
+#include <stdio.h>
+#include <errno.h>
+#include <assert.h>
+#include <bsp.h>
+
+#include <rtems/rtems_bsdnet.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/ethernet.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <rtems/rtems_mii_ioctl.h>
+
+#include <bsp/if_tsec_pub.h>
+
+#define STATIC
+#define PARANOIA
+#undef DEBUG
+
+
+#ifdef TEST_MII_TIMING
+
+#include <libcpu/spr.h>
+
+SPR_RO(TBRL)
+
+static inline uint32_t tb_rd()
+{
+ return _read_TBRL();
+}
+#endif
+
+struct tsec_private;
+
+/* Forward declarations */
+static void
+phy_init_irq( int install, struct tsec_private *mp, void (*tsec_lisr)(rtems_irq_hdl_param) );
+
+static void
+phy_en_irq(struct tsec_private *mp);
+
+static void
+phy_en_irq_at_phy(struct tsec_private *mp);
+
+static void
+phy_dis_irq(struct tsec_private *mp);
+
+static void
+phy_dis_irq_at_phy(struct tsec_private *mp);
+
+static int
+phy_irq_pending(struct tsec_private *mp);
+
+static uint32_t
+phy_ack_irq(struct tsec_private *mp);
+
+static void
+tsec_update_mcast(struct ifnet *ifp);
+
+#if defined(PARANOIA) || defined(DEBUG)
+void tsec_dump_tring(struct tsec_private *mp);
+void tsec_dump_rring(struct tsec_private *mp);
+#endif
+
+#ifdef DEBUG
+#ifdef TSEC_RX_RING_SIZE
+#undef TSEC_RX_RING_SIZE
+#endif
+#define TSEC_RX_RING_SIZE 4
+
+#ifdef TSEC_TX_RING_SIZE
+#undef TSEC_TX_RING_SIZE
+#endif
+#define TSEC_TX_RING_SIZE 2
+#else
+#ifndef TSEC_RX_RING_SIZE
+#define TSEC_RX_RING_SIZE 40
+#endif
+#ifndef TSEC_TX_RING_SIZE
+#define TSEC_TX_RING_SIZE 200
+#endif
+#endif
+
+/********** Helper Macros and Definitions ******/
+
+/*
+ * Align 'p' up to a multiple of 'a' which must be
+ * a power of two. Result is cast to (uintptr_t)
+ */
+#define ALIGNTO(p,a) ((((uintptr_t)(p)) + (a) - 1) & ~((a)-1))
+
+
+/*
+ * Not obvious from the doc: RX buffers apparently must be 32-byte
+ * aligned :-(; TX buffers have no alignment requirement.
+ * I found this by testing, T.S, 11/2007
+ */
+#define RX_BUF_ALIGNMENT 32
+
+/*
+ * Alignment req. for buffer descriptors (BDs)
+ */
+#define BD_ALIGNMENT 8
+
+
+#define ETH_RX_OFFSET 0
+#define ETH_CRC_LEN 0
+
+#define CPU2BUS_ADDR(x) (x)
+#define BUS2CPU_ADDR(x) (x)
+
+/*
+ * Whether to automatically try to reclaim descriptors
+ * when enqueueing new packets
+ */
+#if 1
+#define TSEC_CLEAN_ON_SEND(mp) (BSP_tsec_swipe_tx(mp))
+#else
+#define TSEC_CLEAN_ON_SEND(mp) (-1)
+#endif
+
+#define TX_AVAILABLE_RING_SIZE(mp) (mp)->tx_ring_size
+
+#define DRVNAME "tsec"
+
+/*
+ * Event(s) posted by ISRs to driver task
+ */
+#define EV_PER_UNIT 1
+
+#define TSEC_ETH_EVENT( unit ) ( 1 << (EV_PER_UNIT * (unit) ))
+#if EV_PER_UNIT > 1
+#define TSEC_PHY_EVENT( unit ) ( 1 << (EV_PER_UNIT * (unit) + 1))
+#endif
+
+#define EV_IS_ETH(ev) ( (ev) & 1 )
+#if EV_PER_UNIT > 1
+#define EV_IS_PHY(ev) ( (ev) & 2 )
+#endif
+
+#ifndef MAXEBERRS
+#define MAXEBERRS 10
+#endif
+
+#define EV_IS_ANY(ev) ( (ev) & ((1<<EV_PER_UNIT) - 1) )
+
+#define EV_MSK ( ( 1 << (EV_PER_UNIT * TSEC_NUM_DRIVER_SLOTS) ) - 1)
+
+
+/********** Register Definitions ****************/
+
+/*
+ * Most registers/bits apply to the FEC also;
+ * things that are not supported by the FEC
+ * are commented 'TSEC only'
+ */
+
+#define TSEC_IEVENT 0x010
+#define TSEC_IEVENT_BABR (1<<(31- 0))
+#define TSEC_IEVENT_RXC (1<<(31- 1))
+#define TSEC_IEVENT_BSY (1<<(31- 2))
+#define TSEC_IEVENT_EBERR (1<<(31- 3))
+/*
+ * Misuse reserved bit 4 to flag link interrupts
+ * (which are totally external to the TSEC).
+ * Because reading the MII is so slow we don't
+ * want to poll MII unnecessarily from RX/TX ISRs
+ */
+#define TSEC_LINK_INTR (1<<(31- 4))
+#define TSEC_IEVENT_MSRO (1<<(31- 5))
+#define TSEC_IEVENT_GTSC (1<<(31- 6))
+#define TSEC_IEVENT_BABT (1<<(31- 7))
+#define TSEC_IEVENT_TXC (1<<(31- 8))
+#define TSEC_IEVENT_TXE (1<<(31- 9))
+#define TSEC_IEVENT_TXB (1<<(31-10))
+#define TSEC_IEVENT_TXF (1<<(31-11))
+#define TSEC_IEVENT_LC (1<<(31-13))
+#define TSEC_IEVENT_CRLXDA (1<<(31-14))
+#define TSEC_IEVENT_XFUN (1<<(31-15))
+#define TSEC_IEVENT_RXB (1<<(31-16))
+#define TSEC_IEVENT_GRSC (1<<(31-23))
+#define TSEC_IEVENT_RXF (1<<(31-24))
+#define TSEC_IEVENT_ALL (-1)
+
+#if TSEC_TXIRQ != ( TSEC_IEVENT_TXE | TSEC_IEVENT_TXF )
+#error "mismatch in definition: TSEC_TXIRQ"
+#endif
+
+#if TSEC_RXIRQ != ( TSEC_IEVENT_RXF | TSEC_IEVENT_BABR | TSEC_IEVENT_EBERR )
+#error "mismatch in definition: TSEC_RXIRQ"
+#endif
+
+#if TSEC_LKIRQ != TSEC_LINK_INTR
+#error "mismatch in definition: TSEC_LKIRQ"
+#endif
+
+#define TSEC_IMASK 0x014
+#define TSEC_IMASK_BABREN (1<<(31- 0))
+#define TSEC_IMASK_RXCEN (1<<(31- 1))
+#define TSEC_IMASK_BSYEN (1<<(31- 2))
+#define TSEC_IMASK_EBERREN (1<<(31- 3))
+#define TSEC_IMASK_MSROEN (1<<(31- 5))
+#define TSEC_IMASK_GTSCEN (1<<(31- 6))
+#define TSEC_IMASK_BABTEN (1<<(31- 7))
+#define TSEC_IMASK_TXCEN (1<<(31- 8))
+#define TSEC_IMASK_TXEEN (1<<(31- 9))
+#define TSEC_IMASK_TXBEN (1<<(31-10))
+#define TSEC_IMASK_TXFEN (1<<(31-11))
+#define TSEC_IMASK_LCEN (1<<(31-13))
+#define TSEC_IMASK_CRLXDAEN (1<<(31-14))
+#define TSEC_IMASK_XFUNEN (1<<(31-15))
+#define TSEC_IMASK_RXBEN (1<<(31-16))
+#define TSEC_IMASK_GRSCEN (1<<(31-23))
+#define TSEC_IMASK_RXFEN (1<<(31-24))
+#define TSEC_IMASK_NONE (0)
+#define TSEC_EDIS 0x018
+#define TSEC_ECNTRL 0x020 /* TSEC only */
+#define TSEC_ECNTRL_CLRCNT (1<<(31-17))
+#define TSEC_ECNTRL_AUTOZ (1<<(31-18))
+#define TSEC_ECNTRL_STEN (1<<(31-19))
+#define TSEC_ECNTRL_TBIM (1<<(31-26))
+#define TSEC_ECNTRL_RPM (1<<(31-27))
+#define TSEC_ECNTRL_R100M (1<<(31-28))
+#define TSEC_MINFLR 0x024
+#define TSEC_PTV 0x028
+#define TSEC_DMACTRL 0x02c
+#define TSEC_DMACTRL_TDSEN (1<<(31-24))
+#define TSEC_DMACTRL_TBDSEN (1<<(31-25))
+#define TSEC_DMACTRL_GRS (1<<(31-27))
+#define TSEC_DMACTRL_GTS (1<<(31-28))
+#define TSEC_DMACTRL_WWR (1<<(31-30))
+#define TSEC_DMACTRL_WOP (1<<(31-31))
+#define TSEC_TBIPA 0x030 /* TSEC only */
+#define TSEC_FIFO_PAUSE_CTRL 0x04c
+#define TSEC_FIFO_TX_THR 0x08c
+#define TSEC_FIFO_TX_STARVE 0x098
+#define TSEC_FIFO_TX_STARVE_SHUTOFF 0x09c
+#define TSEC_TCTRL 0x100
+#define TSEC_TCTRL_THDR (1<<(31-20))
+#define TSEC_TCTRL_RFC_PAUSE (1<<(31-27))
+#define TSEC_TCTRL_TFC_PAUSE (1<<(31-28))
+#define TSEC_TSTAT 0x104
+#define TSEC_TSTAT_THLT (1<<(31- 0))
+#define TSEC_TBDLEN 0x10c
+#define TSEC_TXIC 0x110 /* TSEC only */
+#define TSEC_IC_ICEN (1<<(31- 0))
+#define TSEC_IC_ICFCT(x) (((x)&0xff)<<(31-10))
+#define TSEC_IC_ICTT(x) (((x)&0xffff)<<(31-31))
+#define TSEC_CTBPTR 0x124
+#define TSEC_TBPTR 0x184
+#define TSEC_TBASE 0x204
+#define TSEC_OSTBD 0x2b0
+#define TSEC_OSTBDP 0x2b4
+#define TSEC_RCTRL 0x300
+#define TSEC_RCTRL_BC_REJ (1<<(31-27))
+#define TSEC_RCTRL_PROM (1<<(31-28))
+#define TSEC_RCTRL_RSF (1<<(31-29))
+#define TSEC_RSTAT 0x304
+#define TSEC_RSTAT_QHLT (1<<(31- 8))
+#define TSEC_RBDLEN 0x30c
+#define TSEC_RXIC 0x310 /* TSEC only */
+#define TSEC_CRBPTR 0x324
+#define TSEC_MRBLR 0x340
+#define TSEC_RBPTR 0x384
+#define TSEC_RBASE 0x404
+#define TSEC_MACCFG1 0x500
+#define TSEC_MACCFG1_SOFT_RESET (1<<(31- 0))
+#define TSEC_MACCFG1_LOOP_BACK (1<<(31-23))
+#define TSEC_MACCFG1_RX_FLOW (1<<(31-26))
+#define TSEC_MACCFG1_TX_FLOW (1<<(31-27))
+#define TSEC_MACCFG1_SYNCD_RX_EN (1<<(31-28))
+#define TSEC_MACCFG1_RX_EN (1<<(31-29))
+#define TSEC_MACCFG1_SYNCD_TX_EN (1<<(31-30))
+#define TSEC_MACCFG1_TX_EN (1<<(31-31))
+#define TSEC_MACCFG2 0x504
+#define TSEC_MACCFG2_PREAMBLE_7 (7<<(31-19))
+#define TSEC_MACCFG2_PREAMBLE_15 (15<<(31-19))
+#define TSEC_MACCFG2_IF_MODE_MII (1<<(31-23))
+#define TSEC_MACCFG2_IF_MODE_GMII (2<<(31-23))
+#define TSEC_MACCFG2_HUGE_FRAME (1<<(31-26))
+#define TSEC_MACCFG2_LENGTH_CHECK (1<<(31-27))
+#define TSEC_MACCFG2_PAD_CRC (1<<(31-29))
+#define TSEC_MACCFG2_CRC_EN (1<<(31-30))
+#define TSEC_MACCFG2_FD (1<<(31-31))
+#define TSEC_IPGIFG 0x508
+#define TSEC_HAFDUP 0x50c
+#define TSEC_MAXFRM 0x510
+#define TSEC_MIIMCFG 0x520 /* TSEC only */
+#define TSEC_MIIMCOM 0x524 /* TSEC only */
+#define TSEC_MIIMCOM_SCAN (1<<(31-30))
+#define TSEC_MIIMCOM_READ (1<<(31-31))
+#define TSEC_MIIMADD 0x528 /* TSEC only */
+#define TSEC_MIIMADD_ADDR(phy, reg) ((((phy)&0x1f)<<8) | ((reg) & 0x1f))
+#define TSEC_MIIMCON 0x52c /* TSEC only */
+#define TSEC_MIIMSTAT 0x530 /* TSEC only */
+#define TSEC_MIIMIND 0x534 /* TSEC only */
+#define TSEC_MIIMIND_NV (1<<(31-29))
+#define TSEC_MIIMIND_SCAN (1<<(31-30))
+#define TSEC_MIIMIND_BUSY (1<<(31-31))
+#define TSEC_IFSTAT 0x53c
+#define TSEC_MACSTNADDR1 0x540
+#define TSEC_MACSTNADDR2 0x544
+#define TSEC_TR64 0x680 /* TSEC only */
+#define TSEC_TR127 0x684 /* TSEC only */
+#define TSEC_TR255 0x688 /* TSEC only */
+#define TSEC_TR511 0x68c /* TSEC only */
+#define TSEC_TR1K 0x690 /* TSEC only */
+#define TSEC_TRMAX 0x694 /* TSEC only */
+#define TSEC_TRMGV 0x698 /* TSEC only */
+#define TSEC_RBYT 0x69c /* TSEC only */
+#define TSEC_RPKT 0x6a0 /* TSEC only */
+#define TSEC_RFCS 0x6a4 /* TSEC only */
+#define TSEC_RMCA 0x6a8 /* TSEC only */
+#define TSEC_RBCA 0x6ac /* TSEC only */
+#define TSEC_RXCF 0x6b0 /* TSEC only */
+#define TSEC_RXPF 0x6b4 /* TSEC only */
+#define TSEC_RXUO 0x6b8 /* TSEC only */
+#define TSEC_RALN 0x6bc /* TSEC only */
+#define TSEC_RFLR 0x6c0 /* TSEC only */
+#define TSEC_RCDE 0x6c4 /* TSEC only */
+#define TSEC_RCSE 0x6c8 /* TSEC only */
+#define TSEC_RUND 0x6cc /* TSEC only */
+#define TSEC_ROVR 0x6d0 /* TSEC only */
+#define TSEC_RFRG 0x6d4 /* TSEC only */
+#define TSEC_RJBR 0x6d8 /* TSEC only */
+#define TSEC_RDRP 0x6dc /* TSEC only */
+#define TSEC_TBYT 0x6e0 /* TSEC only */
+#define TSEC_TPKT 0x6e4 /* TSEC only */
+#define TSEC_TMCA 0x6e8 /* TSEC only */
+#define TSEC_TBCA 0x6ec /* TSEC only */
+#define TSEC_TXPF 0x6f0 /* TSEC only */
+#define TSEC_TDFR 0x6f4 /* TSEC only */
+#define TSEC_TEDF 0x6f8 /* TSEC only */
+#define TSEC_TSCL 0x6fc /* TSEC only */
+#define TSEC_TMCL 0x700 /* TSEC only */
+#define TSEC_TLCL 0x704 /* TSEC only */
+#define TSEC_TXCL 0x708 /* TSEC only */
+#define TSEC_TNCL 0x70c /* TSEC only */
+#define TSEC_TDRP 0x714 /* TSEC only */
+#define TSEC_TJBR 0x718 /* TSEC only */
+#define TSEC_TFCS 0x71c /* TSEC only */
+#define TSEC_TXCF 0x720 /* TSEC only */
+#define TSEC_TOVR 0x724 /* TSEC only */
+#define TSEC_TUND 0x728 /* TSEC only */
+#define TSEC_TFRG 0x72c /* TSEC only */
+#define TSEC_CAR1 0x730 /* TSEC only */
+#define TSEC_CAR2 0x734 /* TSEC only */
+#define TSEC_CAM1 0x738 /* TSEC only */
+#define TSEC_CAM2 0x73c /* TSEC only */
+#define TSEC_IADDR0 0x800
+#define TSEC_IADDR1 0x804
+#define TSEC_IADDR2 0x808
+#define TSEC_IADDR3 0x80c
+#define TSEC_IADDR4 0x810
+#define TSEC_IADDR5 0x814
+#define TSEC_IADDR6 0x818
+#define TSEC_IADDR7 0x81c
+#define TSEC_GADDR0 0x880
+#define TSEC_GADDR1 0x884
+#define TSEC_GADDR2 0x888
+#define TSEC_GADDR3 0x88c
+#define TSEC_GADDR4 0x890
+#define TSEC_GADDR5 0x894
+#define TSEC_GADDR6 0x898
+#define TSEC_GADDR7 0x89c
+#define TSEC_ATTR 0xbf8
+#define TSEC_ATTR_ELCWT_NONE (0<<(31-18))
+#define TSEC_ATTR_ELCWT_ALLOC (2<<(31-18))
+#define TSEC_ATTR_ELCWT_ALLOC_LOCK (3<<(31-18))
+#define TSEC_ATTR_BDLWT_NONE (0<<(31-21))
+#define TSEC_ATTR_BDLWT_ALLOC (2<<(31-21))
+#define TSEC_ATTR_BDLWT_ALLOC_LOCK (3<<(31-21))
+#define TSEC_ATTR_RDSEN (1<<(31-24))
+#define TSEC_ATTR_RBDSEN (1<<(31-25))
+#define TSEC_ATTRELI 0xbfc
+
+/********** Memory Barriers *********************/
+
+#ifdef __PPC__
+static inline void membarrier(void)
+{
+ asm volatile("sync":::"memory");
+}
+
+#define EIEIO(mem) do { __asm__ volatile("eieio"); } while (0)
+
+#else
+#error "memory barrier not implemented for your CPU architecture"
+#endif
+
+/********** Register Access Primitives **********/
+
+/*
+ * Typedef for base address (uint8_t *) so that
+ * we can do easy pointer arithmetic.
+ */
+typedef volatile uint8_t *FEC_Enet_Base;
+
+/*
+ * All TSEC/FEC registers are 32-bit only.
+ */
+typedef volatile uint32_t FEC_Reg __attribute__((may_alias));
+
+static inline uint32_t
+fec_rd(FEC_Enet_Base b, uint32_t reg)
+{
+#ifdef __BIG_ENDIAN__
+uint32_t rval = *(FEC_Reg *)(b + reg);
+ EIEIO(*(FEC_Reg*)(b+reg));
+ return rval;
+#else
+ return in_be32( (volatile uint32_t*) (b+reg) );
+#endif
+}
+
+static inline void
+fec_wr(FEC_Enet_Base b, uint32_t reg, uint32_t val)
+{
+#ifdef __BIG_ENDIAN__
+ *(FEC_Reg *)(b + reg) = val;
+ EIEIO(*(FEC_Reg*)(b+reg));
+#else
+ out_be32( (volatile uint32_t*) (b+reg), val );
+#endif
+}
+
+/* Set bits in a register */
+static inline void
+fec_set(FEC_Enet_Base b, uint32_t reg, uint32_t val)
+{
+ fec_wr(b, reg, fec_rd(b, reg) | val );
+}
+
+/* Clear bits in a register */
+static inline void
+fec_clr(FEC_Enet_Base b, uint32_t reg, uint32_t val)
+{
+ fec_wr(b, reg, fec_rd(b, reg) & ~val );
+}
+
+/* Clear and set bits in a register */
+static inline void
+fec_csl(FEC_Enet_Base b, uint32_t reg, uint32_t clr, uint32_t set)
+{
+ fec_wr(b, reg, (fec_rd(b, reg) & ~clr) | set);
+}
+
+
+/********** Memory Access Primitives ************/
+
+#ifdef __BIG_ENDIAN__
+static inline uint16_t ld_be16(volatile uint16_t *a)
+{
+ return *a;
+}
+
+static inline uint32_t ld_be32(volatile uint32_t *a)
+{
+ return *a;
+}
+
+static inline void st_be16(volatile uint16_t *a, uint16_t v)
+{
+ *a = v;
+}
+
+static inline void st_be32(volatile uint32_t *a, uint32_t v)
+{
+ *a = v;
+}
+#else
+#error "ld_be32 & friends not implemented"
+#endif
+
+/********** Note About Coherency ****************/
+
+#ifdef SW_COHERENCY
+#error "SW_COHERENCY not implemented"
+/* Note: maintaining BD coherency in software is not trivial
+ * because BDs are smaller than a cache line;
+ * we cannot pad a BD to the length of a cache line because
+ * the TSEC assumes BDs layed out sequentially in memory.
+ * We cannot use zero-length BDs to pad to a full cache
+ * line either because the manual says that the length
+ * field of a TX BD must not be zero.
+ *
+ * We probably would need MMU resources to map BDs
+ * as non-cachable.
+ *
+ * Maintaining buffer coherency would be easier:
+ * - make RX buffers cache aligned so we can
+ * invalidate them w/o overlapping other data.
+ * - TX buffers may be flushed to memory. If cache
+ * lines overlap anything else (besides TX buffers)
+ * then that would only be harmful if (part of) a
+ * TX buffer would share a cache line with another
+ * type of DMA buffer that is written by another
+ * master. Note that BDs have exactly this problem;
+ * we may not flush one BD because the TSEC could
+ * have written another BD to memory covered by
+ * the same cache line.
+ * This second BD could be lost by a DBCF operation:
+ * - writes 1st BD to memory OK
+ * - overwrites 2nd BD with stale data from cache
+ */
+#else
+#define FLUSH_BUF(addr, len) do {} while(0)
+#endif
+
+/********** Driver Data Structures **************/
+
+/* Buffer descriptor layout (defined by hardware) */
+struct tsec_bd {
+ volatile uint16_t flags;
+ volatile uint16_t len;
+ volatile uint32_t buf;
+};
+
+typedef struct tsec_bd TSEC_BD __attribute__((aligned(BD_ALIGNMENT)));
+
+/* BD access primitives */
+
+static inline uint16_t bd_rdfl(TSEC_BD *bd)
+{
+ return ld_be16( & bd->flags );
+}
+
+static inline void bd_wrfl(TSEC_BD *bd, uint16_t v)
+{
+ st_be16( &bd->flags, v );
+}
+
+static inline void bd_setfl(TSEC_BD *bd, uint16_t v)
+{
+ bd_wrfl(bd, bd_rdfl(bd) | v );
+}
+
+static inline void bd_clrfl(TSEC_BD *bd, uint16_t v)
+{
+ bd_wrfl(bd, bd_rdfl(bd) & ~v );
+}
+
+static inline void bd_cslfl(TSEC_BD *bd, uint16_t s, uint16_t c)
+{
+ bd_wrfl( bd, ( bd_rdfl(bd) & ~c ) | s );
+}
+
+static inline uint32_t bd_rdbuf(TSEC_BD *bd)
+{
+ return BUS2CPU_ADDR( ld_be32( &bd->buf ) );
+}
+
+static inline void bd_wrbuf(TSEC_BD *bd, uint32_t addr)
+{
+ st_be32( &bd->buf, CPU2BUS_ADDR(addr) );
+}
+
+/* BD bit definitions */
+
+#define TSEC_TXBD_R ((uint16_t)(1<<(15- 0)))
+#define TSEC_TXBD_PAD_CRC ((uint16_t)(1<<(15- 1)))
+#define TSEC_TXBD_W ((uint16_t)(1<<(15- 2)))
+#define TSEC_TXBD_I ((uint16_t)(1<<(15- 3)))
+#define TSEC_TXBD_L ((uint16_t)(1<<(15- 4)))
+#define TSEC_TXBD_TC ((uint16_t)(1<<(15- 5)))
+#define TSEC_TXBD_DEF ((uint16_t)(1<<(15- 6)))
+#define TSEC_TXBD_TO1 ((uint16_t)(1<<(15- 7)))
+#define TSEC_TXBD_HFE_LC ((uint16_t)(1<<(15- 8)))
+#define TSEC_TXBD_RL ((uint16_t)(1<<(15- 9)))
+#define TSEC_TXBD_RC(x) ((uint16_t)(((x)>>2)&0xf))
+#define TSEC_TXBD_UN ((uint16_t)(1<<(15-14)))
+#define TSEC_TXBD_TXTRUNC ((uint16_t)(1<<(15-15)))
+#define TSEC_TXBD_ERRS (TSEC_TXBD_RL | TSEC_TXBD_UN | TSEC_TXBD_TXTRUNC)
+
+#define TSEC_RXBD_E ((uint16_t)(1<<(15- 0)))
+#define TSEC_RXBD_RO1 ((uint16_t)(1<<(15- 1)))
+#define TSEC_RXBD_W ((uint16_t)(1<<(15- 2)))
+#define TSEC_RXBD_I ((uint16_t)(1<<(15- 3)))
+#define TSEC_RXBD_L ((uint16_t)(1<<(15- 4)))
+#define TSEC_RXBD_F ((uint16_t)(1<<(15- 5)))
+#define TSEC_RXBD_M ((uint16_t)(1<<(15- 7)))
+#define TSEC_RXBD_BC ((uint16_t)(1<<(15- 8)))
+#define TSEC_RXBD_MC ((uint16_t)(1<<(15- 9)))
+#define TSEC_RXBD_LG ((uint16_t)(1<<(15-10)))
+#define TSEC_RXBD_NO ((uint16_t)(1<<(15-11)))
+#define TSEC_RXBD_SH ((uint16_t)(1<<(15-12)))
+#define TSEC_RXBD_CR ((uint16_t)(1<<(15-13)))
+#define TSEC_RXBD_OV ((uint16_t)(1<<(15-14)))
+#define TSEC_RXBD_TR ((uint16_t)(1<<(15-15)))
+
+#define TSEC_RXBD_ERROR \
+ (TSEC_RXBD_LG | TSEC_RXBD_NO | TSEC_RXBD_SH | TSEC_RXBD_CR | TSEC_RXBD_OV | TSEC_RXBD_TR )
+
+/* Driver 'private' data */
+
+#define NUM_MC_HASHES 256
+
+struct tsec_private {
+ FEC_Enet_Base base; /* Controller base address */
+ FEC_Enet_Base phy_base; /* Phy base address (not necessarily identical
+ * with controller base address);
+ * e.g., phy attached to 2nd controller may be
+ * connected to mii bus of 1st controller.
+ */
+ unsigned phy; /* Phy address on mii bus */
+ unsigned unit; /* Driver instance (one-based */
+ int isfec; /* Set if a FEC (not TSEC) controller */
+ struct tsec_softc *sc; /* Pointer to BSD driver struct */
+ TSEC_BD *ring_area; /* Not necessarily aligned */
+ TSEC_BD *tx_ring; /* Aligned array of TX BDs */
+ void **tx_ring_user; /* Array of user pointers (1 per BD) */
+ unsigned tx_ring_size;
+ unsigned tx_head; /* first 'dirty' BD; chip is working on */
+ unsigned tx_tail; /* BDs between head and tail */
+ unsigned tx_avail; /* Number of available/free TX BDs */
+ TSEC_BD *rx_ring; /* Aligned array of RX BDs */
+ void **rx_ring_user; /* Array of user pointers (1 per BD) */
+ unsigned rx_tail; /* Where we left off scanning for full bufs */
+ unsigned rx_ring_size;
+ void (*isr)(void*);
+ void *isr_arg;
+ void (*cleanup_txbuf) /* Callback to cleanup TX ring */
+ (void*, void*, int);
+ void *cleanup_txbuf_arg;
+ void *(*alloc_rxbuf) /* Callback for allocating RX buffer */
+ (int *psize, uintptr_t *paddr);
+ void (*consume_rxbuf) /* callback to consume RX buffer */
+ (void*, void*, int);
+ void *consume_rxbuf_arg;
+ rtems_id tid; /* driver task ID */
+ uint32_t irq_mask;
+ uint32_t irq_mask_cache;
+ uint32_t irq_pending;
+ rtems_event_set event; /* Task synchronization events */
+ struct { /* Statistics */
+ unsigned xirqs;
+ unsigned rirqs;
+ unsigned eirqs;
+ unsigned lirqs;
+ unsigned maxchain;
+ unsigned packet;
+ unsigned odrops;
+ unsigned repack;
+ unsigned eberrs;
+ unsigned dmarst;
+ } stats;
+ uint16_t mc_refcnt[NUM_MC_HASHES];
+};
+
+#define NEXT_TXI(mp, i) (((i)+1) < (mp)->tx_ring_size ? (i)+1 : 0 )
+#define NEXT_RXI(mp, i) (((i)+1) < (mp)->rx_ring_size ? (i)+1 : 0 )
+
+/* Stuff needed for bsdnet support */
+struct tsec_bsdsupp {
+ int oif_flags; /* old / cached if_flags */
+};
+
+/* bsdnet driver data */
+struct tsec_softc {
+ struct arpcom arpcom;
+ struct tsec_bsdsupp bsd;
+ struct tsec_private pvt;
+};
+
+/* BSP glue information */
+typedef struct tsec_bsp_config {
+ uint32_t base;
+ int xirq, rirq, eirq;
+ uint32_t phy_base;
+ int phy_addr;
+} TsecBspConfig;
+
+/********** Global Variables ********************/
+
+/* You may override base addresses
+ * externally - but you must
+ * then also define TSEC_NUM_DRIVER_SLOTS.
+ */
+#ifndef TSEC_CONFIG
+
+static TsecBspConfig tsec_config[] =
+{
+ {
+ base: BSP_8540_CCSR_BASE + 0x24000,
+ xirq: BSP_CORE_IRQ_LOWEST_OFFSET + 13,
+ rirq: BSP_CORE_IRQ_LOWEST_OFFSET + 14,
+ eirq: BSP_CORE_IRQ_LOWEST_OFFSET + 18,
+ phy_base: BSP_8540_CCSR_BASE + 0x24000,
+ phy_addr: 1,
+ },
+ {
+ base: BSP_8540_CCSR_BASE + 0x25000,
+ xirq: BSP_CORE_IRQ_LOWEST_OFFSET + 19,
+ rirq: BSP_CORE_IRQ_LOWEST_OFFSET + 20,
+ eirq: BSP_CORE_IRQ_LOWEST_OFFSET + 23,
+ /* all PHYs are on the 1st adapter's mii bus */
+ phy_base: BSP_8540_CCSR_BASE + 0x24000,
+ phy_addr: 2,
+ },
+};
+
+#define TSEC_CONFIG tsec_config
+
+#endif
+
+#ifndef TSEC_NUM_DRIVER_SLOTS
+#define TSEC_NUM_DRIVER_SLOTS (sizeof(TSEC_CONFIG)/sizeof(TSEC_CONFIG[0]))
+#endif
+
+/* Driver data structs */
+STATIC struct tsec_softc theTsecEths[TSEC_NUM_DRIVER_SLOTS] = { {{{0}}} };
+
+/* Bsdnet driver task ID; since the BSD stack is single-threaded
+ * there is no point having multiple tasks. A single
+ * task handling all adapters (attached to BSD stack)
+ * is good enough.
+ * Note that an adapter might well be used independently
+ * from the BSD stack (use the low-level driver interface)
+ * and be serviced by a separate task.
+ */
+STATIC rtems_id tsec_tid = 0;
+
+/* If we anticipate using adapters independently
+ * from the BSD stack AND if all PHYs are on a single
+ * adapter's MII bus THEN we must mutex-protect
+ * that MII bus.
+ * If not all of these conditions hold then you
+ * may define TSEC_CONFIG_NO_PHY_REGLOCK and
+ * avoid the creation and use of a mutex.
+ */
+#ifndef TSEC_CONFIG_NO_PHY_REGLOCK
+/*
+ * PHY register access protection mutex;
+ * multiple instances of tsec hardware
+ * may share e.g., the first tsec's registers
+ * for accessing the mii bus where all PHYs
+ * may be connected. If we would only deal
+ * with BSD networking then using the normal
+ * networking semaphore would be OK. However,
+ * we want to support standalone drivers and
+ * therefore might require a separate lock.
+ */
+STATIC rtems_id tsec_mtx = 0;
+#define REGLOCK() do { \
+ if ( RTEMS_SUCCESSFUL != rtems_semaphore_obtain(tsec_mtx, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ) \
+ rtems_panic(DRVNAME": unable to lock phy register protection mutex"); \
+ } while (0)
+#define REGUNLOCK() rtems_semaphore_release(tsec_mtx)
+#else
+#define REGLOCK() do { } while (0)
+#define REGUNLOCK() do { } while (0)
+#endif
+
+static void tsec_xisr(rtems_irq_hdl_param arg);
+static void tsec_risr(rtems_irq_hdl_param arg);
+static void tsec_eisr(rtems_irq_hdl_param arg);
+static void tsec_lisr(rtems_irq_hdl_param arg);
+
+static void noop(const rtems_irq_connect_data *unused) { }
+static int nopf(const rtems_irq_connect_data *unused) { return -1; }
+
+/********** Low-level Driver API ****************/
+
+/*
+ * This API provides driver access to applications that
+ * want to use e.g., the second ethernet interface
+ * independently from the BSD TCP/IP stack. E.g., for
+ * raw ethernet packet communication...
+ */
+
+/*
+ * Descriptor scavenger; cleanup the TX ring, passing all buffers
+ * that have been sent to the cleanup_tx() callback.
+ * This routine is called from BSP_tsec_send_buf(), BSP_tsec_init_hw(),
+ * BSP_tsec_stop_hw().
+ *
+ * RETURNS: number of buffers processed.
+ */
+
+int
+BSP_tsec_swipe_tx(struct tsec_private *mp)
+{
+int rval = 0;
+int i;
+TSEC_BD *bd;
+uint16_t flags;
+void *u;
+
+#if DEBUG > 2
+printf("Swipe TX entering:\n");
+tsec_dump_tring(mp);
+#endif
+
+ for ( i = mp->tx_head; bd_rdbuf( (bd = &mp->tx_ring[i]) ); i = NEXT_TXI(mp, i) ) {
+
+ flags = bd_rdfl( bd );
+ if ( (TSEC_TXBD_R & flags) ) {
+ /* nothing more to clean */
+ break;
+ }
+
+ /* tx_ring_user[i] is only set on the last descriptor in a chain;
+ * we only count errors in the last descriptor;
+ */
+ if ( (u=mp->tx_ring_user[i]) ) {
+ mp->cleanup_txbuf(u, mp->cleanup_txbuf_arg, (flags & TSEC_TXBD_ERRS));
+ mp->tx_ring_user[i] = 0;
+ }
+
+ bd_wrbuf( bd, 0 );
+
+ mp->tx_avail++;
+
+ rval++;
+ }
+ mp->tx_head = i;
+
+#if DEBUG > 2
+tsec_dump_tring(mp);
+printf("Swipe TX leaving\n");
+#endif
+
+ return rval;
+}
+
+
+/*
+ * Reset the controller and bring into a known state;
+ * all interrupts are off
+ */
+STATIC void
+tsec_reset_hw(struct tsec_private *mp)
+{
+FEC_Enet_Base b = mp->base;
+
+ /* Make sure all interrupts are off */
+ fec_wr(b, TSEC_IMASK, TSEC_IMASK_NONE);
+
+#ifndef TSEC_CONFIG_NO_PHY_REGLOCK
+ /* don't bother disabling irqs in the PHY if this is
+ * called before the mutex is created;
+ * the PHY ISR is not hooked yet and there can be no
+ * interrupts...
+ */
+ if ( tsec_mtx )
+#endif
+ phy_dis_irq_at_phy( mp );
+
+ mp->irq_mask_cache = 0;
+
+ /* Follow the manual resetting the chip */
+
+ /* Do graceful stop (if not in stop condition already) */
+ if ( ! (TSEC_DMACTRL_GTS & fec_rd(b, TSEC_DMACTRL)) ) {
+ /* Make sure GTSC is clear */
+ fec_wr(b, TSEC_IEVENT, TSEC_IEVENT_GTSC);
+ fec_set(b, TSEC_DMACTRL, TSEC_DMACTRL_GTS);
+ while ( ! (TSEC_IEVENT_GTSC & fec_rd(b, TSEC_IEVENT)) )
+ /* wait */;
+ }
+
+ /* Clear RX/TX enable in MAC */
+ fec_clr(b, TSEC_MACCFG1, TSEC_MACCFG1_RX_EN | TSEC_MACCFG1_TX_EN);
+
+ /* wait for > 8ms */
+ rtems_task_wake_after(1);
+
+ /* set GRS if not already stopped */
+ if ( ! (TSEC_DMACTRL_GRS & fec_rd(b, TSEC_DMACTRL)) ) {
+ /* Make sure GRSC is clear */
+ fec_wr(b, TSEC_IEVENT, TSEC_IEVENT_GRSC);
+ fec_set(b, TSEC_DMACTRL, TSEC_DMACTRL_GRS);
+ while ( ! (TSEC_IEVENT_GRSC & fec_rd(b, TSEC_IEVENT)) )
+ /* wait */;
+ }
+
+ fec_set(b, TSEC_MACCFG1, TSEC_MACCFG1_SOFT_RESET);
+ fec_clr(b, TSEC_MACCFG1, TSEC_MACCFG1_SOFT_RESET);
+
+ /* clear all irqs */
+ fec_wr (b, TSEC_IEVENT, TSEC_IEVENT_ALL);
+}
+
+/* Helper to hook/unhook interrupts */
+
+static void
+install_remove_isrs(int install, struct tsec_private *mp, uint32_t irq_mask)
+{
+ rtems_irq_connect_data xxx;
+ int installed = 0;
+ int line;
+ int unit = mp->unit;
+
+ xxx.on = noop;
+ xxx.off = noop;
+ xxx.isOn = nopf;
+ xxx.handle = mp;
+
+ if ( irq_mask & TSEC_TXIRQ ) {
+ xxx.name = TSEC_CONFIG[unit-1].xirq;
+ xxx.hdl = tsec_xisr;
+ if ( ! (install ?
+ BSP_install_rtems_irq_handler( &xxx ) :
+ BSP_remove_rtems_irq_handler( &xxx ) ) ) {
+ rtems_panic(DRVNAME": Unable to install TX ISR\n");
+ }
+ installed++;
+ }
+
+ if ( (irq_mask & TSEC_RXIRQ) ) {
+ if ( (line = TSEC_CONFIG[unit-1].rirq) < 0 && ! installed ) {
+ /* have no dedicated RX IRQ line; install TX ISR if not already done */
+ line = TSEC_CONFIG[unit-1].xirq;
+ }
+ xxx.name = line;
+ xxx.hdl = tsec_risr;
+ if ( ! (install ?
+ BSP_install_rtems_irq_handler( &xxx ) :
+ BSP_remove_rtems_irq_handler( &xxx ) ) ) {
+ rtems_panic(DRVNAME": Unable to install RX ISR\n");
+ }
+ installed++;
+ }
+
+ if ( (line = TSEC_CONFIG[unit-1].eirq) < 0 && ! installed ) {
+ /* have no dedicated RX IRQ line; install TX ISR if not already done */
+ line = TSEC_CONFIG[unit-1].xirq;
+ }
+ xxx.name = line;
+ xxx.hdl = tsec_eisr;
+ if ( ! (install ?
+ BSP_install_rtems_irq_handler( &xxx ) :
+ BSP_remove_rtems_irq_handler( &xxx ) ) ) {
+ rtems_panic(DRVNAME": Unable to install ERR ISR\n");
+ }
+
+ if ( irq_mask & TSEC_LINK_INTR ) {
+ phy_init_irq( install, mp, tsec_lisr );
+ }
+}
+
+/*
+ * Setup an interface.
+ * Allocates resources for descriptor rings and sets up the driver software structure.
+ *
+ * Arguments:
+ * unit:
+ * interface # (1..2). The interface must not be attached to BSD already.
+ *
+ * driver_tid:
+ * ISR posts RTEMS event # ('unit' - 1) to task with ID 'driver_tid' and disables interrupts
+ * from this interface.
+ *
+ * void (*cleanup_txbuf)(void *user_buf, void *cleanup_txbuf_arg, int error_on_tx_occurred):
+ * Pointer to user-supplied callback to release a buffer that had been sent
+ * by BSP_tsec_send_buf() earlier. The callback is passed 'cleanup_txbuf_arg'
+ * and a flag indicating whether the send had been successful.
+ * The driver no longer accesses 'user_buf' after invoking this callback.
+ * CONTEXT: This callback is executed either by BSP_tsec_swipe_tx() or
+ * BSP_tsec_send_buf(), BSP_tsec_init_hw(), BSP_tsec_stop_hw() (the latter
+ * ones calling BSP_tsec_swipe_tx()).
+ * void *cleanup_txbuf_arg:
+ * Closure argument that is passed on to 'cleanup_txbuf()' callback;
+ *
+ * void *(*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ * Pointer to user-supplied callback to allocate a buffer for subsequent
+ * insertion into the RX ring by the driver.
+ * RETURNS: opaque handle to the buffer (which may be a more complex object
+ * such as an 'mbuf'). The handle is not used by the driver directly
+ * but passed back to the 'consume_rxbuf()' callback.
+ * Size of the available data area and pointer to buffer's data area
+ * in '*psize' and '*p_data_area', respectively.
+ * If no buffer is available, this routine should return NULL in which
+ * case the driver drops the last packet and re-uses the last buffer
+ * instead of handing it out to 'consume_rxbuf()'.
+ * CONTEXT: Called when initializing the RX ring (BSP_tsec_init_hw()) or when
+ * swiping it (BSP_tsec_swipe_rx()).
+ *
+ *
+ * void (*consume_rxbuf)(void *user_buf, void *consume_rxbuf_arg, int len);
+ * Pointer to user-supplied callback to pass a received buffer back to
+ * the user. The driver no longer accesses the buffer after invoking this
+ * callback (with 'len'>0, see below). 'user_buf' is the buffer handle
+ * previously generated by 'alloc_rxbuf()'.
+ * The callback is passed 'cleanup_rxbuf_arg' and a 'len'
+ * argument giving the number of bytes that were received.
+ * 'len' may be <=0 in which case the 'user_buf' argument is NULL.
+ * 'len' == 0 means that the last 'alloc_rxbuf()' had failed,
+ * 'len' < 0 indicates a receiver error. In both cases, the last packet
+ * was dropped/missed and the last buffer will be re-used by the driver.
+ * NOTE: the data are 'prefixed' with two bytes, i.e., the ethernet packet header
+ * is stored at offset 2 in the buffer's data area. Also, the FCS (4 bytes)
+ * is appended. 'len' accounts for both.
+ * CONTEXT: Called from BSP_tsec_swipe_rx().
+ * void *cleanup_rxbuf_arg:
+ * Closure argument that is passed on to 'consume_rxbuf()' callback;
+ *
+ * rx_ring_size, tx_ring_size:
+ * How many big to make the RX and TX descriptor rings. Note that the sizes
+ * may be 0 in which case a reasonable default will be used.
+ * If either ring size is < 0 then the RX or TX will be disabled.
+ * Note that it is illegal in this case to use BSP_tsec_swipe_rx() or
+ * BSP_tsec_swipe_tx(), respectively.
+ *
+ * irq_mask:
+ * Interrupts to enable. OR of flags from above.
+ *
+ */
+
+static struct tsec_private *
+tsec_setup_internal(
+ int unit,
+ rtems_id driver_tid,
+ void (*isr)(void *),
+ void * isr_arg,
+ void (*cleanup_txbuf)(void *user_buf, void *cleanup_txbuf_arg, int error_on_tx_occurred),
+ void * cleanup_txbuf_arg,
+ void * (*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *consume_rxbuf_arg, int len),
+ void * consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+{
+struct tsec_private *mp;
+int i;
+struct ifnet *ifp;
+
+ if ( unit <= 0 || unit > TSEC_NUM_DRIVER_SLOTS ) {
+ printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, TSEC_NUM_DRIVER_SLOTS);
+ return 0;
+ }
+
+ ifp = &theTsecEths[unit-1].arpcom.ac_if;
+ if ( ifp->if_init ) {
+ if ( ifp->if_init ) {
+ printk(DRVNAME": instance %i already attached.\n", unit);
+ return 0;
+ }
+ }
+
+
+ if ( rx_ring_size < 0 && tx_ring_size < 0 )
+ return 0;
+
+ mp = &theTsecEths[unit - 1].pvt;
+
+ memset(mp, 0, sizeof(*mp));
+
+ mp->sc = &theTsecEths[unit - 1];
+ mp->unit = unit;
+
+ mp->base = (FEC_Enet_Base)TSEC_CONFIG[unit-1].base;
+ mp->phy_base = (FEC_Enet_Base)TSEC_CONFIG[unit-1].phy_base;
+ mp->phy = TSEC_CONFIG[unit-1].phy_addr;
+ mp->tid = driver_tid;
+ /* use odd event flags for link status IRQ */
+ mp->event = TSEC_ETH_EVENT((unit-1));
+
+ mp->cleanup_txbuf = cleanup_txbuf;
+ mp->cleanup_txbuf_arg = cleanup_txbuf_arg;
+ mp->alloc_rxbuf = alloc_rxbuf;
+ mp->consume_rxbuf = consume_rxbuf;
+ mp->consume_rxbuf_arg = consume_rxbuf_arg;
+
+ /* stop hw prior to setting ring-size to anything nonzero
+ * so that the rings are not swept.
+ */
+ BSP_tsec_stop_hw(mp);
+
+ if ( 0 == rx_ring_size )
+ rx_ring_size = TSEC_RX_RING_SIZE;
+ if ( 0 == tx_ring_size )
+ tx_ring_size = TSEC_TX_RING_SIZE;
+
+ mp->rx_ring_size = rx_ring_size < 0 ? 0 : rx_ring_size;
+ mp->tx_ring_size = tx_ring_size < 0 ? 0 : tx_ring_size;
+
+ /* allocate ring area; add 1 entry -- room for alignment */
+ assert( !mp->ring_area );
+ mp->ring_area = malloc(
+ sizeof(*mp->ring_area) *
+ (mp->rx_ring_size + mp->tx_ring_size + 1),
+ M_DEVBUF,
+ M_WAIT );
+ assert( mp->ring_area );
+
+ mp->tx_ring_user = malloc( sizeof(*mp->tx_ring_user) *
+ (mp->rx_ring_size + mp->tx_ring_size),
+ M_DEVBUF,
+ M_WAIT );
+ assert( mp->tx_ring_user );
+
+ mp->rx_ring_user = mp->tx_ring_user + mp->tx_ring_size;
+
+ /* Initialize TX ring */
+ mp->tx_ring = (TSEC_BD *) ALIGNTO(mp->ring_area,BD_ALIGNMENT);
+
+ mp->rx_ring = mp->tx_ring + mp->tx_ring_size;
+
+ for ( i=0; i<mp->tx_ring_size; i++ ) {
+ bd_wrbuf( &mp->tx_ring[i], 0 );
+ bd_wrfl( &mp->tx_ring[i], TSEC_TXBD_I );
+ mp->tx_ring_user[i] = 0;
+ }
+ /* set wrap-around flag on last BD */
+ if ( mp->tx_ring_size )
+ bd_setfl( &mp->tx_ring[i-1], TSEC_TXBD_W );
+
+ mp->tx_tail = mp->tx_head = 0;
+ mp->tx_avail = mp->tx_ring_size;
+
+ /* Initialize RX ring (buffers are allocated later) */
+ for ( i=0; i<mp->rx_ring_size; i++ ) {
+ bd_wrbuf( &mp->rx_ring[i], 0 );
+ bd_wrfl( &mp->rx_ring[i], TSEC_RXBD_I );
+ mp->rx_ring_user[i] = 0;
+ }
+ /* set wrap-around flag on last BD */
+ if ( mp->rx_ring_size )
+ bd_setfl( &mp->rx_ring[i-1], TSEC_RXBD_W );
+
+ if ( irq_mask ) {
+ if ( rx_ring_size == 0 )
+ irq_mask &= ~ TSEC_RXIRQ;
+ if ( tx_ring_size == 0 )
+ irq_mask &= ~ TSEC_TXIRQ;
+ }
+
+#ifndef TSEC_CONFIG_NO_PHY_REGLOCK
+ if ( ! tsec_mtx ) {
+ rtems_status_code sc;
+ rtems_id new_mtx;
+ rtems_interrupt_level l;
+ sc = rtems_semaphore_create(
+ rtems_build_name('t','s','e','X'),
+ 1,
+ RTEMS_BINARY_SEMAPHORE | RTEMS_PRIORITY | RTEMS_INHERIT_PRIORITY | RTEMS_DEFAULT_ATTRIBUTES,
+ 0,
+ &new_mtx);
+ if ( RTEMS_SUCCESSFUL != sc ) {
+ rtems_error(sc,DRVNAME": creating mutex\n");
+ rtems_panic("unable to proceed\n");
+ }
+ rtems_interrupt_disable( l );
+ if ( ! tsec_mtx ) {
+ tsec_mtx = new_mtx;
+ new_mtx = 0;
+ }
+ rtems_interrupt_enable( l );
+
+ if ( new_mtx ) {
+ /* another task was faster installing the mutex */
+ rtems_semaphore_delete( new_mtx );
+ }
+
+ }
+#endif
+
+ if ( irq_mask ) {
+ install_remove_isrs( 1, mp, irq_mask );
+ }
+
+ mp->irq_mask = irq_mask;
+
+ /* mark as used */
+ ifp->if_init = (void*)(-1);
+
+ return mp;
+}
+
+struct tsec_private *
+BSP_tsec_setup(
+ int unit,
+ rtems_id driver_tid,
+ void (*cleanup_txbuf)(void *user_buf, void *cleanup_txbuf_arg, int error_on_tx_occurred),
+ void * cleanup_txbuf_arg,
+ void * (*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *consume_rxbuf_arg, int len),
+ void * consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+{
+ if ( irq_mask && ! driver_tid ) {
+ printk(DRVNAME": must supply a TID if irq_mask not zero\n");
+ return 0;
+ }
+ return tsec_setup_internal(
+ unit,
+ driver_tid,
+ 0, 0,
+ cleanup_txbuf, cleanup_txbuf_arg,
+ alloc_rxbuf,
+ consume_rxbuf, consume_rxbuf_arg,
+ rx_ring_size,
+ tx_ring_size,
+ irq_mask
+ );
+}
+
+struct tsec_private *
+BSP_tsec_setup_1(
+ int unit,
+ void (*isr)(void*),
+ void * isr_arg,
+ void (*cleanup_txbuf)(void *user_buf, void *cleanup_txbuf_arg, int error_on_tx_occurred),
+ void * cleanup_txbuf_arg,
+ void * (*alloc_rxbuf)(int *p_size, uintptr_t *p_data_addr),
+ void (*consume_rxbuf)(void *user_buf, void *consume_rxbuf_arg, int len),
+ void * consume_rxbuf_arg,
+ int rx_ring_size,
+ int tx_ring_size,
+ int irq_mask
+)
+{
+ if ( irq_mask && ! isr ) {
+ printk(DRVNAME": must supply a ISR if irq_mask not zero\n");
+ return 0;
+ }
+ return tsec_setup_internal(
+ unit,
+ 0,
+ isr, isr_arg,
+ cleanup_txbuf, cleanup_txbuf_arg,
+ alloc_rxbuf,
+ consume_rxbuf, consume_rxbuf_arg,
+ rx_ring_size,
+ tx_ring_size,
+ irq_mask
+ );
+}
+
+void
+BSP_tsec_reset_stats(struct tsec_private *mp)
+{
+FEC_Enet_Base b = mp->base;
+int i;
+ memset( &mp->stats, 0, sizeof( mp->stats ) );
+ if ( mp->isfec )
+ return;
+ for ( i=TSEC_TR64; i<=TSEC_TFRG; i+=4 )
+ fec_wr( b, i, 0 );
+
+}
+
+/*
+ * retrieve media status from the PHY
+ * and set duplex mode in MACCFG2 based
+ * on the result.
+ *
+ * RETURNS: media word (or -1 if BSP_tsec_media_ioctl() fails)
+ */
+static int
+mac_set_duplex(struct tsec_private *mp)
+{
+int media = IFM_MAKEWORD(0, 0, 0, 0);
+
+ if ( 0 == BSP_tsec_media_ioctl(mp, SIOCGIFMEDIA, &media)) {
+ if ( IFM_LINK_OK & media ) {
+ /* update duplex setting in MACCFG2 */
+ if ( IFM_FDX & media ) {
+ fec_set( mp->base, TSEC_MACCFG2, TSEC_MACCFG2_FD );
+ } else {
+ fec_clr( mp->base, TSEC_MACCFG2, TSEC_MACCFG2_FD );
+ }
+ }
+ return media;
+ }
+ return -1;
+}
+
+/*
+ * Initialize interface hardware
+ *
+ * 'mp' handle obtained by from BSP_tsec_setup().
+ * 'promisc' whether to set promiscuous flag.
+ * 'enaddr' pointer to six bytes with MAC address. Read
+ * from the device if NULL.
+ */
+void
+BSP_tsec_init_hw(struct tsec_private *mp, int promisc, unsigned char *enaddr)
+{
+FEC_Enet_Base b = mp->base;
+unsigned i;
+uint32_t v;
+int sz;
+
+ BSP_tsec_stop_hw(mp);
+
+#ifdef PARANOIA
+ assert( mp->tx_avail == mp->tx_ring_size );
+ assert( mp->tx_head == mp->tx_tail );
+ for ( i=0; i<mp->tx_ring_size; i++ ) {
+ assert( mp->tx_ring_user[i] == 0 );
+ }
+#endif
+
+ /* make sure RX ring is filled */
+ for ( i=0; i<mp->rx_ring_size; i++ ) {
+ uintptr_t data_area;
+ if ( ! (mp->rx_ring_user[i] = mp->alloc_rxbuf( &sz, &data_area)) ) {
+ rtems_panic(DRVNAME": unable to fill RX ring");
+ }
+ if ( data_area & (RX_BUF_ALIGNMENT-1) )
+ rtems_panic(DRVNAME": RX buffers must be %i-byte aligned", RX_BUF_ALIGNMENT);
+
+ bd_wrbuf( &mp->rx_ring[i], data_area );
+ st_be16 ( &mp->rx_ring[i].len, sz );
+ bd_setfl( &mp->rx_ring[i], TSEC_RXBD_E | TSEC_RXBD_I );
+ }
+
+ mp->tx_tail = mp->tx_head = 0;
+
+ mp->rx_tail = 0;
+
+ /* tell chip what the ring areas are */
+ fec_wr( b, TSEC_TBASE, (uint32_t)mp->tx_ring );
+ fec_wr( b, TSEC_RBASE, (uint32_t)mp->rx_ring );
+
+ /* clear and disable IRQs */
+ fec_wr( b, TSEC_IEVENT, TSEC_IEVENT_ALL );
+ fec_wr( b, TSEC_IMASK, TSEC_IMASK_NONE );
+ mp->irq_mask_cache = 0;
+
+ /* bring other regs. into a known state */
+ fec_wr( b, TSEC_EDIS, 0 );
+
+ if ( !mp->isfec )
+ fec_wr( b, TSEC_ECNTRL, TSEC_ECNTRL_CLRCNT | TSEC_ECNTRL_STEN );
+
+ fec_wr( b, TSEC_MINFLR, 64 );
+ fec_wr( b, TSEC_PTV, 0 );
+
+ v = TSEC_DMACTRL_WWR;
+
+ if ( mp->tx_ring_size )
+ v |= TSEC_DMACTRL_TDSEN | TSEC_DMACTRL_TBDSEN | TSEC_DMACTRL_WOP;
+
+ fec_wr( b, TSEC_DMACTRL, v );
+
+ fec_wr( b, TSEC_FIFO_PAUSE_CTRL, 0 );
+ fec_wr( b, TSEC_FIFO_TX_THR, 256 );
+ fec_wr( b, TSEC_FIFO_TX_STARVE, 128 );
+ fec_wr( b, TSEC_FIFO_TX_STARVE_SHUTOFF, 256 );
+ fec_wr( b, TSEC_TCTRL, 0 );
+ if ( !mp->isfec ) {
+ /* FIXME: use IRQ coalescing ? not sure how to
+ * set the timer (bad if it depends on the speed
+ * setting).
+ */
+ fec_wr( b, TSEC_TXIC, 0);
+ }
+ fec_wr( b, TSEC_OSTBD, 0 );
+ fec_wr( b, TSEC_RCTRL, (promisc ? TSEC_RCTRL_PROM : 0) );
+ fec_wr( b, TSEC_RSTAT, TSEC_RSTAT_QHLT );
+ if ( !mp->isfec ) {
+ /* FIXME: use IRQ coalescing ? not sure how to
+ * set the timer (bad if it depends on the speed
+ * setting).
+ */
+ fec_wr( b, TSEC_RXIC, 0 );
+ }
+ fec_wr( b, TSEC_MRBLR, sz & ~63 );
+
+ /* Reset config. as per manual */
+ fec_wr( b, TSEC_IPGIFG, 0x40605060 );
+ fec_wr( b, TSEC_HAFDUP, 0x00a1f037 );
+ fec_wr( b, TSEC_MAXFRM, 1536 );
+
+ if ( enaddr ) {
+ union {
+ uint32_t u;
+ uint16_t s[2];
+ uint8_t c[4];
+ } x;
+ fec_wr( b, TSEC_MACSTNADDR1, ld_le32( (volatile uint32_t*)(enaddr + 2) ) );
+ x.s[0] = ld_le16( (volatile uint16_t *)(enaddr) );
+ fec_wr( b, TSEC_MACSTNADDR2, x.u );
+ }
+
+ for ( i=0; i<8*4; i+=4 ) {
+ fec_wr( b, TSEC_IADDR0 + i, 0 );
+ }
+
+ BSP_tsec_mcast_filter_clear(mp);
+
+ BSP_tsec_reset_stats(mp);
+
+ fec_wr( b, TSEC_ATTR, (TSEC_ATTR_RDSEN | TSEC_ATTR_RBDSEN) );
+ fec_wr( b, TSEC_ATTRELI, 0 );
+
+ /* The interface type is probably board dependent; leave alone...
+ v = mp->isfec ? TSEC_MACCFG2_IF_MODE_MII : TSEC_MACCFG2_IF_MODE_GMII;
+ */
+
+ fec_clr( b, TSEC_MACCFG2,
+ TSEC_MACCFG2_PREAMBLE_15
+ | TSEC_MACCFG2_HUGE_FRAME
+ | TSEC_MACCFG2_LENGTH_CHECK );
+
+ fec_set( b, TSEC_MACCFG2,
+ TSEC_MACCFG2_PREAMBLE_7
+ | TSEC_MACCFG2_PAD_CRC );
+
+ mac_set_duplex( mp );
+
+ v = 0;
+ if ( mp->rx_ring_size ) {
+ v |= TSEC_MACCFG1_RX_EN;
+ }
+ if ( mp->tx_ring_size ) {
+ v |= TSEC_MACCFG1_TX_EN;
+ }
+
+ fec_wr( b, TSEC_MACCFG1, v);
+
+ /* The following sequency (FWIW) ensures that
+ *
+ * - PHY and TSEC interrupts are enabled atomically
+ * - IRQS are not globally off while accessing the PHY
+ * (slow MII)
+ */
+
+ if ( (TSEC_LINK_INTR & mp->irq_mask) ) {
+ /* disable PHY irq at PIC (fast) */
+ phy_dis_irq( mp );
+ /* enable PHY irq (MII operation, slow) */
+ phy_en_irq_at_phy (mp );
+ }
+
+ BSP_tsec_enable_irq_mask( mp, mp->irq_mask );
+}
+
+static void
+hash_prog(struct tsec_private *mp, uint32_t tble, const uint8_t *enaddr, int accept)
+{
+uint8_t s;
+uint32_t reg, bit;
+
+ s = ether_crc32_le(enaddr, ETHER_ADDR_LEN);
+
+ /* bit-reverse */
+ s = ((s&0x0f) << 4) | ((s&0xf0) >> 4);
+ s = ((s&0x33) << 2) | ((s&0xcc) >> 2);
+ s = ((s&0x55) << 1) | ((s&0xaa) >> 1);
+
+ reg = tble + ((s >> (5-2)) & ~3);
+ bit = 1 << (31 - (s & 31));
+
+ if ( accept ) {
+ if ( 0 == mp->mc_refcnt[s]++ )
+ fec_set( mp->base, reg, bit );
+ } else {
+ if ( mp->mc_refcnt[s] > 0 && 0 == --mp->mc_refcnt[s] )
+ fec_clr( mp->base, reg, bit );
+ }
+}
+
+void
+BSP_tsec_mcast_filter_clear(struct tsec_private *mp)
+{
+int i;
+ for ( i=0; i<8*4; i+=4 ) {
+ fec_wr( mp->base, TSEC_GADDR0 + i, 0 );
+ }
+ for ( i=0; i<NUM_MC_HASHES; i++ )
+ mp->mc_refcnt[i] = 0;
+}
+
+void
+BSP_tsec_mcast_filter_accept_all(struct tsec_private *mp)
+{
+int i;
+ for ( i=0; i<8*4; i+=4 ) {
+ fec_wr( mp->base, TSEC_GADDR0 + i, 0xffffffff );
+ }
+ for ( i=0; i<NUM_MC_HASHES; i++ )
+ mp->mc_refcnt[i]++;
+}
+
+static void
+mcast_filter_prog(struct tsec_private *mp, uint8_t *enaddr, int accept)
+{
+static const uint8_t bcst[6]={0xff, 0xff, 0xff, 0xff, 0xff, 0xff};
+ if ( ! (enaddr[0] & 0x01) ) {
+ /* not a multicast address; ignore */
+ return;
+ }
+ if ( 0 == memcmp( enaddr, bcst, sizeof(bcst) ) ) {
+ /* broadcast; ignore */
+ return;
+ }
+ hash_prog(mp, TSEC_GADDR0, enaddr, accept);
+}
+
+void
+BSP_tsec_mcast_filter_accept_add(struct tsec_private *mp, uint8_t *enaddr)
+{
+ mcast_filter_prog(mp, enaddr, 1 /* accept */);
+}
+
+void
+BSP_tsec_mcast_filter_accept_del(struct tsec_private *mp, uint8_t *enaddr)
+{
+ mcast_filter_prog(mp, enaddr, 0 /* delete */);
+}
+
+void
+BSP_tsec_dump_stats(struct tsec_private *mp, FILE *f)
+{
+FEC_Enet_Base b;
+
+ if ( !mp )
+ mp = &theTsecEths[0].pvt;
+
+ if ( ! f )
+ f = stdout;
+
+ fprintf(f, DRVNAME"%i Statistics:\n", mp->unit);
+
+ b = mp->base;
+
+ fprintf(f, "TX IRQS: %u\n", mp->stats.xirqs);
+ fprintf(f, "RX IRQS: %u\n", mp->stats.rirqs);
+ fprintf(f, "ERR IRQS: %u\n", mp->stats.eirqs);
+ fprintf(f, "bus errs: %u\n", mp->stats.eberrs);
+ fprintf(f, "dmawhack: %u\n", mp->stats.dmarst);
+ fprintf(f, "LNK IRQS: %u\n", mp->stats.lirqs);
+ fprintf(f, "maxchain: %u\n", mp->stats.maxchain);
+ fprintf(f, "xpackets: %u\n", mp->stats.packet);
+ fprintf(f, "odrops: %u\n", mp->stats.odrops);
+ fprintf(f, "repack: %u\n", mp->stats.repack);
+
+ if ( mp->isfec ) {
+ fprintf(f,"FEC has no HW counters\n");
+ return;
+ }
+
+ fprintf(f,"TSEC MIB counters (modulo 2^32):\n");
+
+ fprintf(f,"RX bytes %"PRIu32"\n", fec_rd( b, TSEC_RBYT ));
+ fprintf(f,"RX pkts %"PRIu32"\n", fec_rd( b, TSEC_RPKT ));
+ fprintf(f,"RX FCS errs %"PRIu32"\n", fec_rd( b, TSEC_RFCS ));
+ fprintf(f,"RX mcst pkts %"PRIu32"\n", fec_rd( b, TSEC_RMCA ));
+ fprintf(f,"RX bcst pkts %"PRIu32"\n", fec_rd( b, TSEC_RBCA ));
+ fprintf(f,"RX pse frms %"PRIu32"\n", fec_rd( b, TSEC_RXPF ));
+ fprintf(f,"RX drop %"PRIu32"\n", fec_rd( b, TSEC_RDRP ));
+ fprintf(f,"TX bytes %"PRIu32"\n", fec_rd( b, TSEC_TBYT ));
+ fprintf(f,"TX pkts %"PRIu32"\n", fec_rd( b, TSEC_TPKT ));
+ fprintf(f,"TX FCS errs %"PRIu32"\n", fec_rd( b, TSEC_TFCS ));
+ fprintf(f,"TX mcst pkts %"PRIu32"\n", fec_rd( b, TSEC_TMCA ));
+ fprintf(f,"TX bcst pkts %"PRIu32"\n", fec_rd( b, TSEC_TBCA ));
+ fprintf(f,"TX pse frms %"PRIu32"\n", fec_rd( b, TSEC_TXPF ));
+ fprintf(f,"TX drop %"PRIu32"\n", fec_rd( b, TSEC_TDRP ));
+ fprintf(f,"TX coll %"PRIu32"\n", fec_rd( b, TSEC_TSCL ));
+ fprintf(f,"TX mcoll %"PRIu32"\n", fec_rd( b, TSEC_TMCL ));
+ fprintf(f,"TX late coll %"PRIu32"\n", fec_rd( b, TSEC_TLCL ));
+ fprintf(f,"TX exc coll %"PRIu32"\n", fec_rd( b, TSEC_TXCL ));
+ fprintf(f,"TX defer %"PRIu32"\n", fec_rd( b, TSEC_TDFR ));
+ fprintf(f,"TX exc defer %"PRIu32"\n", fec_rd( b, TSEC_TEDF ));
+ fprintf(f,"TX oversz %"PRIu32"\n", fec_rd( b, TSEC_TOVR ));
+ fprintf(f,"TX undersz %"PRIu32"\n", fec_rd( b, TSEC_TUND ));
+}
+
+/*
+ * Shutdown hardware and clean out the rings
+ */
+void
+BSP_tsec_stop_hw(struct tsec_private *mp)
+{
+unsigned i;
+ /* stop and reset hardware */
+ tsec_reset_hw( mp );
+
+ if ( mp->tx_ring_size ) {
+ /* should be OK to clear all ownership flags */
+ for ( i=0; i<mp->tx_ring_size; i++ ) {
+ bd_clrfl( &mp->tx_ring[i], TSEC_TXBD_R );
+ }
+ BSP_tsec_swipe_tx(mp);
+#if DEBUG > 0
+ tsec_dump_tring(mp);
+ fflush(stderr); fflush(stdout);
+#endif
+#ifdef PARANOIA
+ assert( mp->tx_avail == mp->tx_ring_size );
+ assert( mp->tx_head == mp->tx_tail );
+ for ( i=0; i<mp->tx_ring_size; i++ ) {
+ assert( !bd_rdbuf( & mp->tx_ring[i] ) );
+ assert( !mp->tx_ring_user[i] );
+ }
+#endif
+ }
+
+ if ( mp->rx_ring_size ) {
+ for ( i=0; i<mp->rx_ring_size; i++ ) {
+ bd_clrfl( &mp->rx_ring[i], TSEC_RXBD_E );
+ bd_wrbuf( &mp->rx_ring[i], 0 );
+ if ( mp->rx_ring_user[i] )
+ mp->consume_rxbuf( mp->rx_ring_user[i], mp->consume_rxbuf_arg, 0 );
+ mp->rx_ring_user[i] = 0;
+ }
+ }
+}
+
+/*
+ * calls BSP_tsec_stop_hw(), releases all resources and marks the interface
+ * as unused.
+ * RETURNS 0 on success, nonzero on failure.
+ * NOTE: the handle MUST NOT be used after successful execution of this
+ * routine.
+ */
+int
+BSP_tsec_detach(struct tsec_private *mp)
+{
+
+ if ( ! mp || !mp->sc || ! mp->sc->arpcom.ac_if.if_init ) {
+ fprintf(stderr,"Unit not setup -- programming error!\n");
+ return -1;
+ }
+
+ BSP_tsec_stop_hw(mp);
+
+ install_remove_isrs( 0, mp, mp->irq_mask );
+
+ free( (void*)mp->ring_area, M_DEVBUF );
+ free( (void*)mp->tx_ring_user, M_DEVBUF );
+ memset(mp, 0, sizeof(*mp));
+ __asm__ __volatile__("":::"memory");
+
+ /* mark as unused */
+ mp->sc->arpcom.ac_if.if_init = 0;
+
+ return 0;
+}
+
+/*
+ * Enqueue a mbuf chain or a raw data buffer for transmission;
+ * RETURN: #bytes sent or -1 if there are not enough free descriptors
+ *
+ * If 'len' is <=0 then 'm_head' is assumed to point to a mbuf chain.
+ * OTOH, a raw data packet (or a different type of buffer)
+ * may be sent (non-BSD driver) by pointing data_p to the start of
+ * the data and passing 'len' > 0.
+ * 'm_head' is passed back to the 'cleanup_txbuf()' callback.
+ *
+ * Comments: software cache-flushing incurs a penalty if the
+ * packet cannot be queued since it is flushed anyways.
+ * The algorithm is slightly more efficient in the normal
+ * case, though.
+ *
+ * RETURNS: # bytes enqueued to device for transmission or -1 if no
+ * space in the TX ring was available.
+ */
+
+#if 0
+#define NEXT_TXD(mp, bd) ((bd_rdfl( bd ) & TSEC_TXBD_W) ? mp->tx_ring : (bd + 1))
+#endif
+
+/*
+ * allocate a new cluster and copy an existing chain there;
+ * old chain is released...
+ */
+static struct mbuf *
+repackage_chain(struct mbuf *m_head)
+{
+struct mbuf *m;
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+
+ if ( !m ) {
+ goto bail;
+ }
+
+ MCLGET(m, M_DONTWAIT);
+
+ if ( !(M_EXT & m->m_flags) ) {
+ m_freem(m);
+ m = 0;
+ goto bail;
+ }
+
+ m_copydata(m_head, 0, MCLBYTES, mtod(m, caddr_t));
+ m->m_pkthdr.len = m->m_len = m_head->m_pkthdr.len;
+
+bail:
+ m_freem(m_head);
+ return m;
+}
+
+static inline unsigned
+tsec_assign_desc( TSEC_BD *bd, uint32_t buf, unsigned len, uint32_t flags)
+{
+ st_be16 ( &bd->len, (uint16_t)len );
+ bd_wrbuf( bd, buf );
+ bd_cslfl( bd, flags, TSEC_TXBD_R | TSEC_TXBD_L );
+ return len;
+}
+
+
+int
+BSP_tsec_send_buf(struct tsec_private *mp, void *m_head, void *data_p, int len)
+{
+int rval;
+register TSEC_BD *bd;
+register unsigned l,d,t;
+register struct mbuf *m1;
+int nmbs;
+int ismbuf = (len <= 0);
+
+#if DEBUG > 2
+ printf("send entering...\n");
+ tsec_dump_tring(mp);
+#endif
+/* Only way to get here is when we discover that the mbuf chain
+ * is too long for the tx ring
+ */
+startover:
+
+ rval = 0;
+
+#ifdef PARANOIA
+ assert(m_head);
+#endif
+
+ /* if no descriptor is available; try to wipe the queue */
+ if ( (mp->tx_avail < 1) && TSEC_CLEAN_ON_SEND(mp)<=0 ) {
+ return -1;
+ }
+
+ t = mp->tx_tail;
+
+#ifdef PARANOIA
+ assert( ! bd_rdbuf( &mp->tx_ring[t] ) );
+ assert( ! mp->tx_ring_user[t] );
+#endif
+
+ if ( ! (m1 = m_head) )
+ return 0;
+
+ if ( ismbuf ) {
+ /* find first mbuf with actual data */
+ while ( 0 == m1->m_len ) {
+ if ( ! (m1 = m1->m_next) ) {
+ /* end reached and still no data to send ?? */
+ m_freem(m_head);
+ return 0;
+ }
+ }
+ }
+
+ /* Don't use the first descriptor yet because BSP_tsec_swipe_tx()
+ * needs bd->buf == NULL as a marker. Hence, we
+ * start with the second mbuf and fill the first descriptor
+ * last.
+ */
+
+ l = t;
+ d = NEXT_TXI(mp,t);
+
+ mp->tx_avail--;
+
+ nmbs = 1;
+ if ( ismbuf ) {
+ register struct mbuf *m;
+ for ( m=m1->m_next; m; m=m->m_next ) {
+ if ( 0 == m->m_len )
+ continue; /* skip empty mbufs */
+
+ nmbs++;
+
+ if ( mp->tx_avail < 1 && TSEC_CLEAN_ON_SEND(mp)<=0 ) {
+ /* not enough descriptors; cleanup...
+ * the first slot was never used, so we start
+ * at mp->d_tx_h->next;
+ */
+ for ( l = NEXT_TXI(mp, t); l!=d; l=NEXT_TXI(mp, l) ) {
+ bd = & mp->tx_ring[l];
+#ifdef PARANOIA
+ assert( mp->tx_ring_user[l] == 0 );
+#endif
+ bd_wrbuf( bd, 0 );
+ bd_clrfl( bd, TSEC_TXBD_R | TSEC_TXBD_L );
+
+ mp->tx_avail++;
+ }
+ mp->tx_avail++;
+ if ( nmbs > TX_AVAILABLE_RING_SIZE(mp) ) {
+ /* this chain will never fit into the ring */
+ if ( nmbs > mp->stats.maxchain )
+ mp->stats.maxchain = nmbs;
+ mp->stats.repack++;
+ if ( ! (m_head = repackage_chain(m_head)) ) {
+ /* no cluster available */
+ mp->stats.odrops++;
+#ifdef PARANOIA
+ printf("send return 0\n");
+ tsec_dump_tring(mp);
+#endif
+ return 0;
+ }
+#ifdef PARANOIA
+ printf("repackaged; start over\n");
+#endif
+ goto startover;
+ }
+#ifdef PARANOIA
+ printf("send return -1\n");
+ tsec_dump_tring(mp);
+#endif
+ return -1;
+ }
+
+ mp->tx_avail--;
+
+#ifdef PARANOIA
+ assert( ! mp->tx_ring_user[d] );
+ if ( d == t ) {
+ tsec_dump_tring(mp);
+ printf("l %i, d %i, t %i, nmbs %i\n", l,d,t, nmbs);
+ } else
+ assert( d != t );
+ assert( ! bd_rdbuf( &mp->tx_ring[d] ) );
+#endif
+
+ /* fill this slot */
+ rval += tsec_assign_desc( &mp->tx_ring[d], mtod(m, uint32_t), m->m_len, TSEC_TXBD_R);
+
+ FLUSH_BUF(mtod(m, uint32_t), m->m_len);
+
+ l = d;
+ d = NEXT_TXI(mp, d);
+ }
+
+ /* fill first slot - don't release to DMA yet */
+ rval += tsec_assign_desc( &mp->tx_ring[t], mtod(m1, uint32_t), m1->m_len, 0);
+
+
+ FLUSH_BUF(mtod(m1, uint32_t), m1->m_len);
+
+ } else {
+ /* fill first slot with raw buffer - don't release to DMA yet */
+ rval += tsec_assign_desc( &mp->tx_ring[t], (uint32_t)data_p, len, 0);
+
+ FLUSH_BUF( (uint32_t)data_p, len);
+ }
+
+ /* tag last slot; this covers the case where 1st==last */
+ bd_setfl( &mp->tx_ring[l], TSEC_TXBD_L );
+
+ /* mbuf goes into last desc */
+ mp->tx_ring_user[l] = m_head;
+
+ membarrier();
+
+ /* turn over the whole chain by flipping ownership of the first desc */
+ bd_setfl( &mp->tx_ring[t], TSEC_TXBD_R );
+
+ membarrier();
+
+#if DEBUG > 2
+ printf("send return (l=%i, t=%i, d=%i) %i\n", l, t, d, rval);
+ tsec_dump_tring(mp);
+#endif
+
+ /* notify the device */
+ fec_wr( mp->base, TSEC_TSTAT, TSEC_TSTAT_THLT );
+
+ /* Update softc */
+ mp->stats.packet++;
+ if ( nmbs > mp->stats.maxchain )
+ mp->stats.maxchain = nmbs;
+
+ /* remember new tail */
+ mp->tx_tail = d;
+
+ return rval; /* #bytes sent */
+}
+
+/*
+ * Retrieve all received buffers from the RX ring, replacing them
+ * by fresh ones (obtained from the alloc_rxbuf() callback). The
+ * received buffers are passed to consume_rxbuf().
+ *
+ * RETURNS: number of buffers processed.
+ */
+int
+BSP_tsec_swipe_rx(struct tsec_private *mp)
+{
+int rval = 0, err;
+unsigned i;
+uint16_t flags;
+TSEC_BD *bd;
+void *newbuf;
+int sz;
+uint16_t len;
+uintptr_t baddr;
+
+ i = mp->rx_tail;
+ bd = mp->rx_ring + i;
+ flags = bd_rdfl( bd );
+
+ while ( ! (TSEC_RXBD_E & flags) ) {
+
+ /* err is not valid if not qualified by TSEC_RXBD_L */
+ if ( ( err = (TSEC_RXBD_ERROR & flags) ) ) {
+ /* make sure error is < 0 */
+ err |= 0xffff0000;
+ /* pass 'L' flag out so they can verify... */
+ err |= (flags & TSEC_RXBD_L);
+ }
+
+#ifdef PARANOIA
+ assert( flags & TSEC_RXBD_L );
+ assert( mp->rx_ring_user[i] );
+#endif
+
+ if ( err || !(newbuf = mp->alloc_rxbuf(&sz, &baddr)) ) {
+ /* drop packet and recycle buffer */
+ newbuf = mp->rx_ring_user[i];
+ mp->consume_rxbuf( 0, mp->consume_rxbuf_arg, err );
+ } else {
+ len = ld_be16( &bd->len );
+
+#ifdef PARANOIA
+ assert( 0 == (baddr & (RX_BUF_ALIGNMENT-1)) );
+ assert( len > 0 );
+#endif
+
+ mp->consume_rxbuf( mp->rx_ring_user[i], mp->consume_rxbuf_arg, len );
+
+ mp->rx_ring_user[i] = newbuf;
+ st_be16( &bd->len, sz );
+ bd_wrbuf( bd, baddr );
+ }
+
+ RTEMS_COMPILER_MEMORY_BARRIER();
+
+ bd_wrfl( &mp->rx_ring[i], (flags & ~TSEC_RXBD_ERROR) | TSEC_RXBD_E );
+
+ rval++;
+
+ i = NEXT_RXI( mp, i );
+ bd = mp->rx_ring + i;
+ flags = bd_rdfl( bd );
+ }
+
+ fec_wr( mp->base, TSEC_RSTAT, TSEC_RSTAT_QHLT );
+
+ mp->rx_tail = i;
+ return rval;
+}
+
+/* read ethernet address from hw to buffer */
+void
+BSP_tsec_read_eaddr(struct tsec_private *mp, unsigned char *eaddr)
+{
+union {
+ uint32_t u;
+ uint16_t s[2];
+ uint8_t c[4];
+} x;
+ st_le32( (volatile uint32_t *)(eaddr+2), fec_rd(mp->base, TSEC_MACSTNADDR1) );
+ x.u = fec_rd(mp->base, TSEC_MACSTNADDR2);
+ st_le16( (volatile uint16_t *)(eaddr), x.s[0]);
+}
+
+/* mdio / mii interface wrappers for rtems_mii_ioctl API */
+
+/*
+ * Busy-wait -- this can take a while: I measured ~550 timebase-ticks
+ * @333333333Hz, TB divisor is 8 -> 13us
+ */
+static inline void mii_wait(FEC_Enet_Base b)
+{
+ while ( (TSEC_MIIMIND_BUSY & fec_rd( b, TSEC_MIIMIND )) )
+ ;
+}
+
+/* MII operations are rather slow :-( */
+static int
+tsec_mdio_rd(int phyidx, void *uarg, unsigned reg, uint32_t *pval)
+{
+uint32_t v;
+#ifdef TEST_MII_TIMING
+uint32_t t;
+#endif
+struct tsec_private *mp = uarg;
+FEC_Enet_Base b = mp->phy_base;
+
+ if ( phyidx != 0 )
+ return -1; /* only one phy supported for now */
+
+ /* write phy and register address */
+ fec_wr( b, TSEC_MIIMADD, TSEC_MIIMADD_ADDR(mp->phy,reg) );
+
+ /* clear READ bit */
+ v = fec_rd( b, TSEC_MIIMCOM );
+ fec_wr( b, TSEC_MIIMCOM, v & ~TSEC_MIIMCOM_READ );
+
+#ifdef TEST_MII_TIMING
+ t = tb_rd();
+#endif
+
+ /* trigger READ operation by READ-bit 0-->1 transition */
+ fec_wr( b, TSEC_MIIMCOM, v | TSEC_MIIMCOM_READ );
+
+ /* (busy) wait for completion */
+
+ mii_wait( b );
+
+ /* Ugly workaround: I observed that the link status
+ * is not correctly reported when the link changes to
+ * a good status - a failed link is reported until
+ * we read twice :-(
+ */
+ if ( MII_BMSR == reg ) {
+ /* trigger a second read operation */
+ fec_wr( b, TSEC_MIIMCOM, v & ~TSEC_MIIMCOM_READ );
+ fec_wr( b, TSEC_MIIMCOM, v | TSEC_MIIMCOM_READ );
+ mii_wait( b );
+ }
+
+#ifdef TEST_MII_TIMING
+ t = tb_rd() - t;
+ printf("Reading MII took %"PRIi32"\n", t);
+#endif
+ /* return result */
+ *pval = fec_rd( b, TSEC_MIIMSTAT ) & 0xffff;
+ return 0;
+}
+
+STATIC int
+tsec_mdio_wr(int phyidx, void *uarg, unsigned reg, uint32_t val)
+{
+#ifdef TEST_MII_TIMING
+uint32_t t;
+#endif
+struct tsec_private *mp = uarg;
+FEC_Enet_Base b = mp->phy_base;
+
+ if ( phyidx != 0 )
+ return -1; /* only one phy supported for now */
+
+#ifdef TEST_MII_TIMING
+ t = tb_rd();
+#endif
+
+ fec_wr( b, TSEC_MIIMADD, TSEC_MIIMADD_ADDR(mp->phy,reg) );
+ fec_wr( b, TSEC_MIIMCON, val & 0xffff );
+
+ mii_wait( b );
+
+#ifdef TEST_MII_TIMING
+ t = tb_rd() - t;
+ printf("Writing MII took %"PRIi32"\n", t);
+#endif
+
+ return 0;
+}
+
+/* Public, locked versions */
+uint32_t
+BSP_tsec_mdio_rd(struct tsec_private *mp, unsigned reg)
+{
+uint32_t val, rval;
+
+ REGLOCK();
+ rval = tsec_mdio_rd(0, mp, reg, &val ) ? -1 : val;
+ REGUNLOCK();
+
+ return rval;
+}
+
+int
+BSP_tsec_mdio_wr(struct tsec_private *mp, unsigned reg, uint32_t val)
+{
+int rval;
+
+ REGLOCK();
+ rval = tsec_mdio_wr(0, mp, reg, val);
+ REGUNLOCK();
+
+ return rval;
+}
+
+static struct rtems_mdio_info tsec_mdio = {
+ mdio_r: tsec_mdio_rd,
+ mdio_w: tsec_mdio_wr,
+ has_gmii: 1,
+};
+
+
+/*
+ * read/write media word.
+ * 'cmd': can be SIOCGIFMEDIA, SIOCSIFMEDIA, 0 or 1. The latter
+ * are aliased to the former for convenience.
+ * 'parg': pointer to media word.
+ *
+ * RETURNS: 0 on success, nonzero on error
+ */
+int
+BSP_tsec_media_ioctl(struct tsec_private *mp, int cmd, int *parg)
+{
+int rval;
+ /* alias cmd == 0,1 for convenience when calling from shell */
+ switch ( cmd ) {
+ case 0: cmd = SIOCGIFMEDIA;
+ break;
+ case 1: cmd = SIOCSIFMEDIA;
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ break;
+ default: return -1;
+ }
+ REGLOCK();
+ tsec_mdio.has_gmii = mp->isfec ? 0 : 1;
+ rval = rtems_mii_ioctl(&tsec_mdio, mp, cmd, parg);
+ REGUNLOCK();
+ return rval;
+}
+
+/* Interrupt related routines */
+
+/*
+ * When it comes to interrupts the chip has two rather
+ * annoying features:
+ * 1 once an IRQ is pending, clearing the IMASK does not
+ * de-assert the interrupt line.
+ * 2 the chip has three physical interrupt lines even though
+ * all events are reported in a single register. Rather
+ * useless; we must hook 3 ISRs w/o any real benefit.
+ * In fact, it makes our life a bit more difficult:
+ *
+ * Hence, for (1) we would have to mask interrupts at the PIC
+ * but to re-enable them we would have to do that three times
+ * because of (2).
+ *
+ * Therefore, we take the following approach:
+ *
+ * ISR masks interrupts on the TSEC, acks/clears them
+ * and stores the acked irqs in the device struct where
+ * it is picked up by BSP_tsec_ack_irq_mask().
+ *
+ */
+
+static inline uint32_t
+tsec_dis_irqs(struct tsec_private *mp, uint32_t mask)
+{
+uint32_t rval;
+
+ rval = mp->irq_mask_cache;
+ if ( (TSEC_LINK_INTR & mask & mp->irq_mask_cache) )
+ phy_dis_irq( mp );
+ mp->irq_mask_cache = rval & ~mask;
+ fec_wr( mp->base, TSEC_IMASK, (mp->irq_mask_cache & ~TSEC_LINK_INTR) );
+
+ return rval;
+}
+
+static inline uint32_t
+tsec_dis_clr_irqs(struct tsec_private *mp)
+{
+uint32_t rval;
+FEC_Enet_Base b = mp->base;
+
+ rval = fec_rd( b, TSEC_IEVENT);
+
+ /* Make sure we mask out the link intr */
+ rval &= ~TSEC_LINK_INTR;
+
+ tsec_dis_irqs( mp, rval );
+ fec_wr( b, TSEC_IEVENT, rval );
+
+ return rval;
+}
+
+/*
+ * We have 3 different ISRs just so we can count
+ * interrupt types independently...
+ */
+
+static void tsec_xisr(rtems_irq_hdl_param arg)
+{
+struct tsec_private *mp = (struct tsec_private *)arg;
+rtems_interrupt_level l;
+
+ rtems_interrupt_disable( l );
+ mp->irq_pending |= tsec_dis_clr_irqs( mp );
+ rtems_interrupt_enable( l );
+
+ mp->stats.xirqs++;
+
+ if ( mp->isr )
+ mp->isr( mp->isr_arg );
+ else
+ rtems_bsdnet_event_send( mp->tid, mp->event );
+}
+
+static void tsec_risr(rtems_irq_hdl_param arg)
+{
+struct tsec_private *mp = (struct tsec_private *)arg;
+rtems_interrupt_level l;
+
+ rtems_interrupt_disable( l );
+ mp->irq_pending |= tsec_dis_clr_irqs( mp );
+ rtems_interrupt_enable( l );
+
+ mp->stats.rirqs++;
+
+ if ( mp->isr )
+ mp->isr( mp->isr_arg );
+ else
+ rtems_bsdnet_event_send( mp->tid, mp->event );
+}
+
+static void tsec_eisr(rtems_irq_hdl_param arg)
+{
+struct tsec_private *mp = (struct tsec_private *)arg;
+rtems_interrupt_level l;
+uint32_t pending;
+
+ rtems_interrupt_disable( l );
+ /* make local copy since ISR may ack and clear mp->pending;
+ * also, we want the fresh bits not the ORed state including
+ * the past...
+ */
+ mp->irq_pending |= (pending = tsec_dis_clr_irqs( mp ));
+ rtems_interrupt_enable( l );
+
+ mp->stats.eirqs++;
+
+ if ( mp->isr )
+ mp->isr( mp->isr_arg );
+ else
+ rtems_bsdnet_event_send( mp->tid, mp->event );
+
+ if ( (TSEC_IEVENT_TXE & pending) ) {
+ if ( (TSEC_IEVENT_EBERR & pending) && ++mp->stats.eberrs > MAXEBERRS ) {
+ printk(DRVNAME" BAD error: max # of DMA bus errors reached\n");
+ } else {
+ /* Restart DMA -- do we have to clear DMACTRL[GTS], too ?? */
+ fec_wr( mp->base, TSEC_TSTAT, TSEC_TSTAT_THLT );
+ mp->stats.dmarst++;
+ }
+ }
+}
+
+static void tsec_lisr(rtems_irq_hdl_param arg)
+{
+struct tsec_private *mp = (struct tsec_private *)arg;
+rtems_interrupt_level l;
+
+ if ( phy_irq_pending( mp ) ) {
+
+ rtems_interrupt_disable( l );
+ tsec_dis_irqs( mp, TSEC_LINK_INTR );
+ mp->irq_pending |= TSEC_LINK_INTR;
+ rtems_interrupt_enable( l );
+
+ mp->stats.lirqs++;
+
+ if ( mp->isr )
+ mp->isr( mp->isr_arg );
+ else
+ rtems_bsdnet_event_send( mp->tid, mp->event );
+ }
+}
+
+/* Enable interrupts at device */
+void
+BSP_tsec_enable_irq_mask(struct tsec_private *mp, uint32_t mask)
+{
+rtems_interrupt_level l;
+
+ mask &= mp->irq_mask;
+
+ rtems_interrupt_disable( l );
+ if ( (TSEC_LINK_INTR & mask) && ! (TSEC_LINK_INTR & mp->irq_mask_cache) )
+ phy_en_irq( mp );
+ mp->irq_mask_cache |= mask;
+ fec_wr( mp->base, TSEC_IMASK, (mp->irq_mask_cache & ~TSEC_LINK_INTR) );
+ rtems_interrupt_enable( l );
+}
+
+void
+BSP_tsec_enable_irqs(struct tsec_private *mp)
+{
+ BSP_tsec_enable_irq_mask(mp, -1);
+}
+
+/* Disable interrupts at device */
+uint32_t
+BSP_tsec_disable_irq_mask(struct tsec_private *mp, uint32_t mask)
+{
+uint32_t rval;
+rtems_interrupt_level l;
+
+ rtems_interrupt_disable( l );
+ rval = tsec_dis_irqs(mp, mask);
+ rtems_interrupt_enable( l );
+
+ return rval;
+}
+
+void
+BSP_tsec_disable_irqs(struct tsec_private *mp)
+{
+rtems_interrupt_level l;
+
+ rtems_interrupt_disable( l );
+ tsec_dis_irqs(mp, -1);
+ rtems_interrupt_enable( l );
+}
+
+/*
+ * Acknowledge (and clear) interrupts.
+ * RETURNS: interrupts that were raised.
+ */
+uint32_t
+BSP_tsec_ack_irq_mask(struct tsec_private *mp, uint32_t mask)
+{
+uint32_t rval;
+rtems_interrupt_level l;
+
+ rtems_interrupt_disable( l );
+ rval = mp->irq_pending;
+ mp->irq_pending &= ~ mask;
+ rtems_interrupt_enable( l );
+
+ if ( (rval & TSEC_LINK_INTR & mask) ) {
+ /* interacting with the PHY is slow so
+ * we do it only if we have to...
+ */
+ phy_ack_irq( mp );
+ }
+
+ return rval & mp->irq_mask;
+}
+
+uint32_t
+BSP_tsec_ack_irqs(struct tsec_private *mp)
+{
+ return BSP_tsec_ack_irq_mask(mp, -1);
+}
+
+/* Retrieve the driver daemon TID that was passed to
+ * BSP_tsec_setup().
+ */
+
+rtems_id
+BSP_tsec_get_tid(struct tsec_private *mp)
+{
+ return mp->tid;
+}
+
+struct tsec_private *
+BSP_tsec_getp(unsigned index)
+{
+ if ( index >= TSEC_NUM_DRIVER_SLOTS )
+ return 0;
+ return & theTsecEths[index].pvt;
+}
+
+/*
+ *
+ * Example driver task loop (note: no synchronization of
+ * buffer access shown!).
+ * RTEMS_EVENTx = 0,1 or 2 depending on IF unit.
+ *
+ * / * setup (obtain handle) and initialize hw here * /
+ *
+ * do {
+ * / * ISR disables IRQs and posts event * /
+ * rtems_event_receive( RTEMS_EVENTx, RTEMS_WAIT | RTEMS_EVENT_ANY, RTEMS_NO_TIMEOUT, &evs );
+ * irqs = BSP_tsec_ack_irqs(handle);
+ * if ( irqs & BSP_TSEC_IRQ_TX ) {
+ * BSP_tsec_swipe_tx(handle); / * cleanup_txbuf() callback executed * /
+ * }
+ * if ( irqs & BSP_TSEC_IRQ_RX ) {
+ * BSP_tsec_swipe_rx(handle); / * alloc_rxbuf() and consume_rxbuf() executed * /
+ * }
+ * BSP_tsec_enable_irq_mask(handle, -1);
+ * } while (1);
+ *
+ */
+
+/* BSDNET SUPPORT/GLUE ROUTINES */
+
+STATIC void
+tsec_stop(struct tsec_softc *sc)
+{
+ BSP_tsec_stop_hw(&sc->pvt);
+ sc->arpcom.ac_if.if_timer = 0;
+}
+
+/* allocate a mbuf for RX with a properly aligned data buffer
+ * RETURNS 0 if allocation fails
+ */
+static void *
+alloc_mbuf_rx(int *psz, uintptr_t *paddr)
+{
+struct mbuf *m;
+unsigned long l,o;
+
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if ( !m )
+ return 0;
+ MCLGET(m, M_DONTWAIT);
+ if ( ! (m->m_flags & M_EXT) ) {
+ m_freem(m);
+ return 0;
+ }
+
+ o = mtod(m, unsigned long);
+ l = ALIGNTO(o, RX_BUF_ALIGNMENT) - o;
+
+ /* align start of buffer */
+ m->m_data += l;
+
+ /* reduced length */
+ l = MCLBYTES - l;
+
+ m->m_len = m->m_pkthdr.len = l;
+ *psz = m->m_len;
+ *paddr = mtod(m, unsigned long);
+
+ return (void*) m;
+}
+
+static void consume_rx_mbuf(void *buf, void *arg, int len)
+{
+struct ifnet *ifp = arg;
+struct mbuf *m = buf;
+
+ if ( len <= 0 ) {
+ ifp->if_iqdrops++;
+ if ( len < 0 ) {
+ ifp->if_ierrors++;
+ }
+ if ( m )
+ m_freem(m);
+ } else {
+ struct ether_header *eh;
+
+ eh = (struct ether_header *)(mtod(m, unsigned long) + ETH_RX_OFFSET);
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header) - ETH_RX_OFFSET - ETH_CRC_LEN;
+ m->m_data += sizeof(struct ether_header) + ETH_RX_OFFSET;
+ m->m_pkthdr.rcvif = ifp;
+
+ ifp->if_ipackets++;
+ ifp->if_ibytes += m->m_pkthdr.len;
+
+ /* send buffer upwards */
+ if (0) {
+ /* Low-level debugging */
+ int i;
+ for (i=0; i<13; i++) {
+ printf("%02X:",((char*)eh)[i]);
+ }
+ printf("%02X\n",((char*)eh)[i]);
+ for (i=0; i<m->m_len; i++) {
+ if ( !(i&15) )
+ printf("\n");
+ printf("0x%02x ",mtod(m,char*)[i]);
+ }
+ printf("\n");
+ }
+
+ if (0) /* Low-level debugging/testing without bsd stack */
+ m_freem(m);
+ else
+ ether_input(ifp, eh, m);
+ }
+}
+
+static void release_tx_mbuf(void *buf, void *arg, int err)
+{
+struct ifnet *ifp = arg;
+struct mbuf *mb = buf;
+
+ if ( err ) {
+ ifp->if_oerrors++;
+ } else {
+ ifp->if_opackets++;
+ }
+ ifp->if_obytes += mb->m_pkthdr.len;
+ m_freem(mb);
+}
+
+/* BSDNET DRIVER CALLBACKS */
+
+static void
+tsec_init(void *arg)
+{
+struct tsec_softc *sc = arg;
+struct ifnet *ifp = &sc->arpcom.ac_if;
+int media;
+
+ BSP_tsec_init_hw(&sc->pvt, ifp->if_flags & IFF_PROMISC, sc->arpcom.ac_enaddr);
+
+ /* Determine initial link status and block sender if there is no link */
+ media = IFM_MAKEWORD(0, 0, 0, 0);
+ if ( 0 == BSP_tsec_media_ioctl(&sc->pvt, SIOCGIFMEDIA, &media) ) {
+ if ( (IFM_LINK_OK & media) ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ } else {
+ ifp->if_flags |= IFF_OACTIVE;
+ }
+ }
+
+ tsec_update_mcast(ifp);
+ ifp->if_flags |= IFF_RUNNING;
+ sc->arpcom.ac_if.if_timer = 0;
+}
+
+/* bsdnet driver entry to start transmission */
+static void
+tsec_start(struct ifnet *ifp)
+{
+struct tsec_softc *sc = ifp->if_softc;
+struct mbuf *m = 0;
+
+ while ( ifp->if_snd.ifq_head ) {
+ IF_DEQUEUE( &ifp->if_snd, m );
+ if ( BSP_tsec_send_buf(&sc->pvt, m, 0, 0) < 0 ) {
+ IF_PREPEND( &ifp->if_snd, m);
+ ifp->if_flags |= IFF_OACTIVE;
+ break;
+ }
+ /* need to do this really only once
+ * but it's cheaper this way.
+ */
+ ifp->if_timer = 2*IFNET_SLOWHZ;
+ }
+}
+
+/* bsdnet driver entry; */
+static void
+tsec_watchdog(struct ifnet *ifp)
+{
+struct tsec_softc *sc = ifp->if_softc;
+
+ ifp->if_oerrors++;
+ printk(DRVNAME"%i: watchdog timeout; resetting\n", ifp->if_unit);
+
+ tsec_init(sc);
+ tsec_start(ifp);
+}
+
+static void
+tsec_update_mcast(struct ifnet *ifp)
+{
+struct tsec_softc *sc = ifp->if_softc;
+struct ether_multi *enm;
+struct ether_multistep step;
+
+ if ( IFF_ALLMULTI & ifp->if_flags ) {
+ BSP_tsec_mcast_filter_accept_all( &sc->pvt );
+ } else {
+ BSP_tsec_mcast_filter_clear( &sc->pvt );
+
+ ETHER_FIRST_MULTI(step, (struct arpcom *)ifp, enm);
+
+ while ( enm ) {
+ if ( memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN) )
+ assert( !"Should never get here; IFF_ALLMULTI should be set!" );
+
+ BSP_tsec_mcast_filter_accept_add(&sc->pvt, enm->enm_addrlo);
+
+ ETHER_NEXT_MULTI(step, enm);
+ }
+ }
+}
+
+/* bsdnet driver ioctl entry */
+static int
+tsec_ioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data)
+{
+struct tsec_softc *sc = ifp->if_softc;
+struct ifreq *ifr = (struct ifreq *)data;
+#if 0
+uint32_t v;
+#endif
+int error = 0;
+int f;
+
+ switch ( cmd ) {
+ case SIOCSIFFLAGS:
+ f = ifp->if_flags;
+ if ( f & IFF_UP ) {
+ if ( ! ( f & IFF_RUNNING ) ) {
+ tsec_init(sc);
+ } else {
+ if ( (f & IFF_PROMISC) != (sc->bsd.oif_flags & IFF_PROMISC) ) {
+ /* Hmm - the manual says we must change the RCTRL
+ * register only after a reset or if DMACTRL[GRS]
+ * is cleared which is the normal operating
+ * condition. I hope this is legal ??
+ */
+ if ( (f & IFF_PROMISC) ) {
+ fec_set( sc->pvt.base, TSEC_RCTRL, TSEC_RCTRL_PROM );
+ } else {
+ fec_clr( sc->pvt.base, TSEC_RCTRL, TSEC_RCTRL_PROM );
+ }
+ }
+ /* FIXME: other flag changes are ignored/unimplemented */
+ }
+ } else {
+ if ( f & IFF_RUNNING ) {
+ tsec_stop(sc);
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+ }
+ }
+ sc->bsd.oif_flags = ifp->if_flags;
+ break;
+
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ error = BSP_tsec_media_ioctl(&sc->pvt, cmd, &ifr->ifr_media);
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ error = (cmd == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &sc->arpcom)
+ : ether_delmulti(ifr, &sc->arpcom);
+
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING) {
+ tsec_update_mcast(ifp);
+ }
+ error = 0;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ BSP_tsec_dump_stats( &sc->pvt, stdout );
+ break;
+
+ default:
+ error = ether_ioctl(ifp, cmd, data);
+ break;
+ }
+
+ return error;
+}
+
+/* DRIVER TASK */
+
+/* Daemon task does all the 'interrupt' work */
+static void tsec_daemon(void *arg)
+{
+struct tsec_softc *sc;
+struct ifnet *ifp;
+rtems_event_set evs;
+ for (;;) {
+ rtems_bsdnet_event_receive( EV_MSK, RTEMS_WAIT | RTEMS_EVENT_ANY, RTEMS_NO_TIMEOUT, &evs );
+ evs &= EV_MSK;
+ for ( sc = theTsecEths; evs; evs>>=EV_PER_UNIT, sc++ ) {
+ if ( EV_IS_ANY(evs) ) {
+
+ register uint32_t x;
+
+ ifp = &sc->arpcom.ac_if;
+
+ if ( !(ifp->if_flags & IFF_UP) ) {
+ tsec_stop(sc);
+ ifp->if_flags &= ~(IFF_UP|IFF_RUNNING);
+ continue;
+ }
+
+ if ( !(ifp->if_flags & IFF_RUNNING) ) {
+ /* event could have been pending at the time hw was stopped;
+ * just ignore...
+ */
+ continue;
+ }
+
+ x = BSP_tsec_ack_irqs(&sc->pvt);
+
+ if ( TSEC_LINK_INTR & x ) {
+ /* phy status changed */
+ int media;
+
+#ifdef DEBUG
+ printf("LINK INTR\n");
+#endif
+ if ( -1 != (media = mac_set_duplex( &sc->pvt )) ) {
+#ifdef DEBUG
+ rtems_ifmedia2str( media, 0, 0 );
+ printf("\n");
+#endif
+ if ( IFM_LINK_OK & media ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ tsec_start(ifp);
+ } else {
+ /* stop sending */
+ ifp->if_flags |= IFF_OACTIVE;
+ }
+ }
+ }
+
+ /* free tx chain */
+ if ( (TSEC_TXIRQ & x) && BSP_tsec_swipe_tx(&sc->pvt) ) {
+ ifp->if_flags &= ~IFF_OACTIVE;
+ if ( TX_AVAILABLE_RING_SIZE(&sc->pvt) == sc->pvt.tx_avail )
+ ifp->if_timer = 0;
+ tsec_start(ifp);
+ }
+ if ( (TSEC_RXIRQ & x) )
+ BSP_tsec_swipe_rx(&sc->pvt);
+
+ BSP_tsec_enable_irq_mask(&sc->pvt, -1);
+ }
+ }
+ }
+}
+
+/* PUBLIC RTEMS BSDNET ATTACH FUNCTION */
+int
+rtems_tsec_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+char *unitName;
+int unit,i,cfgUnits;
+struct tsec_softc *sc;
+struct ifnet *ifp;
+
+ unit = rtems_bsdnet_parse_driver_name(ifcfg, &unitName);
+ if ( unit <= 0 || unit > TSEC_NUM_DRIVER_SLOTS ) {
+ printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, TSEC_NUM_DRIVER_SLOTS);
+ return 1;
+ }
+
+ sc = &theTsecEths[unit-1];
+ ifp = &sc->arpcom.ac_if;
+
+ if ( attaching ) {
+ if ( ifp->if_init ) {
+ printk(DRVNAME": instance %i already attached.\n", unit);
+ return -1;
+ }
+
+ for ( i=cfgUnits = 0; i<TSEC_NUM_DRIVER_SLOTS; i++ ) {
+ if ( theTsecEths[i].arpcom.ac_if.if_init )
+ cfgUnits++;
+ }
+ cfgUnits++; /* this new one */
+
+ /* lazy init of TID should still be thread-safe because we are protected
+ * by the global networking semaphore..
+ */
+ if ( !tsec_tid ) {
+ /* newproc uses the 1st 4 chars of name string to build an rtems name */
+ tsec_tid = rtems_bsdnet_newproc("FECd", 4096, tsec_daemon, 0);
+ }
+
+ if ( !BSP_tsec_setup( unit,
+ tsec_tid,
+ release_tx_mbuf, ifp,
+ alloc_mbuf_rx,
+ consume_rx_mbuf, ifp,
+ ifcfg->rbuf_count,
+ ifcfg->xbuf_count,
+ TSEC_RXIRQ | TSEC_TXIRQ | TSEC_LINK_INTR) ) {
+ return -1;
+ }
+
+ if ( nmbclusters < sc->pvt.rx_ring_size * cfgUnits + 60 /* arbitrary */ ) {
+ printk(DRVNAME"%i: (tsec ethernet) Your application has not enough mbuf clusters\n", unit);
+ printk( " configured for this driver.\n");
+ return -1;
+ }
+
+ if ( ifcfg->hardware_address ) {
+ memcpy(sc->arpcom.ac_enaddr, ifcfg->hardware_address, ETHER_ADDR_LEN);
+ } else {
+ /* read back from hardware assuming that MotLoad already had set it up */
+ BSP_tsec_read_eaddr(&sc->pvt, sc->arpcom.ac_enaddr);
+ }
+
+ ifp->if_softc = sc;
+ ifp->if_unit = unit;
+ ifp->if_name = unitName;
+
+ ifp->if_mtu = ifcfg->mtu ? ifcfg->mtu : ETHERMTU;
+
+ ifp->if_init = tsec_init;
+ ifp->if_ioctl = tsec_ioctl;
+ ifp->if_start = tsec_start;
+ ifp->if_output = ether_output;
+ /*
+ * While nonzero, the 'if->if_timer' is decremented
+ * (by the networking code) at a rate of IFNET_SLOWHZ (1hz) and 'if_watchdog'
+ * is called when it expires.
+ * If either of those fields is 0 the feature is disabled.
+ */
+ ifp->if_watchdog = tsec_watchdog;
+ ifp->if_timer = 0;
+
+ sc->bsd.oif_flags = /* ... */
+ ifp->if_flags = IFF_BROADCAST | IFF_MULTICAST | IFF_SIMPLEX;
+
+ /*
+ * if unset, this set to 10Mbps by ether_ifattach; seems to be unused by bsdnet stack;
+ * could be updated along with phy speed, though...
+ ifp->if_baudrate = 10000000;
+ */
+
+ /* NOTE: ether_output drops packets if ifq_len >= ifq_maxlen
+ * but this is the packet count, not the fragment count!
+ ifp->if_snd.ifq_maxlen = sc->pvt.tx_ring_size;
+ */
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+#ifdef TSEC_DETACH_HACK
+ if ( !ifp->if_addrlist ) /* do only the first time [reattach hack] */
+#endif
+ {
+ if_attach(ifp);
+ ether_ifattach(ifp);
+ }
+
+ } else {
+#ifdef TSEC_DETACH_HACK
+ if ( !ifp->if_init ) {
+ printk(DRVNAME": instance %i not attached.\n", unit);
+ return -1;
+ }
+ return tsec_detach(sc);
+#else
+ printk(DRVNAME": interface detaching not implemented\n");
+ return -1;
+#endif
+ }
+
+ return 0;
+}
+
+/* PHY stuff should really not be in this driver but separate :-(
+ * However, I don't have time right now to implement clean
+ * boundaries:
+ * - PHY driver should only know about the PHY
+ * - TSEC driver only provides MII access and knows
+ * how to deal with a PHY interrupt.
+ * - BSP knows how interrupts are routed. E.g., the MVME3100
+ * shares a single IRQ line among 3 PHYs (for the three ports)
+ * and provides a special 'on-board' register for determining
+ * what PHY raised an interrupt w/o the need to do any MII IO.
+ * Integrating all these bits in a clean way is not as easy as
+ * just hacking away, sorry...
+ */
+
+/*
+ * Broadcom 54xx PHY register definitions. Unfriendly Broadcom doesn't
+ * release specs for their products :-( -- valuable info comes from
+ * the linux driver by
+ * Maciej W. Rozycki <macro@linux-mips.org>
+ * Amy Fong
+ */
+
+#define BCM54xx_GBCR 0x09 /* gigabit control */
+#define BCM54xx_GBCR_FD (1<<9) /* full-duplex cap. */
+
+#define BCM54xx_ECR 0x10 /* extended control */
+#define BCM54xx_ECR_IM (1<<12) /* IRQ mask */
+#define BCM54xx_ECR_IF (1<<12) /* IRQ force */
+
+#define BCM54xx_ESR 0x11 /* extended status */
+#define BCM54xx_ESR_IRQ (1<<12) /* IRQ pending */
+
+#define BCM54xx_AUXCR 0x18 /* AUX control */
+#define BCM54xx_AUXCR_PWR10BASET (1<<2)
+
+#define BCM54xx_AUXST 0x19 /* AUX status */
+#define BCM54xx_AUXST_LNKMM (7<<8) /* link mode mask */
+
+/* link mode (linux' syngem_phy.c helped here...)
+ *
+ * 0: no link
+ * 1: 10BT half
+ * 2: 10BT full
+ * 3: 100BT half
+ * 4: 100BT half
+ * 5: 100BT full
+ * 6: 1000BT full
+ * 7: 1000BT full
+ */
+
+#define BCM54xx_ISR 0x1a /* IRQ status */
+#define BCM54xx_IMR 0x1b /* IRQ mask */
+#define BCM54xx_IRQ_CRC (1<< 0) /* CRC error */
+#define BCM54xx_IRQ_LNK (1<< 1) /* LINK status chg. */
+#define BCM54xx_IRQ_SPD (1<< 2) /* SPEED change */
+#define BCM54xx_IRQ_DUP (1<< 3) /* LINK status chg. */
+#define BCM54xx_IRQ_LRS (1<< 4) /* Lcl. RX status chg.*/
+#define BCM54xx_IRQ_RRS (1<< 5) /* Rem. RX status chg.*/
+#define BCM54xx_IRQ_SSE (1<< 6) /* Scrambler sync err */
+#define BCM54xx_IRQ_UHCD (1<< 7) /* Unsupp. HCD neg. */
+#define BCM54xx_IRQ_NHCD (1<< 8) /* No HCD */
+#define BCM54xx_IRQ_HCDL (1<< 9) /* No HCD Link */
+#define BCM54xx_IRQ_ANPR (1<<10) /* Aneg. pg. req. */
+#define BCM54xx_IRQ_LC (1<<11) /* All ctrs. < 128 */
+#define BCM54xx_IRQ_HC (1<<12) /* Ctr > 32768 */
+#define BCM54xx_IRQ_MDIX (1<<13) /* MDIX status chg. */
+#define BCM54xx_IRQ_PSERR (1<<14) /* Pair swap error */
+
+#define PHY_IRQS ( BCM54xx_IRQ_LNK | BCM54xx_IRQ_SPD | BCM54xx_IRQ_DUP )
+
+
+static void
+phy_en_irq_at_phy( struct tsec_private *mp )
+{
+uint32_t ecr;
+
+ REGLOCK();
+ tsec_mdio_rd( 0, mp, BCM54xx_ECR, &ecr );
+ ecr &= ~BCM54xx_ECR_IM;
+ tsec_mdio_wr( 0, mp, BCM54xx_ECR, ecr );
+ REGUNLOCK();
+}
+
+static void
+phy_dis_irq_at_phy( struct tsec_private *mp )
+{
+uint32_t ecr;
+
+ REGLOCK();
+ tsec_mdio_rd( 0, mp, BCM54xx_ECR, &ecr );
+ ecr |= BCM54xx_ECR_IM;
+ tsec_mdio_wr( 0, mp, BCM54xx_ECR, ecr );
+ REGUNLOCK();
+}
+
+static void
+phy_init_irq( int install, struct tsec_private *mp, void (*isr)(rtems_irq_hdl_param) )
+{
+uint32_t v;
+rtems_irq_connect_data xxx;
+
+ xxx.on = noop;
+ xxx.off = noop;
+ xxx.isOn = nopf;
+ xxx.name = BSP_PHY_IRQ;
+ xxx.handle = mp;
+ xxx.hdl = isr;
+
+ phy_dis_irq_at_phy( mp );
+
+ REGLOCK();
+ /* Select IRQs we want */
+ tsec_mdio_wr( 0, mp, BCM54xx_IMR, ~ PHY_IRQS );
+ /* clear pending irqs */
+ tsec_mdio_rd( 0, mp, BCM54xx_ISR, &v );
+ REGUNLOCK();
+
+ /* install shared ISR */
+ if ( ! (install ?
+ BSP_install_rtems_shared_irq_handler( &xxx ) :
+ BSP_remove_rtems_irq_handler( &xxx )) ) {
+ rtems_panic( "Unable to %s shared irq handler (PHY)\n", install ? "install" : "remove" );
+ }
+}
+
+/* Because on the MVME3100 multiple PHYs (belonging to different
+ * TSEC instances) share a single interrupt line and we want
+ * to disable interrupts at the PIC rather than in the individual
+ * PHYs (because access to those is slow) we must implement
+ * nesting...
+ */
+STATIC int phy_irq_dis_level = 0;
+
+/* assume 'en_irq' / 'dis_irq' cannot be interrupted.
+ * Either because they are called from an ISR (all
+ * tsec + phy isrs must have the same priority) or
+ * from a IRQ-protected section of code
+ */
+
+static void
+phy_en_irq(struct tsec_private *mp)
+{
+ phy_irq_dis_level &= ~(1<<mp->unit);
+ if ( 0 == phy_irq_dis_level ) {
+ BSP_enable_irq_at_pic( BSP_PHY_IRQ );
+ }
+}
+
+
+static void
+phy_dis_irq(struct tsec_private *mp)
+{
+ phy_irq_dis_level |= (1<<mp->unit);
+ BSP_disable_irq_at_pic( BSP_PHY_IRQ );
+}
+
+static int
+phy_irq_pending(struct tsec_private *mp)
+{
+ /* MVME3100 speciality: we can check for a pending
+ * PHY IRQ w/o having to access the MII bus :-)
+ */
+ return in_8( BSP_MVME3100_IRQ_DETECT_REG ) & (1 << (mp->unit - 1));
+}
+
+static uint32_t
+phy_ack_irq(struct tsec_private *mp)
+{
+uint32_t v;
+
+ REGLOCK();
+ tsec_mdio_rd( 0, mp, BCM54xx_ISR, &v );
+ REGUNLOCK();
+
+#ifdef DEBUG
+ printf("phy_ack_irq: 0x%08"PRIx32"\n", v);
+#endif
+
+ return v;
+}
+
+#if defined(PARANOIA) || defined(DEBUG)
+
+static void dumpbd(TSEC_BD *bd)
+{
+ printf("Flags 0x%04"PRIx16", len 0x%04"PRIx16", buf 0x%08"PRIx32"\n",
+ bd_rdfl( bd ), ld_be16( &bd->len ), bd_rdbuf( bd ) );
+}
+
+void tsec_dump_rring(struct tsec_private *mp)
+{
+int i;
+TSEC_BD *bd;
+ if ( !mp ) {
+ printf("Neet tsec_private * arg\n");
+ return;
+ }
+ for ( i=0; i<mp->rx_ring_size; i++ ) {
+ bd = &mp->rx_ring[i];
+ printf("[%i]: ", i);
+ dumpbd(bd);
+ }
+}
+
+void tsec_dump_tring(struct tsec_private *mp)
+{
+int i;
+TSEC_BD *bd;
+ if ( !mp ) {
+ printf("Neet tsec_private * arg\n");
+ return;
+ }
+ for ( i=0; i<mp->tx_ring_size; i++ ) {
+ bd = &mp->tx_ring[i];
+ printf("[%i]: ", i);
+ dumpbd(bd);
+ }
+ printf("Avail: %i; Head %i; Tail %i\n", mp->tx_avail, mp->tx_head, mp->tx_tail);
+}
+#endif
+
+
+#ifdef DEBUG
+
+#undef free
+#undef malloc
+
+#include <stdlib.h>
+
+void cleanup_txbuf_test(void *u, void *a, int err)
+{
+ printf("cleanup_txbuf_test (releasing buf 0x%8p)\n", u);
+ free(u);
+ if ( err )
+ printf("cleanup_txbuf_test: an error was detected\n");
+}
+
+void *alloc_rxbuf_test(int *p_size, uintptr_t *p_data_addr)
+{
+void *rval;
+
+ *p_size = 1600;
+ rval = malloc( *p_size + RX_BUF_ALIGNMENT );
+ *p_data_addr = (uintptr_t)ALIGNTO(rval,RX_BUF_ALIGNMENT);
+
+ /* PRIxPTR is still broken :-( */
+ printf("alloc_rxxbuf_test: allocated %i bytes @0x%8p/0x%08"PRIx32"\n",
+ *p_size, rval, (uint32_t)*p_data_addr);
+
+ return rval;
+}
+
+void consume_rxbuf_test(void *user_buf, void *consume_rxbuf_arg, int len)
+{
+int i;
+uintptr_t d = (uintptr_t)ALIGNTO(user_buf,RX_BUF_ALIGNMENT);
+
+ /* PRIxPTR is still broken */
+ printf("consuming rx buf 0x%8p (data@ 0x%08"PRIx32")\n",user_buf, (uint32_t)d);
+ if ( len > 32 )
+ len = 32;
+ if ( len < 0 )
+ printf("consume_rxbuf_test: ERROR occurred: 0x%x\n", len);
+ else {
+ printf("RX:");
+ for ( i=0; i<len; i++ ) {
+ if ( 0 == (i&0xf) )
+ printf("\n ");
+ printf("0x%02x ", ((char*)d)[i]);
+ }
+ printf("\n");
+ free(user_buf);
+ }
+}
+
+unsigned char pkt[100];
+
+void * tsec_up()
+{
+struct tsec_private *tsec =
+ BSP_tsec_setup( 1, 0,
+ cleanup_txbuf_test, 0,
+ alloc_rxbuf_test,
+ consume_rxbuf_test, 0,
+ 2,
+ 2,
+ 0);
+ BSP_tsec_init_hw(tsec, 0, 0);
+ memset(pkt,0,100);
+ memset(pkt,0xff,6);
+ BSP_tsec_read_eaddr(tsec, pkt+6);
+ pkt[12] = 0;
+ pkt[13] = 64;
+ return tsec;
+}
+
+#ifdef DEBUG_MODULAR
+int
+_cexpModuleInitialize(void*u)
+{
+extern int ifattach();
+extern int ifconf();
+extern int rtconf();
+ ifattach("ts1",rtems_tsec_attach,0);
+ ifconf("ts1","134.79.33.137","255.255.252.0");
+ ifconf("pcn1",0,0);
+ rtconf(0, "134.79.33.86",0,0);
+ return 0;
+}
+#endif
+#endif
diff --git a/bsps/powerpc/mvme5500/net/if_100MHz/GT64260eth.c b/bsps/powerpc/mvme5500/net/if_100MHz/GT64260eth.c
new file mode 100644
index 0000000..91f90cc
--- /dev/null
+++ b/bsps/powerpc/mvme5500/net/if_100MHz/GT64260eth.c
@@ -0,0 +1,1574 @@
+/* GT64260eth.c : GT64260 10/100 Mb ethernet MAC driver
+ *
+ * Copyright (c) 2003,2004 Brookhaven National Laboratory
+ * S. Kate Feng <feng1@bnl.gov>
+ * All rights reserved
+ *
+ * Acknowledgements:
+ * netBSD : Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * Marvell : NDA document for the discovery system controller
+ *
+ * Some notes from the author, S. Kate Feng :
+ *
+ * 1) Mvme5500 uses Eth0 (controller 0) of the GT64260 to implement
+ * the 10/100 BaseT Ethernet with PCI Master Data Byte Swap\
+ * control.
+ * 2) Implemented hardware snoop instead of software snoop
+ * to ensure SDRAM cache coherency. (Copyright : NDA item)
+ * 3) Added S/W support for multi mbuf. (TODO : Let the H/W do it)
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#define BYTE_ORDER BIG_ENDIAN
+
+#include <rtems.h>
+#include <rtems/bspIo.h> /* printk */
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_bsdnet_internal.h>
+#include <stdio.h> /* printf for statistics */
+#include <string.h>
+
+#include <libcpu/io.h> /* inp & friends */
+#include <libcpu/spr.h> /* registers.h is included here */
+#include <bsp.h>
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/mbuf.h>
+
+#include <errno.h>
+
+/* #include <sys/queue.h> */
+
+#include <sys/socket.h>
+#include <sys/sockio.h> /* SIOCADDMULTI, SIOC... */
+#include <net/if.h>
+#include <net/if_dl.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#ifdef INET
+#include <netinet/in_var.h>
+#endif
+
+#include <bsp/irq.h>
+#include <bsp/GT64260ethreg.h>
+#include <bsp/GT64260eth.h>
+#include <bsp/VPD.h>
+
+extern unsigned char ReadConfVPD_buff(int offset); /* in startup/bspstart.c */
+
+#define GT_ETH_TASK_NAME "Geth"
+#define PKT_BUF_SZ 1536
+#define SOFTC_ALIGN 31
+#define HASH_ALIGN 15
+
+#define TXQ_HiLmt_OFF 2
+
+/* <skf>
+ * 1. printk debug is for diagnosis only, which may cause
+ * unexpected result, especially if txq is under heavy load
+ * because CPU is fast with a decent cache.
+ */
+#define GTeth_debug 0
+#define GTeth_rx_debug 0
+
+#if 0
+#define GE_FORGOT
+#define GE_NORX
+#define GT_DEBUG
+#endif
+
+/* RTEMS event to kill the daemon */
+#define KILL_EVENT RTEMS_EVENT_1
+/* RTEMS event to (re)start the transmitter */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+/* RTEMS events used by the ISR */
+#define RX_EVENT RTEMS_EVENT_3
+#define TX_EVENT RTEMS_EVENT_4
+#define ERR_EVENT RTEMS_EVENT_5
+
+#define ALL_EVENTS (KILL_EVENT|START_TRANSMIT_EVENT|RX_EVENT|TX_EVENT|ERR_EVENT)
+
+enum GTeth_whack_op {
+ GE_WHACK_START, GE_WHACK_RESTART,
+ GE_WHACK_CHANGE, GE_WHACK_STOP
+};
+
+enum GTeth_hash_op {
+ GE_HASH_ADD, GE_HASH_REMOVE,
+};
+
+#define ET_MINLEN 64 /* minimum message length */
+
+static int GTeth_ifioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data);
+static void GTeth_ifstart (struct ifnet *);
+static void GTeth_ifchange(struct GTeth_softc *sc);
+static void GTeth_init_rx_ring(struct GTeth_softc *sc);
+static void GT64260eth_daemon(void *arg);
+static int GT64260eth_sendpacket(struct GTeth_softc *sc,struct mbuf *m);
+static unsigned GTeth_txq_done(struct GTeth_softc *sc);
+static void GTeth_tx_cleanup(struct GTeth_softc *sc);
+static void GTeth_tx_start(struct GTeth_softc *sc);
+static void GTeth_tx_stop(struct GTeth_softc *sc);
+static void GTeth_rx_cleanup(struct GTeth_softc *sc);
+static int GT64260eth_rx(struct GTeth_softc *sc);
+static void GTeth_rx_setup(struct GTeth_softc *sc);
+static void GTeth_rxprio_setup(struct GTeth_softc *sc);
+static void GTeth_rx_stop(struct GTeth_softc *dc);
+static void GT64260eth_isr(void);
+static int GTeth_hash_compute(struct GTeth_softc *sc,unsigned char eaddr[ETHER_ADDR_LEN]);
+static int GTeth_hash_entry_op(struct GTeth_softc *sc, enum GTeth_hash_op op,
+ enum GTeth_rxprio prio,unsigned char eaddr[ETHER_ADDR_LEN]);
+
+static int GTeth_hash_fill(struct GTeth_softc *sc);
+static void GTeth_hash_init(struct GTeth_softc *sc);
+
+static struct GTeth_softc *root_GT64260eth_dev = NULL;
+
+static void GT64260eth_irq_on(const rtems_irq_connect_data *irq)
+{
+ struct GTeth_softc *sc;
+
+ for (sc= root_GT64260eth_dev; sc; sc= sc-> next_module) {
+ outl(0x30883444,ETH0_EIMR); /* MOTLoad default interrupt mask */
+ return;
+ }
+}
+
+static void GT64260eth_irq_off(const rtems_irq_connect_data *irq)
+{
+ struct GTeth_softc *sc;
+
+ for (sc= root_GT64260eth_dev; sc; sc= sc-> next_module)
+ outl(0, ETH0_EIMR);
+}
+
+static int GT64260eth_irq_is_on(const rtems_irq_connect_data *irq)
+{
+ return(inl(ETH0_EICR) & ETH_IR_EtherIntSum);
+}
+
+static void GT64260eth_isr(void)
+{
+ struct GTeth_softc *sc = root_GT64260eth_dev;
+ rtems_event_set events=0;
+ uint32_t cause;
+
+
+ cause = inl(ETH0_EICR);
+ outl( ~cause,ETH0_EICR); /* clear the ICR */
+
+ if ( (!cause) || (cause & 0x803d00)) {
+ sc->intr_errsts[sc->intr_err_ptr2++]=cause;
+ sc->intr_err_ptr2 %=INTR_ERR_SIZE; /* Till Straumann */
+ events |= ERR_EVENT;
+ }
+
+ /* ETH_IR_RxBuffer_3|ETH_IR_RxError_3 */
+ if (cause & 0x880000) {
+ sc->stats.rxInterrupts++;
+ events |= RX_EVENT;
+ }
+ /* If there is an error, we want to continue to next descriptor */
+ /* ETH_IR_TxBufferHigh|ETH_IR_TxEndHigh|ETH_IR_TxErrorHigh */
+ if (cause & 0x444) {
+ sc->stats.txInterrupts++;
+ events |= TX_EVENT;
+ /* It seems to be unnecessary. However, it's there
+ * to be on the safe side due to the datasheet.
+ * So far, it does not seem to affect the network performance
+ * based on the EPICS catime.
+ */
+ /* ETH_ESDCMR_TXDH | ETH_ESDCMR_ERD = 0x800080 */
+ if ((sc->txq_nactive > 1)&& ((inl(ETH0_ESDCMR)&ETH_ESDCMR_TXDH)==0))
+ outl(0x800080,ETH0_ESDCMR);
+
+
+ }
+ rtems_bsdnet_event_send(sc->daemonTid, events);
+}
+
+static rtems_irq_connect_data GT64260ethIrqData={
+ BSP_MAIN_ETH0_IRQ,
+ (rtems_irq_hdl) GT64260eth_isr,
+ NULL,
+ (rtems_irq_enable) GT64260eth_irq_on,
+ (rtems_irq_disable) GT64260eth_irq_off,
+ (rtems_irq_is_enabled) GT64260eth_irq_is_on,
+};
+
+static void GT64260eth_init_hw(struct GTeth_softc *sc)
+{
+
+#ifdef GT_DEBUG
+ printk("GT64260eth_init_hw(");
+#endif
+ /* Kate Feng : Turn the hardware snoop on as MOTLoad did not have
+ * it on by default.
+ */
+ outl(RxBSnoopEn|TxBSnoopEn|RxDSnoopEn|TxDSnoopEn, GT_CUU_Eth0_AddrCtrlLow);
+ outl(HashSnoopEn, GT_CUU_Eth0_AddrCtrlHigh);
+
+ sc->rxq_intrbits=0;
+ sc->sc_flags=0;
+
+#ifndef GE_NORX
+ GTeth_rx_setup(sc);
+#endif
+
+#ifndef GE_NOTX
+ GTeth_tx_start(sc);
+#endif
+
+ sc->sc_pcr |= ETH_EPCR_HS_512;
+ outl(sc->sc_pcr, ETH0_EPCR);
+ outl(sc->sc_pcxr, ETH0_EPCXR); /* port config. extended reg. */
+ outl(0, ETH0_EICR); /* interrupt cause register */
+ outl(sc->sc_intrmask, ETH0_EIMR);
+#ifndef GE_NOHASH
+ /* Port Hash Table Pointer Reg*/
+ outl(((unsigned) sc->sc_hashtable),ETH0_EHTPR);
+#endif
+#ifndef GE_NORX
+ outl(ETH_ESDCMR_ERD,ETH0_ESDCMR); /* enable Rx DMA in SDMA Command Register */
+ sc->sc_flags |= GE_RXACTIVE;
+#endif
+#ifdef GT_DEBUG
+ printk("SDCMR 0x%x ", inl(ETH0_ESDCMR));
+#endif
+
+ /* connect the interrupt handler which should
+ * take care of enabling interrupts
+ */
+ if (!BSP_install_rtems_irq_handler(&GT64260ethIrqData))
+ printk("GT64260eth: unable to install ISR");
+
+ /* The ethernet port is ready to transmit/receive */
+ outl(sc->sc_pcr | ETH_EPCR_EN, ETH0_EPCR);
+
+#ifdef GT_DEBUG
+ printk(")\n");
+#endif
+}
+
+static void GT64260eth_stop_hw(struct GTeth_softc *sc)
+{
+
+ printk("GT64260eth_stop_hw(");
+
+ /* remove our interrupt handler which will also
+ * disable interrupts at the MPIC and the device
+ * itself
+ */
+ if (!BSP_remove_rtems_irq_handler(&GT64260ethIrqData))
+ printk("GT64260eth: unable to remove IRQ handler!");
+
+ outl(sc->sc_pcr, ETH0_EPCR);
+ outl(0, ETH0_EIMR);
+
+ sc->arpcom.ac_if.if_flags &= ~IFF_RUNNING;
+#ifndef GE_NOTX
+ GTeth_tx_stop(sc);
+#endif
+#ifndef GE_NORX
+ GTeth_rx_stop(sc);
+#endif
+ sc->sc_hashtable = NULL;
+ if (GTeth_debug>0) printk(")");
+}
+
+static void GT64260eth_stop(struct GTeth_softc *sc)
+{
+ if (GTeth_debug>0) printk("GT64260eth_stop(");
+
+ /* The hardware is shutdown in the daemon */
+ /* kill the daemon. We also must release the networking
+ * semaphore or there'll be a deadlock...
+ */
+ rtems_bsdnet_event_send(sc->daemonTid, KILL_EVENT);
+ rtems_bsdnet_semaphore_release();
+
+ sc->daemonTid=0;
+ /* now wait for it to die */
+ rtems_semaphore_obtain(sc->daemonSync,RTEMS_WAIT,RTEMS_NO_TIMEOUT);
+
+ /* reacquire the bsdnet semaphore */
+ rtems_bsdnet_semaphore_obtain();
+ if (GTeth_debug>0) printk(")");
+}
+
+static void GT64260eth_ifinit(void *arg)
+{
+ struct GTeth_softc *sc = (struct GTeth_softc*)arg;
+ int i;
+
+#ifdef GT_DEBUG
+ printk("GT64260eth_ifinit(): daemon ID: 0x%08x)\n", sc->daemonTid);
+#endif
+ if (sc->daemonTid) {
+#ifdef GT_DEBUG
+ printk("GT64260eth: daemon already up, doing nothing\n");
+#endif
+ return;
+ }
+
+#ifndef GE_NOHASH
+ /* Mvme5500, the user must initialize the hash table before enabling the
+ * Ethernet controller
+ */
+ GTeth_hash_init(sc);
+ GTeth_hash_fill(sc);
+#endif
+
+ sc->intr_err_ptr1=0;
+ sc->intr_err_ptr2=0;
+ for (i=0; i< INTR_ERR_SIZE; i++) sc->intr_errsts[i]=0;
+
+ /* initialize the hardware (we are holding the network semaphore at this point) */
+ (void)GT64260eth_init_hw(sc);
+
+ /* launch network daemon */
+
+ /* NOTE:
+ * in ss-20011025 (and later) any task created by 'bsdnet_newproc' is
+ * wrapped by code which acquires the network semaphore...
+ */
+ sc->daemonTid = rtems_bsdnet_newproc(GT_ETH_TASK_NAME,4096,GT64260eth_daemon,arg);
+
+ /* Tell the world that we're running */
+ sc->arpcom.ac_if.if_flags |= IFF_RUNNING;
+
+}
+
+/* attach parameter tells us whether to attach or to detach the driver */
+/* Attach this instance, and then all the sub-devices */
+int rtems_GT64260eth_driver_attach(struct rtems_bsdnet_ifconfig *config, int attach)
+{
+ struct GTeth_softc *sc;
+ struct ifnet *ifp;
+ unsigned sdcr, data;
+ unsigned char hwaddr[6];
+ int i, unit, phyaddr;
+ void *softc_mem;
+ char *name;
+
+ unit = rtems_bsdnet_parse_driver_name(config, &name);
+ if (unit < 0) return 0;
+
+ printk("\nEthernet driver name %s unit %d \n",name, unit);
+ printk("RTEMS-mvme5500 BSP Copyright (c) 2004, Brookhaven National Lab., Shuchen Kate Feng \n");
+ /* Make certain elements e.g. descriptor lists are aligned. */
+ softc_mem = rtems_bsdnet_malloc(sizeof(*sc) + SOFTC_ALIGN, M_FREE, M_NOWAIT);
+
+ /* Check for the very unlikely case of no memory. */
+ if (softc_mem == NULL)
+ printk("GT64260eth: OUT OF MEMORY");
+
+ sc = (void *)(((long)softc_mem + SOFTC_ALIGN) & ~SOFTC_ALIGN);
+ memset(sc, 0, sizeof(*sc));
+
+ if (GTeth_debug>0) printk("txq_desc[0] addr:%x, rxq_desc[0] addr:%x, sizeof sc %d\n",&sc->txq_desc[0], &sc->rxq_desc[0], sizeof(*sc));
+
+ sc->sc_macno = unit-1;
+
+ data = inl(ETH_EPAR);
+ phyaddr = ETH_EPAR_PhyAD_GET(data, sc->sc_macno);
+
+ /* try to read HW address from the device if not overridden
+ * by config
+ */
+ if (config->hardware_address) {
+ memcpy(hwaddr, config->hardware_address, ETHER_ADDR_LEN);
+ } else {
+ printk("Read EEPROM ");
+ for (i = 0; i < 6; i++)
+ hwaddr[i] = ReadConfVPD_buff(VPD_ENET0_OFFSET+i);
+ }
+
+#ifdef GT_DEBUG
+ printk("using MAC addr from device:");
+ for (i = 0; i < ETHER_ADDR_LEN; i++) printk("%x:", hwaddr[i]);
+ printk("\n");
+#endif
+
+ memcpy(sc->arpcom.ac_enaddr, hwaddr, ETHER_ADDR_LEN);
+
+ ifp = &sc->arpcom.ac_if;
+
+ sc->sc_pcr = inl(ETH0_EPCR);
+ sc->sc_pcxr = inl(ETH0_EPCXR);
+ sc->sc_intrmask = inl(ETH0_EIMR) | ETH_IR_MIIPhySTC;
+
+ printk("address %s\n", ether_sprintf(hwaddr));
+
+#ifdef GT_DEBUG
+ printk(", pcr %x, pcxr %x ", sc->sc_pcr, sc->sc_pcxr);
+#endif
+
+
+ sc->sc_pcxr |= ETH_EPCXR_PRIOrx_Override;
+ sc->sc_pcxr |= (3<<6); /* highest priority only */
+ sc->sc_pcxr &= ~ETH_EPCXR_RMIIEn; /* MII mode */
+
+ /* Max. Frame Length (packet) allowed for reception is 1536 bytes,
+ * instead of 2048 (MOTLoad default) or 64K.
+ */
+ sc->sc_pcxr &= ~(3 << 14);
+ sc->sc_pcxr |= (ETH_EPCXR_MFL_1536 << 14);
+ sc->sc_max_frame_length = PKT_BUF_SZ;
+
+
+ if (sc->sc_pcr & ETH_EPCR_EN) {
+ int tries = 1000;
+ /* Abort transmitter and receiver and wait for them to quiese*/
+ outl(ETH_ESDCMR_AR|ETH_ESDCMR_AT,ETH0_ESDCMR);
+ do {
+ rtems_bsp_delay(100);
+ } while (tries-- > 0 && (inl(ETH0_ESDCMR) & (ETH_ESDCMR_AR|ETH_ESDCMR_AT)));
+ }
+#ifdef GT_DEBUG
+ printk(", phy %d (mii)\n", phyaddr);
+ printk("ETH0_ESDCMR %x ", inl(ETH0_ESDCMR));
+#endif
+
+ sc->sc_pcr &= ~(ETH_EPCR_EN | ETH_EPCR_RBM | ETH_EPCR_PM | ETH_EPCR_PBF);
+
+#ifdef GT_DEBUG
+ printk("Now sc_pcr %x,sc_pcxr %x", sc->sc_pcr, sc->sc_pcxr);
+#endif
+
+ /*
+ * Now turn off the GT. If it didn't quiese, too ***ing bad.
+ */
+ outl(sc->sc_pcr, ETH0_EPCR);
+ outl(sc->sc_intrmask, ETH0_EIMR);
+ sdcr = inl(ETH0_ESDCR);
+ /* Burst size is limited to 4 64bit words */
+ ETH_ESDCR_BSZ_SET(sdcr, ETH_ESDCR_BSZ_4);
+ sdcr |= ETH_ESDCR_RIFB;/*limit interrupt on frame boundaries, instead of buffer*/
+#if 0
+ sdcr &= ~(ETH_ESDCR_BLMT|ETH_ESDCR_BLMR); /* MOTLoad defualt Big-endian */
+#endif
+ outl(sdcr, ETH0_ESDCR);
+
+#ifdef GT_DEBUG
+ printk("sdcr %x \n", sdcr);
+#endif
+
+ if (phyaddr== -1) printk("MII auto negotiation ?");
+
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+
+ ifp->if_softc = sc;
+
+ /* set this interface's name and unit */
+ ifp->if_unit = unit;
+ ifp->if_name = name;
+
+ ifp->if_mtu = config->mtu ? config->mtu : ETHERMTU;
+
+ ifp->if_init = GT64260eth_ifinit;
+ ifp->if_ioctl = GTeth_ifioctl;
+ ifp->if_start = GTeth_ifstart;
+ ifp->if_output = ether_output;
+
+ /* ifp->if_watchdog = GTeth_ifwatchdog;*/
+
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /* create the synchronization semaphore */
+ if (RTEMS_SUCCESSFUL != rtems_semaphore_create(
+ rtems_build_name('G','e','t','h'),0,0,0,&sc->daemonSync))
+ printk("GT64260eth: semaphore creation failed");
+
+ sc->next_module = root_GT64260eth_dev;
+ root_GT64260eth_dev = sc;
+
+ /* Actually attach the interface */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+#ifdef GT_DEBUG
+ printk("GT64260eth: Ethernet driver has been attached (handle 0x%08x,ifp 0x%08x)\n",sc, ifp);
+#endif
+
+ return(1);
+}
+
+static void GT64260eth_stats(struct GTeth_softc *sc)
+{
+#if 0
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ printf(" Rx Interrupts:%-8lu\n", sc->stats.rxInterrupts);
+ printf(" Receive Packets:%-8lu\n", ifp->if_ipackets);
+ printf(" Receive errors:%-8lu\n", ifp->if_ierrors);
+ printf(" Framing Errors:%-8lu\n", sc->stats.frame_errors);
+ printf(" Crc Errors:%-8lu\n", sc->stats.crc_errors);
+ printf(" Oversized Frames:%-8lu\n", sc->stats.length_errors);
+ printf(" Active Rxqs:%-8u\n", sc->rxq_active);
+ printf(" Tx Interrupts:%-8lu\n", sc->stats.txInterrupts);
+#endif
+ printf("Multi-BuffTx Packets:%-8lu\n", sc->stats.txMultiBuffPacket);
+ printf("Multi-BuffTx max len:%-8lu\n", sc->stats.txMultiMaxLen);
+ printf("SingleBuffTx max len:%-8lu\n", sc->stats.txSinglMaxLen);
+ printf("Multi-BuffTx maxloop:%-8lu\n", sc->stats.txMultiMaxLoop);
+ printf("Tx buffer max len :%-8lu\n", sc->stats.txBuffMaxLen);
+#if 0
+ printf(" Transmitt Packets:%-8lu\n", ifp->if_opackets);
+ printf(" Transmitt errors:%-8lu\n", ifp->if_oerrors);
+ printf(" Tx/Rx collisions:%-8lu\n", ifp->if_collisions);
+ printf(" Active Txqs:%-8u\n", sc->txq_nactive);
+#endif
+}
+
+void GT64260eth_printStats(void)
+{
+ GT64260eth_stats(root_GT64260eth_dev);
+}
+
+static int GTeth_ifioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data)
+{
+ struct GTeth_softc *sc = ifp->if_softc;
+ struct ifreq *ifr = (struct ifreq *) data;
+
+ int error = 0;
+
+#ifdef GT_DEBUG
+ printk("GTeth_ifioctl(");
+#endif
+
+ switch (cmd) {
+ default:
+ if (GTeth_debug >0) {
+ printk("etherioctl(");
+ if (cmd== SIOCSIFADDR) printk("SIOCSIFADDR ");
+ }
+ return ether_ioctl(ifp, cmd, data);
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP|IFF_RUNNING)) {
+ case IFF_RUNNING: /* not up, so we stop */
+ GT64260eth_stop(sc);
+ break;
+ case IFF_UP: /* not running, so we start */
+ GT64260eth_ifinit(sc);
+ break;
+ case IFF_UP|IFF_RUNNING:/* active->active, update */
+ GT64260eth_stop(sc);
+ GT64260eth_ifinit(sc);
+ break;
+ default: /* idle->idle: do nothing */
+ break;
+ }
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ GT64260eth_stats (sc);
+ break;
+ case SIOCADDMULTI:
+ case SIOCDELMULTI:
+ error = (cmd == SIOCADDMULTI)
+ ? ether_addmulti(ifr, &sc->arpcom)
+ : ether_delmulti(ifr, &sc->arpcom);
+ if (error == ENETRESET) {
+ if (ifp->if_flags & IFF_RUNNING)
+ GTeth_ifchange(sc);
+ else
+ error = 0;
+ }
+ break;
+ case SIOCSIFMTU:
+ if (ifr->ifr_mtu > ETHERMTU || ifr->ifr_mtu < ETHERMIN) {
+ error = EINVAL;
+ break;
+ }
+ ifp->if_mtu = ifr->ifr_mtu;
+ break;
+ }
+
+#ifdef GT_DEBUG
+ printk("exit ioctl\n");
+#endif
+ return error;
+}
+
+static void GTeth_ifstart(struct ifnet *ifp)
+{
+ struct GTeth_softc *sc = ifp->if_softc;
+
+#ifdef GT_DEBUG
+ printk("GTeth_ifstart(");
+#endif
+
+ if ((ifp->if_flags & IFF_RUNNING) == 0) {
+#ifdef GT_DEBUG
+ printk("IFF_RUNNING==0\n");
+#endif
+ return;
+ }
+
+ ifp->if_flags |= IFF_OACTIVE;
+ rtems_bsdnet_event_send (sc->daemonTid, START_TRANSMIT_EVENT);
+#ifdef GT_DEBUG
+ printk(")\n");
+#endif
+}
+
+/* Initialize the Rx rings */
+static void GTeth_init_rx_ring(struct GTeth_softc *sc)
+{
+ int i;
+ volatile struct GTeth_desc *rxd;
+ unsigned nxtaddr;
+
+ sc->rxq_fi=0;
+ sc->rxq_head_desc = &sc->rxq_desc[0];
+ rxd = sc->rxq_head_desc;
+
+ sc->rxq_desc_busaddr = (unsigned long) sc->rxq_head_desc;
+#ifdef GT_DEBUG
+ printk("rxq_desc_busaddr %x ,&sc->rxq_desc[0] %x\n",
+ sc->rxq_desc_busaddr, sc->rxq_head_desc);
+#endif
+
+ nxtaddr = sc->rxq_desc_busaddr + sizeof(*rxd);
+ sc->rx_buf_sz = (sc->arpcom.ac_if.if_mtu <= 1500 ? PKT_BUF_SZ : sc->arpcom.ac_if.if_mtu + 32);
+ sc->rxq_active = RX_RING_SIZE;
+
+ for (i = 0; i < RX_RING_SIZE; i++, rxd++, nxtaddr += sizeof(*rxd)) {
+ struct mbuf *m;
+
+ rxd->ed_lencnt= sc->rx_buf_sz <<16;
+ rxd->ed_cmdsts = RX_CMD_F|RX_CMD_L|RX_CMD_O|RX_CMD_EI;
+
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+ m->m_pkthdr.rcvif = &sc->arpcom.ac_if;
+ sc->rxq_mbuf[i] = m;
+
+ /* convert mbuf pointer to data pointer of correct type */
+ rxd->ed_bufptr = (unsigned) mtod(m, void *);
+
+ /*
+ * update the nxtptr to point to the next txd.
+ */
+ if (i == RX_RING_SIZE - 1)
+ nxtaddr = sc->rxq_desc_busaddr;
+ rxd->ed_nxtptr = nxtaddr;
+
+#ifdef GT_DEBUG
+ printk("ed_lencnt %x, rx_buf_sz %x ",rxd->ed_lencnt, sc->rx_buf_sz);
+ printk("ed_cmdsts %x \n",rxd->ed_cmdsts);
+ printk("mbuf @ 0x%x, next desc. @ 0x%x\n",rxd->ed_bufptr,rxd->ed_nxtptr);
+#endif
+ }
+}
+
+void GTeth_rxprio_setup(struct GTeth_softc *sc)
+{
+
+ GTeth_init_rx_ring(sc);
+
+ sc->rxq_intrbits = ETH_IR_RxBuffer|ETH_IR_RxError|ETH_IR_RxBuffer_3|ETH_IR_RxError_3;
+}
+
+static int GT64260eth_rx(struct GTeth_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ int nloops=0;
+
+#ifdef GT_DEBUG
+ if (GTeth_rx_debug>0) printk("GT64260eth_rx(");
+#endif
+
+ while (sc->rxq_active > 0) {
+ volatile struct GTeth_desc *rxd = &sc->rxq_desc[sc->rxq_fi];
+ struct ether_header *eh;
+ unsigned int cmdsts;
+ unsigned int byteCount;
+
+ cmdsts = rxd->ed_cmdsts;
+
+ /*
+ * Sometimes the GE "forgets" to reset the ownership bit.
+ * But if the length has been rewritten, the packet is ours
+ * so pretend the O bit is set.
+ *
+ */
+ byteCount = rxd->ed_lencnt & 0xffff;
+
+ if (cmdsts & RX_CMD_O) {
+ if (byteCount == 0)
+ return(0);
+
+ /* <Kate Feng> Setting command/status to be zero seems to eliminate
+ * the spurious interrupt associated with the GE_FORGOT issue.
+ */
+ rxd->ed_cmdsts=0;
+
+#ifdef GE_FORGOT
+ /*
+ * For dignosis purpose only. Not a good practice to turn it on
+ */
+ printk("Rxq %d %d %d\n", sc->rxq_fi, byteCount,nloops);
+#endif
+ }
+
+ /* GT gave the ownership back to the CPU or the length has
+ * been rewritten , which means there
+ * is new packet in the descriptor/buffer
+ */
+
+ nloops++;
+ /*
+ * If this is not a single buffer packet with no errors
+ * or for some reason it's bigger than our frame size,
+ * ignore it and go to the next packet.
+ */
+ if ((cmdsts & (RX_CMD_F|RX_CMD_L|RX_STS_ES)) !=
+ (RX_CMD_F|RX_CMD_L) ||
+ byteCount > sc->sc_max_frame_length) {
+ --sc->rxq_active;
+ ifp->if_ipackets++;
+ ifp->if_ierrors++;
+ if (cmdsts & RX_STS_OR) sc->stats.or_errors++;
+ if (cmdsts & RX_STS_CE) sc->stats.crc_errors++;
+ if (cmdsts & RX_STS_MFL) sc->stats.length_errors++;
+ if (cmdsts & RX_STS_SF) sc->stats.frame_errors++;
+ if ((cmdsts & RX_STS_LC) || (cmdsts & RX_STS_COL))
+ ifp->if_collisions++;
+ /* recycle the buffer */
+ m->m_len=sc->rx_buf_sz;
+ }
+ else {
+ m = sc->rxq_mbuf[sc->rxq_fi];
+ m->m_len = m->m_pkthdr.len = byteCount - sizeof(struct ether_header);
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ ifp->if_ipackets++;
+ ifp->if_ibytes+=byteCount;
+ --sc->rxq_active;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ }
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxq_mbuf[sc->rxq_fi]= m;
+ /* convert mbuf pointer to data pointer of correct type */
+ rxd->ed_bufptr = (unsigned) mtod(m, void*);
+ rxd->ed_lencnt = (unsigned long) sc->rx_buf_sz <<16;
+ rxd->ed_cmdsts = RX_CMD_F|RX_CMD_L|RX_CMD_O|RX_CMD_EI;
+
+ if (++sc->rxq_fi == RX_RING_SIZE) sc->rxq_fi = 0;
+
+ sc->rxq_active++;
+ } /* while (sc->rxq_active > 0) */
+#ifdef GT_DEBUG
+ if (GTeth_rx_debug>0) printk(")");
+#endif
+ return nloops;
+}
+
+static void GTeth_rx_setup(struct GTeth_softc *sc)
+{
+
+ if (GTeth_rx_debug>0) printk("GTeth_rx_setup(");
+
+ GTeth_rxprio_setup(sc);
+
+ if ((sc->sc_flags & GE_RXACTIVE) == 0) {
+ /* First Rx Descriptor Pointer 3 */
+ outl( sc->rxq_desc_busaddr, ETH0_EFRDP3);
+ /* Current Rx Descriptor Pointer 3 */
+ outl( sc->rxq_desc_busaddr,ETH0_ECRDP3);
+#ifdef GT_DEBUG
+ printk("ETH0_EFRDP3 0x%x, ETH0_ECRDP3 0x%x \n", inl(ETH0_EFRDP3),
+ inl(ETH0_ECRDP3));
+#endif
+ }
+ sc->sc_intrmask |= sc->rxq_intrbits;
+
+ if (GTeth_rx_debug>0) printk(")\n");
+}
+
+static void GTeth_rx_cleanup(struct GTeth_softc *sc)
+{
+ int i;
+
+ if (GTeth_rx_debug>0) printk( "GTeth_rx_cleanup(");
+
+ for (i=0; i< RX_RING_SIZE; i++) {
+ if (sc->rxq_mbuf[i]) {
+ m_freem(sc->rxq_mbuf[i]);
+ sc->rxq_mbuf[i]=0;
+ }
+ }
+ if (GTeth_rx_debug>0) printk(")");
+}
+
+static void GTeth_rx_stop(struct GTeth_softc *sc)
+{
+ if (GTeth_rx_debug>0) printk( "GTeth_rx_stop(");
+ sc->sc_flags &= ~GE_RXACTIVE;
+ sc->sc_idlemask &= ~(ETH_IR_RxBits|ETH_IR_RxBuffer_3|ETH_IR_RxError_3);
+ sc->sc_intrmask &= ~(ETH_IR_RxBits|ETH_IR_RxBuffer_3|ETH_IR_RxError_3);
+ outl(sc->sc_intrmask, ETH0_EIMR);
+ outl(ETH_ESDCMR_AR, ETH0_ESDCMR); /* abort receive */
+ do {
+ rtems_bsp_delay(10);
+ } while (inl(ETH0_ESDCMR) & ETH_ESDCMR_AR);
+ GTeth_rx_cleanup(sc);
+ if (GTeth_rx_debug>0) printk(")");
+}
+
+static void GTeth_txq_free(struct GTeth_softc *sc, unsigned cmdsts)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ volatile struct GTeth_desc *txd = &sc->txq_desc[sc->txq_fi];
+
+ /* ownership is sent back to CPU */
+ if (GTeth_debug>0) printk("txq%d,active %d\n", sc->txq_fi, sc->txq_nactive);
+
+ txd->ed_cmdsts &= ~TX_CMD_O; /* <skf> in case GT forgot */
+
+ /* statistics */
+ ifp->if_opackets++;
+ ifp->if_obytes += sc->txq_mbuf[sc->txq_fi]->m_len;
+ if (cmdsts & TX_STS_ES) {
+ ifp->if_oerrors++;
+ if ((cmdsts & TX_STS_LC) || (cmdsts & TX_STS_COL))
+ ifp->if_collisions++;
+ }
+ /* Free the original mbuf chain */
+ m_freem(sc->txq_mbuf[sc->txq_fi]);
+ sc->txq_mbuf[sc->txq_fi] = 0;
+ ifp->if_timer = 5;
+
+ sc->txq_free++;
+ if (++sc->txq_fi == TX_RING_SIZE) sc->txq_fi = 0;
+ --sc->txq_nactive;
+}
+
+#if UNUSED
+static int txq_high_limit(struct GTeth_softc *sc)
+{
+ /*
+ * Have we [over]consumed our limit of descriptors?
+ * Do we have enough free descriptors?
+ */
+ if ( TX_RING_SIZE == sc->txq_nactive + TXQ_HiLmt_OFF) {
+ volatile struct GTeth_desc *txd2 = &sc->txq_desc[sc->txq_fi];
+ unsigned cmdsts;
+
+ cmdsts = txd2->ed_cmdsts;
+ if (cmdsts & TX_CMD_O) { /* Ownership (1=GT 0=CPU) */
+ int nextin;
+
+ /*
+ * Sometime the Discovery forgets to update the
+ * last descriptor. See if CPU owned the descriptor
+ * after it (since we know we've turned that to
+ * the discovery and if CPU owned it, the Discovery
+ * gave it back). If CPU does, we know the Discovery
+ * gave back this one but forgot to mark it back to CPU.
+ */
+ nextin = (sc->txq_fi + 1) % TX_RING_SIZE;
+ if (sc->txq_desc[nextin].ed_cmdsts & TX_CMD_O) {
+#if 0
+ printk("Overconsuming Tx descriptors!\n");
+#endif
+ return 1;
+ }
+ printk("Txq %d forgot\n", sc->txq_fi);
+ }
+ /* Txq ring is almost full, let's free the current buffer here */
+#if 0
+ printk("Txq ring near full, free desc%d\n",sc->txq_fi);
+#endif
+ GTeth_txq_free(sc, cmdsts);
+ } /* end if ( TX_RING_SIZE == sc->txq_nactive + TXQ_HiLmt_OFF) */
+ return 0;
+}
+#endif
+
+static int GT64260eth_sendpacket(struct GTeth_softc *sc,struct mbuf *m)
+{
+ volatile struct GTeth_desc *txd = &sc->txq_desc[sc->txq_lo];
+ unsigned intrmask = sc->sc_intrmask;
+ unsigned loop=0, index= sc->txq_lo;
+
+ /*
+ * The end-of-list descriptor we put on last time is the starting point
+ * for this packet. The GT is supposed to terminate list processing on
+ * a NULL nxtptr but that currently is broken so a CPU-owned descriptor
+ * must terminate the list.
+ */
+ intrmask = sc->sc_intrmask;
+
+ if ( !(m->m_next)) {/* single buffer packet */
+ sc->txq_mbuf[index]= m;
+ sc->stats.txSinglMaxLen= MAX(m->m_len, sc->stats.txSinglMaxLen);
+ }
+ else /* multiple mbufs in this packet */
+ {
+ struct mbuf *mtp, *mdest;
+ volatile unsigned char *pt;
+ int len, y;
+
+#ifdef GT_DEBUG
+ printk("multi mbufs ");
+#endif
+ MGETHDR(mdest, M_WAIT, MT_DATA);
+ MCLGET(mdest, M_WAIT);
+ pt = (volatile unsigned char *)mdest->m_data;
+ for (mtp=m,len=0;mtp;mtp=mtp->m_next) {
+ loop++;
+ if ( (y=(len+mtp->m_len)) > sizeof(union mcluster)) {
+ /* GT64260 allows us to chain the remaining to the next
+ * free descriptors.
+ */
+ printk("packet size %x > mcluster %x\n", y,sizeof(union mcluster));
+ printk("GT64260eth : packet too large ");
+ }
+ memcpy((void *)pt,(char *)mtp->m_data, mtp->m_len);
+ pt += mtp->m_len;
+#if 0
+ printk("%d ",mtp->m_len);
+#endif
+ len += mtp->m_len;
+ sc->stats.txBuffMaxLen=MAX(mtp->m_len,sc->stats.txBuffMaxLen);
+ }
+ sc->stats.txMultiMaxLoop=MAX(loop, sc->stats.txMultiMaxLoop);
+#if 0
+ printk("\n");
+#endif
+ mdest->m_len=len;
+ /* free old mbuf chain */
+ m_freem(m);
+ sc->txq_mbuf[index] = m = mdest;
+ sc->stats.txMultiBuffPacket++;
+ sc->stats.txMultiMaxLen= MAX(m->m_len, sc->stats.txMultiMaxLen);
+ }
+ if (m->m_len < ET_MINLEN) m->m_len = ET_MINLEN;
+
+ txd->ed_bufptr = (unsigned) mtod(m, void*);
+ txd->ed_lencnt = m->m_len << 16;
+ /*txd->ed_cmdsts = TX_CMD_L|TX_CMD_GC|TX_CMD_P|TX_CMD_O|TX_CMD_F|TX_CMD_EI;*/
+ txd->ed_cmdsts = 0x80c70000;
+ while (txd->ed_cmdsts != 0x80c70000);
+ memBar();
+
+#ifdef GT_DEBUG
+ printk("len = %d, cmdsts 0x%x ", m->m_len,txd->ed_cmdsts);
+#endif
+
+ /*
+ * Tell the SDMA engine to "Fetch!"
+ * Start Tx high.
+ */
+ sc->txq_nactive++;
+ outl(0x800080, ETH0_ESDCMR); /* ETH_ESDCMR_TXDH| ETH_ESDCMR_ERD */
+ if ( ++sc->txq_lo == TX_RING_SIZE) sc->txq_lo = 0;
+ sc->txq_free--;
+
+#if 0
+ /*
+ * Since we have put an item into the packet queue, we now want
+ * an interrupt when the transmit queue finishes processing the
+ * list. But only update the mask if needs changing.
+ */
+ intrmask |= sc->txq_intrbits & ( ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh);
+ if (sc->sc_intrmask != intrmask) {
+ sc->sc_intrmask = intrmask;
+ outl(sc->sc_intrmask, ETH0_EIMR);
+ }
+#endif
+
+#if 0
+ printk("EICR= %x, EIMR= %x ", inl(ETH0_EICR), inl(ETH0_EIMR));
+ printk("%s:transmit frame #%d queued in slot %d.\n",
+ sc->arpcom.ac_if.if_name, sc->txq_lo, index);
+ printk("pcr %x, pcxr %x DMA dcr %x cmr %x\n", inl(ETH0_EPCR), inl(ETH0_EPCXR), inl(ETH0_ESDCR), inl(ETH0_ESDCMR));
+#endif
+
+ return 1;
+}
+
+static unsigned GTeth_txq_done(struct GTeth_softc *sc)
+{
+ if (GTeth_debug>0) printk("Txdone(" );
+
+ while (sc->txq_nactive > 0) {
+ /* next to be returned to the CPU */
+ volatile struct GTeth_desc *txd = &sc->txq_desc[sc->txq_fi];
+ unsigned cmdsts;
+
+ /* if GT64260 still owns it ....... */
+ if ((cmdsts = txd->ed_cmdsts) & TX_CMD_O) {
+ int nextin;
+
+ /* Someone quoted :
+ * "Sometimes the Discovery forgets to update the
+ * ownership bit in the descriptor."
+ * <skf> More correctly, the last descriptor of each
+ * transmitted frame is returned to CPU ownership and
+ * status is updated only after the actual transmission
+ * of the packet is completed. Also, if there is an error
+ * during transmission, we want to continue the
+ * transmission of the next descriptor, in additions to
+ * reporting the error.
+ */
+ /* The last descriptor */
+ if (sc->txq_nactive == 1) return(0);
+
+ /*
+ * Sometimes the Discovery forgets to update the
+ * ownership bit in the descriptor. See if CPU owned
+ * the descriptor after it (since we know we've turned
+ * that to the Discovery and if CPU owned it now then the
+ * Discovery gave it back). If we do, we know the
+ * Discovery gave back this one but forgot to mark it
+ * back to CPU.
+ */
+ nextin = (sc->txq_fi + 1) % TX_RING_SIZE;
+
+ if (sc->txq_desc[nextin].ed_cmdsts & TX_CMD_O) return(0);
+ printk("Txq%d forgot\n",sc->txq_fi);
+ } /* end checking GT64260eth owner */
+ GTeth_txq_free(sc, cmdsts);
+ } /* end while */
+ if (GTeth_debug>0) printk(")\n");
+ return(1);
+}
+
+static void GTeth_tx_start(struct GTeth_softc *sc)
+{
+ int i;
+ volatile struct GTeth_desc *txd;
+ unsigned nxtaddr;
+
+#ifdef GT_DEBUG
+ printk("GTeth_tx_start(");
+#endif
+ sc->sc_intrmask &= ~(ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh|
+ ETH_IR_TxEndLow |ETH_IR_TxBufferLow);
+
+ txd = &sc->txq_desc[0];
+ sc->txq_desc_busaddr = (unsigned long) &sc->txq_desc[0];
+#ifdef GT_DEBUG
+ printk("txq_desc_busaddr %x, &sc->txq_desc[0] %x \n",
+ sc->txq_desc_busaddr,&sc->txq_desc[0]);
+#endif
+
+ nxtaddr = sc->txq_desc_busaddr + sizeof(*txd);
+
+ sc->txq_pendq.ifq_maxlen = 10;
+ sc->txq_pendq.ifq_head= NULL;
+ sc->txq_pendq.ifq_tail= NULL;
+ sc->txq_nactive = 0;
+ sc->txq_fi = 0;
+ sc->txq_lo = 0;
+ sc->txq_inptr = PKT_BUF_SZ;
+ sc->txq_outptr = 0;
+ sc->txq_free = TX_RING_SIZE;
+
+ for (i = 0; i < TX_RING_SIZE;
+ i++, txd++, nxtaddr += sizeof(*txd)) {
+ sc->txq_mbuf[i]=0;
+ txd->ed_bufptr = 0;
+
+ /*
+ * update the nxtptr to point to the next txd.
+ */
+ txd->ed_cmdsts = 0;
+ if ( i== TX_RING_SIZE-1) nxtaddr = sc->txq_desc_busaddr;
+ txd->ed_nxtptr = nxtaddr;
+#ifdef GT_DEBUG
+ printk("next desc. @ 0x%x\n",txd->ed_nxtptr);
+#endif
+ }
+
+ sc->txq_intrbits = ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh;
+ sc->txq_esdcmrbits = ETH_ESDCMR_TXDH; /* Start Tx high */
+ sc->txq_epsrbits = ETH_EPSR_TxHigh;
+ /* offset to current tx desc ptr reg */
+ sc->txq_ectdp = (caddr_t)ETH0_ECTDP1;
+ /* Current Tx Desc Pointer 1 */
+ outl(sc->txq_desc_busaddr,ETH0_ECTDP1);
+
+#ifdef GT_DEBUG
+ printk(")\n");
+#endif
+}
+
+static void GTeth_tx_cleanup(struct GTeth_softc *sc)
+{
+ int i;
+
+ for (i=0; i< TX_RING_SIZE; i++) {
+ if (sc->txq_mbuf[i]) {
+ m_freem(sc->txq_mbuf[i]);
+ sc->txq_mbuf[i]=0;
+ }
+ }
+}
+
+static void GTeth_tx_stop(struct GTeth_softc *sc)
+{
+ /* SDMA command register : stop Tx high and low */
+ outl(ETH_ESDCMR_STDH|ETH_ESDCMR_STDL, ETH0_ESDCMR);
+
+ GTeth_txq_done(sc);
+ sc->sc_intrmask &= ~(ETH_IR_TxEndHigh|ETH_IR_TxBufferHigh|
+ ETH_IR_TxEndLow |ETH_IR_TxBufferLow);
+ GTeth_tx_cleanup(sc);
+
+ sc->arpcom.ac_if.if_timer = 0;
+}
+
+static void GTeth_ifchange(struct GTeth_softc *sc)
+{
+ if (GTeth_debug>0) printk("GTeth_ifchange(");
+ if (GTeth_debug>5) printk("(pcr=%#x,imr=%#x)",inl(ETH0_EPCR),inl(ETH0_EIMR));
+ /* printk("SIOCADDMULTI (SIOCDELMULTI): is it about rx or tx ?\n");*/
+ outl(sc->sc_pcr | ETH_EPCR_EN, ETH0_EPCR);
+ outl(sc->sc_intrmask, ETH0_EIMR);
+ GTeth_ifstart(&sc->arpcom.ac_if);
+ /* Current Tx Desc Pointer 0 and 1 */
+ if (GTeth_debug>5) printk("(ectdp0=%#x, ectdp1=%#x)",
+ inl(ETH0_ECTDP0), inl(ETH0_ECTDP1));
+ if (GTeth_debug>0) printk(")");
+}
+
+static int GTeth_hash_compute(struct GTeth_softc *sc,unsigned char eaddr[ETHER_ADDR_LEN])
+{
+ unsigned w0, add0, add1;
+ unsigned result;
+
+ if (GTeth_debug>0) printk("GTeth_hash_compute(");
+ add0 = ((unsigned) eaddr[5] << 0) |
+ ((unsigned) eaddr[4] << 8) |
+ ((unsigned) eaddr[3] << 16);
+
+ add0 = ((add0 & 0x00f0f0f0) >> 4) | ((add0 & 0x000f0f0f) << 4);
+ add0 = ((add0 & 0x00cccccc) >> 2) | ((add0 & 0x00333333) << 2);
+ add0 = ((add0 & 0x00aaaaaa) >> 1) | ((add0 & 0x00555555) << 1);
+
+ add1 = ((unsigned) eaddr[2] << 0) |
+ ((unsigned) eaddr[1] << 8) |
+ ((unsigned) eaddr[0] << 16);
+
+ add1 = ((add1 & 0x00f0f0f0) >> 4) | ((add1 & 0x000f0f0f) << 4);
+ add1 = ((add1 & 0x00cccccc) >> 2) | ((add1 & 0x00333333) << 2);
+ add1 = ((add1 & 0x00aaaaaa) >> 1) | ((add1 & 0x00555555) << 1);
+
+#ifdef GT_DEBUG
+ printk("eaddr= %s add1:%x add0:%x\n", ether_sprintf1(eaddr), add1, add0);
+#endif
+
+ /*
+ * hashResult is the 15 bits Hash entry address.
+ * ethernetADD is a 48 bit number, which is derived from the Ethernet
+ * MAC address, by nibble swapping in every byte (i.e MAC address
+ * of 0x123456789abc translates to ethernetADD of 0x21436587a9cb).
+ */
+ if ((sc->sc_pcr & ETH_EPCR_HM) == 0) {
+ /*
+ * hashResult[14:0] = hashFunc0(ethernetADD[47:0])
+ *
+ * hashFunc0 calculates the hashResult in the following manner:
+ * hashResult[ 8:0] = ethernetADD[14:8,1,0]
+ * XOR ethernetADD[23:15] XOR ethernetADD[32:24]
+ */
+ result = (add0 & 3) | ((add0 >> 6) & ~3);
+ result ^= (add0 >> 15) ^ (add1 >> 0);
+ result &= 0x1ff;
+ /*
+ * hashResult[14:9] = ethernetADD[7:2]
+ */
+ result |= (add0 & ~3) << 7; /* excess bits will be masked */
+#ifdef GT_DEBUG
+ printk("hash result %x ", result & 0x7fff);
+#endif
+ } else {
+#define TRIBITFLIP 073516240 /* yes its in octal */
+ /*
+ * hashResult[14:0] = hashFunc1(ethernetADD[47:0])
+ *
+ * hashFunc1 calculates the hashResult in the following manner:
+ * hashResult[08:00] = ethernetADD[06:14]
+ * XOR ethernetADD[15:23] XOR ethernetADD[24:32]
+ */
+ w0 = ((add0 >> 6) ^ (add0 >> 15) ^ (add1)) & 0x1ff;
+ /*
+ * Now bitswap those 9 bits
+ */
+ result = 0;
+ result |= ((TRIBITFLIP >> (((w0 >> 0) & 7) * 3)) & 7) << 6;
+ result |= ((TRIBITFLIP >> (((w0 >> 3) & 7) * 3)) & 7) << 3;
+ result |= ((TRIBITFLIP >> (((w0 >> 6) & 7) * 3)) & 7) << 0;
+
+ /*
+ * hashResult[14:09] = ethernetADD[00:05]
+ */
+ result |= ((TRIBITFLIP >> (((add0 >> 0) & 7) * 3)) & 7) << 12;
+ result |= ((TRIBITFLIP >> (((add0 >> 3) & 7) * 3)) & 7) << 9;
+#ifdef GT_DEBUG
+ printk("1(%#x)", result);
+#endif
+ }
+#ifdef GT_DEBUG
+ printk(")");
+#endif
+
+ /* 1/2K address filtering (MOTLoad default )? ->16KB memory required
+ * or 8k address filtering ? -> 256KB memory required
+ */
+ return result & ((sc->sc_pcr & ETH_EPCR_HS_512) ? 0x7ff : 0x7fff);
+}
+
+static int GTeth_hash_entry_op(struct GTeth_softc *sc, enum GTeth_hash_op op,
+ enum GTeth_rxprio prio,unsigned char eaddr[ETHER_ADDR_LEN])
+{
+ unsigned long long he;
+ unsigned long long *maybe_he_p = NULL;
+ int limit;
+ int hash;
+ int maybe_hash = 0;
+
+#ifdef GT_DEBUG
+ printk("GTeth_hash_entry_op(prio %d ", prio);
+#endif
+
+ hash = GTeth_hash_compute(sc, eaddr);
+
+ if (sc->sc_hashtable == NULL) {
+ printk("hashtable == NULL!");
+ }
+#ifdef GT_DEBUG
+ printk("Hash computed %x eaddr %s\n", hash,ether_sprintf1(eaddr));
+#endif
+
+ /*
+ * Assume we are going to insert so create the hash entry we
+ * are going to insert. We also use it to match entries we
+ * will be removing. The datasheet is wrong for this.
+ */
+ he = (((unsigned long long) eaddr[5]) << 43) |
+ (((unsigned long long) eaddr[4]) << 35) |
+ (((unsigned long long) eaddr[3]) << 27) |
+ (((unsigned long long) eaddr[2]) << 19) |
+ (((unsigned long long) eaddr[1]) << 11) |
+ (((unsigned long long) eaddr[0]) << 3) |
+ ((unsigned long long) HSH_PRIO_INS(prio) | HSH_V | HSH_R);
+ /* he = 0x1b1acd87d08005;*/
+ /*
+ * The GT will search upto 12 entries for a hit, so we must mimic that.
+ */
+ hash &= (sc->sc_hashmask / sizeof(he));
+
+#ifdef GT_DEBUG
+ if (GTeth_debug>0) {
+ unsigned val1, val2;
+
+ val1= he & 0xffffffff;
+ val2= (he >>32) & 0xffffffff;
+ printk("Hash addr value %x%x, entry %x\n",val2,val1, hash);
+ }
+#endif
+
+ for (limit = HSH_LIMIT; limit > 0 ; --limit) {
+ /*
+ * Does the GT wrap at the end, stop at the, or overrun the
+ * end? Assume it wraps for now. Stash a copy of the
+ * current hash entry.
+ */
+ unsigned long long *he_p = &sc->sc_hashtable[hash];
+ unsigned long long thishe = *he_p;
+
+ /*
+ * If the hash entry isn't valid, that break the chain. And
+ * this entry a good candidate for reuse.
+ */
+ if ((thishe & HSH_V) == 0) {
+ maybe_he_p = he_p;
+ break;
+ }
+
+ /*
+ * If the hash entry has the same address we are looking for
+ * then ... if we are removing and the skip bit is set, its
+ * already been removed. if are adding and the skip bit is
+ * clear, then its already added. In either return EBUSY
+ * indicating the op has already been done. Otherwise flip
+ * the skip bit and return 0.
+ */
+ if (((he ^ thishe) & HSH_ADDR_MASK) == 0) {
+ if (((op == GE_HASH_REMOVE) && (thishe & HSH_S)) ||
+ ((op == GE_HASH_ADD) && (thishe & HSH_S) == 0))
+ return EBUSY;
+ *he_p = thishe ^ HSH_S;
+
+ if (GTeth_debug>0) {
+ unsigned val1, val2;
+
+ val1= *he_p & 0xffffffff;
+ val2= (*he_p >>32) & 0xffffffff;
+ printk("flip skip bit result %x%x entry %x ",val2,val1, hash);
+ }
+ return 0;
+ }
+
+ /*
+ * If we haven't found a slot for the entry and this entry
+ * is currently being skipped, return this entry.
+ */
+ if (maybe_he_p == NULL && (thishe & HSH_S)) {
+ maybe_he_p = he_p;
+ maybe_hash = hash;
+ }
+ hash = (hash + 1) & (sc->sc_hashmask / sizeof(he));
+ }
+
+ /*
+ * If we got here, then there was no entry to remove.
+ */
+ if (op == GE_HASH_REMOVE) {
+ printk("GT64260eth : No entry to remove\n");
+ return ENOENT;
+ }
+
+ /*
+ * If we couldn't find a slot, return an error.
+ */
+ if (maybe_he_p == NULL) {
+ printk("GT64260eth : No slot found");
+ return ENOSPC;
+ }
+
+ /* Update the entry.*/
+ *maybe_he_p = he;
+ if (GTeth_debug>0) {
+ unsigned val1, val2;
+#if 0
+ unsigned long *pt= sc->sc_hashtable;
+ int i, loop;
+
+ for (loop= 0; loop< 256; loop++) {
+ printk("%d)", loop);
+ for (i=0; i< 16; i++, pt++) printk("%x ",*pt);
+ printk("\n");
+ }
+#endif
+ val1= he & 0xffffffff;
+ val2= (he >>32) & 0xffffffff;
+ printk("Update Hash result %x%x, table addr %x entry %x )\n",val2, val1, maybe_he_p, hash);
+ }
+ return 0;
+}
+
+static int GTeth_hash_fill(struct GTeth_softc *sc)
+{
+ struct ether_multistep step;
+ struct ether_multi *enm;
+ int error;
+
+#ifdef GT_DEBUG
+ printk( "GTeth_hash_fill(");
+#endif
+ error = GTeth_hash_entry_op(sc,GE_HASH_ADD,GE_RXPRIO_HI,sc->arpcom.ac_enaddr);
+
+ if (error) {
+ if (GTeth_debug>0) printk("!");
+ return error;
+ }
+
+ sc->sc_flags &= ~GE_ALLMULTI;
+ if ((sc->arpcom.ac_if.if_flags & IFF_PROMISC) == 0)
+ sc->sc_pcr &= ~ETH_EPCR_PM;
+ /* see lib/include/netinet/if_ether.h */
+ ETHER_FIRST_MULTI(step, &sc->arpcom, enm);
+ while (enm != NULL) {
+ if (memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN)) {
+ /* Frames are received regardless of their destinatin address */
+ sc->sc_flags |= GE_ALLMULTI;
+ sc->sc_pcr |= ETH_EPCR_PM;
+ } else {
+ /* Frames are only received if the destinatin address is found
+ * in the hash table
+ */
+ error = GTeth_hash_entry_op(sc, GE_HASH_ADD,
+ GE_RXPRIO_MEDLO, enm->enm_addrlo);
+ if (error == ENOSPC) break;
+ }
+ ETHER_NEXT_MULTI(step, enm);
+ }
+#ifdef GT_DEBUG
+ printk(")\n");
+#endif
+ return error;
+}
+
+static void GTeth_hash_init(struct GTeth_softc *sc)
+{
+ void *hash_mem;
+
+ if (GTeth_debug>0) printk("GTeth_hash_init(");
+ /* MOTLoad defualt : 512 bytes of address filtering, which
+ * requires 16KB of memory
+ */
+#if 1
+ hash_mem = rtems_bsdnet_malloc(HASH_DRAM_SIZE + HASH_ALIGN, M_FREE, M_NOWAIT);
+ sc->sc_hashtable =(void *)(((long)hash_mem+ HASH_ALIGN) & ~HASH_ALIGN);
+#else
+ /* only for test */
+ hash_mem = 0x68F000;
+ sc->sc_hashtable =(unsigned long long *)hash_mem;
+#endif
+ sc->sc_hashmask = HASH_DRAM_SIZE - 1;
+
+ memset((void *)sc->sc_hashtable, 0,HASH_DRAM_SIZE);
+#ifdef GT_DEBUG
+ printk("hashtable addr:%x, mask %x)\n", sc->sc_hashtable,sc->sc_hashmask);
+#endif
+}
+
+#ifdef GT64260eth_DEBUG
+static void GT64260eth_error(struct GTeth_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned int intr_status= sc->intr_errsts[sc->intr_err_ptr1];
+
+ /* read and reset the status; because this is written
+ * by the ISR, we must disable interrupts here
+ */
+ if (intr_status) {
+ printk("%s%d: ICR = 0x%x ",
+ ifp->if_name, ifp->if_unit, intr_status);
+#if 1
+ if (intr_status & INTR_RX_ERROR) {
+ printk("Rxq error, if_ierrors %d\n",
+ ifp->if_ierrors);
+ }
+#endif
+ /* Rx error is handled in GT64260eth_rx() */
+ if (intr_status & INTR_TX_ERROR) {
+ ifp->if_oerrors++;
+ printk("Txq error, if_oerrors %d\n",ifp->if_oerrors);
+ }
+ }
+ else
+ printk("%s%d: Ghost interrupt ?\n",ifp->if_name,
+ ifp->if_unit);
+ sc->intr_errsts[sc->intr_err_ptr1++]=0;
+ sc->intr_err_ptr1 %= INTR_ERR_SIZE; /* Till Straumann */
+}
+#endif
+
+/* The daemon does all of the work; RX, TX and cleaning up buffers/descriptors */
+static void GT64260eth_daemon(void *arg)
+{
+ struct GTeth_softc *sc = (struct GTeth_softc*)arg;
+ rtems_event_set events;
+ struct mbuf *m=0;
+ struct ifnet *ifp=&sc->arpcom.ac_if;
+
+#if 0
+ /* see comments in GT64260eth_init(); in newer versions of
+ * rtems, we hold the network semaphore at this point
+ */
+ rtems_semaphore_release(sc->daemonSync);
+#endif
+
+ /* NOTE: our creator possibly holds the bsdnet_semaphore.
+ * since that has PRIORITY_INVERSION enabled, our
+ * subsequent call to bsdnet_event_receive() will
+ * _not_ release it. It's still in posession of our
+ * owner.
+ * This is different from how killing this task
+ * is handled.
+ */
+
+ for (;;) {
+ /* sleep until there's work to be done */
+ /* Note: bsdnet_event_receive() acquires
+ * the global bsdnet semaphore for
+ * mutual exclusion.
+ */
+ rtems_bsdnet_event_receive(ALL_EVENTS,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ if (KILL_EVENT & events) break;
+
+#ifndef GE_NORX
+ if (events & RX_EVENT) GT64260eth_rx(sc);
+#endif
+#if 0
+ printk("%x ", inb(ETH0_EPSR));
+ if ( ((i++) % 15)==0) printk("\n");
+#endif
+
+ /* clean up and try sending packets */
+ do {
+ if (sc->txq_nactive) GTeth_txq_done(sc);
+
+ while (sc->txq_free>0) {
+ if (sc->txq_free>TXQ_HiLmt_OFF) {
+ m=0;
+ IF_DEQUEUE(&ifp->if_snd,m);
+ if (m==0) break;
+ GT64260eth_sendpacket(sc, m);
+ }
+ else {
+ GTeth_txq_done(sc);
+ break;
+ }
+ }
+ /* we leave this loop
+ * - either because there's no free buffer
+ * (m=0 initializer && !sc->txq_free)
+ * - or there's nothing to send (IF_DEQUEUE
+ * returned 0
+ */
+ } while (m);
+
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ /* Log errors and other uncommon events. */
+#ifdef GT64260eth_DEBUG
+ if (events & ERR_EVENT) GT64260eth_error(sc);
+#endif
+ } /* end for(;;) { rtems_bsdnet_event_receive() .....*/
+
+ ifp->if_flags &= ~(IFF_RUNNING|IFF_OACTIVE);
+
+ /* shut down the hardware */
+ GT64260eth_stop_hw(sc);
+ /* flush the output queue */
+ for (;;) {
+ IF_DEQUEUE(&ifp->if_snd,m);
+ if (!m) break;
+ m_freem(m);
+ }
+ /* as of 'rtems_bsdnet_event_receive()' we own the
+ * networking semaphore
+ */
+ rtems_bsdnet_semaphore_release();
+ rtems_semaphore_release(sc->daemonSync);
+
+ /* Note that I dont use sc->daemonTid here -
+ * theoretically, that variable could already
+ * hold a newly created TID
+ */
+ rtems_task_exit();
+}
+
diff --git a/bsps/powerpc/mvme5500/net/if_1GHz/if_wm.c b/bsps/powerpc/mvme5500/net/if_1GHz/if_wm.c
new file mode 100644
index 0000000..7487347
--- /dev/null
+++ b/bsps/powerpc/mvme5500/net/if_1GHz/if_wm.c
@@ -0,0 +1,1765 @@
+/*
+ * Copyright (c) 2004,2005 RTEMS/Mvme5500 port by S. Kate Feng <feng1@bnl.gov>
+ * under the Deaprtment of Energy contract DE-AC02-98CH10886
+ * Brookhaven National Laboratory, All rights reserved
+ *
+ * Acknowledgements:
+ * netBSD : Copyright (c) 2001, 2002, 2003, 2004 Wasabi Systems, Inc.
+ * Jason R. Thorpe for Wasabi Systems, Inc.
+ * Intel : NDA document
+ *
+ * Some notes from the author, S. Kate Feng :
+ *
+ * 1) The error reporting routine i82544EI_error() employs two pointers
+ * for the error report buffer. One for the ISR and another one for
+ * the error report.
+ * 2) Enable the hardware Auto-Negotiation state machine.
+ * 3) Set Big Endian mode in the WMREG_CTRL so that we do not need htole32
+ * because PPC is big endian mode.
+ * However, the data packet structure defined in if_wmreg.h
+ * should be redefined for the big endian mode.
+ * 4) To ensure the cache coherence, the MOTLoad had the PCI
+ * snoop control registers (0x1f00) set to "snoop to WB region" for
+ * the entire 512MB of memory.
+ * 5) MOTLoad default :
+ * little endian mode, cache line size is 32 bytes, no checksum control,
+ * hardware auto-neg. state machine disabled. PCI control "snoop
+ * to WB region", MII mode (PHY) instead of TBI mode.
+ * 6) We currently only use 32-bit (instead of 64-bit) DMA addressing.
+ * 7) Implementation for Jumbo Frame and TCP checksum is not completed yet.
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#define BYTE_ORDER BIG_ENDIAN
+
+#include <rtems.h>
+#include <rtems/bspIo.h> /* printk */
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_bsdnet_internal.h>
+
+#include <inttypes.h>
+#include <stdio.h> /* printf for statistics */
+#include <string.h>
+
+#include <libcpu/io.h> /* inp & friends */
+#include <libcpu/spr.h> /* registers.h is included here */
+#include <bsp.h>
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/mbuf.h>
+
+#include <errno.h>
+
+/* #include <sys/queue.h> */
+
+#include <sys/socket.h>
+#include <sys/sockio.h> /* SIOCADDMULTI, SIOC... */
+#include <net/if.h>
+#include <net/if_dl.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <net/ethernet.h>
+
+#ifdef INET
+#include <netinet/in_var.h>
+#endif
+
+#include <bsp/irq.h>
+#include <bsp/pci.h>
+#include <bsp/pcireg.h>
+#include <bsp/if_wmreg.h>
+
+extern int pci_mem_find(int b, int d, int f, int reg, unsigned *basep,unsigned *sizep);
+
+#define WMREG_RADV 0x282c /* Receive Interrupt Absolute Delay Timer */
+
+#define ETHERTYPE_FLOWCONTROL 0x8808 /* 802.3x flow control packet */
+
+#define i82544EI_TASK_NAME "IGHz"
+#define SOFTC_ALIGN 4095
+
+#define IF_ERR_BUFSZE 16
+
+/*#define WM_DEBUG*/
+#ifdef WM_DEBUG
+#define WM_DEBUG_LINK 0x01
+#define WM_DEBUG_TX 0x02
+#define WM_DEBUG_RX 0x04
+#define WM_DEBUG_GMII 0x08
+static int wm_debug = WM_DEBUG_TX|WM_DEBUG_RX|WM_DEBUG_LINK; /* May 7, 2009 */
+
+#define DPRINTF(x, y) if (wm_debug & (x)) printk y
+#else
+#define DPRINTF(x, y) /* nothing */
+#endif /* WM_DEBUG */
+
+/* RTEMS event to kill the daemon */
+#define KILL_EVENT RTEMS_EVENT_1
+/* RTEMS event to (re)start the transmitter */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+/* RTEMS events used by the ISR */
+#define RX_EVENT RTEMS_EVENT_3
+#define TX_EVENT RTEMS_EVENT_4
+#define ERR_EVENT RTEMS_EVENT_5
+#define INIT_EVENT RTEMS_EVENT_6
+
+#define ALL_EVENTS (KILL_EVENT|START_TRANSMIT_EVENT|RX_EVENT|TX_EVENT|ERR_EVENT|INIT_EVENT)
+
+/* <skf> used 64 in 4.8.0, TOD; try 4096 */
+#define NTXDESC 256
+#define NTXDESC_MASK (NTXDESC - 1)
+#define WM_NEXTTX(x) (((x) + 1) & NTXDESC_MASK)
+
+#define NRXDESC 256
+#define NRXDESC_MASK (NRXDESC - 1)
+#define WM_NEXTRX(x) (((x) + 1) & NRXDESC_MASK)
+#define WM_PREVRX(x) (((x) - 1) & NRXDESC_MASK)
+
+#define WM_CDOFF(x) offsetof(struct wm_control_data, x)
+#define WM_CDTXOFF(x) WM_CDOFF(sc_txdescs[(x)])
+#define WM_CDRXOFF(x) WM_CDOFF(sc_rxdescs[(x)])
+
+#define TXQ_HiLmt_OFF 32
+
+static uint32_t TxDescCmd;
+static unsigned BSP_1GHz_membase;
+
+/*
+ * Software state per device.
+ */
+struct wm_softc {
+ wiseman_txdesc_t sc_txdescs[NTXDESC]; /* transmit descriptor memory */
+ wiseman_rxdesc_t sc_rxdescs[NRXDESC]; /* receive descriptor memory */
+ struct mbuf *txs_mbuf[NTXDESC]; /* transmit buffer memory */
+ struct mbuf *rxs_mbuf[NRXDESC]; /* receive buffer memory */
+ struct wm_softc *next_module;
+ volatile unsigned int if_errsts[IF_ERR_BUFSZE]; /* intr_status */
+ unsigned int if_err_ptr1; /* ptr used in i82544EI_error() */
+ unsigned int if_err_ptr2; /* ptr used in ISR */
+ int txs_firstdesc; /* first descriptor in packet */
+ int txs_lastdesc; /* last descriptor in packet */
+ int txs_ndesc; /* # of descriptors used */
+ unsigned sc_membase; /* Memory space base address */
+ unsigned sc_memsize; /* Memory space size */
+
+ char dv_xname[16]; /* external name (name + unit) */
+ void *sc_sdhook; /* shutdown hook */
+ struct arpcom arpcom; /* rtems if structure, contains ifnet */
+ int sc_flags; /* flags; see below */
+ int sc_bus_speed; /* PCI/PCIX bus speed */
+ int sc_flowflags; /* 802.3x flow control flags */
+
+ void *sc_ih; /* interrupt cookie */
+
+ int sc_ee_addrbits; /* EEPROM address bits */
+ rtems_id daemonTid;
+ rtems_id daemonSync; /* synchronization with the daemon */
+
+ int txq_next; /* next Tx descriptor ready for transmitting */
+ uint32_t txq_nactive; /* number of active TX descriptors */
+ uint32_t txq_fi; /* next free Tx descriptor */
+ uint32_t txq_free; /* number of free Tx jobs */
+ uint32_t sc_txctx_ipcs; /* cached Tx IP cksum ctx */
+ uint32_t sc_txctx_tucs; /* cached Tx TCP/UDP cksum ctx */
+
+ int sc_rxptr; /* next ready Rx descriptor/queue ent */
+ int sc_rxdiscard;
+ int sc_rxlen;
+
+ uint32_t sc_ctrl; /* prototype CTRL register */
+ uint32_t sc_ctrl_ext; /* prototype CTRL_EXT register */
+
+ uint32_t sc_icr; /* prototype interrupt bits */
+ uint32_t sc_tctl; /* prototype TCTL register */
+ uint32_t sc_rctl; /* prototype RCTL register */
+ uint32_t sc_tipg; /* prototype TIPG register */
+ uint32_t sc_fcrtl; /* prototype FCRTL register */
+ uint32_t sc_pba; /* prototype PBA register */
+
+ int sc_mchash_type; /* multicast filter offset */
+
+ /* statistics */
+ struct {
+ volatile unsigned long rxInterrupts;
+ volatile unsigned long txInterrupts;
+ unsigned long linkInterrupts;
+ unsigned long length_errors;
+ unsigned long frame_errors;
+ unsigned long crc_errors;
+ unsigned long rxOvrRunInterrupts; /* Rx overrun interrupt */
+ unsigned long rxSeqErr;
+ unsigned long rxC_ordered;
+ unsigned long ghostInterrupts;
+ unsigned long linkStatusChng;
+ } stats;
+};
+
+/* <skf> our memory address seen from the PCI bus should be 1:1 */
+#define htole32(x) le32toh(x)
+#define le32toh(x) CPU_swap_u32((unsigned int) x)
+#define le16toh(x) CPU_swap_u16(x)
+
+/* sc_flags */
+#define WM_F_HAS_MII 0x01 /* has MII */
+/* 82544 EI does not perform EEPROM handshake, EEPROM interface is not SPI */
+#define WM_F_EEPROM_HANDSHAKE 0x02 /* requires EEPROM handshake */
+#define WM_F_EEPROM_SPI 0x04 /* EEPROM is SPI */
+#define WM_F_IOH_VALID 0x10 /* I/O handle is valid */
+#define WM_F_BUS64 0x20 /* bus is 64-bit */
+#define WM_F_PCIX 0x40 /* bus is PCI-X */
+
+#define CSR_READ(sc,reg) in_le32((volatile uint32_t *)(sc->sc_membase+reg))
+#define CSR_WRITE(sc,reg,val) out_le32((volatile uint32_t *)(sc->sc_membase+reg), val)
+
+#define WM_CDTXADDR(sc) ( (uint32_t) &sc->sc_txdescs[0] )
+#define WM_CDRXADDR(sc) ( (uint32_t) &sc->sc_rxdescs[0] )
+
+static struct wm_softc *root_i82544EI_dev = NULL;
+
+static void i82544EI_ifstart(struct ifnet *ifp);
+static int wm_ioctl(struct ifnet *ifp, ioctl_command_t cmd,caddr_t data);
+static void i82544EI_ifinit(void *arg);
+static void wm_stop(struct ifnet *ifp, int disable);
+static void wm_gmii_mediainit(struct wm_softc *sc);
+
+static void wm_rxdrain(struct wm_softc *sc);
+static int wm_add_rxbuf(struct wm_softc *sc, int idx);
+static int wm_read_eeprom(struct wm_softc *sc,int word,int wordcnt, uint16_t *data);
+static void i82544EI_daemon(void *arg);
+static void wm_set_filter(struct wm_softc *sc);
+static void i82544EI_rx(struct wm_softc *sc);
+static void i82544EI_isr(rtems_irq_hdl_param handle);
+static void i82544EI_sendpacket(struct wm_softc *sc, struct mbuf *m);
+
+static void i82544EI_irq_on(const rtems_irq_connect_data *irq)
+{
+ struct wm_softc *sc;
+ unsigned int irqMask= ICR_TXDW | ICR_LSC | ICR_RXSEQ | ICR_RXDMT0 | ICR_RXO | ICR_RXT0 | ICR_RXCFG;
+
+ for (sc= root_i82544EI_dev; sc; sc= sc-> next_module) {
+ CSR_WRITE(sc,WMREG_IMS,(CSR_READ(sc,WMREG_IMS)| irqMask) );
+ return;
+ }
+}
+
+static void i82544EI_irq_off(const rtems_irq_connect_data *irq)
+{
+ struct wm_softc *sc;
+ unsigned int irqMask= ICR_TXDW | ICR_LSC | ICR_RXSEQ | ICR_RXDMT0 | ICR_RXO | ICR_RXT0 |ICR_RXCFG ;
+
+ for (sc= root_i82544EI_dev; sc; sc= sc-> next_module) {
+ CSR_WRITE(sc,WMREG_IMS, (CSR_READ(sc,WMREG_IMS) & ~irqMask) );
+ return;
+ }
+}
+
+static int i82544EI_irq_is_on(const rtems_irq_connect_data *irq)
+{
+ return(CSR_READ(root_i82544EI_dev,WMREG_ICR) & root_i82544EI_dev->sc_icr);
+}
+
+static rtems_irq_connect_data i82544IrqData={
+ BSP_GPP_82544_IRQ,
+ (rtems_irq_hdl) i82544EI_isr,
+ (rtems_irq_hdl_param) NULL,
+ (rtems_irq_enable) i82544EI_irq_on,
+ (rtems_irq_disable) i82544EI_irq_off,
+ (rtems_irq_is_enabled) i82544EI_irq_is_on,
+};
+
+int rtems_i82544EI_driver_attach(struct rtems_bsdnet_ifconfig *config, int attach)
+{
+ struct wm_softc *sc;
+ struct ifnet *ifp;
+ uint8_t enaddr[ETHER_ADDR_LEN];
+ uint16_t myea[ETHER_ADDR_LEN / 2], cfg1, cfg2, swdpin;
+ unsigned reg;
+ int b,d,f; /* PCI bus/device/function */
+ int unit;
+ void *softc_mem;
+ char *name;
+
+ unit = rtems_bsdnet_parse_driver_name(config, &name);
+ if (unit < 0) return 0;
+
+ if ( !strncmp((const char *)name,"autoz",5))
+ memcpy(name,"gtGHz",5);
+
+ printk("\nAttaching MVME5500 1GHz NIC%d\n", unit);
+ printk("RTEMS-mvme5500 BSP Copyright (c) 2004,2005,2008, Brookhaven National Lab., Shuchen Kate Feng \n");
+
+ /* Make sure certain elements e.g. descriptor lists are aligned.*/
+ softc_mem = rtems_bsdnet_malloc(sizeof(*sc) + SOFTC_ALIGN, M_FREE, M_NOWAIT);
+
+ /* Check for the very unlikely case of no memory. */
+ if (softc_mem == NULL)
+ rtems_panic("i82544EI: OUT OF MEMORY");
+
+ sc = (void *)(((long)softc_mem + SOFTC_ALIGN) & ~SOFTC_ALIGN);
+ memset(sc, 0, sizeof(*sc));
+
+ sprintf(sc->dv_xname, "%s%d", name, unit);
+
+ if (pci_find_device(PCI_VENDOR_ID_INTEL,PCI_DEVICE_ID_INTEL_82544EI_COPPER,
+ unit-1,&b, &d, &f))
+ rtems_panic("i82544EI device ID not found\n");
+
+#ifdef WM_DEBUG
+ printk("82544EI:b%d, d%d, f%d\n", b, d,f);
+#endif
+
+ /* Memory-mapped acccess is required for normal operation.*/
+ if ( pci_mem_find(b,d,f,PCI_MAPREG_START, &sc->sc_membase, &sc->sc_memsize))
+ rtems_panic("i82544EI: unable to map memory space\n");
+
+#ifdef WM_DEBUG
+ printk("Memory base addr 0x%x\n", sc->sc_membase);
+#endif
+ BSP_1GHz_membase= sc->sc_membase;
+
+#ifdef WM_DEBUG
+ printk("Memory base addr 0x%x\n", sc->sc_membase);
+ printk("txdesc[0] addr:0x%x, rxdesc[0] addr:0x%x, sizeof sc %d\n",&sc->sc_txdescs[0], &sc->sc_rxdescs[0], sizeof(*sc));
+#endif
+
+
+ sc->sc_ctrl=CSR_READ(sc,WMREG_CTRL);
+ /*
+ * Determine a few things about the bus we're connected to.
+ */
+ reg = CSR_READ(sc,WMREG_STATUS);
+ if (reg & STATUS_BUS64) sc->sc_flags |= WM_F_BUS64;
+ sc->sc_bus_speed = (reg & STATUS_PCI66) ? 66 : 33;
+#ifdef WM_DEBUG
+ printk("%s%d: %d-bit %dMHz PCI bus\n",name, unit,
+ (sc->sc_flags & WM_F_BUS64) ? 64 : 32, sc->sc_bus_speed);
+#endif
+
+ /*
+ * Setup some information about the EEPROM.
+ */
+
+ sc->sc_ee_addrbits = 6;
+
+#ifdef WM_DEBUG
+ printk("%s%d: %u word (%d address bits) MicroWire EEPROM\n",
+ name, unit, 1U << sc->sc_ee_addrbits,
+ sc->sc_ee_addrbits);
+#endif
+
+ /*
+ * Read the Ethernet address from the EEPROM.
+ */
+ if (wm_read_eeprom(sc, EEPROM_OFF_MACADDR,
+ sizeof(myea) / sizeof(myea[0]), myea))
+ rtems_panic("i82544ei 1GHZ ethernet: unable to read Ethernet address");
+
+ enaddr[0] = myea[0] & 0xff;
+ enaddr[1] = myea[0] >> 8;
+ enaddr[2] = myea[1] & 0xff;
+ enaddr[3] = myea[1] >> 8;
+ enaddr[4] = myea[2] & 0xff;
+ enaddr[5] = myea[2] >> 8;
+
+ memcpy(sc->arpcom.ac_enaddr, enaddr, ETHER_ADDR_LEN);
+#ifdef WM_DEBUG
+ printk("%s: Ethernet address %s\n", sc->dv_xname,
+ ether_sprintf(enaddr));
+#endif
+
+ /*
+ * Read the config info from the EEPROM, and set up various
+ * bits in the control registers based on their contents.
+ */
+ if (wm_read_eeprom(sc, EEPROM_OFF_CFG1, 1, &cfg1)) {
+ printk("%s: unable to read CFG1 from EEPROM\n",sc->dv_xname);
+ return(0);
+ }
+ if (wm_read_eeprom(sc, EEPROM_OFF_CFG2, 1, &cfg2)) {
+ printk("%s: unable to read CFG2 from EEPROM\n",sc->dv_xname);
+ return(0);
+ }
+ if (wm_read_eeprom(sc, EEPROM_OFF_SWDPIN, 1, &swdpin)) {
+ printk("%s: unable to read SWDPIN from EEPROM\n",sc->dv_xname);
+ return(0);
+ }
+
+ if (cfg1 & EEPROM_CFG1_ILOS) sc->sc_ctrl |= CTRL_ILOS;
+ sc->sc_ctrl|=((swdpin >> EEPROM_SWDPIN_SWDPIO_SHIFT) & 0xf) <<
+ CTRL_SWDPIO_SHIFT;
+ sc->sc_ctrl |= ((swdpin >> EEPROM_SWDPIN_SWDPIN_SHIFT) & 0xf) <<
+ CTRL_SWDPINS_SHIFT;
+
+ CSR_WRITE(sc,WMREG_CTRL, sc->sc_ctrl);
+#if 0
+ CSR_WRITE(sc,WMREG_CTRL_EXT, sc->sc_ctrl_ext);
+#endif
+
+ /*
+ * Determine if we're TBI or GMII mode, and initialize the
+ * media structures accordingly.
+ */
+ if ((CSR_READ(sc, WMREG_STATUS) & STATUS_TBIMODE) != 0) {
+ /* 1000BASE-X : fiber (TBI mode)
+ wm_tbi_mediainit(sc); */
+ } else { /* 1000BASE-T : copper (internal PHY mode), for the mvme5500 */
+ wm_gmii_mediainit(sc);
+ }
+
+ ifp = &sc->arpcom.ac_if;
+ /* set this interface's name and unit */
+ ifp->if_unit = unit;
+ ifp->if_name = name;
+ ifp->if_softc = sc;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+#ifdef RTEMS_ETHERMTU_JUMBO
+ sc->arpcom.ec_capabilities |= ETHERCAP_JUMBO_MTU;
+ ifp->if_mtu = config->mtu ? config->mtu : ETHERMTU_JUMBO;
+#else
+ ifp->if_mtu = config->mtu ? config->mtu : ETHERMTU;
+#endif
+#ifdef RTEMS_CKSUM_OFFLOAD
+ /* < skf> The following is really not related to jumbo frame
+ sc->arpcom.ec_capabilities |= ETHERCAP_VLAN_MTU;*/
+ ifp->if_capabilities |= IFCAP_CSUM_IPv4_Tx | IFCAP_CSUM_IPv4_Rx |
+ IFCAP_CSUM_TCPv4_Tx | IFCAP_CSUM_TCPv4_Rx |
+ IFCAP_CSUM_UDPv4_Tx | IFCAP_CSUM_UDPv4_Rx |
+ IFCAP_CSUM_TCPv6_Tx | IFCAP_CSUM_UDPv6_Tx |
+ IFCAP_TSOv4; /* TCP segmentation offload. */
+#endif
+
+ ifp->if_ioctl = wm_ioctl;
+ ifp->if_start = i82544EI_ifstart;
+ /* ifp->if_watchdog = wm_watchdog;*/
+ ifp->if_init = i82544EI_ifinit;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ ifp->if_output = ether_output;
+
+ /* create the synchronization semaphore */
+ if (RTEMS_SUCCESSFUL != rtems_semaphore_create(
+ rtems_build_name('I','G','H','Z'),0,0,0,&sc->daemonSync))
+ rtems_panic("i82544EI: semaphore creation failed");
+
+ i82544IrqData.handle= (rtems_irq_hdl_param) sc;
+ /* sc->next_module = root_i82544EI_dev;*/
+ root_i82544EI_dev = sc;
+
+ /* Attach the interface. */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+#ifdef WM_DEBUG
+ printk("82544EI: Ethernet driver has been attached (handle 0x%08x,ifp 0x%08x)\n",sc, ifp);
+#endif
+
+ return(1);
+}
+
+/*
+ * wm_reset:
+ *
+ * Reset the i82544 chip.
+ */
+static void wm_reset(struct wm_softc *sc)
+{
+ int i;
+
+ /* Packet Buffer Allocation (PBA)
+ * Writing PBA sets the receive portion of the buffer.
+ * the remainder is used for the transmit buffer.
+ *
+ * 82544 has a Packet Buffer of 64K.
+ * Default allocation : PBA=40K for Rx, leaving 24K for Tx.
+ * Default for jumbo: PBA=48K for Rx, leaving 16K for Tx.
+ */
+ sc->sc_pba = sc->arpcom.ac_if.if_mtu > 8192 ? PBA_40K : PBA_48K;
+ CSR_WRITE(sc, WMREG_PBA, sc->sc_pba);
+
+ /* device reset */
+ CSR_WRITE(sc, WMREG_CTRL, CTRL_RST);
+ rtems_bsp_delay(10000);
+
+ for (i = 0; i < 1000; i++) {
+ if ((CSR_READ(sc, WMREG_CTRL) & CTRL_RST) == 0)
+ break;
+ rtems_bsp_delay(20);
+ }
+ if (CSR_READ(sc, WMREG_CTRL) & CTRL_RST)
+ printk("Intel 82544 1GHz reset failed to complete\n");
+
+ sc->sc_ctrl_ext = CSR_READ(sc,WMREG_CTRL_EXT);
+ sc->sc_ctrl_ext |= CTRL_EXT_EE_RST;
+ CSR_WRITE(sc, WMREG_CTRL_EXT, sc->sc_ctrl_ext);
+ CSR_READ(sc, WMREG_STATUS);
+ /* Wait for EEPROM reload */
+ rtems_bsp_delay(2000);
+ sc->sc_ctrl= CSR_READ(sc, WMREG_CTRL);
+}
+
+/*
+ * i82544EI_ifstart: [ifnet interface function]
+ *
+ * Start packet transmission on the interface.
+ */
+static void
+i82544EI_ifstart(struct ifnet *ifp)
+{
+ struct wm_softc *sc = ifp->if_softc;
+
+#ifdef WM_DEBUG
+ printk("i82544EI_ifstart(");
+#endif
+
+ if ((ifp->if_flags & IFF_RUNNING) == 0) {
+#ifdef WM_DEBUG
+ printk("IFF_RUNNING==0\n");
+#endif
+ return;
+ }
+
+ ifp->if_flags |= IFF_OACTIVE;
+ rtems_bsdnet_event_send (sc->daemonTid, START_TRANSMIT_EVENT);
+#ifdef WM_DEBUG
+ printk(")\n");
+#endif
+}
+
+static void i82544EI_stats(struct wm_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ printf(" Ghost Interrupts:%-8lu\n", sc->stats.ghostInterrupts);
+ printf(" Rx Interrupts:%-8lu\n", sc->stats.rxInterrupts);
+ printf(" Receive Packets:%-8u\n", (unsigned)CSR_READ(sc,WMREG_GPRC));
+ printf(" Receive Overrun:%-8lu\n", sc->stats.rxOvrRunInterrupts);
+ printf(" Receive errors:%-8u\n", (unsigned)CSR_READ(sc,WMREG_RXERRC));
+ printf(" Rx sequence error:%-8lu\n", sc->stats.rxSeqErr);
+ printf(" Rx /C/ ordered:%-8lu\n", sc->stats.rxC_ordered);
+ printf(" Rx Length Errors:%-8u\n", (unsigned)CSR_READ(sc,WMREG_RLEC));
+ printf(" Tx Interrupts:%-8lu\n", sc->stats.txInterrupts);
+ printf(" Transmitt Packets:%-8u\n", (unsigned)CSR_READ(sc,WMREG_GPTC));
+ printf(" Transmitt errors:%-8lu\n", ifp->if_oerrors);
+ printf(" Active Txqs:%-8lu\n", sc->txq_nactive);
+ printf(" collisions:%-8u\n", (unsigned)CSR_READ(sc,WMREG_COLC));
+ printf(" Crc Errors:%-8u\n", (unsigned)CSR_READ(sc,WMREG_CRCERRS));
+ printf(" Link Status Change:%-8lu\n", sc->stats.linkStatusChng);
+}
+
+/*
+ * wm_ioctl: [ifnet interface function]
+ *
+ * Handle control requests from the operator.
+ */
+static int wm_ioctl(struct ifnet *ifp, ioctl_command_t cmd,caddr_t data)
+{
+ struct wm_softc *sc = ifp->if_softc;
+ int error=0;
+
+ switch (cmd) {
+ default:
+ error = ether_ioctl(ifp, cmd, data);
+ if (error == ENETRESET) {
+ /*
+ * Multicast list has changed; set the hardware filter
+ * accordingly.
+ */
+ wm_set_filter(sc);
+ error = 0;
+ }
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ i82544EI_stats(sc);
+ break;
+ }
+
+ /* Try to get more packets going.*/
+ i82544EI_ifstart(ifp);
+ return (error);
+}
+
+/*
+ * wm_isr:
+ *
+ * Interrupt service routine.
+ */
+static void i82544EI_isr(rtems_irq_hdl_param handle)
+{
+ volatile struct wm_softc *sc = (struct wm_softc *) handle;
+ uint32_t icr;
+ rtems_event_set events=0;
+
+ /* Reading the WMREG_ICR clears the interrupt bits */
+ icr = CSR_READ(sc,WMREG_ICR);
+
+ if ( icr & (ICR_RXDMT0|ICR_RXT0)) {
+ sc->stats.rxInterrupts++;
+ events |= RX_EVENT;
+ }
+
+ if (icr & ICR_TXDW) {
+ sc->stats.txInterrupts++;
+ events |= TX_EVENT;
+ }
+ /* <SKF> Rx overrun : no available receive buffer
+ * or PCI receive bandwidth inadequate.
+ */
+ if (icr & ICR_RXO) {
+ sc->stats.rxOvrRunInterrupts++;
+ events |= INIT_EVENT;
+ }
+ if (icr & ICR_RXSEQ) /* framing error */ {
+ sc->if_errsts[sc->if_err_ptr2++]=icr;
+ if ( sc->if_err_ptr2 ==IF_ERR_BUFSZE) sc->if_err_ptr2=0;
+ events |= ERR_EVENT;
+ sc->stats.rxSeqErr++;
+ }
+ if ( !icr) sc->stats.ghostInterrupts++;
+
+ if (icr & ICR_LSC) sc->stats.linkStatusChng++;
+ if (icr & ICR_RXCFG) sc->stats.rxC_ordered++;
+
+ rtems_bsdnet_event_send(sc->daemonTid, events);
+}
+
+/*
+ * i82544EI_sendpacket:
+ *
+ * Helper; handle transmit interrupts.
+ */
+static void i82544EI_sendpacket(struct wm_softc *sc, struct mbuf *m)
+{
+
+#ifdef WM_DEBUG_TX
+ printk("sendpacket(");
+#endif
+
+ if ( !(m->m_next)) { /* single buffer packet */
+ sc->txs_mbuf[sc->txq_next]= m;
+ /* Note: we currently only use 32-bit DMA addresses. */
+ sc->sc_txdescs[sc->txq_next].wtx_addr.wa_low = htole32(mtod(m, void*));
+ sc->sc_txdescs[sc->txq_next].wtx_cmdlen =htole32(TxDescCmd | m->m_len);
+ sc->txs_lastdesc= sc->txq_next;
+ sc->txq_next = WM_NEXTTX(sc->txq_next);
+ sc->txq_nactive++;
+ sc->txq_free--;
+ }
+ else /* multiple mbufs in this packet */
+ {
+ struct mbuf *mtp, *mdest;
+ volatile unsigned char *pt;
+ int len, y, loop=0;
+
+#ifdef WM_DEBUG_TX
+ printk("multi mbufs ");
+#endif
+ mtp = m;
+ while ( mtp) {
+ MGETHDR(mdest, M_WAIT, MT_DATA);
+ MCLGET(mdest, M_WAIT);
+ pt = (volatile unsigned char *)mdest->m_data;
+ for ( len=0;mtp;mtp=mtp->m_next) {
+ loop++;
+ /* Each descriptor gets a 2k (MCLBYTES) buffer, although
+ * the length of each descriptor can be up to 16288 bytes.
+ * For packets which fill more than one buffer ( >2k), we
+ * chain them together.
+ * <Kate Feng> : This effective for packets > 2K
+ * The other way is effective for packets < 2K
+ */
+ if ( ((y=(len+mtp->m_len)) > sizeof(union mcluster))) {
+ printk(" >%d, use next descriptor\n", sizeof(union mcluster));
+ break;
+ }
+ memcpy((void *)pt,(char *)mtp->m_data, mtp->m_len);
+ pt += mtp->m_len;
+ len += mtp->m_len;
+ } /* end for loop */
+ mdest->m_len=len;
+ sc->txs_mbuf[sc->txq_next] = mdest;
+ /* Note: we currently only use 32-bit DMA addresses. */
+ sc->sc_txdescs[sc->txq_next].wtx_addr.wa_low = htole32(mtod(mdest, void*));
+ sc->sc_txdescs[sc->txq_next].wtx_cmdlen = htole32(TxDescCmd|mdest->m_len);
+ sc->txs_lastdesc = sc->txq_next;
+ sc->txq_next = WM_NEXTTX(sc->txq_next);
+ sc->txq_nactive ++;
+ if (sc->txq_free)
+ sc->txq_free--;
+ else
+ rtems_panic("i8254EI : no more free descriptors");
+ } /* end for while */
+ /* free old mbuf chain */
+ m_freem(m);
+ m=0;
+ } /* end multiple mbufs */
+
+ DPRINTF(WM_DEBUG_TX,("%s: TX: desc %d: cmdlen 0x%08x\n", sc->dv_xname,
+ sc->txs_lastdesc, le32toh(sc->sc_txdescs[sc->txs_lastdesc].wtx_cmdlen)));
+ DPRINTF(WM_DEBUG_TX,("status 0x%08x\n",sc->sc_txdescs[sc->txq_fi].wtx_fields.wtxu_status));
+
+ memBar();
+
+ /* This is the location where software writes the first NEW descriptor */
+ CSR_WRITE(sc,WMREG_TDT, sc->txq_next);
+
+ DPRINTF(WM_DEBUG_TX,("%s: addr 0x%08x, TX: TDH %d, TDT %d\n",sc->dv_xname,
+ le32toh(sc->sc_txdescs[sc->txs_lastdesc].wtx_addr.wa_low), CSR_READ(sc,WMREG_TDH),
+ CSR_READ(sc,WMREG_TDT)));
+
+ DPRINTF(WM_DEBUG_TX,("%s: TX: finished transmitting packet, job %d\n",
+ sc->dv_xname, sc->txq_next));
+
+}
+
+static void i82544EI_txq_free(struct wm_softc *sc, uint8_t status)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ /* We might use the statistics registers instead of variables
+ * to keep tack of the network statistics
+ */
+
+ /* statistics */
+ ifp->if_opackets++;
+
+ if (status & (WTX_ST_EC|WTX_ST_LC)) {
+ ifp->if_oerrors++;
+
+ if (status & WTX_ST_LC)
+ printf("%s: late collision\n", sc->dv_xname);
+ else if (status & WTX_ST_EC) {
+ ifp->if_collisions += 16;
+ printf("%s: excessive collisions\n", sc->dv_xname);
+ }
+ }
+ /* Free the original mbuf chain */
+ m_freem(sc->txs_mbuf[sc->txq_fi]);
+ sc->txs_mbuf[sc->txq_fi] = 0;
+ sc->sc_txdescs[sc->txq_fi].wtx_fields.wtxu_status=0;
+
+ sc->txq_free ++;
+ sc->txq_fi = WM_NEXTTX(sc->txq_fi);
+ --sc->txq_nactive;
+}
+
+static void i82544EI_txq_done(struct wm_softc *sc)
+{
+ uint8_t status;
+
+ /*
+ * Go through the Tx list and free mbufs for those
+ * frames which have been transmitted.
+ */
+ while ( sc->txq_nactive > 0) {
+ status = sc->sc_txdescs[sc->txq_fi].wtx_fields.wtxu_status;
+ if ((status & WTX_ST_DD) == 0) break;
+ i82544EI_txq_free(sc, status);
+ DPRINTF(WM_DEBUG_TX,("%s: TX: job %d done\n",
+ sc->dv_xname, sc->txq_fi));
+ }
+}
+
+static void wm_init_rxdesc(struct wm_softc *sc, int x)
+{
+ wiseman_rxdesc_t *__rxd = &(sc)->sc_rxdescs[(x)];
+ struct mbuf *m;
+
+ m = sc->rxs_mbuf[x];
+
+ __rxd->wrx_addr.wa_low=htole32(mtod(m, void*));
+ __rxd->wrx_addr.wa_high = 0;
+ __rxd->wrx_len = 0;
+ __rxd->wrx_cksum = 0;
+ __rxd->wrx_status = 0;
+ __rxd->wrx_errors = 0;
+ __rxd->wrx_special = 0;
+ /* Receive Descriptor Tail: add Rx desc. to H/W free list */
+ CSR_WRITE(sc,WMREG_RDT, (x));
+}
+
+static void i82544EI_rx(struct wm_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ int i, len;
+ uint8_t status, errors;
+ struct ether_header *eh;
+
+#ifdef WM_DEBUG
+ printk("i82544EI_rx()\n");
+#endif
+
+ for (i = sc->sc_rxptr;; i = WM_NEXTRX(i)) {
+ DPRINTF(WM_DEBUG_RX, ("%s: RX: checking descriptor %d\n",
+ sc->dv_xname, i));
+
+ status = sc->sc_rxdescs[i].wrx_status;
+ if ((status & WRX_ST_DD) == 0) break; /* descriptor not done */
+
+ errors = sc->sc_rxdescs[i].wrx_errors;
+ len = le16toh(sc->sc_rxdescs[i].wrx_len);
+ m = sc->rxs_mbuf[i];
+ if (sc->sc_rxdiscard) {
+ printk("RX: discarding contents of descriptor %d\n", i);
+ wm_init_rxdesc(sc, i);
+ if (status & WRX_ST_EOP) {
+ /* Reset our state. */
+ printk("RX: resetting rxdiscard -> 0\n");
+ sc->sc_rxdiscard = 0;
+ }
+ continue;
+ }
+
+ /*
+ * If an error occurred, update stats and drop the packet.
+ */
+ if (errors &(WRX_ER_CE|WRX_ER_SE|WRX_ER_SEQ|WRX_ER_CXE|WRX_ER_RXE)) {
+ ifp->if_ierrors++;
+ if (errors & WRX_ER_SE)
+ printk("%s: symbol error\n",sc->dv_xname);
+ else if (errors & WRX_ER_SEQ)
+ printk("%s: receive sequence error\n",sc->dv_xname);
+ else if (errors & WRX_ER_CE)
+ printk("%s: CRC error\n",sc->dv_xname);
+ m_freem(m);
+ goto give_it_back;
+ }
+
+ /*
+ * No errors. Receive the packet.
+ *
+ * Note, we have configured the chip to include the
+ * CRC with every packet.
+ */
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header);
+
+ DPRINTF(WM_DEBUG_RX,("%s: RX: buffer at %p len %d\n",
+ sc->dv_xname, m->m_data, len));
+
+
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+ /* Pass it on. */
+ ifp->if_ipackets++;
+
+ give_it_back:
+ /* Add a new receive buffer to the ring.*/
+ if (wm_add_rxbuf(sc, i) != 0) {
+ /*
+ * Failed, throw away what we've done so
+ * far, and discard the rest of the packet.
+ */
+ printk("Failed in wm_add_rxbuf(), drop packet\n");
+ ifp->if_ierrors++;
+ wm_init_rxdesc(sc, i);
+ if ((status & WRX_ST_EOP) == 0)
+ sc->sc_rxdiscard = 1;
+ m_freem(m);
+ }
+ } /* end for */
+
+ /* Update the receive pointer. */
+ sc->sc_rxptr = i;
+ DPRINTF(WM_DEBUG_RX, ("%s: RX: rxptr -> %d\n", sc->dv_xname, i));
+}
+
+static int i82544EI_init_hw(struct wm_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ int i,error;
+ uint8_t cksumfields;
+
+#if 0
+ /* KATETODO : sc_align_tweak */
+ /*
+ * *_HDR_ALIGNED_P is constant 1 if __NO_STRICT_ALIGMENT is set.
+ * There is a small but measurable benefit to avoiding the adjusment
+ * of the descriptor so that the headers are aligned, for normal mtu,
+ * on such platforms. One possibility is that the DMA itself is
+ * slightly more efficient if the front of the entire packet (instead
+ * of the front of the headers) is aligned.
+ *
+ * Note we must always set align_tweak to 0 if we are using
+ * jumbo frames.
+ */
+#ifdef __NO_STRICT_ALIGNMENT
+ sc->sc_align_tweak = 0;
+#else
+ if ((ifp->if_mtu + ETHER_HDR_LEN + ETHER_CRC_LEN) > (MCLBYTES - 2))
+ sc->sc_align_tweak = 0;
+ else
+ sc->sc_align_tweak = 2;
+#endif /* __NO_STRICT_ALIGNMENT */
+#endif
+
+ /* Cancel any pending I/O. */
+ wm_stop(ifp, 0);
+
+ /* update statistics before reset */
+ ifp->if_collisions += CSR_READ(sc, WMREG_COLC);
+ ifp->if_ierrors += CSR_READ(sc, WMREG_RXERRC);
+
+ /* Reset the chip to a known state. */
+ wm_reset(sc);
+
+ /* Initialize the error buffer ring */
+ sc->if_err_ptr1=0;
+ sc->if_err_ptr2=0;
+ for (i=0; i< IF_ERR_BUFSZE; i++) sc->if_errsts[i]=0;
+
+ /* Initialize the transmit descriptor ring. */
+ memset( (void *) sc->sc_txdescs, 0, sizeof(sc->sc_txdescs));
+ sc->txq_free = NTXDESC;
+ sc->txq_next = 0;
+ sc->txs_lastdesc = 0;
+ sc->txq_next = 0;
+ sc->txq_free = NTXDESC;
+ sc->txq_nactive = 0;
+
+ sc->sc_txctx_ipcs = 0xffffffff;
+ sc->sc_txctx_tucs = 0xffffffff;
+
+ CSR_WRITE(sc,WMREG_TBDAH, 0);
+ CSR_WRITE(sc,WMREG_TBDAL, WM_CDTXADDR(sc));
+#ifdef WM_DEBUG
+ printk("TBDAL 0x%x, TDLEN %d\n", WM_CDTXADDR(sc), sizeof(sc->sc_txdescs));
+#endif
+ CSR_WRITE(sc,WMREG_TDLEN, sizeof(sc->sc_txdescs));
+ CSR_WRITE(sc,WMREG_TDH, 0);
+ CSR_WRITE(sc,WMREG_TDT, 0);
+ CSR_WRITE(sc,WMREG_TIDV, 0 );
+ /* CSR_WRITE(sc,WMREG_TADV, 128); not for 82544 */
+
+ CSR_WRITE(sc,WMREG_TXDCTL, TXDCTL_PTHRESH(0) |
+ TXDCTL_HTHRESH(0) | TXDCTL_WTHRESH(0));
+ CSR_WRITE(sc,WMREG_RXDCTL, RXDCTL_PTHRESH(0) |
+ RXDCTL_HTHRESH(0) | RXDCTL_WTHRESH(1) | RXDCTL_GRAN );
+
+ CSR_WRITE(sc,WMREG_TQSA_LO, 0);
+ CSR_WRITE(sc,WMREG_TQSA_HI, 0);
+
+ /*
+ * Set up checksum offload parameters for
+ * this packet.
+ */
+#ifdef RTEMS_CKSUM_OFFLOAD
+ if (m0->m_pkthdr.csum_flags & (M_CSUM_TSOv4|M_CSUM_TSOv6|
+ M_CSUM_IPv4|M_CSUM_TCPv4|M_CSUM_UDPv4|
+ M_CSUM_TCPv6|M_CSUM_UDPv6)) {
+ if (wm_tx_offload(sc, txs, &TxDescCmd,&cksumfields) != 0) {
+ /* Error message already displayed. */
+ continue;
+ }
+ } else {
+#endif
+ TxDescCmd = 0;
+ cksumfields = 0;
+#ifdef RTEMS_CKSUM_OFFLOAD
+ }
+#endif
+
+ TxDescCmd |= WTX_CMD_EOP|WTX_CMD_IFCS|WTX_CMD_RS;
+
+ /* Initialize the transmit job descriptors. */
+ for (i = 0; i < NTXDESC; i++) {
+ sc->txs_mbuf[i] = 0;
+ sc->sc_txdescs[i].wtx_fields.wtxu_options=cksumfields;
+ sc->sc_txdescs[i].wtx_addr.wa_high = 0;
+ sc->sc_txdescs[i].wtx_addr.wa_low = 0;
+ sc->sc_txdescs[i].wtx_cmdlen = htole32(TxDescCmd);
+ }
+
+ /*
+ * Initialize the receive descriptor and receive job
+ * descriptor rings.
+ */
+ memset( (void *) sc->sc_rxdescs, 0, sizeof(sc->sc_rxdescs));
+ CSR_WRITE(sc,WMREG_RDBAH, 0);
+ CSR_WRITE(sc,WMREG_RDBAL, WM_CDRXADDR(sc));
+ CSR_WRITE(sc,WMREG_RDLEN, sizeof(sc->sc_rxdescs));
+ CSR_WRITE(sc,WMREG_RDH, 0);
+ CSR_WRITE(sc,WMREG_RDT, 0);
+ CSR_WRITE(sc,WMREG_RDTR, 0 |RDTR_FPD);
+ /* CSR_WRITE(sc, WMREG_RADV, 256); not for 82544. */
+
+ for (i = 0; i < NRXDESC; i++) {
+ if (sc->rxs_mbuf[i] == NULL) {
+ if ((error = wm_add_rxbuf(sc, i)) != 0) {
+ printk("%s%d: unable to allocate or map rx buffer"
+ "%d, error = %d\n",ifp->if_name,ifp->if_unit, i, error);
+ /*
+ * XXX Should attempt to run with fewer receive
+ * XXX buffers instead of just failing.
+ */
+ wm_rxdrain(sc);
+ return(error);
+ }
+ } else {
+ printk("sc->rxs_mbuf[%d] not NULL.\n", i);
+ wm_init_rxdesc(sc, i);
+ }
+ }
+ sc->sc_rxptr = 0;
+ sc->sc_rxdiscard = 0;
+
+ /*
+ * Clear out the VLAN table -- we don't use it (yet).
+ */
+ CSR_WRITE(sc,WMREG_VET, 0);
+ for (i = 0; i < WM_VLAN_TABSIZE; i++)
+ CSR_WRITE(sc,WMREG_VFTA + (i << 2), 0);
+
+#if 0
+ /* Use MOTLoad default
+ *
+ * Set up flow-control parameters.
+ */
+ CSR_WRITE(sc,WMREG_FCAL, FCAL_CONST);/* same as MOTLOAD 0x00c28001 */
+ CSR_WRITE(sc,WMREG_FCAH, FCAH_CONST);/* same as MOTLOAD 0x00000100 */
+ CSR_WRITE(sc,WMREG_FCT, ETHERTYPE_FLOWCONTROL);/* same as MOTLoad 0x8808 */
+
+
+ /* safe,even though MOTLoad default all 0 */
+ sc->sc_fcrtl = FCRTL_DFLT;
+
+ CSR_WRITE(sc,WMREG_FCRTH, FCRTH_DFLT);
+ CSR_WRITE(sc,WMREG_FCRTL, sc->sc_fcrtl);
+ /*KATETO CSR_WRITE(sc,WMREG_FCTTV, FCTTV_DFLT);*/
+ CSR_WRITE(sc,WMREG_FCTTV, 0x100);
+#endif
+
+ sc->sc_ctrl &= ~CTRL_VME;
+ /* TODO : not here.
+ Configures flow control settings after link is established
+ sc->sc_ctrl |= CTRL_TFCE | CTRL_RFCE; */
+
+ /* Write the control registers. */
+ CSR_WRITE(sc,WMREG_CTRL, sc->sc_ctrl);
+#if 0
+ CSR_WRITE(sc,WMREG_CTRL_EXT, sc->sc_ctrl_ext);
+#endif
+
+ /* MOTLoad : WMREG_RXCSUM (0x5000)= 0, no Rx checksum offloading */
+#ifdef RTEMS_CKSUM_OFFLOAD
+ /*
+ * Set up checksum offload parameters.
+ */
+ reg = CSR_READ(sc, WMREG_RXCSUM);
+ reg &= ~(RXCSUM_IPOFL | RXCSUM_IPV6OFL | RXCSUM_TUOFL);
+ if (ifp->if_capenable & IFCAP_CSUM_IPv4_Rx)
+ reg |= RXCSUM_IPOFL;
+ if (ifp->if_capenable & (IFCAP_CSUM_TCPv4_Rx | IFCAP_CSUM_UDPv4_Rx))
+ reg |= RXCSUM_IPOFL | RXCSUM_TUOFL;
+ if (ifp->if_capenable & (IFCAP_CSUM_TCPv6_Rx | IFCAP_CSUM_UDPv6_Rx))
+ reg |= RXCSUM_IPV6OFL | RXCSUM_TUOFL;
+ CSR_WRITE(sc, WMREG_RXCSUM, reg);
+#endif
+
+ /*
+ * Set up the interrupt registers.
+ */
+ CSR_WRITE(sc,WMREG_IMC, 0xffffffffU);
+
+ /* Reading the WMREG_ICR clears the interrupt bits */
+ CSR_READ(sc,WMREG_ICR);
+
+ /* printf("WMREG_IMS 0x%x\n", CSR_READ(sc,WMREG_IMS));*/
+
+ sc->sc_icr = ICR_TXDW | ICR_LSC | ICR_RXSEQ | ICR_RXCFG | ICR_RXDMT0 | ICR_RXO | ICR_RXT0;
+
+ CSR_WRITE(sc,WMREG_IMS, sc->sc_icr);
+
+ /* Set up the inter-packet gap. */
+ CSR_WRITE(sc,WMREG_TIPG, sc->sc_tipg);
+
+#if 0 /* XXXJRT */
+ /* Set the VLAN ethernetype. */
+ CSR_WRITE(sc,WMREG_VET, ETHERTYPE_VLAN);
+#endif
+
+ /*
+ * Set up the transmit control register; we start out with
+ * a collision distance suitable for FDX, but update it when
+ * we resolve the media type.
+ */
+ sc->sc_tctl = TCTL_EN | TCTL_PSP | TCTL_CT(TX_COLLISION_THRESHOLD) |
+ TCTL_COLD(TX_COLLISION_DISTANCE_FDX) |
+ TCTL_RTLC /* retransmit on late collision */;
+
+ /*
+ * Set up the receive control register; we actually program
+ * the register when we set the receive filter. Use multicast
+ * address offset type 0.
+ *
+ * Only the i82544 has the ability to strip the incoming
+ * CRC (RCTL_SECRC).
+ */
+ sc->sc_mchash_type = 0;
+ sc->sc_rctl = RCTL_EN | RCTL_LBM_NONE | RCTL_RDMTS_1_2 | RCTL_LPE |
+ RCTL_DPF | RCTL_MO(sc->sc_mchash_type)|RCTL_SECRC;
+
+ if (MCLBYTES == 2048) {
+ sc->sc_rctl |= RCTL_2k;
+ } else {
+ switch(MCLBYTES) {
+ case 4096:
+ sc->sc_rctl |= RCTL_BSEX | RCTL_BSEX_4k;
+ break;
+ case 8192:
+ sc->sc_rctl |= RCTL_BSEX | RCTL_BSEX_8k;
+ break;
+ case 16384:
+ sc->sc_rctl |= RCTL_BSEX | RCTL_BSEX_16k;
+ break;
+ default:
+ rtems_panic("wm_init: MCLBYTES %d unsupported",
+ MCLBYTES);
+ break;
+ }
+ }
+
+#ifdef WM_DEBUG
+ printk("RDBAL 0x%x,RDLEN %d, RDT %d\n",CSR_READ(sc,WMREG_RDBAL),CSR_READ(sc,WMREG_RDLEN), CSR_READ(sc,WMREG_RDT));
+#endif
+
+ /* Set the receive filter. */
+ wm_set_filter(sc);
+
+ CSR_WRITE(sc,WMREG_TCTL, sc->sc_tctl);
+
+ /* Map and establish our interrupt. */
+ if (!BSP_install_rtems_irq_handler(&i82544IrqData))
+ rtems_panic("1GHZ ethernet: unable to install ISR");
+
+ return(0);
+}
+
+void BSP_rdTIDV(void)
+{
+ printf("Reg TIDV: 0x%" PRIx32 "\n", in_le32((volatile uint32_t *) (BSP_1GHz_membase+WMREG_TIDV)));
+}
+void BSP_rdRDTR(void)
+{
+ printf("Reg RDTR: 0x%" PRIx32 "\n", in_le32((volatile uint32_t *) (BSP_1GHz_membase+WMREG_RDTR)));
+}
+
+void BSP_setTIDV(int val)
+{
+ out_le32((volatile uint32_t *) (BSP_1GHz_membase+WMREG_TIDV), val);
+}
+
+void BSP_setRDTR(int val)
+{
+ out_le32((volatile uint32_t *) (BSP_1GHz_membase+WMREG_RDTR), val);
+}
+/*
+ * i82544EI_ifinit: [ifnet interface function]
+ *
+ * Initialize the interface.
+ */
+static void i82544EI_ifinit(void *arg)
+{
+ struct wm_softc *sc = (struct wm_softc*)arg;
+
+#ifdef WM_DEBUG
+ printk("i82544EI_ifinit(): daemon ID: 0x%08x)\n", sc->daemonTid);
+#endif
+ if (sc->daemonTid) {
+#ifdef WM_DEBUG
+ printk("i82544EI: daemon already up, doing nothing\n");
+#endif
+ return;
+ }
+ i82544EI_init_hw(sc);
+
+ sc->daemonTid = rtems_bsdnet_newproc(i82544EI_TASK_NAME,4096,i82544EI_daemon,arg);
+
+ /* ...all done! */
+ sc->arpcom.ac_if.if_flags |= IFF_RUNNING;
+
+#ifdef WM_DEBUG
+ printk(")");
+#endif
+}
+
+/*
+ * wm_txdrain:
+ *
+ * Drain the transmit queue.
+ */
+static void wm_txdrain(struct wm_softc *sc)
+{
+ int i;
+
+ /* Release any queued transmit buffers. */
+ for (i = 0; i < NTXDESC; i++) {
+ if (sc->txs_mbuf[i] != NULL) {
+ m_freem(sc->txs_mbuf[i]);
+ sc->txs_mbuf[i] = NULL;
+ }
+ }
+}
+
+/*
+ * wm_rxdrain:
+ *
+ * Drain the receive queue.
+ */
+static void wm_rxdrain(struct wm_softc *sc)
+{
+ int i;
+
+ for (i = 0; i < NRXDESC; i++) {
+ if (sc->rxs_mbuf[i] != NULL) {
+ m_freem(sc->rxs_mbuf[i]);
+ sc->rxs_mbuf[i] = NULL;
+ }
+ }
+}
+
+static void i82544EI_tx_stop(struct wm_softc *sc)
+{
+ wm_txdrain(sc);
+}
+
+static void i82544EI_rx_stop(struct wm_softc *sc)
+{
+ wm_rxdrain(sc);
+}
+
+static void i82544EI_stop_hw(struct wm_softc *sc)
+{
+#ifdef WM_DEBUG
+ printk("i82544EI_stop_hw(");
+#endif
+
+ /* remove our interrupt handler which will also
+ * disable interrupts at the MPIC and the device
+ * itself
+ */
+ if (!BSP_remove_rtems_irq_handler(&i82544IrqData))
+ rtems_panic("i82544EI: unable to remove IRQ handler!");
+
+ CSR_WRITE(sc,WMREG_IMS, 0);
+
+ sc->arpcom.ac_if.if_flags &= ~IFF_RUNNING;
+ i82544EI_tx_stop(sc);
+ i82544EI_rx_stop(sc);
+#ifdef WM_DEBUG
+ printk(")");
+#endif
+}
+
+/*
+ * wm_stop: [ifnet interface function]
+ *
+ * Stop transmission on the interface.
+ */
+static void wm_stop(struct ifnet *ifp, int disable)
+{
+ struct wm_softc *sc = ifp->if_softc;
+
+#ifdef WM_DEBUG
+ printk("wm_stop(");
+#endif
+ /* Stop the transmit and receive processes. */
+ CSR_WRITE(sc,WMREG_TCTL, 0);
+ CSR_WRITE(sc,WMREG_RCTL, 0);
+
+ wm_txdrain(sc);
+ wm_rxdrain(sc);
+
+ /* Mark the interface as down */
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+#ifdef WM_DEBUG
+ printk(")\n");
+#endif
+}
+
+/*
+ * wm_eeprom_sendbits:
+ *
+ * Send a series of bits to the EEPROM.
+ */
+static void wm_eeprom_sendbits(struct wm_softc *sc, uint32_t bits, int nbits)
+{
+ uint32_t reg;
+ int x;
+
+ reg = CSR_READ(sc,WMREG_EECD);
+
+ for (x = nbits; x > 0; x--) {
+ if (bits & (1U << (x - 1)))
+ reg |= EECD_DI;
+ else
+ reg &= ~EECD_DI;
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ rtems_bsp_delay(2);
+ CSR_WRITE(sc,WMREG_EECD, reg | EECD_SK);
+ rtems_bsp_delay(2);
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ rtems_bsp_delay(2);
+ }
+}
+
+/*
+ * wm_eeprom_recvbits:
+ *
+ * Receive a series of bits from the EEPROM.
+ */
+static void wm_eeprom_recvbits(struct wm_softc *sc, uint32_t *valp, int nbits)
+{
+ uint32_t reg, val;
+ int x;
+
+ reg = CSR_READ(sc,WMREG_EECD) & ~EECD_DI;
+
+ val = 0;
+ for (x = nbits; x > 0; x--) {
+ CSR_WRITE(sc,WMREG_EECD, reg | EECD_SK);
+ rtems_bsp_delay(2);
+ if (CSR_READ(sc,WMREG_EECD) & EECD_DO)
+ val |= (1U << (x - 1));
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ rtems_bsp_delay(2);
+ }
+ *valp = val;
+}
+
+/*
+ * wm_read_eeprom_uwire:
+ *
+ * Read a word from the EEPROM using the MicroWire protocol.
+ *
+ * (The 82544EI Gigabit Ethernet Controller is compatible with
+ * most MicroWire interface, serial EEPROM devices.)
+ */
+static int wm_read_eeprom_uwire(struct wm_softc *sc, int word, int wordcnt, uint16_t *data)
+{
+ uint32_t reg, val;
+ int i;
+
+ for (i = 0; i < wordcnt; i++) {
+ /* Clear SK and DI. */
+ reg = CSR_READ(sc,WMREG_EECD) & ~(EECD_SK | EECD_DI);
+ CSR_WRITE(sc,WMREG_EECD, reg);
+
+ /* Set CHIP SELECT. */
+ reg |= EECD_CS;
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ rtems_bsp_delay(2);
+
+ /* Shift in the READ command. */
+ wm_eeprom_sendbits(sc, UWIRE_OPC_READ, 3);
+
+ /* Shift in address. */
+ wm_eeprom_sendbits(sc, word + i, sc->sc_ee_addrbits);
+
+ /* Shift out the data. */
+ wm_eeprom_recvbits(sc, &val, 16);
+ data[i] = val & 0xffff;
+
+ /* Clear CHIP SELECT. */
+ reg = CSR_READ(sc,WMREG_EECD) & ~EECD_CS;
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ rtems_bsp_delay(2);
+ }
+ return (0);
+}
+
+#if 0
+/*
+ * wm_acquire_eeprom:
+ *
+ * Perform the EEPROM handshake required on some chips.
+ */
+static int wm_acquire_eeprom(struct wm_softc *sc)
+{
+ uint32_t reg;
+ int x;
+
+ reg = CSR_READ(sc,WMREG_EECD);
+
+ /* Request EEPROM access. */
+ reg |= EECD_EE_REQ;
+ CSR_WRITE(sc,WMREG_EECD, reg);
+
+ /* ..and wait for it to be granted. */
+ for (x = 0; x < 100; x++) {
+ reg = CSR_READ(sc,WMREG_EECD);
+ if (reg & EECD_EE_GNT) break;
+ rtems_bsp_delay(500);
+ }
+ if ((reg & EECD_EE_GNT) == 0) {
+ printk("Could not acquire EEPROM GNT x= %d\n", x);
+ reg &= ~EECD_EE_REQ;
+ CSR_WRITE(sc,WMREG_EECD, reg);
+ return (1);
+ }
+
+ return (0);
+}
+#endif
+
+/*
+ * wm_read_eeprom:
+ *
+ * Read data from the serial EEPROM.
+ * 82544EI does not Perform the EEPROM handshake
+ */
+static int wm_read_eeprom(struct wm_softc *sc, int word, int wordcnt, uint16_t *data)
+{
+#if 0
+ /* base on the datasheet, this does not seem to be applicable */
+ if (wm_acquire_eeprom(sc))
+ return(1);
+#endif
+ return(wm_read_eeprom_uwire(sc, word, wordcnt, data));
+}
+
+/*
+ * wm_add_rxbuf:
+ *
+ * Add a receive buffer to the indiciated descriptor.
+ */
+static int wm_add_rxbuf(struct wm_softc *sc, int idx)
+{
+ struct mbuf *m;
+
+ MGETHDR(m, M_WAIT, MT_DATA);
+ if (m == NULL) return (ENOBUFS);
+ MCLGET(m, M_WAIT);
+ if ((m->m_flags & M_EXT) == 0) {
+ m_freem(m);
+ return (ENOBUFS);
+ }
+ m->m_pkthdr.rcvif = &sc->arpcom.ac_if;
+ sc->rxs_mbuf[idx] = m;
+ /* m->m_len = m->m_pkthdr.len = m->m_ext.ext_size;*/
+ wm_init_rxdesc(sc, idx);
+#if 0
+ printk("sc->rxs_mbuf[%d]= 0x%x, mbuf @ 0x%x\n",
+ idx, sc->rxs_mbuf[idx], le32toh(sc->sc_rxdescs[idx].wrx_addr.wa_low));
+#endif
+ return(0);
+}
+
+/*
+ * wm_set_ral:
+ *
+ * Set an entery in the receive address list.
+ */
+static void
+wm_set_ral(struct wm_softc *sc, const uint8_t *enaddr, int idx)
+{
+ uint32_t ral_lo, ral_hi;
+
+ if (enaddr != NULL) {
+ ral_lo = enaddr[0]|(enaddr[1] << 8)|(enaddr[2] << 16)|(enaddr[3] << 24);
+ ral_hi = enaddr[4] | (enaddr[5] << 8);
+ ral_hi |= RAL_AV;
+ } else {
+ ral_lo = 0;
+ ral_hi = 0;
+ }
+
+ CSR_WRITE(sc,WMREG_RAL_LO(WMREG_CORDOVA_RAL_BASE, idx),ral_lo);
+ CSR_WRITE(sc,WMREG_RAL_HI(WMREG_CORDOVA_RAL_BASE, idx),ral_hi);
+}
+
+/*
+ * wm_mchash:
+ *
+ * Compute the hash of the multicast address for the 4096-bit
+ * multicast filter.
+ */
+static uint32_t
+wm_mchash(struct wm_softc *sc, const uint8_t *enaddr)
+{
+ static const int lo_shift[4] = { 4, 3, 2, 0 };
+ static const int hi_shift[4] = { 4, 5, 6, 8 };
+ uint32_t hash;
+
+ hash = (enaddr[4] >> lo_shift[sc->sc_mchash_type]) |
+ (((uint16_t) enaddr[5]) << hi_shift[sc->sc_mchash_type]);
+
+ return (hash & 0xfff);
+}
+
+/*
+ * wm_set_filter: Set up the receive filter.
+ */
+static void wm_set_filter(struct wm_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct ether_multi *enm;
+ struct ether_multistep step;
+ uint32_t mta_reg;
+ uint32_t hash, reg, bit;
+ int i;
+
+#ifdef WM_DEBUG
+ printk("wm_set_filter(");
+#endif
+ mta_reg = WMREG_CORDOVA_MTA;
+ sc->sc_rctl &= ~(RCTL_BAM | RCTL_UPE | RCTL_MPE);
+
+ if (ifp->if_flags & IFF_BROADCAST)
+ sc->sc_rctl |= RCTL_BAM;
+ if (ifp->if_flags & IFF_PROMISC) {
+ sc->sc_rctl |= RCTL_UPE;
+ goto allmulti;
+ }
+
+ /*
+ * Set the station address in the first RAL slot, and
+ * clear the remaining slots.
+ */
+ wm_set_ral(sc, sc->arpcom.ac_enaddr, 0);
+ for (i = 1; i < WM_RAL_TABSIZE; i++)
+ wm_set_ral(sc, NULL, i);
+
+ /* Clear out the multicast table. */
+ for (i = 0; i < WM_MC_TABSIZE; i++)
+ CSR_WRITE(sc,mta_reg + (i << 2), 0);
+
+ ETHER_FIRST_MULTI(step, &sc->arpcom, enm);
+ while (enm != NULL) {
+ if (memcmp(enm->enm_addrlo, enm->enm_addrhi, ETHER_ADDR_LEN)) {
+ /*
+ * We must listen to a range of multicast addresses.
+ * For now, just accept all multicasts, rather than
+ * trying to set only those filter bits needed to match
+ * the range. (At this time, the only use of address
+ * ranges is for IP multicast routing, for which the
+ * range is big enough to require all bits set.)
+ */
+ goto allmulti;
+ }
+
+ hash = wm_mchash(sc, enm->enm_addrlo);
+
+ reg = (hash >> 5) & 0x7f;
+ bit = hash & 0x1f;
+
+ hash = CSR_READ(sc,mta_reg + (reg << 2));
+ hash |= 1U << bit;
+
+ /* XXX Hardware bug?? */
+ if ((reg & 0xe) == 1) {
+ bit = CSR_READ(sc,mta_reg + ((reg - 1) << 2));
+ CSR_WRITE(sc,mta_reg + (reg << 2), hash);
+ CSR_WRITE(sc,mta_reg + ((reg - 1) << 2), bit);
+ } else
+ CSR_WRITE(sc,mta_reg + (reg << 2), hash);
+
+ ETHER_NEXT_MULTI(step, enm);
+ }
+
+ ifp->if_flags &= ~IFF_ALLMULTI;
+ goto setit;
+
+ allmulti:
+ ifp->if_flags |= IFF_ALLMULTI;
+ sc->sc_rctl |= RCTL_MPE;
+
+ setit:
+ CSR_WRITE(sc,WMREG_RCTL, sc->sc_rctl);
+
+#ifdef WM_DEBUG
+ printk("RCTL 0x%x)\n", CSR_READ(sc,WMREG_RCTL));
+#endif
+}
+
+static void i82544EI_error(struct wm_softc *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ unsigned long intr_status= sc->if_errsts[sc->if_err_ptr1];
+
+ /* read and reset the status; because this is written
+ * by the ISR, we must disable interrupts here
+ */
+ if (intr_status) {
+ printk("Error %s%d:", ifp->if_name, ifp->if_unit);
+ if (intr_status & ICR_RXSEQ) {
+ printk("Rxq framing error (ICR= %x), if_ierrors %d\n",
+ intr_status, ifp->if_ierrors);
+ }
+ }
+ else
+ printk("%s%d: Ghost interrupt ?\n",ifp->if_name,ifp->if_unit);
+ sc->if_errsts[sc->if_err_ptr1]=0;
+ if ((++sc->if_err_ptr1)==IF_ERR_BUFSZE) sc->if_err_ptr1=0; /* Till Straumann */
+}
+
+void i82544EI_printStats(void)
+{
+ i82544EI_stats(root_i82544EI_dev);
+}
+
+/* The daemon does all of the work; RX, TX and cleaning up buffers/descriptors */
+static void i82544EI_daemon(void *arg)
+{
+ struct wm_softc *sc = (struct wm_softc*)arg;
+ rtems_event_set events;
+ struct mbuf *m=0;
+ struct ifnet *ifp=&sc->arpcom.ac_if;
+
+#ifdef WM_DEBUG
+ printk("i82544EI_daemon()\n");
+#endif
+
+ /* NOTE: our creator possibly holds the bsdnet_semaphore.
+ * since that has PRIORITY_INVERSION enabled, our
+ * subsequent call to bsdnet_event_receive() will
+ * _not_ release it. It's still in posession of our
+ * owner.
+ * This is different from how killing this task
+ * is handled.
+ */
+
+ for (;;) {
+ /* sleep until there's work to be done */
+ /* Note: bsdnet_event_receive() acquires
+ * the global bsdnet semaphore for
+ * mutual exclusion.
+ */
+ rtems_bsdnet_event_receive(ALL_EVENTS,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ if (KILL_EVENT & events) break;
+
+ if (events & RX_EVENT) i82544EI_rx(sc); /* in ISR instead */
+
+ /* clean up and try sending packets */
+ do {
+ i82544EI_txq_done(sc);
+
+ while (sc->txq_free>0) {
+ if (sc->txq_free>TXQ_HiLmt_OFF) {
+ m=0;
+ IF_DEQUEUE(&ifp->if_snd,m);
+ if (m==0) break;
+ i82544EI_sendpacket(sc, m);
+ }
+ else {
+ i82544EI_txq_done(sc);
+ break;
+ }
+ }
+ /* we leave this loop
+ * - either because there's no free buffer
+ * (m=0 initializer && !sc->txq_free)
+ * - or there's nothing to send (IF_DEQUEUE
+ * returned 0
+ */
+ } while (m);
+
+ ifp->if_flags &= ~IFF_OACTIVE;
+
+ /* Log errors and other uncommon events. */
+ if (events & ERR_EVENT) i82544EI_error(sc);
+ /* Rx overrun */
+ if ( events & INIT_EVENT) {
+ printk("Warnning, Rx overrun. Make sure the old mbuf was free\n");
+ i82544EI_ifinit(arg);
+ }
+
+ } /* end for(;;) { rtems_bsdnet_event_receive() .....*/
+
+ printf("out of daemon\n");
+ ifp->if_flags &= ~(IFF_RUNNING|IFF_OACTIVE);
+
+ /* shut down the hardware */
+ i82544EI_stop_hw(sc);
+ /* flush the output queue */
+ for (;;) {
+ IF_DEQUEUE(&ifp->if_snd,m);
+ if (!m) break;
+ m_freem(m);
+ }
+ /* as of 'rtems_bsdnet_event_receive()' we own the
+ * networking semaphore
+ */
+ rtems_bsdnet_semaphore_release();
+ rtems_semaphore_release(sc->daemonSync);
+
+ /* Note that I dont use sc->daemonTid here -
+ * theoretically, that variable could already
+ * hold a newly created TID
+ */
+ rtems_task_exit();
+}
+
+/*
+ * wm_gmii_reset:
+ *
+ * Reset the PHY.
+ */
+static void wm_gmii_reset(struct wm_softc *sc)
+{
+
+ CSR_WRITE(sc, WMREG_CTRL, sc->sc_ctrl | CTRL_PHY_RESET);
+ rtems_bsp_delay(20000);
+
+ CSR_WRITE(sc, WMREG_CTRL, sc->sc_ctrl);
+ rtems_bsp_delay(20000);
+
+}
+
+/*
+ * wm_gmii_mediainit:
+ *
+ * Initialize media for use on 1000BASE-T devices.
+ */
+static void wm_gmii_mediainit(struct wm_softc *sc)
+{
+ /* struct ifnet *ifp = &sc->arpcom.ac_if;*/
+
+ /* We have MII. */
+ sc->sc_flags |= WM_F_HAS_MII;
+
+#if 0
+ /* <skf> May 2009 : The value that should be programmed into IPGT is 10 */
+ sc->sc_tipg = TIPG_IPGT(10)+TIPG_IPGR1(8)+TIPG_IPGR2(6);
+#else
+ sc->sc_tipg = TIPG_1000T_DFLT; /* 0x602008 */
+#endif
+
+ /*
+ * Let the chip set speed/duplex on its own based on
+ * signals from the PHY.
+ * XXXbouyer - I'm not sure this is right for the 80003,
+ * the em driver only sets CTRL_SLU here - but it seems to work.
+ */
+ sc->sc_ctrl |= CTRL_SLU;
+ CSR_WRITE(sc, WMREG_CTRL, sc->sc_ctrl);
+
+ wm_gmii_reset(sc);
+
+#if 0
+ /* Initialize our media structures and probe the GMII. */
+ sc->sc_mii.mii_ifp = ifp;
+
+ sc->sc_mii.mii_readreg = wm_gmii_i82544_readreg;
+ sc->sc_mii.mii_writereg = wm_gmii_i82544_writereg;
+ sc->sc_mii.mii_statchg = wm_gmii_statchg;
+
+ ifmedia_init(&sc->sc_mii.mii_media, IFM_IMASK, wm_gmii_mediachange,
+ wm_gmii_mediastatus);
+
+ mii_attach(&sc->sc_dev, &sc->sc_mii, 0xffffffff, MII_PHY_ANY,
+ MII_OFFSET_ANY, MIIF_DOPAUSE);
+ if (LIST_FIRST(&sc->sc_mii.mii_phys) == NULL) {
+ ifmedia_add(&sc->sc_mii.mii_media, IFM_ETHER|IFM_NONE, 0, NULL);
+ ifmedia_set(&sc->sc_mii.mii_media, IFM_ETHER|IFM_NONE);
+ } else
+ ifmedia_set(&sc->sc_mii.mii_media, IFM_ETHER|IFM_AUTO);
+#endif
+}
diff --git a/bsps/powerpc/mvme5500/net/if_1GHz/pci_map.c b/bsps/powerpc/mvme5500/net/if_1GHz/pci_map.c
new file mode 100644
index 0000000..26b143e
--- /dev/null
+++ b/bsps/powerpc/mvme5500/net/if_1GHz/pci_map.c
@@ -0,0 +1,135 @@
+/* $NetBSD: pci_map.c,v 1.12 2002/05/30 12:06:43 drochner Exp $ */
+
+/*-
+ * Copyright (c) 2004, 2005 Brookhaven National Laboratory
+ * S. Kate Feng <feng1@bnl.gov>
+ *
+ * Copyright (c) 1998, 2000 The NetBSD Foundation, Inc.
+ * All rights reserved.
+ *
+ * This code is derived from software contributed to The NetBSD Foundation
+ * by Charles M. Hannum; by William R. Studenmund; by Jason R. Thorpe.
+ *
+ */
+
+/*
+ * PCI device mapping.
+ */
+
+#include <sys/cdefs.h>
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <rtems/rtems/types.h>
+
+#include <bsp/pci.h>
+#include <bsp/pcireg.h>
+
+extern int pci_get_capability(int b, int d, int f, int capid,int *offset,uint32_t *value);
+extern int pci_mem_find(int b, int d, int f, int reg, unsigned *basep,unsigned *sizep);
+extern int pci_io_find(int b, int d, int f, int reg,unsigned *basep,unsigned *sizep);
+
+int pci_io_find(int b, int d, int f, int reg,unsigned *basep,unsigned *sizep)
+{
+ uint32_t address, mask;
+
+ if (reg < PCI_MAPREG_START ||
+#if 0
+ /*
+ * Can't do this check; some devices have mapping registers
+ * way out in left field.
+ */
+ reg >= PCI_MAPREG_END ||
+#endif
+ (reg & 3))
+ rtems_panic("pci_io_find: bad request");
+
+ /*
+ * Section 6.2.5.1, `Address Maps', tells us that:
+ *
+ * 1) The builtin software should have already mapped the device in a
+ * reasonable way.
+ *
+ * 2) A device which wants 2^n bytes of memory will hardwire the bottom
+ * n bits of the address to 0. As recommended, we write all 1s and see
+ * what we get back.
+ */
+ pci_read_config_dword(b,d,f,reg, &address);
+ if ( !(address & PCI_MAPREG_TYPE_IO)) return(1);
+ pci_write_config_dword(b,d,f,reg, 0xffffffff);
+ pci_read_config_dword(b,d,f,reg,&mask);
+ pci_write_config_dword(b,d,f,reg, address);
+
+ if ( (*sizep = PCI_MAPREG_IO_SIZE(mask))== 0) {
+ printk("pci_io_find: void region\n");
+ return(1);
+ }
+ *basep = PCI_MAPREG_IO_ADDR(address);
+ return(0);
+}
+
+int pci_mem_find(int b, int d, int f, int reg, unsigned *basep,unsigned *sizep)
+{
+ uint32_t address, mask;
+
+ if (reg < PCI_MAPREG_START ||
+#if 0
+ /*
+ * Can't do this check; some devices have mapping registers
+ * way out in left field.
+ */
+ reg >= PCI_MAPREG_END ||
+#endif
+ (reg & 3))
+ rtems_panic("pci_mem_find: bad request");
+
+ pci_read_config_dword(b,d,f,reg, &address);
+ if (address & PCI_MAPREG_TYPE_IO) {
+ printk("pci_mem_find: expected type mem, found I/O\n");
+ return(1);
+ }
+
+ /*
+ * Section 6.2.5.1, `Address Maps', tells us that:
+ *
+ * 1) The builtin software should have already mapped the device in a
+ * reasonable way.
+ *
+ * 2) A device which wants 2^n bytes of memory will hardwire the bottom
+ * n bits of the address to 0. As recommended, we write all 1s and see
+ * what we get back.
+ */
+ pci_write_config_dword(b,d,f,reg, 0xffffffff);
+ pci_read_config_dword(b,d,f,reg,&mask);
+ pci_write_config_dword(b,d,f,reg, address);
+ if ( (*sizep = PCI_MAPREG_MEM_SIZE(mask))== 0) {
+ printk("pci_io_find: void region\n");
+ return (1);
+ }
+ *basep = PCI_MAPREG_MEM_ADDR(address);
+ return(0);
+}
+
+int pci_get_capability(int b, int d, int f, int capid,int *offset,uint32_t *value)
+{
+ uint32_t reg, ofs;
+
+ /* i82544EI PCI_CAPLISTPTR_REG */
+ pci_read_config_dword(b,d,f,PCI_CAPLISTPTR_REG, &reg);
+ ofs = PCI_CAPLIST_PTR(reg);
+ while (ofs != 0) {
+#ifdef DIAGNOSTIC
+ if ((ofs & 3) || (ofs < 0x40))
+ panic("pci_get_capability");
+#endif
+ pci_read_config_dword(b,d,f,ofs, &reg);
+ if (PCI_CAPLIST_CAP(reg) == capid) {
+ if (offset)
+ *offset = ofs;
+ if (value)
+ *value = reg;
+ return (1);
+ }
+ ofs = PCI_CAPLIST_NEXT(reg);
+ }
+ return (0);
+}
diff --git a/bsps/powerpc/psim/net/README b/bsps/powerpc/psim/net/README
new file mode 100644
index 0000000..4ca2877
--- /dev/null
+++ b/bsps/powerpc/psim/net/README
@@ -0,0 +1,141 @@
+PSIM NETWORKING HOWTO
+=====================
+
+IMPLEMENTATION INFORMATION
+
+1) NIC hardware emulation.
+
+ In order to simulate networking the simulator (PSIM in our case)
+ has to emulate some networking hardware.
+ At the time of this writing (2009/09 - gdb-6.8) no such emulation
+ is available.
+ However, a patch has been created which adds this functionality
+ to PSIM (see diff in this directory). Unfortunately, implementing
+ a network chip (or some other sort of 'data-source') in PSIM is
+ not quite that simple since PSIM is at the end of the day a single-
+ threaded, monolithic application which has no built-in support for
+ external asynchronous events (e.g., NIC packet reception or a
+ character arriving at a UART [the PSIM BSP uses a polled console
+ driver]).
+ In order to add such asynchronous support, the 'async_io' module
+ was added to PSIM. 'async_io' uses OS-support in the form of
+ a signal (SIGIO) that the OS sends to the PSIM process when I/O
+ becomes possible. The signal handler then executes a callback
+ which e.g., may schedule a PSIM interrupt.
+ However, the use of SIGIO and the O_ASYNC fcntl-flag is not portable
+ (BSD and linux only).
+ The 'ethtap' NIC emulation uses another not quite portable OS
+ service -- the host OS' TUN/TAP device which is some sort of
+ pipe with a networking-interface on one end and a file-system
+ interface on the other. The 'ethtap' NIC reads/writes packets
+ to the file-system interface and they then become available
+ to the host OS' networking.
+ This ascii-art shows how a RTEMS application inside PSIM can
+ communicate with an application on the host with both using
+ sockets. (If the host sets up proper routing table entries
+ then the RTEMS APP can even communicate with the internet...)
+
+
+ RTEMS APP HOST APP
+ | |
+ ............. ............
+ . <socket> . .<socket> .
+ .RTEMS BSD . . HOST OS .
+ .networking . .networking.
+ ............. ............
+
+ ....................... .....................
+ .RTEMS BSD IF "ifsim1". . HOST OS IF: "tap0".
+ .e.g., 10.0.0.100 . . e.g., 10.0.0.1 .
+ ....................... .....................
+ o
+ ............. o
+ .RTEMS ifsim. o
+ . driver . o
+ ............. o
+ || o
+ || o
+ --------------- o
+ ethtap o
+ hw emulation o
+ --------------- o
+ ^ o
+ | o
+ -----> /dev/net/tun (special file on host OS) ooo
+
+
+2) Device-tree. Once PSIM supports the 'ethtap' device then it
+ must be added to the device tree. The following properties are
+ relevant (The register addresses must match with what the
+ BSP/if_sim expects):
+
+ #### ETHTAP @ 0x0c100020 for 0x40
+ #
+
+ /ethtap@0x0c100020/reg 0x0c100020 0x40
+ # route interrupt to open-pic
+ /ethtap@0x0c100020 > 0 irq0 /opic@0x0c130000
+ # 'tun' device on host
+ /ethtap@0x0c100020/tun-device "/dev/net/tun"
+ # name of 'tap' device to use
+ /ethtap@0x0c100020/tap-ifname "tap0"
+ # ethernet address of simulated IF
+ /ethtap@0x0c100020/hw-address "00:00:00:22:11:00"
+ # generate CRC and append to received packet before
+ # handing over to the simulation. This is mostly for
+ # debugging the rtems device driver. If unsure, leave 'false'.
+ /ethtap@0x0c100020/enable-crc false
+
+ The 'tun-device' and 'tap-ifname' properties allow you to
+ configure the name of the special-file and the 'tap' interface
+ on the host.
+
+3) RTEMS driver. The 'if_sim' driver implements a driver for
+ the 'ethtap' device.
+
+USAGE INFORMATION
+
+1) Configure application for networking; the
+ RTEMS_BSP_NETWORK_DRIVER_NAME is "ifsim1"
+ and
+ RTEMS_BSP_NETWORK_DRIVER_ATTACH is rtems_ifsim_attach
+
+2) Patch, configure (--target=powerpc-rtems) and build
+ gdb-6.8. As already mentioned, the NIC emulation only
+ is available if your host-os is linux.
+
+3) Create a 'device-tree' file. The BSP build process produces
+ a shell-script 'psim' residing in
+
+ <bsp_installdir>/powerpc-rtems/psim/tests/
+
+ which can be used for generating a device-tree file.
+
+ Call 'psim -d -n <application>'. The '-n' option adds the
+ emulated interface (the lines above) to the device tree.
+ The resulting file is saved as <application>.device.
+
+ The 'psim' script can also be used to launch an application
+ directly -- just omit the '-d' option.
+
+4) Linux host network configuration:
+ Create a 'permanent' 'tap' interface. This allows you
+ to use 'psim' w/o special privileges (the 'tunctl' command
+ still must be executed by the super-user).
+
+ sudo tunctl -u <uid-of-user-running-psim>
+
+ You now can configure the 'tap0' interface:
+
+ sudo ifconfig tap0 10.0.0.1 up
+
+ and e.g., run a BOOTP server to provide RTEMS with its
+ network configuration:
+
+ sudo dhcpd3 -d tap0
+
+ Assuming that BOOTP gives the RTEMS guest an IP address
+ e.g., '10.0.0.100' you can 'ping' the RTEMS guest
+ from the linux host:
+
+ ping 10.0.0.100
diff --git a/bsps/powerpc/psim/net/gdb-6.8-psim-hw_ethtap.diff b/bsps/powerpc/psim/net/gdb-6.8-psim-hw_ethtap.diff
new file mode 100644
index 0000000..d0aae6e
--- /dev/null
+++ b/bsps/powerpc/psim/net/gdb-6.8-psim-hw_ethtap.diff
@@ -0,0 +1,15893 @@
+ This patch adds a simulated ethernet device 'ethtap' to PSIM.
+ 'ethtap' is currently only supported on linux as it uses
+ two non-portable features:
+ - tun/tap device; packets from/to the emulated system are
+ written-to / read-from an ethernet 'tap' device on the host
+ system (see linux documentation and howtos).
+ - asynchronous IO via fcntl(O_ASYNC). The system notifies
+ the psim process via SIGIO that data has arrived on the
+ file descriptor corresponding to the 'tap' device on the host
+ system. The signal handler then raises a simulated interrupt.
+
+ If this patch is used on a gdb version different from 6.8 then
+ patching the 'configure' and 'config.in' files may fail but they
+ can be recreated with the 'autoconf' and 'autoheader' tools:
+
+ chdir gdb-x.y-srcdir
+ patch -p1 -b < this_patch.diff
+ chdir sim/ppc
+ autoheader
+ autoconf
+
+ At this point you're ready to go...
+
+ More documentation about the 'ethtap' simulated device can be
+ found in sim/ppc/hw_ethtap.c where all the supported device
+ properties etc. are explained.
+
+ Till Straumann, 20090202.
+
+diff -crN gdb-6.8.orig/sim/ppc/async_io.c gdb-6.8/sim/ppc/async_io.c
+*** gdb-6.8.orig/sim/ppc/async_io.c 1969-12-31 16:00:00.000000000 -0800
+--- gdb-6.8/sim/ppc/async_io.c 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 0 ****
+--- 1,244 ----
++ /* This file is part of the program psim.
++
++ Copyright (C) 1994-1996, Andrew Cagney <cagney@highland.com.au>
++
++ 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.
++
++ This file was written by Till Straumann, 2008.
++
++ */
++
++ #ifdef USE_SETSIG
++ #ifdef __linux__
++ #define _GNU_SOURCE /* for F_SETSIG */
++ #endif
++ #endif
++
++ #include <async_io.h>
++
++ #include <fcntl.h>
++ #include <signal.h>
++ #include <stdio.h>
++ #include <errno.h>
++ #include <stdlib.h>
++ #include <string.h>
++ #include <unistd.h>
++
++ #include <poll.h>
++ #define ASYNC_RD_SIGNO SIGIO
++ #define ASYNC_WR_SIGNO SIGIO
++
++ /* Maximum number of file-descriptors we can deal with */
++ #define MAX_FDS 10
++
++
++ static int numFds = 0;
++
++ static struct pollfd pollFds[MAX_FDS];
++
++ static struct {
++ HwAsyncIoCallback cb;
++ void *uarg;
++ } pollCbs[MAX_FDS];
++
++ static sigset_t iomsk;
++
++ static int nest=-1;
++
++ /* Signal Handler */
++ static void
++ hwAsync_sa(int sig
++ #ifdef USE_SIGINFO
++ , struct siginfo *si, void *uctxt
++ #endif
++ )
++ {
++ int i;
++ unsigned reason;
++
++ if ( poll(pollFds, numFds, 0) < 0 ) {
++ fprintf(stderr,"hwAsync_sa(): poll failed: %s\n", strerror(errno));
++ exit(1);
++ }
++
++ /* dispatch callbacks */
++ for ( i=0; i<numFds; i++ ) {
++ if ( pollFds[i].revents ) {
++ if ( pollFds[i].revents & (POLLERR | POLLHUP | POLLNVAL) ) {
++ reason = ASYNC_IO_ERROR;
++ } else {
++ reason = 0;
++ if ( pollFds[i].revents & POLLIN )
++ reason |= ASYNC_IO_READ_POSSIBLE;
++ if ( pollFds[i].revents & POLLOUT )
++ reason |= ASYNC_IO_WRITE_POSSIBLE;
++ }
++ pollCbs[i].cb(pollFds[i].fd, reason, pollCbs[i].uarg);
++ }
++ }
++ }
++
++ /* Do lazy init when the first descriptor is registered */
++ static void
++ hwAsyncIoInit()
++ {
++ struct sigaction sa;
++
++ memset(&sa, 0, sizeof(sa));
++ #ifdef USE_SIGINFO
++ sa.sa_sigaction = hwAsync_sa;
++ sa.sa_flags |= SA_SIGINFO;
++ #else
++ sa.sa_handler = hwAsync_sa;
++ #endif
++
++ sigemptyset(&iomsk);
++ sigaddset(&iomsk, ASYNC_RD_SIGNO);
++ sigaddset(&iomsk, ASYNC_WR_SIGNO);
++
++ sa.sa_mask = iomsk;
++
++ if ( sigaction(ASYNC_RD_SIGNO, &sa, 0) ) {
++ fprintf(stderr, "sigaction(ASYNC_RD_SIGNO) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++
++ #if ASYNC_RD_SIGNO != ASYNC_WR_SIGNO
++ if ( sigaction(ASYNC_WR_SIGNO, &sa, 0) ) {
++ fprintf(stderr, "sigaction(ASYNC_WR_SIGNO) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++ #endif
++
++ nest = 0;
++ }
++
++ int
++ hwAsyncIoBlock()
++ {
++
++ if ( 0 == nest )
++ sigprocmask(SIG_BLOCK, &iomsk, 0);
++ return nest++;
++ }
++
++ void
++ hwAsyncIoUnblock(int lvl)
++ {
++ if ( --nest != lvl ) {
++ fprintf(stderr,"INTERNAL ERROR; nesting should be == level\n");
++ exit(1);
++ }
++ if ( 0 == nest )
++ sigprocmask(SIG_UNBLOCK, &iomsk, 0);
++ }
++
++ static void
++ fdSetup(int fd)
++ {
++
++ if ( fcntl(fd, F_SETFL, O_NONBLOCK | O_ASYNC) ) {
++ fprintf(stderr, "fcntl(F_SETFL) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++
++ #if defined(__linux__) && defined(_GNU_SOURCE)
++ /* si_fd is only set if F_SETSIG is executed (even if specifying SIGIO)! */
++ if ( fcntl(fd, F_SETSIG, SIGIO) ) {
++ fprintf(stderr, "fcntl(F_SETSIG) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++ #endif
++
++ if ( fcntl(fd, F_SETOWN, getpid()) ) {
++ fprintf(stderr, "fcntl(F_SETOWN) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++ }
++
++ int
++ hwAsyncIoUnregister(int fd, HwAsyncIoCallback cb, void *uarg)
++ {
++ int lvl, i;
++
++ for ( i=0; i<numFds; i++ ) {
++ if ( pollFds[i].fd == fd ) {
++
++ lvl = hwAsyncIoBlock();
++ --numFds;
++ while ( i < numFds )
++ pollFds[i] = pollFds[i+1];
++ hwAsyncIoUnblock(lvl);
++
++ if ( fcntl(fd, F_SETFL, 0) ) {
++ fprintf(stderr, "fcntl(F_SETFL) failed: %s\n", strerror(errno));
++ exit(1);
++ }
++ return 0;
++ }
++ }
++
++ return -1;
++ }
++
++ int
++ hwAsyncIoRegister(int fd, HwAsyncIoCallback cb, void *uarg)
++ {
++ int i;
++ int lvl;
++
++ /* lazy init */
++ if ( nest < 0 )
++ hwAsyncIoInit();
++
++ for ( i=0; i<numFds; i++ ) {
++ if ( pollFds[i].fd == fd ) {
++ /* this fd already registered */
++ return -2;
++ }
++ }
++
++ if ( i >= MAX_FDS ) {
++ /* all slots full */
++ return -3;
++ }
++
++ pollFds[i].fd = fd;
++ pollFds[i].events = POLLIN | POLLOUT;
++
++ pollCbs[i].cb = cb;
++ pollCbs[i].uarg = uarg;
++
++ lvl = hwAsyncIoBlock();
++ numFds++;
++ hwAsyncIoUnblock(lvl);
++
++ /* Now set the fd up for asynchronous operation */
++ fdSetup(fd);
++
++ return fd;
++ }
++
++ int
++ hwAsyncIoWrite(int fd, void *buf, size_t cnt)
++ {
++ return write(fd, buf, cnt);
++ }
++
++ int
++ hwAsyncIoRead(int fd, void *buf, size_t cnt)
++ {
++ return read(fd, buf, cnt);
++ }
+diff -crN gdb-6.8.orig/sim/ppc/async_io.h gdb-6.8/sim/ppc/async_io.h
+*** gdb-6.8.orig/sim/ppc/async_io.h 1969-12-31 16:00:00.000000000 -0800
+--- gdb-6.8/sim/ppc/async_io.h 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 0 ****
+--- 1,123 ----
++ /* This file is part of the program psim.
++
++ Copyright (C) 1994-1996, Andrew Cagney <cagney@highland.com.au>
++
++ 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.
++
++ This file was written by Till Straumann, 2008.
++
++ */
++
++ #ifndef _ASYNC_IO_H
++ #define _ASYNC_IO_H
++
++ #include <unistd.h>
++ #include <sys/types.h>
++ #ifdef _POSIX_ASYNCHRONOUS_IO
++ #include <aio.h>
++ #endif
++
++ /* A simple facility to allow asynchronous I/O (which then can
++ * be mapped to simulated interrupts).
++ *
++ * REQUIRES O_ASYNC support from the OS.
++ *
++ * A file descriptor is registered with this facility for
++ * asynchronous I/O. It is then switched to ASYNC mode and
++ * signal delivery of SIGIO is enabled.
++ *
++ * When I/O becomes possible a user callback is dispatched (possibly
++ * executing from signal handler context). The callback can be
++ * used to schedule interrupt delivery.
++ */
++
++ /* Prototype of user callback.
++ *
++ * The callback is passed
++ *
++ * 'fd': file descriptor on which I/O is now possible.
++ * 'reasonBitmask': bitset of events or an error code (if MSB set).
++ * 'uarg': user pointer as passed to the registration routine.
++ *
++ * NOTE: callback may execute from signal handler.
++ */
++
++ #define ASYNC_IO_READ_POSSIBLE 1
++ #define ASYNC_IO_WRITE_POSSIBLE 2
++ #define ASYNC_IO_ERROR (-1)
++ #define ASYNC_IO_ERR(reason) ((int)(reason) < 0)
++
++ typedef void (*HwAsyncIoCallback)(int fd, unsigned reasonBitmask, void *uarg);
++
++ /*
++ * Enable asynchronous, nonblocking I/O on a (open) file descriptor
++ * and register a callback to be dispatched when I/O becomes possible
++ * on 'fd'.
++ *
++ * Arguments:
++ * 'fd': file descriptor to configure for asynchronous I/O.
++ * 'cb': callback to be dispatched when I/O becomes possible.
++ * 'uarg': arbitrary pointer which is passed on to the callback.
++ *
++ * RETURNS: descriptor number (>=0) on success, value < 0 on error.
++ * The descriptor number has to be passed to hwAsyncIoRead/Write
++ * and Unregister and is NOT necessarily identical with the
++ * original file descriptor!
++ *
++ */
++ int
++ hwAsyncIoRegister(int fd, HwAsyncIoCallback cb, void *uarg);
++
++ /*
++ *
++ * Unregisters the callback and removes the ASYNC and NONBLOCK flags.
++ *
++ * RETURNS: zero on success, nonzero on error.
++ *
++ * NOTE: pass DESCRIPTOR number, not original fd.
++ */
++
++ int
++ hwAsyncIoUnregister(int desc, HwAsyncIoCallback cb, void *uarg);
++
++ /*
++ * Disable delivery of SIGIO and thus prevent the callback
++ * from being executed in order to protect a critical section.
++ *
++ * NOTE: Nested calls are possible, i.e., in a sequence
++ * block(), block(), unblock(), unblock() signal delivery
++ * is only re-enabled by the last unblock() operation.
++ *
++ * RETURNS: a 'key' which must be passed to paired 'unblock' operation.
++ */
++ int
++ hwAsyncIoBlock();
++
++ /*
++ * Unnest and possibly re-enable delivery of SIGIO.
++ *
++ * Argument:
++ * 'key': value returned by paired 'block' operation.
++ */
++ void
++ hwAsyncIoUnblock(int level);
++
++ int
++ hwAsyncIoRead(int desc, void *buf, size_t cnt);
++
++ int
++ hwAsyncIoRead(int desc, void *buf, size_t cnt);
++
++ #endif /* _ASYNC_IO_H_ */
+diff -crN gdb-6.8.orig/sim/ppc/config.in gdb-6.8/sim/ppc/config.in
+*** gdb-6.8.orig/sim/ppc/config.in 2006-12-20 20:42:10.000000000 -0800
+--- gdb-6.8/sim/ppc/config.in 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 32,37 ****
+--- 32,41 ----
+ /* Define to 1 if you have the `chown' function. */
+ #undef HAVE_CHOWN
+
++ /* Define to 1 if you have the declaration of `tzname', and to 0 if you don't.
++ */
++ #undef HAVE_DECL_TZNAME
++
+ /* Define to 1 if you have the <dirent.h> header file, and it defines `DIR'.
+ */
+ #undef HAVE_DIRENT_H
+***************
+*** 42,47 ****
+--- 46,54 ----
+ /* Define to 1 if you have the `dup2' function. */
+ #undef HAVE_DUP2
+
++ /* Define if ethtap device is built (linux host only) */
++ #undef HAVE_ETHTAP
++
+ /* Define to 1 if you have the `fchmod' function. */
+ #undef HAVE_FCHMOD
+
+***************
+*** 300,308 ****
+ when building for Cygwin. */
+ #undef USE_WIN32API
+
+! /* Define to 1 if your processor stores words with the most significant byte
+! first (like Motorola and SPARC, unlike Intel and VAX). */
+! #undef WORDS_BIGENDIAN
+
+ /* Define to `int' if <sys/types.h> doesn't define. */
+ #undef gid_t
+--- 307,319 ----
+ when building for Cygwin. */
+ #undef USE_WIN32API
+
+! /* Define WORDS_BIGENDIAN to 1 if your processor stores words with the most
+! significant byte first (like Motorola and SPARC, unlike Intel and VAX). */
+! #if defined __BIG_ENDIAN__
+! # define WORDS_BIGENDIAN 1
+! #elif ! defined __LITTLE_ENDIAN__
+! # undef WORDS_BIGENDIAN
+! #endif
+
+ /* Define to `int' if <sys/types.h> doesn't define. */
+ #undef gid_t
+***************
+*** 310,322 ****
+ /* Define to `int' if <sys/types.h> does not define. */
+ #undef mode_t
+
+! /* Define to `long' if <sys/types.h> does not define. */
+ #undef off_t
+
+ /* Define to `int' if <sys/types.h> does not define. */
+ #undef pid_t
+
+! /* Define to `unsigned' if <sys/types.h> does not define. */
+ #undef size_t
+
+ /* Define to `int' if <sys/types.h> doesn't define. */
+--- 321,333 ----
+ /* Define to `int' if <sys/types.h> does not define. */
+ #undef mode_t
+
+! /* Define to `long int' if <sys/types.h> does not define. */
+ #undef off_t
+
+ /* Define to `int' if <sys/types.h> does not define. */
+ #undef pid_t
+
+! /* Define to `unsigned int' if <sys/types.h> does not define. */
+ #undef size_t
+
+ /* Define to `int' if <sys/types.h> doesn't define. */
+diff -crN gdb-6.8.orig/sim/ppc/configure gdb-6.8/sim/ppc/configure
+*** gdb-6.8.orig/sim/ppc/configure 2008-03-14 14:35:27.000000000 -0700
+--- gdb-6.8/sim/ppc/configure 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 1,25 ****
+ #! /bin/sh
+ # Guess values for system-dependent variables and create Makefiles.
+! # Generated by GNU Autoconf 2.59.
+ #
+! # Copyright (C) 2003 Free Software Foundation, Inc.
+ # This configure script is free software; the Free Software Foundation
+ # gives unlimited permission to copy, distribute and modify it.
+ ## --------------------- ##
+ ## M4sh Initialization. ##
+ ## --------------------- ##
+
+! # Be Bourne compatible
+ if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+ emulate sh
+ NULLCMD=:
+! # Zsh 3.x and 4.x performs word splitting on ${1+"$@"}, which
+ # is contrary to our usage. Disable this feature.
+ alias -g '${1+"$@"}'='"$@"'
+! elif test -n "${BASH_VERSION+set}" && (set -o posix) >/dev/null 2>&1; then
+! set -o posix
+ fi
+- DUALCASE=1; export DUALCASE # for MKS sh
+
+ # Support unset when possible.
+ if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then
+--- 1,82 ----
+ #! /bin/sh
+ # Guess values for system-dependent variables and create Makefiles.
+! # Generated by GNU Autoconf 2.62.
+ #
+! # Copyright (C) 1992, 1993, 1994, 1995, 1996, 1998, 1999, 2000, 2001,
+! # 2002, 2003, 2004, 2005, 2006, 2007, 2008 Free Software Foundation, Inc.
+ # This configure script is free software; the Free Software Foundation
+ # gives unlimited permission to copy, distribute and modify it.
+ ## --------------------- ##
+ ## M4sh Initialization. ##
+ ## --------------------- ##
+
+! # Be more Bourne compatible
+! DUALCASE=1; export DUALCASE # for MKS sh
+ if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+ emulate sh
+ NULLCMD=:
+! # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which
+ # is contrary to our usage. Disable this feature.
+ alias -g '${1+"$@"}'='"$@"'
+! setopt NO_GLOB_SUBST
+! else
+! case `(set -o) 2>/dev/null` in
+! *posix*) set -o posix ;;
+! esac
+!
+! fi
+!
+!
+!
+!
+! # PATH needs CR
+! # Avoid depending upon Character Ranges.
+! as_cr_letters='abcdefghijklmnopqrstuvwxyz'
+! as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ'
+! as_cr_Letters=$as_cr_letters$as_cr_LETTERS
+! as_cr_digits='0123456789'
+! as_cr_alnum=$as_cr_Letters$as_cr_digits
+!
+! as_nl='
+! '
+! export as_nl
+! # Printing a long string crashes Solaris 7 /usr/bin/printf.
+! as_echo='\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\'
+! as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo
+! as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo$as_echo
+! if (test "X`printf %s $as_echo`" = "X$as_echo") 2>/dev/null; then
+! as_echo='printf %s\n'
+! as_echo_n='printf %s'
+! else
+! if test "X`(/usr/ucb/echo -n -n $as_echo) 2>/dev/null`" = "X-n $as_echo"; then
+! as_echo_body='eval /usr/ucb/echo -n "$1$as_nl"'
+! as_echo_n='/usr/ucb/echo -n'
+! else
+! as_echo_body='eval expr "X$1" : "X\\(.*\\)"'
+! as_echo_n_body='eval
+! arg=$1;
+! case $arg in
+! *"$as_nl"*)
+! expr "X$arg" : "X\\(.*\\)$as_nl";
+! arg=`expr "X$arg" : ".*$as_nl\\(.*\\)"`;;
+! esac;
+! expr "X$arg" : "X\\(.*\\)" | tr -d "$as_nl"
+! '
+! export as_echo_n_body
+! as_echo_n='sh -c $as_echo_n_body as_echo'
+! fi
+! export as_echo_body
+! as_echo='sh -c $as_echo_body as_echo'
+! fi
+!
+! # The user is always right.
+! if test "${PATH_SEPARATOR+set}" != set; then
+! PATH_SEPARATOR=:
+! (PATH='/bin;/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 && {
+! (PATH='/bin:/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 ||
+! PATH_SEPARATOR=';'
+! }
+ fi
+
+ # Support unset when possible.
+ if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then
+***************
+*** 29,61 ****
+ fi
+
+
+ # Work around bugs in pre-3.0 UWIN ksh.
+! $as_unset ENV MAIL MAILPATH
+ PS1='$ '
+ PS2='> '
+ PS4='+ '
+
+ # NLS nuisances.
+! for as_var in \
+! LANG LANGUAGE LC_ADDRESS LC_ALL LC_COLLATE LC_CTYPE LC_IDENTIFICATION \
+! LC_MEASUREMENT LC_MESSAGES LC_MONETARY LC_NAME LC_NUMERIC LC_PAPER \
+! LC_TELEPHONE LC_TIME
+! do
+! if (set +x; test -z "`(eval $as_var=C; export $as_var) 2>&1`"); then
+! eval $as_var=C; export $as_var
+! else
+! $as_unset $as_var
+! fi
+! done
+
+ # Required to use basename.
+! if expr a : '\(a\)' >/dev/null 2>&1; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+! if (basename /) >/dev/null 2>&1 && test "X`basename / 2>&1`" = "X/"; then
+ as_basename=basename
+ else
+ as_basename=false
+--- 86,145 ----
+ fi
+
+
++ # IFS
++ # We need space, tab and new line, in precisely that order. Quoting is
++ # there to prevent editors from complaining about space-tab.
++ # (If _AS_PATH_WALK were called with IFS unset, it would disable word
++ # splitting by setting IFS to empty value.)
++ IFS=" "" $as_nl"
++
++ # Find who we are. Look in the path if we contain no directory separator.
++ case $0 in
++ *[\\/]* ) as_myself=$0 ;;
++ *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
++ for as_dir in $PATH
++ do
++ IFS=$as_save_IFS
++ test -z "$as_dir" && as_dir=.
++ test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break
++ done
++ IFS=$as_save_IFS
++
++ ;;
++ esac
++ # We did not find ourselves, most probably we were run as `sh COMMAND'
++ # in which case we are not to be found in the path.
++ if test "x$as_myself" = x; then
++ as_myself=$0
++ fi
++ if test ! -f "$as_myself"; then
++ $as_echo "$as_myself: error: cannot find myself; rerun with an absolute file name" >&2
++ { (exit 1); exit 1; }
++ fi
++
+ # Work around bugs in pre-3.0 UWIN ksh.
+! for as_var in ENV MAIL MAILPATH
+! do ($as_unset $as_var) >/dev/null 2>&1 && $as_unset $as_var
+! done
+ PS1='$ '
+ PS2='> '
+ PS4='+ '
+
+ # NLS nuisances.
+! LC_ALL=C
+! export LC_ALL
+! LANGUAGE=C
+! export LANGUAGE
+
+ # Required to use basename.
+! if expr a : '\(a\)' >/dev/null 2>&1 &&
+! test "X`expr 00001 : '.*\(...\)'`" = X001; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+! if (basename -- /) >/dev/null 2>&1 && test "X`basename -- / 2>&1`" = "X/"; then
+ as_basename=basename
+ else
+ as_basename=false
+***************
+*** 63,219 ****
+
+
+ # Name of the executable.
+! as_me=`$as_basename "$0" ||
+ $as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \
+ X"$0" : 'X\(//\)$' \| \
+! X"$0" : 'X\(/\)$' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X/"$0" |
+! sed '/^.*\/\([^/][^/]*\)\/*$/{ s//\1/; q; }
+! /^X\/\(\/\/\)$/{ s//\1/; q; }
+! /^X\/\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+
+
+- # PATH needs CR, and LINENO needs CR and PATH.
+- # Avoid depending upon Character Ranges.
+- as_cr_letters='abcdefghijklmnopqrstuvwxyz'
+- as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ'
+- as_cr_Letters=$as_cr_letters$as_cr_LETTERS
+- as_cr_digits='0123456789'
+- as_cr_alnum=$as_cr_Letters$as_cr_digits
+
+! # The user is always right.
+! if test "${PATH_SEPARATOR+set}" != set; then
+! echo "#! /bin/sh" >conf$$.sh
+! echo "exit 0" >>conf$$.sh
+! chmod +x conf$$.sh
+! if (PATH="/nonexistent;."; conf$$.sh) >/dev/null 2>&1; then
+! PATH_SEPARATOR=';'
+! else
+! PATH_SEPARATOR=:
+! fi
+! rm -f conf$$.sh
+ fi
+
+
+! as_lineno_1=$LINENO
+! as_lineno_2=$LINENO
+! as_lineno_3=`(expr $as_lineno_1 + 1) 2>/dev/null`
+! test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x$as_lineno_3" = "x$as_lineno_2" || {
+! # Find who we are. Look in the path if we contain no path at all
+! # relative or not.
+! case $0 in
+! *[\\/]* ) as_myself=$0 ;;
+! *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+! for as_dir in $PATH
+! do
+! IFS=$as_save_IFS
+! test -z "$as_dir" && as_dir=.
+! test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break
+! done
+
+! ;;
+! esac
+! # We did not find ourselves, most probably we were run as `sh COMMAND'
+! # in which case we are not to be found in the path.
+! if test "x$as_myself" = x; then
+! as_myself=$0
+! fi
+! if test ! -f "$as_myself"; then
+! { echo "$as_me: error: cannot find myself; rerun with an absolute path" >&2
+! { (exit 1); exit 1; }; }
+! fi
+! case $CONFIG_SHELL in
+! '')
+ as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+ for as_dir in /bin$PATH_SEPARATOR/usr/bin$PATH_SEPARATOR$PATH
+ do
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+! for as_base in sh bash ksh sh5; do
+! case $as_dir in
+ /*)
+! if ("$as_dir/$as_base" -c '
+ as_lineno_1=$LINENO
+ as_lineno_2=$LINENO
+- as_lineno_3=`(expr $as_lineno_1 + 1) 2>/dev/null`
+ test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x$as_lineno_3" = "x$as_lineno_2" ') 2>/dev/null; then
+! $as_unset BASH_ENV || test "${BASH_ENV+set}" != set || { BASH_ENV=; export BASH_ENV; }
+! $as_unset ENV || test "${ENV+set}" != set || { ENV=; export ENV; }
+! CONFIG_SHELL=$as_dir/$as_base
+! export CONFIG_SHELL
+! exec "$CONFIG_SHELL" "$0" ${1+"$@"}
+! fi;;
+! esac
+! done
+! done
+! ;;
+! esac
+
+ # Create $as_me.lineno as a copy of $as_myself, but with $LINENO
+ # uniformly replaced by the line number. The first 'sed' inserts a
+! # line-number line before each line; the second 'sed' does the real
+! # work. The second script uses 'N' to pair each line-number line
+! # with the numbered line, and appends trailing '-' during
+! # substitution so that $LINENO is not a special case at line end.
+ # (Raja R Harinath suggested sed '=', and Paul Eggert wrote the
+! # second 'sed' script. Blame Lee E. McMahon for sed's syntax. :-)
+! sed '=' <$as_myself |
+ sed '
+ N
+! s,$,-,
+! : loop
+! s,^\(['$as_cr_digits']*\)\(.*\)[$]LINENO\([^'$as_cr_alnum'_]\),\1\2\1\3,
+ t loop
+! s,-$,,
+! s,^['$as_cr_digits']*\n,,
+ ' >$as_me.lineno &&
+! chmod +x $as_me.lineno ||
+! { echo "$as_me: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&2
+ { (exit 1); exit 1; }; }
+
+ # Don't try to exec as it changes $[0], causing all sort of problems
+ # (the dirname of $[0] is not the place where we might find the
+! # original and so on. Autoconf is especially sensible to this).
+! . ./$as_me.lineno
+ # Exit status is that of the last command.
+ exit
+ }
+
+
+! case `echo "testing\c"; echo 1,2,3`,`echo -n testing; echo 1,2,3` in
+! *c*,-n*) ECHO_N= ECHO_C='
+! ' ECHO_T=' ' ;;
+! *c*,* ) ECHO_N=-n ECHO_C= ECHO_T= ;;
+! *) ECHO_N= ECHO_C='\c' ECHO_T= ;;
+! esac
+
+! if expr a : '\(a\)' >/dev/null 2>&1; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+ rm -f conf$$ conf$$.exe conf$$.file
+! echo >conf$$.file
+! if ln -s conf$$.file conf$$ 2>/dev/null; then
+! # We could just check for DJGPP; but this test a) works b) is more generic
+! # and c) will remain valid once DJGPP supports symlinks (DJGPP 2.04).
+! if test -f conf$$.exe; then
+! # Don't use ln at all; we don't have any links
+! as_ln_s='cp -p'
+! else
+ as_ln_s='ln -s'
+ fi
+- elif ln conf$$.file conf$$ 2>/dev/null; then
+- as_ln_s=ln
+ else
+ as_ln_s='cp -p'
+ fi
+! rm -f conf$$ conf$$.exe conf$$.file
+
+ if mkdir -p . 2>/dev/null; then
+ as_mkdir_p=:
+--- 147,537 ----
+
+
+ # Name of the executable.
+! as_me=`$as_basename -- "$0" ||
+ $as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \
+ X"$0" : 'X\(//\)$' \| \
+! X"$0" : 'X\(/\)' \| . 2>/dev/null ||
+! $as_echo X/"$0" |
+! sed '/^.*\/\([^/][^/]*\)\/*$/{
+! s//\1/
+! q
+! }
+! /^X\/\(\/\/\)$/{
+! s//\1/
+! q
+! }
+! /^X\/\(\/\).*/{
+! s//\1/
+! q
+! }
+! s/.*/./; q'`
+
++ # CDPATH.
++ $as_unset CDPATH
+
+
+! if test "x$CONFIG_SHELL" = x; then
+! if (eval ":") 2>/dev/null; then
+! as_have_required=yes
+! else
+! as_have_required=no
+ fi
+
++ if test $as_have_required = yes && (eval ":
++ (as_func_return () {
++ (exit \$1)
++ }
++ as_func_success () {
++ as_func_return 0
++ }
++ as_func_failure () {
++ as_func_return 1
++ }
++ as_func_ret_success () {
++ return 0
++ }
++ as_func_ret_failure () {
++ return 1
++ }
+
+! exitcode=0
+! if as_func_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_success failed.
+! fi
+
+! if as_func_failure; then
+! exitcode=1
+! echo as_func_failure succeeded.
+! fi
+!
+! if as_func_ret_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_ret_success failed.
+! fi
+!
+! if as_func_ret_failure; then
+! exitcode=1
+! echo as_func_ret_failure succeeded.
+! fi
+!
+! if ( set x; as_func_ret_success y && test x = \"\$1\" ); then
+! :
+! else
+! exitcode=1
+! echo positional parameters were not saved.
+! fi
+!
+! test \$exitcode = 0) || { (exit 1); exit 1; }
+!
+! (
+! as_lineno_1=\$LINENO
+! as_lineno_2=\$LINENO
+! test \"x\$as_lineno_1\" != \"x\$as_lineno_2\" &&
+! test \"x\`expr \$as_lineno_1 + 1\`\" = \"x\$as_lineno_2\") || { (exit 1); exit 1; }
+! ") 2> /dev/null; then
+! :
+! else
+! as_candidate_shells=
+ as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+ for as_dir in /bin$PATH_SEPARATOR/usr/bin$PATH_SEPARATOR$PATH
+ do
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+! case $as_dir in
+ /*)
+! for as_base in sh bash ksh sh5; do
+! as_candidate_shells="$as_candidate_shells $as_dir/$as_base"
+! done;;
+! esac
+! done
+! IFS=$as_save_IFS
+!
+!
+! for as_shell in $as_candidate_shells $SHELL; do
+! # Try only shells that exist, to save several forks.
+! if { test -f "$as_shell" || test -f "$as_shell.exe"; } &&
+! { ("$as_shell") 2> /dev/null <<\_ASEOF
+! if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+! emulate sh
+! NULLCMD=:
+! # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which
+! # is contrary to our usage. Disable this feature.
+! alias -g '${1+"$@"}'='"$@"'
+! setopt NO_GLOB_SUBST
+! else
+! case `(set -o) 2>/dev/null` in
+! *posix*) set -o posix ;;
+! esac
+!
+! fi
+!
+!
+! :
+! _ASEOF
+! }; then
+! CONFIG_SHELL=$as_shell
+! as_have_required=yes
+! if { "$as_shell" 2> /dev/null <<\_ASEOF
+! if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+! emulate sh
+! NULLCMD=:
+! # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which
+! # is contrary to our usage. Disable this feature.
+! alias -g '${1+"$@"}'='"$@"'
+! setopt NO_GLOB_SUBST
+! else
+! case `(set -o) 2>/dev/null` in
+! *posix*) set -o posix ;;
+! esac
+!
+! fi
+!
+!
+! :
+! (as_func_return () {
+! (exit $1)
+! }
+! as_func_success () {
+! as_func_return 0
+! }
+! as_func_failure () {
+! as_func_return 1
+! }
+! as_func_ret_success () {
+! return 0
+! }
+! as_func_ret_failure () {
+! return 1
+! }
+!
+! exitcode=0
+! if as_func_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_success failed.
+! fi
+!
+! if as_func_failure; then
+! exitcode=1
+! echo as_func_failure succeeded.
+! fi
+!
+! if as_func_ret_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_ret_success failed.
+! fi
+!
+! if as_func_ret_failure; then
+! exitcode=1
+! echo as_func_ret_failure succeeded.
+! fi
+!
+! if ( set x; as_func_ret_success y && test x = "$1" ); then
+! :
+! else
+! exitcode=1
+! echo positional parameters were not saved.
+! fi
+!
+! test $exitcode = 0) || { (exit 1); exit 1; }
+!
+! (
+ as_lineno_1=$LINENO
+ as_lineno_2=$LINENO
+ test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x`expr $as_lineno_1 + 1`" = "x$as_lineno_2") || { (exit 1); exit 1; }
+!
+! _ASEOF
+! }; then
+! break
+! fi
+!
+! fi
+!
+! done
+!
+! if test "x$CONFIG_SHELL" != x; then
+! for as_var in BASH_ENV ENV
+! do ($as_unset $as_var) >/dev/null 2>&1 && $as_unset $as_var
+! done
+! export CONFIG_SHELL
+! exec "$CONFIG_SHELL" "$as_myself" ${1+"$@"}
+! fi
+!
+!
+! if test $as_have_required = no; then
+! echo This script requires a shell more modern than all the
+! echo shells that I found on your system. Please install a
+! echo modern shell, or manually run the script under such a
+! echo shell if you do have one.
+! { (exit 1); exit 1; }
+! fi
+!
+!
+! fi
+!
+! fi
+!
+!
+!
+! (eval "as_func_return () {
+! (exit \$1)
+! }
+! as_func_success () {
+! as_func_return 0
+! }
+! as_func_failure () {
+! as_func_return 1
+! }
+! as_func_ret_success () {
+! return 0
+! }
+! as_func_ret_failure () {
+! return 1
+! }
+!
+! exitcode=0
+! if as_func_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_success failed.
+! fi
+!
+! if as_func_failure; then
+! exitcode=1
+! echo as_func_failure succeeded.
+! fi
+!
+! if as_func_ret_success; then
+! :
+! else
+! exitcode=1
+! echo as_func_ret_success failed.
+! fi
+!
+! if as_func_ret_failure; then
+! exitcode=1
+! echo as_func_ret_failure succeeded.
+! fi
+!
+! if ( set x; as_func_ret_success y && test x = \"\$1\" ); then
+! :
+! else
+! exitcode=1
+! echo positional parameters were not saved.
+! fi
+!
+! test \$exitcode = 0") || {
+! echo No shell found that supports shell functions.
+! echo Please tell bug-autoconf@gnu.org about your system,
+! echo including any error possibly output before this message.
+! echo This can help us improve future autoconf versions.
+! echo Configuration will now proceed without shell functions.
+! }
+!
+!
+!
+! as_lineno_1=$LINENO
+! as_lineno_2=$LINENO
+! test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x`expr $as_lineno_1 + 1`" = "x$as_lineno_2" || {
+
+ # Create $as_me.lineno as a copy of $as_myself, but with $LINENO
+ # uniformly replaced by the line number. The first 'sed' inserts a
+! # line-number line after each line using $LINENO; the second 'sed'
+! # does the real work. The second script uses 'N' to pair each
+! # line-number line with the line containing $LINENO, and appends
+! # trailing '-' during substitution so that $LINENO is not a special
+! # case at line end.
+ # (Raja R Harinath suggested sed '=', and Paul Eggert wrote the
+! # scripts with optimization help from Paolo Bonzini. Blame Lee
+! # E. McMahon (1931-1989) for sed's syntax. :-)
+! sed -n '
+! p
+! /[$]LINENO/=
+! ' <$as_myself |
+ sed '
++ s/[$]LINENO.*/&-/
++ t lineno
++ b
++ :lineno
+ N
+! :loop
+! s/[$]LINENO\([^'$as_cr_alnum'_].*\n\)\(.*\)/\2\1\2/
+ t loop
+! s/-\n.*//
+ ' >$as_me.lineno &&
+! chmod +x "$as_me.lineno" ||
+! { $as_echo "$as_me: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&2
+ { (exit 1); exit 1; }; }
+
+ # Don't try to exec as it changes $[0], causing all sort of problems
+ # (the dirname of $[0] is not the place where we might find the
+! # original and so on. Autoconf is especially sensitive to this).
+! . "./$as_me.lineno"
+ # Exit status is that of the last command.
+ exit
+ }
+
+
+! if (as_dir=`dirname -- /` && test "X$as_dir" = X/) >/dev/null 2>&1; then
+! as_dirname=dirname
+! else
+! as_dirname=false
+! fi
+
+! ECHO_C= ECHO_N= ECHO_T=
+! case `echo -n x` in
+! -n*)
+! case `echo 'x\c'` in
+! *c*) ECHO_T=' ';; # ECHO_T is single tab character.
+! *) ECHO_C='\c';;
+! esac;;
+! *)
+! ECHO_N='-n';;
+! esac
+! if expr a : '\(a\)' >/dev/null 2>&1 &&
+! test "X`expr 00001 : '.*\(...\)'`" = X001; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+ rm -f conf$$ conf$$.exe conf$$.file
+! if test -d conf$$.dir; then
+! rm -f conf$$.dir/conf$$.file
+! else
+! rm -f conf$$.dir
+! mkdir conf$$.dir 2>/dev/null
+! fi
+! if (echo >conf$$.file) 2>/dev/null; then
+! if ln -s conf$$.file conf$$ 2>/dev/null; then
+ as_ln_s='ln -s'
++ # ... but there are two gotchas:
++ # 1) On MSYS, both `ln -s file dir' and `ln file dir' fail.
++ # 2) DJGPP < 2.04 has no symlinks; `ln -s' creates a wrapper executable.
++ # In both cases, we have to default to `cp -p'.
++ ln -s conf$$.file conf$$.dir 2>/dev/null && test ! -f conf$$.exe ||
++ as_ln_s='cp -p'
++ elif ln conf$$.file conf$$ 2>/dev/null; then
++ as_ln_s=ln
++ else
++ as_ln_s='cp -p'
+ fi
+ else
+ as_ln_s='cp -p'
+ fi
+! rm -f conf$$ conf$$.exe conf$$.dir/conf$$.file conf$$.file
+! rmdir conf$$.dir 2>/dev/null
+
+ if mkdir -p . 2>/dev/null; then
+ as_mkdir_p=:
+***************
+*** 222,228 ****
+ as_mkdir_p=false
+ fi
+
+! as_executable_p="test -f"
+
+ # Sed expression to map a string onto a valid CPP name.
+ as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'"
+--- 540,567 ----
+ as_mkdir_p=false
+ fi
+
+! if test -x / >/dev/null 2>&1; then
+! as_test_x='test -x'
+! else
+! if ls -dL / >/dev/null 2>&1; then
+! as_ls_L_option=L
+! else
+! as_ls_L_option=
+! fi
+! as_test_x='
+! eval sh -c '\''
+! if test -d "$1"; then
+! test -d "$1/.";
+! else
+! case $1 in
+! -*)set "./$1";;
+! esac;
+! case `ls -ld'$as_ls_L_option' "$1" 2>/dev/null` in
+! ???[sx]*):;;*)false;;esac;fi
+! '\'' sh
+! '
+! fi
+! as_executable_p=$as_test_x
+
+ # Sed expression to map a string onto a valid CPP name.
+ as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'"
+***************
+*** 231,269 ****
+ as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'"
+
+
+- # IFS
+- # We need space, tab and new line, in precisely that order.
+- as_nl='
+- '
+- IFS=" $as_nl"
+-
+- # CDPATH.
+- $as_unset CDPATH
+
+
+ # Name of the host.
+ # hostname on some systems (SVR3.2, Linux) returns a bogus exit status,
+ # so uname gets run too.
+ ac_hostname=`(hostname || uname -n) 2>/dev/null | sed 1q`
+
+- exec 6>&1
+-
+ #
+ # Initializations.
+ #
+ ac_default_prefix=/usr/local
+ ac_config_libobj_dir=.
+ cross_compiling=no
+ subdirs=
+ MFLAGS=
+ MAKEFLAGS=
+ SHELL=${CONFIG_SHELL-/bin/sh}
+
+- # Maximum number of lines to put in a shell here document.
+- # This variable seems obsolete. It should probably be removed, and
+- # only ac_max_sed_lines should be used.
+- : ${ac_max_here_lines=38}
+-
+ # Identity of this package.
+ PACKAGE_NAME=
+ PACKAGE_TARNAME=
+--- 570,596 ----
+ as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'"
+
+
+
++ exec 7<&0 </dev/null 6>&1
+
+ # Name of the host.
+ # hostname on some systems (SVR3.2, Linux) returns a bogus exit status,
+ # so uname gets run too.
+ ac_hostname=`(hostname || uname -n) 2>/dev/null | sed 1q`
+
+ #
+ # Initializations.
+ #
+ ac_default_prefix=/usr/local
++ ac_clean_files=
+ ac_config_libobj_dir=.
++ LIBOBJS=
+ cross_compiling=no
+ subdirs=
+ MFLAGS=
+ MAKEFLAGS=
+ SHELL=${CONFIG_SHELL-/bin/sh}
+
+ # Identity of this package.
+ PACKAGE_NAME=
+ PACKAGE_TARNAME=
+***************
+*** 275,320 ****
+ # Factoring default headers for most tests.
+ ac_includes_default="\
+ #include <stdio.h>
+! #if HAVE_SYS_TYPES_H
+ # include <sys/types.h>
+ #endif
+! #if HAVE_SYS_STAT_H
+ # include <sys/stat.h>
+ #endif
+! #if STDC_HEADERS
+ # include <stdlib.h>
+ # include <stddef.h>
+ #else
+! # if HAVE_STDLIB_H
+ # include <stdlib.h>
+ # endif
+ #endif
+! #if HAVE_STRING_H
+! # if !STDC_HEADERS && HAVE_MEMORY_H
+ # include <memory.h>
+ # endif
+ # include <string.h>
+ #endif
+! #if HAVE_STRINGS_H
+ # include <strings.h>
+ #endif
+! #if HAVE_INTTYPES_H
+ # include <inttypes.h>
+- #else
+- # if HAVE_STDINT_H
+- # include <stdint.h>
+- # endif
+ #endif
+! #if HAVE_UNISTD_H
+ # include <unistd.h>
+ #endif"
+
+! ac_subst_vars='sim_environment sim_alignment sim_assert sim_bitsize sim_endian sim_hostendian sim_float sim_scache sim_default_model sim_hw_cflags sim_hw_objs sim_hw sim_inline sim_packages sim_regparm sim_reserved_bits sim_smp sim_stdcall sim_xor_endian WARN_CFLAGS WERROR_CFLAGS SHELL PATH_SEPARATOR PACKAGE_NAME PACKAGE_TARNAME PACKAGE_VERSION PACKAGE_STRING PACKAGE_BUGREPORT exec_prefix prefix program_transform_name bindir sbindir libexecdir datadir sysconfdir sharedstatedir localstatedir libdir includedir oldincludedir infodir mandir build_alias host_alias target_alias DEFS ECHO_C ECHO_N ECHO_T LIBS INSTALL_PROGRAM INSTALL_SCRIPT INSTALL_DATA CC CFLAGS LDFLAGS CPPFLAGS ac_ct_CC EXEEXT OBJEXT USE_NLS LIBINTL LIBINTL_DEP INCINTL XGETTEXT GMSGFMT POSUB CATALOGS DATADIRNAME INSTOBJEXT GENCAT CATOBJEXT build build_cpu build_vendor build_os host host_cpu host_vendor host_os target target_cpu target_vendor target_os CPP EGREP LIBOBJS CC_FOR_BUILD CFLAGS_FOR_BUILD HDEFINES AR RANLIB ac_ct_RANLIB sim_cflags sim_warnings sim_line_nr sim_config sim_opcode sim_switch sim_dup sim_decode_mechanism sim_jump sim_filter sim_icache sim_hw_src sim_hw_obj sim_pk_src sim_pk_obj sim_bswap sim_igen_smp sim_hostbitsize sim_env sim_timebase sim_trace sim_reserved sim_monitor sim_model sim_model_issue sim_stdio sim_termio sim_devzero sim_callback sim_targ_vals sim_fpu_cflags sim_fpu LTLIBOBJS'
+ ac_subst_files=''
+
+ # Initialize some variables set by options.
+ ac_init_help=
+ ac_init_version=false
+ # The variables have the same names as the options, with
+ # dashes changed to underlines.
+ cache_file=/dev/null
+--- 602,831 ----
+ # Factoring default headers for most tests.
+ ac_includes_default="\
+ #include <stdio.h>
+! #ifdef HAVE_SYS_TYPES_H
+ # include <sys/types.h>
+ #endif
+! #ifdef HAVE_SYS_STAT_H
+ # include <sys/stat.h>
+ #endif
+! #ifdef STDC_HEADERS
+ # include <stdlib.h>
+ # include <stddef.h>
+ #else
+! # ifdef HAVE_STDLIB_H
+ # include <stdlib.h>
+ # endif
+ #endif
+! #ifdef HAVE_STRING_H
+! # if !defined STDC_HEADERS && defined HAVE_MEMORY_H
+ # include <memory.h>
+ # endif
+ # include <string.h>
+ #endif
+! #ifdef HAVE_STRINGS_H
+ # include <strings.h>
+ #endif
+! #ifdef HAVE_INTTYPES_H
+ # include <inttypes.h>
+ #endif
+! #ifdef HAVE_STDINT_H
+! # include <stdint.h>
+! #endif
+! #ifdef HAVE_UNISTD_H
+ # include <unistd.h>
+ #endif"
+
+! ac_subst_vars='sim_environment
+! sim_alignment
+! sim_assert
+! sim_bitsize
+! sim_endian
+! sim_hostendian
+! sim_float
+! sim_scache
+! sim_default_model
+! sim_hw_cflags
+! sim_hw_objs
+! sim_hw
+! sim_inline
+! sim_packages
+! sim_regparm
+! sim_reserved_bits
+! sim_smp
+! sim_stdcall
+! sim_xor_endian
+! WARN_CFLAGS
+! WERROR_CFLAGS
+! SHELL
+! PATH_SEPARATOR
+! PACKAGE_NAME
+! PACKAGE_TARNAME
+! PACKAGE_VERSION
+! PACKAGE_STRING
+! PACKAGE_BUGREPORT
+! exec_prefix
+! prefix
+! program_transform_name
+! bindir
+! sbindir
+! libexecdir
+! datarootdir
+! datadir
+! sysconfdir
+! sharedstatedir
+! localstatedir
+! includedir
+! oldincludedir
+! docdir
+! infodir
+! htmldir
+! dvidir
+! pdfdir
+! psdir
+! libdir
+! localedir
+! mandir
+! DEFS
+! ECHO_C
+! ECHO_N
+! ECHO_T
+! LIBS
+! build_alias
+! host_alias
+! target_alias
+! INSTALL_PROGRAM
+! INSTALL_SCRIPT
+! INSTALL_DATA
+! CC
+! CFLAGS
+! LDFLAGS
+! CPPFLAGS
+! ac_ct_CC
+! EXEEXT
+! OBJEXT
+! USE_NLS
+! LIBINTL
+! LIBINTL_DEP
+! INCINTL
+! XGETTEXT
+! GMSGFMT
+! POSUB
+! CATALOGS
+! DATADIRNAME
+! INSTOBJEXT
+! GENCAT
+! CATOBJEXT
+! CPP
+! GREP
+! EGREP
+! build
+! build_cpu
+! build_vendor
+! build_os
+! host
+! host_cpu
+! host_vendor
+! host_os
+! target
+! target_cpu
+! target_vendor
+! target_os
+! LIBOBJS
+! CC_FOR_BUILD
+! CFLAGS_FOR_BUILD
+! HDEFINES
+! AR
+! RANLIB
+! sim_cflags
+! sim_warnings
+! sim_line_nr
+! sim_config
+! sim_opcode
+! sim_switch
+! sim_dup
+! sim_decode_mechanism
+! sim_jump
+! sim_filter
+! sim_icache
+! sim_hw_src
+! sim_hw_obj
+! sim_pk_src
+! sim_pk_obj
+! sim_bswap
+! sim_igen_smp
+! sim_hostbitsize
+! sim_env
+! sim_timebase
+! sim_trace
+! sim_reserved
+! sim_monitor
+! sim_model
+! sim_model_issue
+! sim_stdio
+! sim_termio
+! sim_devzero
+! sim_callback
+! sim_targ_vals
+! sim_fpu_cflags
+! sim_fpu
+! sim_async_io_src
+! sim_async_io_obj
+! LTLIBOBJS'
+ ac_subst_files=''
++ ac_user_opts='
++ enable_option_checking
++ enable_sim_alignment
++ enable_sim_assert
++ enable_sim_bitsize
++ enable_sim_bswap
++ enable_sim_cflags
++ enable_sim_config
++ enable_sim_decode_mechanism
++ enable_sim_default_model
++ enable_sim_duplicate
++ enable_sim_endian
++ enable_sim_env
++ enable_sim_filter
++ enable_sim_float
++ enable_sim_hardware
++ enable_sim_hostbitsize
++ enable_sim_hostendian
++ enable_sim_icache
++ enable_sim_inline
++ enable_sim_jump
++ enable_sim_line_nr
++ enable_sim_model
++ enable_sim_model_issue
++ enable_sim_monitor
++ enable_sim_opcode
++ enable_sim_packages
++ enable_sim_regparm
++ enable_sim_reserved_bits
++ enable_sim_smp
++ enable_sim_stdcall
++ enable_sim_stdio
++ enable_sim_switch
++ enable_sim_timebase
++ enable_sim_trace
++ enable_sim_warnings
++ enable_sim_xor_endian
++ '
++ ac_precious_vars='build_alias
++ host_alias
++ target_alias
++ CC
++ CFLAGS
++ LDFLAGS
++ LIBS
++ CPPFLAGS
++ CPP'
++
+
+ # Initialize some variables set by options.
+ ac_init_help=
+ ac_init_version=false
++ ac_unrecognized_opts=
++ ac_unrecognized_sep=
+ # The variables have the same names as the options, with
+ # dashes changed to underlines.
+ cache_file=/dev/null
+***************
+*** 337,370 ****
+ # and all the variables that are supposed to be based on exec_prefix
+ # by default will actually change.
+ # Use braces instead of parens because sh, perl, etc. also accept them.
+ bindir='${exec_prefix}/bin'
+ sbindir='${exec_prefix}/sbin'
+ libexecdir='${exec_prefix}/libexec'
+! datadir='${prefix}/share'
+ sysconfdir='${prefix}/etc'
+ sharedstatedir='${prefix}/com'
+ localstatedir='${prefix}/var'
+- libdir='${exec_prefix}/lib'
+ includedir='${prefix}/include'
+ oldincludedir='/usr/include'
+! infodir='${prefix}/info'
+! mandir='${prefix}/man'
+
+ ac_prev=
+ for ac_option
+ do
+ # If the previous option needs an argument, assign it.
+ if test -n "$ac_prev"; then
+! eval "$ac_prev=\$ac_option"
+ ac_prev=
+ continue
+ fi
+
+! ac_optarg=`expr "x$ac_option" : 'x[^=]*=\(.*\)'`
+
+ # Accept the important Cygnus configure options, so we can diagnose typos.
+
+! case $ac_option in
+
+ -bindir | --bindir | --bindi | --bind | --bin | --bi)
+ ac_prev=bindir ;;
+--- 848,895 ----
+ # and all the variables that are supposed to be based on exec_prefix
+ # by default will actually change.
+ # Use braces instead of parens because sh, perl, etc. also accept them.
++ # (The list follows the same order as the GNU Coding Standards.)
+ bindir='${exec_prefix}/bin'
+ sbindir='${exec_prefix}/sbin'
+ libexecdir='${exec_prefix}/libexec'
+! datarootdir='${prefix}/share'
+! datadir='${datarootdir}'
+ sysconfdir='${prefix}/etc'
+ sharedstatedir='${prefix}/com'
+ localstatedir='${prefix}/var'
+ includedir='${prefix}/include'
+ oldincludedir='/usr/include'
+! docdir='${datarootdir}/doc/${PACKAGE}'
+! infodir='${datarootdir}/info'
+! htmldir='${docdir}'
+! dvidir='${docdir}'
+! pdfdir='${docdir}'
+! psdir='${docdir}'
+! libdir='${exec_prefix}/lib'
+! localedir='${datarootdir}/locale'
+! mandir='${datarootdir}/man'
+
+ ac_prev=
++ ac_dashdash=
+ for ac_option
+ do
+ # If the previous option needs an argument, assign it.
+ if test -n "$ac_prev"; then
+! eval $ac_prev=\$ac_option
+ ac_prev=
+ continue
+ fi
+
+! case $ac_option in
+! *=*) ac_optarg=`expr "X$ac_option" : '[^=]*=\(.*\)'` ;;
+! *) ac_optarg=yes ;;
+! esac
+
+ # Accept the important Cygnus configure options, so we can diagnose typos.
+
+! case $ac_dashdash$ac_option in
+! --)
+! ac_dashdash=yes ;;
+
+ -bindir | --bindir | --bindi | --bind | --bin | --bi)
+ ac_prev=bindir ;;
+***************
+*** 386,418 ****
+ --config-cache | -C)
+ cache_file=config.cache ;;
+
+! -datadir | --datadir | --datadi | --datad | --data | --dat | --da)
+ ac_prev=datadir ;;
+! -datadir=* | --datadir=* | --datadi=* | --datad=* | --data=* | --dat=* \
+! | --da=*)
+ datadir=$ac_optarg ;;
+
+ -disable-* | --disable-*)
+! ac_feature=`expr "x$ac_option" : 'x-*disable-\(.*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_feature" : ".*[^-_$as_cr_alnum]" >/dev/null &&
+! { echo "$as_me: error: invalid feature name: $ac_feature" >&2
+ { (exit 1); exit 1; }; }
+! ac_feature=`echo $ac_feature | sed 's/-/_/g'`
+! eval "enable_$ac_feature=no" ;;
+
+ -enable-* | --enable-*)
+! ac_feature=`expr "x$ac_option" : 'x-*enable-\([^=]*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_feature" : ".*[^-_$as_cr_alnum]" >/dev/null &&
+! { echo "$as_me: error: invalid feature name: $ac_feature" >&2
+ { (exit 1); exit 1; }; }
+! ac_feature=`echo $ac_feature | sed 's/-/_/g'`
+! case $ac_option in
+! *=*) ac_optarg=`echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"`;;
+! *) ac_optarg=yes ;;
+ esac
+! eval "enable_$ac_feature='$ac_optarg'" ;;
+
+ -exec-prefix | --exec_prefix | --exec-prefix | --exec-prefi \
+ | --exec-pref | --exec-pre | --exec-pr | --exec-p | --exec- \
+--- 911,971 ----
+ --config-cache | -C)
+ cache_file=config.cache ;;
+
+! -datadir | --datadir | --datadi | --datad)
+ ac_prev=datadir ;;
+! -datadir=* | --datadir=* | --datadi=* | --datad=*)
+ datadir=$ac_optarg ;;
+
++ -datarootdir | --datarootdir | --datarootdi | --datarootd | --dataroot \
++ | --dataroo | --dataro | --datar)
++ ac_prev=datarootdir ;;
++ -datarootdir=* | --datarootdir=* | --datarootdi=* | --datarootd=* \
++ | --dataroot=* | --dataroo=* | --dataro=* | --datar=*)
++ datarootdir=$ac_optarg ;;
++
+ -disable-* | --disable-*)
+! ac_useropt=`expr "x$ac_option" : 'x-*disable-\(.*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null &&
+! { $as_echo "$as_me: error: invalid feature name: $ac_useropt" >&2
+ { (exit 1); exit 1; }; }
+! ac_useropt_orig=$ac_useropt
+! ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'`
+! case $ac_user_opts in
+! *"
+! "enable_$ac_useropt"
+! "*) ;;
+! *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--disable-$ac_useropt_orig"
+! ac_unrecognized_sep=', ';;
+! esac
+! eval enable_$ac_useropt=no ;;
+!
+! -docdir | --docdir | --docdi | --doc | --do)
+! ac_prev=docdir ;;
+! -docdir=* | --docdir=* | --docdi=* | --doc=* | --do=*)
+! docdir=$ac_optarg ;;
+!
+! -dvidir | --dvidir | --dvidi | --dvid | --dvi | --dv)
+! ac_prev=dvidir ;;
+! -dvidir=* | --dvidir=* | --dvidi=* | --dvid=* | --dvi=* | --dv=*)
+! dvidir=$ac_optarg ;;
+
+ -enable-* | --enable-*)
+! ac_useropt=`expr "x$ac_option" : 'x-*enable-\([^=]*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null &&
+! { $as_echo "$as_me: error: invalid feature name: $ac_useropt" >&2
+ { (exit 1); exit 1; }; }
+! ac_useropt_orig=$ac_useropt
+! ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'`
+! case $ac_user_opts in
+! *"
+! "enable_$ac_useropt"
+! "*) ;;
+! *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--enable-$ac_useropt_orig"
+! ac_unrecognized_sep=', ';;
+ esac
+! eval enable_$ac_useropt=\$ac_optarg ;;
+
+ -exec-prefix | --exec_prefix | --exec-prefix | --exec-prefi \
+ | --exec-pref | --exec-pre | --exec-pr | --exec-p | --exec- \
+***************
+*** 439,444 ****
+--- 992,1003 ----
+ -host=* | --host=* | --hos=* | --ho=*)
+ host_alias=$ac_optarg ;;
+
++ -htmldir | --htmldir | --htmldi | --htmld | --html | --htm | --ht)
++ ac_prev=htmldir ;;
++ -htmldir=* | --htmldir=* | --htmldi=* | --htmld=* | --html=* | --htm=* \
++ | --ht=*)
++ htmldir=$ac_optarg ;;
++
+ -includedir | --includedir | --includedi | --included | --include \
+ | --includ | --inclu | --incl | --inc)
+ ac_prev=includedir ;;
+***************
+*** 463,475 ****
+ | --libexe=* | --libex=* | --libe=*)
+ libexecdir=$ac_optarg ;;
+
+ -localstatedir | --localstatedir | --localstatedi | --localstated \
+! | --localstate | --localstat | --localsta | --localst \
+! | --locals | --local | --loca | --loc | --lo)
+ ac_prev=localstatedir ;;
+ -localstatedir=* | --localstatedir=* | --localstatedi=* | --localstated=* \
+! | --localstate=* | --localstat=* | --localsta=* | --localst=* \
+! | --locals=* | --local=* | --loca=* | --loc=* | --lo=*)
+ localstatedir=$ac_optarg ;;
+
+ -mandir | --mandir | --mandi | --mand | --man | --ma | --m)
+--- 1022,1037 ----
+ | --libexe=* | --libex=* | --libe=*)
+ libexecdir=$ac_optarg ;;
+
++ -localedir | --localedir | --localedi | --localed | --locale)
++ ac_prev=localedir ;;
++ -localedir=* | --localedir=* | --localedi=* | --localed=* | --locale=*)
++ localedir=$ac_optarg ;;
++
+ -localstatedir | --localstatedir | --localstatedi | --localstated \
+! | --localstate | --localstat | --localsta | --localst | --locals)
+ ac_prev=localstatedir ;;
+ -localstatedir=* | --localstatedir=* | --localstatedi=* | --localstated=* \
+! | --localstate=* | --localstat=* | --localsta=* | --localst=* | --locals=*)
+ localstatedir=$ac_optarg ;;
+
+ -mandir | --mandir | --mandi | --mand | --man | --ma | --m)
+***************
+*** 534,539 ****
+--- 1096,1111 ----
+ | --progr-tra=* | --program-tr=* | --program-t=*)
+ program_transform_name=$ac_optarg ;;
+
++ -pdfdir | --pdfdir | --pdfdi | --pdfd | --pdf | --pd)
++ ac_prev=pdfdir ;;
++ -pdfdir=* | --pdfdir=* | --pdfdi=* | --pdfd=* | --pdf=* | --pd=*)
++ pdfdir=$ac_optarg ;;
++
++ -psdir | --psdir | --psdi | --psd | --ps)
++ ac_prev=psdir ;;
++ -psdir=* | --psdir=* | --psdi=* | --psd=* | --ps=*)
++ psdir=$ac_optarg ;;
++
+ -q | -quiet | --quiet | --quie | --qui | --qu | --q \
+ | -silent | --silent | --silen | --sile | --sil)
+ silent=yes ;;
+***************
+*** 584,609 ****
+ ac_init_version=: ;;
+
+ -with-* | --with-*)
+! ac_package=`expr "x$ac_option" : 'x-*with-\([^=]*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_package" : ".*[^-_$as_cr_alnum]" >/dev/null &&
+! { echo "$as_me: error: invalid package name: $ac_package" >&2
+ { (exit 1); exit 1; }; }
+! ac_package=`echo $ac_package| sed 's/-/_/g'`
+! case $ac_option in
+! *=*) ac_optarg=`echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"`;;
+! *) ac_optarg=yes ;;
+ esac
+! eval "with_$ac_package='$ac_optarg'" ;;
+
+ -without-* | --without-*)
+! ac_package=`expr "x$ac_option" : 'x-*without-\(.*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_package" : ".*[^-_$as_cr_alnum]" >/dev/null &&
+! { echo "$as_me: error: invalid package name: $ac_package" >&2
+ { (exit 1); exit 1; }; }
+! ac_package=`echo $ac_package | sed 's/-/_/g'`
+! eval "with_$ac_package=no" ;;
+
+ --x)
+ # Obsolete; use --with-x.
+--- 1156,1193 ----
+ ac_init_version=: ;;
+
+ -with-* | --with-*)
+! ac_useropt=`expr "x$ac_option" : 'x-*with-\([^=]*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null &&
+! { $as_echo "$as_me: error: invalid package name: $ac_useropt" >&2
+ { (exit 1); exit 1; }; }
+! ac_useropt_orig=$ac_useropt
+! ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'`
+! case $ac_user_opts in
+! *"
+! "with_$ac_useropt"
+! "*) ;;
+! *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--with-$ac_useropt_orig"
+! ac_unrecognized_sep=', ';;
+ esac
+! eval with_$ac_useropt=\$ac_optarg ;;
+
+ -without-* | --without-*)
+! ac_useropt=`expr "x$ac_option" : 'x-*without-\(.*\)'`
+ # Reject names that are not valid shell variable names.
+! expr "x$ac_useropt" : ".*[^-+._$as_cr_alnum]" >/dev/null &&
+! { $as_echo "$as_me: error: invalid package name: $ac_useropt" >&2
+ { (exit 1); exit 1; }; }
+! ac_useropt_orig=$ac_useropt
+! ac_useropt=`$as_echo "$ac_useropt" | sed 's/[-+.]/_/g'`
+! case $ac_user_opts in
+! *"
+! "with_$ac_useropt"
+! "*) ;;
+! *) ac_unrecognized_opts="$ac_unrecognized_opts$ac_unrecognized_sep--without-$ac_useropt_orig"
+! ac_unrecognized_sep=', ';;
+! esac
+! eval with_$ac_useropt=no ;;
+
+ --x)
+ # Obsolete; use --with-x.
+***************
+*** 623,629 ****
+ | --x-librar=* | --x-libra=* | --x-libr=* | --x-lib=* | --x-li=* | --x-l=*)
+ x_libraries=$ac_optarg ;;
+
+! -*) { echo "$as_me: error: unrecognized option: $ac_option
+ Try \`$0 --help' for more information." >&2
+ { (exit 1); exit 1; }; }
+ ;;
+--- 1207,1213 ----
+ | --x-librar=* | --x-libra=* | --x-libr=* | --x-lib=* | --x-li=* | --x-l=*)
+ x_libraries=$ac_optarg ;;
+
+! -*) { $as_echo "$as_me: error: unrecognized option: $ac_option
+ Try \`$0 --help' for more information." >&2
+ { (exit 1); exit 1; }; }
+ ;;
+***************
+*** 632,648 ****
+ ac_envvar=`expr "x$ac_option" : 'x\([^=]*\)='`
+ # Reject names that are not valid shell variable names.
+ expr "x$ac_envvar" : ".*[^_$as_cr_alnum]" >/dev/null &&
+! { echo "$as_me: error: invalid variable name: $ac_envvar" >&2
+ { (exit 1); exit 1; }; }
+! ac_optarg=`echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"`
+! eval "$ac_envvar='$ac_optarg'"
+ export $ac_envvar ;;
+
+ *)
+ # FIXME: should be removed in autoconf 3.0.
+! echo "$as_me: WARNING: you should use --build, --host, --target" >&2
+ expr "x$ac_option" : ".*[^-._$as_cr_alnum]" >/dev/null &&
+! echo "$as_me: WARNING: invalid host type: $ac_option" >&2
+ : ${build_alias=$ac_option} ${host_alias=$ac_option} ${target_alias=$ac_option}
+ ;;
+
+--- 1216,1231 ----
+ ac_envvar=`expr "x$ac_option" : 'x\([^=]*\)='`
+ # Reject names that are not valid shell variable names.
+ expr "x$ac_envvar" : ".*[^_$as_cr_alnum]" >/dev/null &&
+! { $as_echo "$as_me: error: invalid variable name: $ac_envvar" >&2
+ { (exit 1); exit 1; }; }
+! eval $ac_envvar=\$ac_optarg
+ export $ac_envvar ;;
+
+ *)
+ # FIXME: should be removed in autoconf 3.0.
+! $as_echo "$as_me: WARNING: you should use --build, --host, --target" >&2
+ expr "x$ac_option" : ".*[^-._$as_cr_alnum]" >/dev/null &&
+! $as_echo "$as_me: WARNING: invalid host type: $ac_option" >&2
+ : ${build_alias=$ac_option} ${host_alias=$ac_option} ${target_alias=$ac_option}
+ ;;
+
+***************
+*** 651,681 ****
+
+ if test -n "$ac_prev"; then
+ ac_option=--`echo $ac_prev | sed 's/_/-/g'`
+! { echo "$as_me: error: missing argument to $ac_option" >&2
+ { (exit 1); exit 1; }; }
+ fi
+
+! # Be sure to have absolute paths.
+! for ac_var in exec_prefix prefix
+! do
+! eval ac_val=$`echo $ac_var`
+! case $ac_val in
+! [\\/$]* | ?:[\\/]* | NONE | '' ) ;;
+! *) { echo "$as_me: error: expected an absolute directory name for --$ac_var: $ac_val" >&2
+! { (exit 1); exit 1; }; };;
+ esac
+! done
+
+! # Be sure to have absolute paths.
+! for ac_var in bindir sbindir libexecdir datadir sysconfdir sharedstatedir \
+! localstatedir libdir includedir oldincludedir infodir mandir
+ do
+! eval ac_val=$`echo $ac_var`
+ case $ac_val in
+! [\\/$]* | ?:[\\/]* ) ;;
+! *) { echo "$as_me: error: expected an absolute directory name for --$ac_var: $ac_val" >&2
+! { (exit 1); exit 1; }; };;
+ esac
+ done
+
+ # There might be people who depend on the old broken behavior: `$host'
+--- 1234,1272 ----
+
+ if test -n "$ac_prev"; then
+ ac_option=--`echo $ac_prev | sed 's/_/-/g'`
+! { $as_echo "$as_me: error: missing argument to $ac_option" >&2
+ { (exit 1); exit 1; }; }
+ fi
+
+! if test -n "$ac_unrecognized_opts"; then
+! case $enable_option_checking in
+! no) ;;
+! fatal) { $as_echo "$as_me: error: Unrecognized options: $ac_unrecognized_opts" >&2
+! { (exit 1); exit 1; }; } ;;
+! *) $as_echo "$as_me: WARNING: Unrecognized options: $ac_unrecognized_opts" >&2 ;;
+ esac
+! fi
+
+! # Check all directory arguments for consistency.
+! for ac_var in exec_prefix prefix bindir sbindir libexecdir datarootdir \
+! datadir sysconfdir sharedstatedir localstatedir includedir \
+! oldincludedir docdir infodir htmldir dvidir pdfdir psdir \
+! libdir localedir mandir
+ do
+! eval ac_val=\$$ac_var
+! # Remove trailing slashes.
+ case $ac_val in
+! */ )
+! ac_val=`expr "X$ac_val" : 'X\(.*[^/]\)' \| "X$ac_val" : 'X\(.*\)'`
+! eval $ac_var=\$ac_val;;
+! esac
+! # Be sure to have absolute directory names.
+! case $ac_val in
+! [\\/$]* | ?:[\\/]* ) continue;;
+! NONE | '' ) case $ac_var in *prefix ) continue;; esac;;
+ esac
++ { $as_echo "$as_me: error: expected an absolute directory name for --$ac_var: $ac_val" >&2
++ { (exit 1); exit 1; }; }
+ done
+
+ # There might be people who depend on the old broken behavior: `$host'
+***************
+*** 689,695 ****
+ if test "x$host_alias" != x; then
+ if test "x$build_alias" = x; then
+ cross_compiling=maybe
+! echo "$as_me: WARNING: If you wanted to set the --build type, don't use --host.
+ If a cross compiler is detected then cross compile mode will be used." >&2
+ elif test "x$build_alias" != "x$host_alias"; then
+ cross_compiling=yes
+--- 1280,1286 ----
+ if test "x$host_alias" != x; then
+ if test "x$build_alias" = x; then
+ cross_compiling=maybe
+! $as_echo "$as_me: WARNING: If you wanted to set the --build type, don't use --host.
+ If a cross compiler is detected then cross compile mode will be used." >&2
+ elif test "x$build_alias" != "x$host_alias"; then
+ cross_compiling=yes
+***************
+*** 702,775 ****
+ test "$silent" = yes && exec 6>/dev/null
+
+
+ # Find the source files, if location was not specified.
+ if test -z "$srcdir"; then
+ ac_srcdir_defaulted=yes
+! # Try the directory containing this script, then its parent.
+! ac_confdir=`(dirname "$0") 2>/dev/null ||
+! $as_expr X"$0" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$0" : 'X\(//\)[^/]' \| \
+! X"$0" : 'X\(//\)$' \| \
+! X"$0" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$0" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+ srcdir=$ac_confdir
+! if test ! -r $srcdir/$ac_unique_file; then
+ srcdir=..
+ fi
+ else
+ ac_srcdir_defaulted=no
+ fi
+! if test ! -r $srcdir/$ac_unique_file; then
+! if test "$ac_srcdir_defaulted" = yes; then
+! { echo "$as_me: error: cannot find sources ($ac_unique_file) in $ac_confdir or .." >&2
+! { (exit 1); exit 1; }; }
+! else
+! { echo "$as_me: error: cannot find sources ($ac_unique_file) in $srcdir" >&2
+ { (exit 1); exit 1; }; }
+- fi
+ fi
+! (cd $srcdir && test -r ./$ac_unique_file) 2>/dev/null ||
+! { echo "$as_me: error: sources are in $srcdir, but \`cd $srcdir' does not work" >&2
+ { (exit 1); exit 1; }; }
+! srcdir=`echo "$srcdir" | sed 's%\([^\\/]\)[\\/]*$%\1%'`
+! ac_env_build_alias_set=${build_alias+set}
+! ac_env_build_alias_value=$build_alias
+! ac_cv_env_build_alias_set=${build_alias+set}
+! ac_cv_env_build_alias_value=$build_alias
+! ac_env_host_alias_set=${host_alias+set}
+! ac_env_host_alias_value=$host_alias
+! ac_cv_env_host_alias_set=${host_alias+set}
+! ac_cv_env_host_alias_value=$host_alias
+! ac_env_target_alias_set=${target_alias+set}
+! ac_env_target_alias_value=$target_alias
+! ac_cv_env_target_alias_set=${target_alias+set}
+! ac_cv_env_target_alias_value=$target_alias
+! ac_env_CC_set=${CC+set}
+! ac_env_CC_value=$CC
+! ac_cv_env_CC_set=${CC+set}
+! ac_cv_env_CC_value=$CC
+! ac_env_CFLAGS_set=${CFLAGS+set}
+! ac_env_CFLAGS_value=$CFLAGS
+! ac_cv_env_CFLAGS_set=${CFLAGS+set}
+! ac_cv_env_CFLAGS_value=$CFLAGS
+! ac_env_LDFLAGS_set=${LDFLAGS+set}
+! ac_env_LDFLAGS_value=$LDFLAGS
+! ac_cv_env_LDFLAGS_set=${LDFLAGS+set}
+! ac_cv_env_LDFLAGS_value=$LDFLAGS
+! ac_env_CPPFLAGS_set=${CPPFLAGS+set}
+! ac_env_CPPFLAGS_value=$CPPFLAGS
+! ac_cv_env_CPPFLAGS_set=${CPPFLAGS+set}
+! ac_cv_env_CPPFLAGS_value=$CPPFLAGS
+! ac_env_CPP_set=${CPP+set}
+! ac_env_CPP_value=$CPP
+! ac_cv_env_CPP_set=${CPP+set}
+! ac_cv_env_CPP_value=$CPP
+
+ #
+ # Report the --help message.
+--- 1293,1368 ----
+ test "$silent" = yes && exec 6>/dev/null
+
+
++ ac_pwd=`pwd` && test -n "$ac_pwd" &&
++ ac_ls_di=`ls -di .` &&
++ ac_pwd_ls_di=`cd "$ac_pwd" && ls -di .` ||
++ { $as_echo "$as_me: error: Working directory cannot be determined" >&2
++ { (exit 1); exit 1; }; }
++ test "X$ac_ls_di" = "X$ac_pwd_ls_di" ||
++ { $as_echo "$as_me: error: pwd does not report name of working directory" >&2
++ { (exit 1); exit 1; }; }
++
++
+ # Find the source files, if location was not specified.
+ if test -z "$srcdir"; then
+ ac_srcdir_defaulted=yes
+! # Try the directory containing this script, then the parent directory.
+! ac_confdir=`$as_dirname -- "$as_myself" ||
+! $as_expr X"$as_myself" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$as_myself" : 'X\(//\)[^/]' \| \
+! X"$as_myself" : 'X\(//\)$' \| \
+! X"$as_myself" : 'X\(/\)' \| . 2>/dev/null ||
+! $as_echo X"$as_myself" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)[^/].*/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\).*/{
+! s//\1/
+! q
+! }
+! s/.*/./; q'`
+ srcdir=$ac_confdir
+! if test ! -r "$srcdir/$ac_unique_file"; then
+ srcdir=..
+ fi
+ else
+ ac_srcdir_defaulted=no
+ fi
+! if test ! -r "$srcdir/$ac_unique_file"; then
+! test "$ac_srcdir_defaulted" = yes && srcdir="$ac_confdir or .."
+! { $as_echo "$as_me: error: cannot find sources ($ac_unique_file) in $srcdir" >&2
+ { (exit 1); exit 1; }; }
+ fi
+! ac_msg="sources are in $srcdir, but \`cd $srcdir' does not work"
+! ac_abs_confdir=`(
+! cd "$srcdir" && test -r "./$ac_unique_file" || { $as_echo "$as_me: error: $ac_msg" >&2
+ { (exit 1); exit 1; }; }
+! pwd)`
+! # When building in place, set srcdir=.
+! if test "$ac_abs_confdir" = "$ac_pwd"; then
+! srcdir=.
+! fi
+! # Remove unnecessary trailing slashes from srcdir.
+! # Double slashes in file names in object file debugging info
+! # mess up M-x gdb in Emacs.
+! case $srcdir in
+! */) srcdir=`expr "X$srcdir" : 'X\(.*[^/]\)' \| "X$srcdir" : 'X\(.*\)'`;;
+! esac
+! for ac_var in $ac_precious_vars; do
+! eval ac_env_${ac_var}_set=\${${ac_var}+set}
+! eval ac_env_${ac_var}_value=\$${ac_var}
+! eval ac_cv_env_${ac_var}_set=\${${ac_var}+set}
+! eval ac_cv_env_${ac_var}_value=\$${ac_var}
+! done
+
+ #
+ # Report the --help message.
+***************
+*** 798,811 ****
+ -n, --no-create do not create output files
+ --srcdir=DIR find the sources in DIR [configure dir or \`..']
+
+- _ACEOF
+-
+- cat <<_ACEOF
+ Installation directories:
+ --prefix=PREFIX install architecture-independent files in PREFIX
+! [$ac_default_prefix]
+ --exec-prefix=EPREFIX install architecture-dependent files in EPREFIX
+! [PREFIX]
+
+ By default, \`make install' will install all the files in
+ \`$ac_default_prefix/bin', \`$ac_default_prefix/lib' etc. You can specify
+--- 1391,1401 ----
+ -n, --no-create do not create output files
+ --srcdir=DIR find the sources in DIR [configure dir or \`..']
+
+ Installation directories:
+ --prefix=PREFIX install architecture-independent files in PREFIX
+! [$ac_default_prefix]
+ --exec-prefix=EPREFIX install architecture-dependent files in EPREFIX
+! [PREFIX]
+
+ By default, \`make install' will install all the files in
+ \`$ac_default_prefix/bin', \`$ac_default_prefix/lib' etc. You can specify
+***************
+*** 815,832 ****
+ For better control, use the options below.
+
+ Fine tuning of the installation directories:
+! --bindir=DIR user executables [EPREFIX/bin]
+! --sbindir=DIR system admin executables [EPREFIX/sbin]
+! --libexecdir=DIR program executables [EPREFIX/libexec]
+! --datadir=DIR read-only architecture-independent data [PREFIX/share]
+! --sysconfdir=DIR read-only single-machine data [PREFIX/etc]
+! --sharedstatedir=DIR modifiable architecture-independent data [PREFIX/com]
+! --localstatedir=DIR modifiable single-machine data [PREFIX/var]
+! --libdir=DIR object code libraries [EPREFIX/lib]
+! --includedir=DIR C header files [PREFIX/include]
+! --oldincludedir=DIR C header files for non-gcc [/usr/include]
+! --infodir=DIR info documentation [PREFIX/info]
+! --mandir=DIR man documentation [PREFIX/man]
+ _ACEOF
+
+ cat <<\_ACEOF
+--- 1405,1429 ----
+ For better control, use the options below.
+
+ Fine tuning of the installation directories:
+! --bindir=DIR user executables [EPREFIX/bin]
+! --sbindir=DIR system admin executables [EPREFIX/sbin]
+! --libexecdir=DIR program executables [EPREFIX/libexec]
+! --sysconfdir=DIR read-only single-machine data [PREFIX/etc]
+! --sharedstatedir=DIR modifiable architecture-independent data [PREFIX/com]
+! --localstatedir=DIR modifiable single-machine data [PREFIX/var]
+! --libdir=DIR object code libraries [EPREFIX/lib]
+! --includedir=DIR C header files [PREFIX/include]
+! --oldincludedir=DIR C header files for non-gcc [/usr/include]
+! --datarootdir=DIR read-only arch.-independent data root [PREFIX/share]
+! --datadir=DIR read-only architecture-independent data [DATAROOTDIR]
+! --infodir=DIR info documentation [DATAROOTDIR/info]
+! --localedir=DIR locale-dependent data [DATAROOTDIR/locale]
+! --mandir=DIR man documentation [DATAROOTDIR/man]
+! --docdir=DIR documentation root [DATAROOTDIR/doc/PACKAGE]
+! --htmldir=DIR html documentation [DOCDIR]
+! --dvidir=DIR dvi documentation [DOCDIR]
+! --pdfdir=DIR pdf documentation [DOCDIR]
+! --psdir=DIR ps documentation [DOCDIR]
+ _ACEOF
+
+ cat <<\_ACEOF
+***************
+*** 848,853 ****
+--- 1445,1451 ----
+ cat <<\_ACEOF
+
+ Optional Features:
++ --disable-option-checking ignore unrecognized --enable/--with options
+ --disable-FEATURE do not include FEATURE (same as --enable-FEATURE=no)
+ --enable-FEATURE[=ARG] include FEATURE [ARG=yes]
+ --enable-sim-alignment=align Specify strict or nonstrict alignment.
+***************
+*** 891,1016 ****
+ CFLAGS C compiler flags
+ LDFLAGS linker flags, e.g. -L<lib dir> if you have libraries in a
+ nonstandard directory <lib dir>
+! CPPFLAGS C/C++ preprocessor flags, e.g. -I<include dir> if you have
+! headers in a nonstandard directory <include dir>
+ CPP C preprocessor
+
+ Use these variables to override the choices made by `configure' or to help
+ it to find libraries and programs with nonstandard names/locations.
+
+ _ACEOF
+ fi
+
+ if test "$ac_init_help" = "recursive"; then
+ # If there are subdirs, report their specific --help.
+- ac_popdir=`pwd`
+ for ac_dir in : $ac_subdirs_all; do test "x$ac_dir" = x: && continue
+! test -d $ac_dir || continue
+ ac_builddir=.
+
+! if test "$ac_dir" != .; then
+! ac_dir_suffix=/`echo "$ac_dir" | sed 's,^\.[\\/],,'`
+! # A "../" for each directory in $ac_dir_suffix.
+! ac_top_builddir=`echo "$ac_dir_suffix" | sed 's,/[^\\/]*,../,g'`
+! else
+! ac_dir_suffix= ac_top_builddir=
+! fi
+
+ case $srcdir in
+! .) # No --srcdir option. We are building in place.
+ ac_srcdir=.
+! if test -z "$ac_top_builddir"; then
+! ac_top_srcdir=.
+! else
+! ac_top_srcdir=`echo $ac_top_builddir | sed 's,/$,,'`
+! fi ;;
+! [\\/]* | ?:[\\/]* ) # Absolute path.
+ ac_srcdir=$srcdir$ac_dir_suffix;
+! ac_top_srcdir=$srcdir ;;
+! *) # Relative path.
+! ac_srcdir=$ac_top_builddir$srcdir$ac_dir_suffix
+! ac_top_srcdir=$ac_top_builddir$srcdir ;;
+! esac
+!
+! # Do not use `cd foo && pwd` to compute absolute paths, because
+! # the directories may not exist.
+! case `pwd` in
+! .) ac_abs_builddir="$ac_dir";;
+! *)
+! case "$ac_dir" in
+! .) ac_abs_builddir=`pwd`;;
+! [\\/]* | ?:[\\/]* ) ac_abs_builddir="$ac_dir";;
+! *) ac_abs_builddir=`pwd`/"$ac_dir";;
+! esac;;
+! esac
+! case $ac_abs_builddir in
+! .) ac_abs_top_builddir=${ac_top_builddir}.;;
+! *)
+! case ${ac_top_builddir}. in
+! .) ac_abs_top_builddir=$ac_abs_builddir;;
+! [\\/]* | ?:[\\/]* ) ac_abs_top_builddir=${ac_top_builddir}.;;
+! *) ac_abs_top_builddir=$ac_abs_builddir/${ac_top_builddir}.;;
+! esac;;
+! esac
+! case $ac_abs_builddir in
+! .) ac_abs_srcdir=$ac_srcdir;;
+! *)
+! case $ac_srcdir in
+! .) ac_abs_srcdir=$ac_abs_builddir;;
+! [\\/]* | ?:[\\/]* ) ac_abs_srcdir=$ac_srcdir;;
+! *) ac_abs_srcdir=$ac_abs_builddir/$ac_srcdir;;
+! esac;;
+! esac
+! case $ac_abs_builddir in
+! .) ac_abs_top_srcdir=$ac_top_srcdir;;
+! *)
+! case $ac_top_srcdir in
+! .) ac_abs_top_srcdir=$ac_abs_builddir;;
+! [\\/]* | ?:[\\/]* ) ac_abs_top_srcdir=$ac_top_srcdir;;
+! *) ac_abs_top_srcdir=$ac_abs_builddir/$ac_top_srcdir;;
+! esac;;
+! esac
+!
+! cd $ac_dir
+! # Check for guested configure; otherwise get Cygnus style configure.
+! if test -f $ac_srcdir/configure.gnu; then
+! echo
+! $SHELL $ac_srcdir/configure.gnu --help=recursive
+! elif test -f $ac_srcdir/configure; then
+! echo
+! $SHELL $ac_srcdir/configure --help=recursive
+! elif test -f $ac_srcdir/configure.ac ||
+! test -f $ac_srcdir/configure.in; then
+! echo
+! $ac_configure --help
+ else
+! echo "$as_me: WARNING: no configuration information is in $ac_dir" >&2
+! fi
+! cd $ac_popdir
+ done
+ fi
+
+! test -n "$ac_init_help" && exit 0
+ if $ac_init_version; then
+ cat <<\_ACEOF
+
+! Copyright (C) 2003 Free Software Foundation, Inc.
+ This configure script is free software; the Free Software Foundation
+ gives unlimited permission to copy, distribute and modify it.
+ _ACEOF
+! exit 0
+ fi
+! exec 5>config.log
+! cat >&5 <<_ACEOF
+ This file contains any messages produced by compilers while
+ running configure, to aid debugging if configure makes a mistake.
+
+ It was created by $as_me, which was
+! generated by GNU Autoconf 2.59. Invocation command line was
+
+ $ $0 $@
+
+ _ACEOF
+ {
+ cat <<_ASUNAME
+ ## --------- ##
+--- 1489,1585 ----
+ CFLAGS C compiler flags
+ LDFLAGS linker flags, e.g. -L<lib dir> if you have libraries in a
+ nonstandard directory <lib dir>
+! LIBS libraries to pass to the linker, e.g. -l<library>
+! CPPFLAGS C/C++/Objective C preprocessor flags, e.g. -I<include dir> if
+! you have headers in a nonstandard directory <include dir>
+ CPP C preprocessor
+
+ Use these variables to override the choices made by `configure' or to help
+ it to find libraries and programs with nonstandard names/locations.
+
+ _ACEOF
++ ac_status=$?
+ fi
+
+ if test "$ac_init_help" = "recursive"; then
+ # If there are subdirs, report their specific --help.
+ for ac_dir in : $ac_subdirs_all; do test "x$ac_dir" = x: && continue
+! test -d "$ac_dir" ||
+! { cd "$srcdir" && ac_pwd=`pwd` && srcdir=. && test -d "$ac_dir"; } ||
+! continue
+ ac_builddir=.
+
+! case "$ac_dir" in
+! .) ac_dir_suffix= ac_top_builddir_sub=. ac_top_build_prefix= ;;
+! *)
+! ac_dir_suffix=/`$as_echo "$ac_dir" | sed 's|^\.[\\/]||'`
+! # A ".." for each directory in $ac_dir_suffix.
+! ac_top_builddir_sub=`$as_echo "$ac_dir_suffix" | sed 's|/[^\\/]*|/..|g;s|/||'`
+! case $ac_top_builddir_sub in
+! "") ac_top_builddir_sub=. ac_top_build_prefix= ;;
+! *) ac_top_build_prefix=$ac_top_builddir_sub/ ;;
+! esac ;;
+! esac
+! ac_abs_top_builddir=$ac_pwd
+! ac_abs_builddir=$ac_pwd$ac_dir_suffix
+! # for backward compatibility:
+! ac_top_builddir=$ac_top_build_prefix
+
+ case $srcdir in
+! .) # We are building in place.
+ ac_srcdir=.
+! ac_top_srcdir=$ac_top_builddir_sub
+! ac_abs_top_srcdir=$ac_pwd ;;
+! [\\/]* | ?:[\\/]* ) # Absolute name.
+ ac_srcdir=$srcdir$ac_dir_suffix;
+! ac_top_srcdir=$srcdir
+! ac_abs_top_srcdir=$srcdir ;;
+! *) # Relative name.
+! ac_srcdir=$ac_top_build_prefix$srcdir$ac_dir_suffix
+! ac_top_srcdir=$ac_top_build_prefix$srcdir
+! ac_abs_top_srcdir=$ac_pwd/$srcdir ;;
+! esac
+! ac_abs_srcdir=$ac_abs_top_srcdir$ac_dir_suffix
+!
+! cd "$ac_dir" || { ac_status=$?; continue; }
+! # Check for guested configure.
+! if test -f "$ac_srcdir/configure.gnu"; then
+! echo &&
+! $SHELL "$ac_srcdir/configure.gnu" --help=recursive
+! elif test -f "$ac_srcdir/configure"; then
+! echo &&
+! $SHELL "$ac_srcdir/configure" --help=recursive
+ else
+! $as_echo "$as_me: WARNING: no configuration information is in $ac_dir" >&2
+! fi || ac_status=$?
+! cd "$ac_pwd" || { ac_status=$?; break; }
+ done
+ fi
+
+! test -n "$ac_init_help" && exit $ac_status
+ if $ac_init_version; then
+ cat <<\_ACEOF
++ configure
++ generated by GNU Autoconf 2.62
+
+! Copyright (C) 1992, 1993, 1994, 1995, 1996, 1998, 1999, 2000, 2001,
+! 2002, 2003, 2004, 2005, 2006, 2007, 2008 Free Software Foundation, Inc.
+ This configure script is free software; the Free Software Foundation
+ gives unlimited permission to copy, distribute and modify it.
+ _ACEOF
+! exit
+ fi
+! cat >config.log <<_ACEOF
+ This file contains any messages produced by compilers while
+ running configure, to aid debugging if configure makes a mistake.
+
+ It was created by $as_me, which was
+! generated by GNU Autoconf 2.62. Invocation command line was
+
+ $ $0 $@
+
+ _ACEOF
++ exec 5>>config.log
+ {
+ cat <<_ASUNAME
+ ## --------- ##
+***************
+*** 1029,1035 ****
+ /bin/arch = `(/bin/arch) 2>/dev/null || echo unknown`
+ /usr/bin/arch -k = `(/usr/bin/arch -k) 2>/dev/null || echo unknown`
+ /usr/convex/getsysinfo = `(/usr/convex/getsysinfo) 2>/dev/null || echo unknown`
+! hostinfo = `(hostinfo) 2>/dev/null || echo unknown`
+ /bin/machine = `(/bin/machine) 2>/dev/null || echo unknown`
+ /usr/bin/oslevel = `(/usr/bin/oslevel) 2>/dev/null || echo unknown`
+ /bin/universe = `(/bin/universe) 2>/dev/null || echo unknown`
+--- 1598,1604 ----
+ /bin/arch = `(/bin/arch) 2>/dev/null || echo unknown`
+ /usr/bin/arch -k = `(/usr/bin/arch -k) 2>/dev/null || echo unknown`
+ /usr/convex/getsysinfo = `(/usr/convex/getsysinfo) 2>/dev/null || echo unknown`
+! /usr/bin/hostinfo = `(/usr/bin/hostinfo) 2>/dev/null || echo unknown`
+ /bin/machine = `(/bin/machine) 2>/dev/null || echo unknown`
+ /usr/bin/oslevel = `(/usr/bin/oslevel) 2>/dev/null || echo unknown`
+ /bin/universe = `(/bin/universe) 2>/dev/null || echo unknown`
+***************
+*** 1041,1048 ****
+ do
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+! echo "PATH: $as_dir"
+ done
+
+ } >&5
+
+--- 1610,1618 ----
+ do
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+! $as_echo "PATH: $as_dir"
+ done
++ IFS=$as_save_IFS
+
+ } >&5
+
+***************
+*** 1064,1070 ****
+ ac_configure_args=
+ ac_configure_args0=
+ ac_configure_args1=
+- ac_sep=
+ ac_must_keep_next=false
+ for ac_pass in 1 2
+ do
+--- 1634,1639 ----
+***************
+*** 1075,1082 ****
+ -q | -quiet | --quiet | --quie | --qui | --qu | --q \
+ | -silent | --silent | --silen | --sile | --sil)
+ continue ;;
+! *" "*|*" "*|*[\[\]\~\#\$\^\&\*\(\)\{\}\\\|\;\<\>\?\"\']*)
+! ac_arg=`echo "$ac_arg" | sed "s/'/'\\\\\\\\''/g"` ;;
+ esac
+ case $ac_pass in
+ 1) ac_configure_args0="$ac_configure_args0 '$ac_arg'" ;;
+--- 1644,1651 ----
+ -q | -quiet | --quiet | --quie | --qui | --qu | --q \
+ | -silent | --silent | --silen | --sile | --sil)
+ continue ;;
+! *\'*)
+! ac_arg=`$as_echo "$ac_arg" | sed "s/'/'\\\\\\\\''/g"` ;;
+ esac
+ case $ac_pass in
+ 1) ac_configure_args0="$ac_configure_args0 '$ac_arg'" ;;
+***************
+*** 1097,1105 ****
+ -* ) ac_must_keep_next=true ;;
+ esac
+ fi
+! ac_configure_args="$ac_configure_args$ac_sep'$ac_arg'"
+! # Get rid of the leading space.
+! ac_sep=" "
+ ;;
+ esac
+ done
+--- 1666,1672 ----
+ -* ) ac_must_keep_next=true ;;
+ esac
+ fi
+! ac_configure_args="$ac_configure_args '$ac_arg'"
+ ;;
+ esac
+ done
+***************
+*** 1110,1117 ****
+ # When interrupted or exit'd, cleanup temporary files, and complete
+ # config.log. We remove comments because anyway the quotes in there
+ # would cause problems or look ugly.
+! # WARNING: Be sure not to use single quotes in there, as some shells,
+! # such as our DU 5.0 friend, will then `close' the trap.
+ trap 'exit_status=$?
+ # Save into config.log some information that might help in debugging.
+ {
+--- 1677,1684 ----
+ # When interrupted or exit'd, cleanup temporary files, and complete
+ # config.log. We remove comments because anyway the quotes in there
+ # would cause problems or look ugly.
+! # WARNING: Use '\'' to represent an apostrophe within the trap.
+! # WARNING: Do not start the trap code with a newline, due to a FreeBSD 4.0 bug.
+ trap 'exit_status=$?
+ # Save into config.log some information that might help in debugging.
+ {
+***************
+*** 1124,1143 ****
+ _ASBOX
+ echo
+ # The following way of writing the cache mishandles newlines in values,
+! {
+ (set) 2>&1 |
+! case `(ac_space='"'"' '"'"'; set | grep ac_space) 2>&1` in
+! *ac_space=\ *)
+ sed -n \
+! "s/'"'"'/'"'"'\\\\'"'"''"'"'/g;
+! s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='"'"'\\2'"'"'/p"
+! ;;
+ *)
+! sed -n \
+! "s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1=\\2/p"
+ ;;
+! esac;
+! }
+ echo
+
+ cat <<\_ASBOX
+--- 1691,1725 ----
+ _ASBOX
+ echo
+ # The following way of writing the cache mishandles newlines in values,
+! (
+! for ac_var in `(set) 2>&1 | sed -n '\''s/^\([a-zA-Z_][a-zA-Z0-9_]*\)=.*/\1/p'\''`; do
+! eval ac_val=\$$ac_var
+! case $ac_val in #(
+! *${as_nl}*)
+! case $ac_var in #(
+! *_cv_*) { $as_echo "$as_me:$LINENO: WARNING: Cache variable $ac_var contains a newline." >&5
+! $as_echo "$as_me: WARNING: Cache variable $ac_var contains a newline." >&2;} ;;
+! esac
+! case $ac_var in #(
+! _ | IFS | as_nl) ;; #(
+! BASH_ARGV | BASH_SOURCE) eval $ac_var= ;; #(
+! *) $as_unset $ac_var ;;
+! esac ;;
+! esac
+! done
+ (set) 2>&1 |
+! case $as_nl`(ac_space='\'' '\''; set) 2>&1` in #(
+! *${as_nl}ac_space=\ *)
+ sed -n \
+! "s/'\''/'\''\\\\'\'''\''/g;
+! s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='\''\\2'\''/p"
+! ;; #(
+ *)
+! sed -n "/^[_$as_cr_alnum]*_cv_[_$as_cr_alnum]*=/p"
+ ;;
+! esac |
+! sort
+! )
+ echo
+
+ cat <<\_ASBOX
+***************
+*** 1148,1169 ****
+ echo
+ for ac_var in $ac_subst_vars
+ do
+! eval ac_val=$`echo $ac_var`
+! echo "$ac_var='"'"'$ac_val'"'"'"
+ done | sort
+ echo
+
+ if test -n "$ac_subst_files"; then
+ cat <<\_ASBOX
+! ## ------------- ##
+! ## Output files. ##
+! ## ------------- ##
+ _ASBOX
+ echo
+ for ac_var in $ac_subst_files
+ do
+! eval ac_val=$`echo $ac_var`
+! echo "$ac_var='"'"'$ac_val'"'"'"
+ done | sort
+ echo
+ fi
+--- 1730,1757 ----
+ echo
+ for ac_var in $ac_subst_vars
+ do
+! eval ac_val=\$$ac_var
+! case $ac_val in
+! *\'\''*) ac_val=`$as_echo "$ac_val" | sed "s/'\''/'\''\\\\\\\\'\'''\''/g"`;;
+! esac
+! $as_echo "$ac_var='\''$ac_val'\''"
+ done | sort
+ echo
+
+ if test -n "$ac_subst_files"; then
+ cat <<\_ASBOX
+! ## ------------------- ##
+! ## File substitutions. ##
+! ## ------------------- ##
+ _ASBOX
+ echo
+ for ac_var in $ac_subst_files
+ do
+! eval ac_val=\$$ac_var
+! case $ac_val in
+! *\'\''*) ac_val=`$as_echo "$ac_val" | sed "s/'\''/'\''\\\\\\\\'\'''\''/g"`;;
+! esac
+! $as_echo "$ac_var='\''$ac_val'\''"
+ done | sort
+ echo
+ fi
+***************
+*** 1175,1200 ****
+ ## ----------- ##
+ _ASBOX
+ echo
+! sed "/^$/d" confdefs.h | sort
+ echo
+ fi
+ test "$ac_signal" != 0 &&
+! echo "$as_me: caught signal $ac_signal"
+! echo "$as_me: exit $exit_status"
+ } >&5
+! rm -f core *.core &&
+! rm -rf conftest* confdefs* conf$$* $ac_clean_files &&
+ exit $exit_status
+! ' 0
+ for ac_signal in 1 2 13 15; do
+ trap 'ac_signal='$ac_signal'; { (exit 1); exit 1; }' $ac_signal
+ done
+ ac_signal=0
+
+ # confdefs.h avoids OS command line length limits that DEFS can exceed.
+! rm -rf conftest* confdefs.h
+! # AIX cpp loses on an empty file, so make sure it contains at least a newline.
+! echo >confdefs.h
+
+ # Predefined preprocessor variables.
+
+--- 1763,1786 ----
+ ## ----------- ##
+ _ASBOX
+ echo
+! cat confdefs.h
+ echo
+ fi
+ test "$ac_signal" != 0 &&
+! $as_echo "$as_me: caught signal $ac_signal"
+! $as_echo "$as_me: exit $exit_status"
+ } >&5
+! rm -f core *.core core.conftest.* &&
+! rm -f -r conftest* confdefs* conf$$* $ac_clean_files &&
+ exit $exit_status
+! ' 0
+ for ac_signal in 1 2 13 15; do
+ trap 'ac_signal='$ac_signal'; { (exit 1); exit 1; }' $ac_signal
+ done
+ ac_signal=0
+
+ # confdefs.h avoids OS command line length limits that DEFS can exceed.
+! rm -f -r conftest* confdefs.h
+
+ # Predefined preprocessor variables.
+
+***************
+*** 1224,1241 ****
+
+
+ # Let the site file select an alternate cache file if it wants to.
+! # Prefer explicitly selected file to automatically selected ones.
+! if test -z "$CONFIG_SITE"; then
+! if test "x$prefix" != xNONE; then
+! CONFIG_SITE="$prefix/share/config.site $prefix/etc/config.site"
+! else
+! CONFIG_SITE="$ac_default_prefix/share/config.site $ac_default_prefix/etc/config.site"
+! fi
+ fi
+! for ac_site_file in $CONFIG_SITE; do
+ if test -r "$ac_site_file"; then
+! { echo "$as_me:$LINENO: loading site script $ac_site_file" >&5
+! echo "$as_me: loading site script $ac_site_file" >&6;}
+ sed 's/^/| /' "$ac_site_file" >&5
+ . "$ac_site_file"
+ fi
+--- 1810,1833 ----
+
+
+ # Let the site file select an alternate cache file if it wants to.
+! # Prefer an explicitly selected file to automatically selected ones.
+! ac_site_file1=NONE
+! ac_site_file2=NONE
+! if test -n "$CONFIG_SITE"; then
+! ac_site_file1=$CONFIG_SITE
+! elif test "x$prefix" != xNONE; then
+! ac_site_file1=$prefix/share/config.site
+! ac_site_file2=$prefix/etc/config.site
+! else
+! ac_site_file1=$ac_default_prefix/share/config.site
+! ac_site_file2=$ac_default_prefix/etc/config.site
+ fi
+! for ac_site_file in "$ac_site_file1" "$ac_site_file2"
+! do
+! test "x$ac_site_file" = xNONE && continue
+ if test -r "$ac_site_file"; then
+! { $as_echo "$as_me:$LINENO: loading site script $ac_site_file" >&5
+! $as_echo "$as_me: loading site script $ac_site_file" >&6;}
+ sed 's/^/| /' "$ac_site_file" >&5
+ . "$ac_site_file"
+ fi
+***************
+*** 1245,1298 ****
+ # Some versions of bash will fail to source /dev/null (special
+ # files actually), so we avoid doing that.
+ if test -f "$cache_file"; then
+! { echo "$as_me:$LINENO: loading cache $cache_file" >&5
+! echo "$as_me: loading cache $cache_file" >&6;}
+ case $cache_file in
+! [\\/]* | ?:[\\/]* ) . $cache_file;;
+! *) . ./$cache_file;;
+ esac
+ fi
+ else
+! { echo "$as_me:$LINENO: creating cache $cache_file" >&5
+! echo "$as_me: creating cache $cache_file" >&6;}
+ >$cache_file
+ fi
+
+ # Check that the precious variables saved in the cache have kept the same
+ # value.
+ ac_cache_corrupted=false
+! for ac_var in `(set) 2>&1 |
+! sed -n 's/^ac_env_\([a-zA-Z_0-9]*\)_set=.*/\1/p'`; do
+ eval ac_old_set=\$ac_cv_env_${ac_var}_set
+ eval ac_new_set=\$ac_env_${ac_var}_set
+! eval ac_old_val="\$ac_cv_env_${ac_var}_value"
+! eval ac_new_val="\$ac_env_${ac_var}_value"
+ case $ac_old_set,$ac_new_set in
+ set,)
+! { echo "$as_me:$LINENO: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&5
+! echo "$as_me: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&2;}
+ ac_cache_corrupted=: ;;
+ ,set)
+! { echo "$as_me:$LINENO: error: \`$ac_var' was not set in the previous run" >&5
+! echo "$as_me: error: \`$ac_var' was not set in the previous run" >&2;}
+ ac_cache_corrupted=: ;;
+ ,);;
+ *)
+ if test "x$ac_old_val" != "x$ac_new_val"; then
+! { echo "$as_me:$LINENO: error: \`$ac_var' has changed since the previous run:" >&5
+! echo "$as_me: error: \`$ac_var' has changed since the previous run:" >&2;}
+! { echo "$as_me:$LINENO: former value: $ac_old_val" >&5
+! echo "$as_me: former value: $ac_old_val" >&2;}
+! { echo "$as_me:$LINENO: current value: $ac_new_val" >&5
+! echo "$as_me: current value: $ac_new_val" >&2;}
+! ac_cache_corrupted=:
+ fi;;
+ esac
+ # Pass precious variables to config.status.
+ if test "$ac_new_set" = set; then
+ case $ac_new_val in
+! *" "*|*" "*|*[\[\]\~\#\$\^\&\*\(\)\{\}\\\|\;\<\>\?\"\']*)
+! ac_arg=$ac_var=`echo "$ac_new_val" | sed "s/'/'\\\\\\\\''/g"` ;;
+ *) ac_arg=$ac_var=$ac_new_val ;;
+ esac
+ case " $ac_configure_args " in
+--- 1837,1897 ----
+ # Some versions of bash will fail to source /dev/null (special
+ # files actually), so we avoid doing that.
+ if test -f "$cache_file"; then
+! { $as_echo "$as_me:$LINENO: loading cache $cache_file" >&5
+! $as_echo "$as_me: loading cache $cache_file" >&6;}
+ case $cache_file in
+! [\\/]* | ?:[\\/]* ) . "$cache_file";;
+! *) . "./$cache_file";;
+ esac
+ fi
+ else
+! { $as_echo "$as_me:$LINENO: creating cache $cache_file" >&5
+! $as_echo "$as_me: creating cache $cache_file" >&6;}
+ >$cache_file
+ fi
+
+ # Check that the precious variables saved in the cache have kept the same
+ # value.
+ ac_cache_corrupted=false
+! for ac_var in $ac_precious_vars; do
+ eval ac_old_set=\$ac_cv_env_${ac_var}_set
+ eval ac_new_set=\$ac_env_${ac_var}_set
+! eval ac_old_val=\$ac_cv_env_${ac_var}_value
+! eval ac_new_val=\$ac_env_${ac_var}_value
+ case $ac_old_set,$ac_new_set in
+ set,)
+! { $as_echo "$as_me:$LINENO: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&5
+! $as_echo "$as_me: error: \`$ac_var' was set to \`$ac_old_val' in the previous run" >&2;}
+ ac_cache_corrupted=: ;;
+ ,set)
+! { $as_echo "$as_me:$LINENO: error: \`$ac_var' was not set in the previous run" >&5
+! $as_echo "$as_me: error: \`$ac_var' was not set in the previous run" >&2;}
+ ac_cache_corrupted=: ;;
+ ,);;
+ *)
+ if test "x$ac_old_val" != "x$ac_new_val"; then
+! # differences in whitespace do not lead to failure.
+! ac_old_val_w=`echo x $ac_old_val`
+! ac_new_val_w=`echo x $ac_new_val`
+! if test "$ac_old_val_w" != "$ac_new_val_w"; then
+! { $as_echo "$as_me:$LINENO: error: \`$ac_var' has changed since the previous run:" >&5
+! $as_echo "$as_me: error: \`$ac_var' has changed since the previous run:" >&2;}
+! ac_cache_corrupted=:
+! else
+! { $as_echo "$as_me:$LINENO: warning: ignoring whitespace changes in \`$ac_var' since the previous run:" >&5
+! $as_echo "$as_me: warning: ignoring whitespace changes in \`$ac_var' since the previous run:" >&2;}
+! eval $ac_var=\$ac_old_val
+! fi
+! { $as_echo "$as_me:$LINENO: former value: \`$ac_old_val'" >&5
+! $as_echo "$as_me: former value: \`$ac_old_val'" >&2;}
+! { $as_echo "$as_me:$LINENO: current value: \`$ac_new_val'" >&5
+! $as_echo "$as_me: current value: \`$ac_new_val'" >&2;}
+ fi;;
+ esac
+ # Pass precious variables to config.status.
+ if test "$ac_new_set" = set; then
+ case $ac_new_val in
+! *\'*) ac_arg=$ac_var=`$as_echo "$ac_new_val" | sed "s/'/'\\\\\\\\''/g"` ;;
+ *) ac_arg=$ac_var=$ac_new_val ;;
+ esac
+ case " $ac_configure_args " in
+***************
+*** 1302,1320 ****
+ fi
+ done
+ if $ac_cache_corrupted; then
+! { echo "$as_me:$LINENO: error: changes in the environment can compromise the build" >&5
+! echo "$as_me: error: changes in the environment can compromise the build" >&2;}
+! { { echo "$as_me:$LINENO: error: run \`make distclean' and/or \`rm $cache_file' and start over" >&5
+! echo "$as_me: error: run \`make distclean' and/or \`rm $cache_file' and start over" >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+- ac_ext=c
+- ac_cpp='$CPP $CPPFLAGS'
+- ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+- ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+- ac_compiler_gnu=$ac_cv_c_compiler_gnu
+-
+
+
+
+--- 1901,1913 ----
+ fi
+ done
+ if $ac_cache_corrupted; then
+! { $as_echo "$as_me:$LINENO: error: changes in the environment can compromise the build" >&5
+! $as_echo "$as_me: error: changes in the environment can compromise the build" >&2;}
+! { { $as_echo "$as_me:$LINENO: error: run \`make distclean' and/or \`rm $cache_file' and start over" >&5
+! $as_echo "$as_me: error: run \`make distclean' and/or \`rm $cache_file' and start over" >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+
+
+
+***************
+*** 1331,1363 ****
+
+
+
+
+
+
+ ac_aux_dir=
+! for ac_dir in $srcdir $srcdir/.. $srcdir/../..; do
+! if test -f $ac_dir/install-sh; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/install-sh -c"
+ break
+! elif test -f $ac_dir/install.sh; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/install.sh -c"
+ break
+! elif test -f $ac_dir/shtool; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/shtool install -c"
+ break
+ fi
+ done
+ if test -z "$ac_aux_dir"; then
+! { { echo "$as_me:$LINENO: error: cannot find install-sh or install.sh in $srcdir $srcdir/.. $srcdir/../.." >&5
+! echo "$as_me: error: cannot find install-sh or install.sh in $srcdir $srcdir/.. $srcdir/../.." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+! ac_config_guess="$SHELL $ac_aux_dir/config.guess"
+! ac_config_sub="$SHELL $ac_aux_dir/config.sub"
+! ac_configure="$SHELL $ac_aux_dir/configure" # This should be Cygnus configure.
+
+ # Find a good install program. We prefer a C program (faster),
+ # so one script is as good as another. But avoid the broken or
+--- 1924,1967 ----
+
+
+
++ ac_ext=c
++ ac_cpp='$CPP $CPPFLAGS'
++ ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
++ ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
++ ac_compiler_gnu=$ac_cv_c_compiler_gnu
+
+
+
+ ac_aux_dir=
+! for ac_dir in "$srcdir" "$srcdir/.." "$srcdir/../.."; do
+! if test -f "$ac_dir/install-sh"; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/install-sh -c"
+ break
+! elif test -f "$ac_dir/install.sh"; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/install.sh -c"
+ break
+! elif test -f "$ac_dir/shtool"; then
+ ac_aux_dir=$ac_dir
+ ac_install_sh="$ac_aux_dir/shtool install -c"
+ break
+ fi
+ done
+ if test -z "$ac_aux_dir"; then
+! { { $as_echo "$as_me:$LINENO: error: cannot find install-sh or install.sh in \"$srcdir\" \"$srcdir/..\" \"$srcdir/../..\"" >&5
+! $as_echo "$as_me: error: cannot find install-sh or install.sh in \"$srcdir\" \"$srcdir/..\" \"$srcdir/../..\"" >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+!
+! # These three variables are undocumented and unsupported,
+! # and are intended to be withdrawn in a future Autoconf release.
+! # They can cause serious problems if a builder's source tree is in a directory
+! # whose full name contains unusual characters.
+! ac_config_guess="$SHELL $ac_aux_dir/config.guess" # Please don't use this var.
+! ac_config_sub="$SHELL $ac_aux_dir/config.sub" # Please don't use this var.
+! ac_configure="$SHELL $ac_aux_dir/configure" # Please don't use this var.
+!
+
+ # Find a good install program. We prefer a C program (faster),
+ # so one script is as good as another. But avoid the broken or
+***************
+*** 1372,1382 ****
+ # SVR4 /usr/ucb/install, which tries to use the nonexistent group "staff"
+ # OS/2's system install, which has a completely different semantic
+ # ./install, which can be erroneously created by make from ./install.sh.
+! echo "$as_me:$LINENO: checking for a BSD-compatible install" >&5
+! echo $ECHO_N "checking for a BSD-compatible install... $ECHO_C" >&6
+ if test -z "$INSTALL"; then
+ if test "${ac_cv_path_install+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+ for as_dir in $PATH
+--- 1976,1987 ----
+ # SVR4 /usr/ucb/install, which tries to use the nonexistent group "staff"
+ # OS/2's system install, which has a completely different semantic
+ # ./install, which can be erroneously created by make from ./install.sh.
+! # Reject install programs that cannot install multiple files.
+! { $as_echo "$as_me:$LINENO: checking for a BSD-compatible install" >&5
+! $as_echo_n "checking for a BSD-compatible install... " >&6; }
+ if test -z "$INSTALL"; then
+ if test "${ac_cv_path_install+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+ for as_dir in $PATH
+***************
+*** 1395,1401 ****
+ # by default.
+ for ac_prog in ginstall scoinst install; do
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_prog$ac_exec_ext"; then
+ if test $ac_prog = install &&
+ grep dspmsg "$as_dir/$ac_prog$ac_exec_ext" >/dev/null 2>&1; then
+ # AIX install. It has an incompatible calling convention.
+--- 2000,2006 ----
+ # by default.
+ for ac_prog in ginstall scoinst install; do
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_prog$ac_exec_ext" && $as_test_x "$as_dir/$ac_prog$ac_exec_ext"; }; then
+ if test $ac_prog = install &&
+ grep dspmsg "$as_dir/$ac_prog$ac_exec_ext" >/dev/null 2>&1; then
+ # AIX install. It has an incompatible calling convention.
+***************
+*** 1405,1434 ****
+ # program-specific install script used by HP pwplus--don't use.
+ :
+ else
+! ac_cv_path_install="$as_dir/$ac_prog$ac_exec_ext -c"
+! break 3
+ fi
+ fi
+ done
+ done
+ ;;
+ esac
+ done
+
+
+ fi
+ if test "${ac_cv_path_install+set}" = set; then
+ INSTALL=$ac_cv_path_install
+ else
+! # As a last resort, use the slow shell script. We don't cache a
+! # path for INSTALL within a source directory, because that will
+ # break other packages using the cache if that directory is
+! # removed, or if the path is relative.
+ INSTALL=$ac_install_sh
+ fi
+ fi
+! echo "$as_me:$LINENO: result: $INSTALL" >&5
+! echo "${ECHO_T}$INSTALL" >&6
+
+ # Use test -z because SunOS4 sh mishandles braces in ${var-val}.
+ # It thinks the first close brace ends the variable substitution.
+--- 2010,2052 ----
+ # program-specific install script used by HP pwplus--don't use.
+ :
+ else
+! rm -rf conftest.one conftest.two conftest.dir
+! echo one > conftest.one
+! echo two > conftest.two
+! mkdir conftest.dir
+! if "$as_dir/$ac_prog$ac_exec_ext" -c conftest.one conftest.two "`pwd`/conftest.dir" &&
+! test -s conftest.one && test -s conftest.two &&
+! test -s conftest.dir/conftest.one &&
+! test -s conftest.dir/conftest.two
+! then
+! ac_cv_path_install="$as_dir/$ac_prog$ac_exec_ext -c"
+! break 3
+! fi
+ fi
+ fi
+ done
+ done
+ ;;
+ esac
++
+ done
++ IFS=$as_save_IFS
+
++ rm -rf conftest.one conftest.two conftest.dir
+
+ fi
+ if test "${ac_cv_path_install+set}" = set; then
+ INSTALL=$ac_cv_path_install
+ else
+! # As a last resort, use the slow shell script. Don't cache a
+! # value for INSTALL within a source directory, because that will
+ # break other packages using the cache if that directory is
+! # removed, or if the value is a relative name.
+ INSTALL=$ac_install_sh
+ fi
+ fi
+! { $as_echo "$as_me:$LINENO: result: $INSTALL" >&5
+! $as_echo "$INSTALL" >&6; }
+
+ # Use test -z because SunOS4 sh mishandles braces in ${var-val}.
+ # It thinks the first close brace ends the variable substitution.
+***************
+*** 1446,1455 ****
+ if test -n "$ac_tool_prefix"; then
+ # Extract the first word of "${ac_tool_prefix}gcc", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}gcc; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+--- 2064,2073 ----
+ if test -n "$ac_tool_prefix"; then
+ # Extract the first word of "${ac_tool_prefix}gcc", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}gcc; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+***************
+*** 1460,1493 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_CC="${ac_tool_prefix}gcc"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! echo "$as_me:$LINENO: result: $CC" >&5
+! echo "${ECHO_T}$CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+ fi
+ if test -z "$ac_cv_prog_CC"; then
+ ac_ct_CC=$CC
+ # Extract the first word of "gcc", so it can be a program name with args.
+ set dummy gcc; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_ac_ct_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$ac_ct_CC"; then
+ ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test.
+--- 2078,2113 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_CC="${ac_tool_prefix}gcc"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! { $as_echo "$as_me:$LINENO: result: $CC" >&5
+! $as_echo "$CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
++
+ fi
+ if test -z "$ac_cv_prog_CC"; then
+ ac_ct_CC=$CC
+ # Extract the first word of "gcc", so it can be a program name with args.
+ set dummy gcc; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_ac_ct_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$ac_ct_CC"; then
+ ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test.
+***************
+*** 1498,1535 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_ac_ct_CC="gcc"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ ac_ct_CC=$ac_cv_prog_ac_ct_CC
+ if test -n "$ac_ct_CC"; then
+! echo "$as_me:$LINENO: result: $ac_ct_CC" >&5
+! echo "${ECHO_T}$ac_ct_CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+! CC=$ac_ct_CC
+ else
+ CC="$ac_cv_prog_CC"
+ fi
+
+ if test -z "$CC"; then
+! if test -n "$ac_tool_prefix"; then
+! # Extract the first word of "${ac_tool_prefix}cc", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}cc; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+--- 2118,2170 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_ac_ct_CC="gcc"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ ac_ct_CC=$ac_cv_prog_ac_ct_CC
+ if test -n "$ac_ct_CC"; then
+! { $as_echo "$as_me:$LINENO: result: $ac_ct_CC" >&5
+! $as_echo "$ac_ct_CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
+! if test "x$ac_ct_CC" = x; then
+! CC=""
+! else
+! case $cross_compiling:$ac_tool_warned in
+! yes:)
+! { $as_echo "$as_me:$LINENO: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&5
+! $as_echo "$as_me: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&2;}
+! ac_tool_warned=yes ;;
+! esac
+! CC=$ac_ct_CC
+! fi
+ else
+ CC="$ac_cv_prog_CC"
+ fi
+
+ if test -z "$CC"; then
+! if test -n "$ac_tool_prefix"; then
+! # Extract the first word of "${ac_tool_prefix}cc", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}cc; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+***************
+*** 1540,1615 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_CC="${ac_tool_prefix}cc"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! echo "$as_me:$LINENO: result: $CC" >&5
+! echo "${ECHO_T}$CC" >&6
+! else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+! fi
+!
+! fi
+! if test -z "$ac_cv_prog_CC"; then
+! ac_ct_CC=$CC
+! # Extract the first word of "cc", so it can be a program name with args.
+! set dummy cc; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+! if test "${ac_cv_prog_ac_ct_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! if test -n "$ac_ct_CC"; then
+! ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test.
+! else
+! as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+! for as_dir in $PATH
+! do
+! IFS=$as_save_IFS
+! test -z "$as_dir" && as_dir=.
+! for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+! ac_cv_prog_ac_ct_CC="cc"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+! break 2
+! fi
+! done
+! done
+!
+! fi
+! fi
+! ac_ct_CC=$ac_cv_prog_ac_ct_CC
+! if test -n "$ac_ct_CC"; then
+! echo "$as_me:$LINENO: result: $ac_ct_CC" >&5
+! echo "${ECHO_T}$ac_ct_CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+- CC=$ac_ct_CC
+- else
+- CC="$ac_cv_prog_CC"
+- fi
+
+ fi
+ if test -z "$CC"; then
+ # Extract the first word of "cc", so it can be a program name with args.
+ set dummy cc; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+--- 2175,2210 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_CC="${ac_tool_prefix}cc"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! { $as_echo "$as_me:$LINENO: result: $CC" >&5
+! $as_echo "$CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
+
++ fi
+ fi
+ if test -z "$CC"; then
+ # Extract the first word of "cc", so it can be a program name with args.
+ set dummy cc; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+***************
+*** 1621,1637 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ if test "$as_dir/$ac_word$ac_exec_ext" = "/usr/ucb/cc"; then
+ ac_prog_rejected=yes
+ continue
+ fi
+ ac_cv_prog_CC="cc"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ if test $ac_prog_rejected = yes; then
+ # We found a bogon in the path, so make sure we never use it.
+--- 2216,2233 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ if test "$as_dir/$ac_word$ac_exec_ext" = "/usr/ucb/cc"; then
+ ac_prog_rejected=yes
+ continue
+ fi
+ ac_cv_prog_CC="cc"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ if test $ac_prog_rejected = yes; then
+ # We found a bogon in the path, so make sure we never use it.
+***************
+*** 1649,1672 ****
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! echo "$as_me:$LINENO: result: $CC" >&5
+! echo "${ECHO_T}$CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+ fi
+ if test -z "$CC"; then
+ if test -n "$ac_tool_prefix"; then
+! for ac_prog in cl
+ do
+ # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args.
+ set dummy $ac_tool_prefix$ac_prog; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+--- 2245,2269 ----
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! { $as_echo "$as_me:$LINENO: result: $CC" >&5
+! $as_echo "$CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
++
+ fi
+ if test -z "$CC"; then
+ if test -n "$ac_tool_prefix"; then
+! for ac_prog in cl.exe
+ do
+ # Extract the first word of "$ac_tool_prefix$ac_prog", so it can be a program name with args.
+ set dummy $ac_tool_prefix$ac_prog; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$CC"; then
+ ac_cv_prog_CC="$CC" # Let the user override the test.
+***************
+*** 1677,1714 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_CC="$ac_tool_prefix$ac_prog"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! echo "$as_me:$LINENO: result: $CC" >&5
+! echo "${ECHO_T}$CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+ test -n "$CC" && break
+ done
+ fi
+ if test -z "$CC"; then
+ ac_ct_CC=$CC
+! for ac_prog in cl
+ do
+ # Extract the first word of "$ac_prog", so it can be a program name with args.
+ set dummy $ac_prog; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_ac_ct_CC+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$ac_ct_CC"; then
+ ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test.
+--- 2274,2313 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_CC="$ac_tool_prefix$ac_prog"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ CC=$ac_cv_prog_CC
+ if test -n "$CC"; then
+! { $as_echo "$as_me:$LINENO: result: $CC" >&5
+! $as_echo "$CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
++
+ test -n "$CC" && break
+ done
+ fi
+ if test -z "$CC"; then
+ ac_ct_CC=$CC
+! for ac_prog in cl.exe
+ do
+ # Extract the first word of "$ac_prog", so it can be a program name with args.
+ set dummy $ac_prog; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_ac_ct_CC+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$ac_ct_CC"; then
+ ac_cv_prog_ac_ct_CC="$ac_ct_CC" # Let the user override the test.
+***************
+*** 1719,1776 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_ac_ct_CC="$ac_prog"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ ac_ct_CC=$ac_cv_prog_ac_ct_CC
+ if test -n "$ac_ct_CC"; then
+! echo "$as_me:$LINENO: result: $ac_ct_CC" >&5
+! echo "${ECHO_T}$ac_ct_CC" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+ test -n "$ac_ct_CC" && break
+ done
+
+! CC=$ac_ct_CC
+ fi
+
+ fi
+
+
+! test -z "$CC" && { { echo "$as_me:$LINENO: error: no acceptable C compiler found in \$PATH
+ See \`config.log' for more details." >&5
+! echo "$as_me: error: no acceptable C compiler found in \$PATH
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+
+ # Provide some information about the compiler.
+! echo "$as_me:$LINENO:" \
+! "checking for C compiler version" >&5
+! ac_compiler=`set X $ac_compile; echo $2`
+! { (eval echo "$as_me:$LINENO: \"$ac_compiler --version </dev/null >&5\"") >&5
+! (eval $ac_compiler --version </dev/null >&5) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+! { (eval echo "$as_me:$LINENO: \"$ac_compiler -v </dev/null >&5\"") >&5
+! (eval $ac_compiler -v </dev/null >&5) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+! { (eval echo "$as_me:$LINENO: \"$ac_compiler -V </dev/null >&5\"") >&5
+! (eval $ac_compiler -V </dev/null >&5) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+
+ cat >conftest.$ac_ext <<_ACEOF
+--- 2318,2409 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_ac_ct_CC="$ac_prog"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ ac_ct_CC=$ac_cv_prog_ac_ct_CC
+ if test -n "$ac_ct_CC"; then
+! { $as_echo "$as_me:$LINENO: result: $ac_ct_CC" >&5
+! $as_echo "$ac_ct_CC" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
++
+ test -n "$ac_ct_CC" && break
+ done
+
+! if test "x$ac_ct_CC" = x; then
+! CC=""
+! else
+! case $cross_compiling:$ac_tool_warned in
+! yes:)
+! { $as_echo "$as_me:$LINENO: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&5
+! $as_echo "$as_me: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&2;}
+! ac_tool_warned=yes ;;
+! esac
+! CC=$ac_ct_CC
+! fi
+ fi
+
+ fi
+
+
+! test -z "$CC" && { { $as_echo "$as_me:$LINENO: error: no acceptable C compiler found in \$PATH
+ See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: no acceptable C compiler found in \$PATH
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+
+ # Provide some information about the compiler.
+! $as_echo "$as_me:$LINENO: checking for C compiler version" >&5
+! set X $ac_compile
+! ac_compiler=$2
+! { (ac_try="$ac_compiler --version >&5"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compiler --version >&5") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+! { (ac_try="$ac_compiler -v >&5"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compiler -v >&5") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+! { (ac_try="$ac_compiler -V >&5"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compiler -V >&5") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }
+
+ cat >conftest.$ac_ext <<_ACEOF
+***************
+*** 1789,1899 ****
+ }
+ _ACEOF
+ ac_clean_files_save=$ac_clean_files
+! ac_clean_files="$ac_clean_files a.out a.exe b.out"
+ # Try to create an executable without -o first, disregard a.out.
+ # It will help us diagnose broken compilers, and finding out an intuition
+ # of exeext.
+! echo "$as_me:$LINENO: checking for C compiler default output file name" >&5
+! echo $ECHO_N "checking for C compiler default output file name... $ECHO_C" >&6
+! ac_link_default=`echo "$ac_link" | sed 's/ -o *conftest[^ ]*//'`
+! if { (eval echo "$as_me:$LINENO: \"$ac_link_default\"") >&5
+! (eval $ac_link_default) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+! # Find the output, starting from the most likely. This scheme is
+! # not robust to junk in `.', hence go to wildcards (a.*) only as a last
+! # resort.
+!
+! # Be careful to initialize this variable, since it used to be cached.
+! # Otherwise an old cache value of `no' led to `EXEEXT = no' in a Makefile.
+! ac_cv_exeext=
+! # b.out is created by i960 compilers.
+! for ac_file in a_out.exe a.exe conftest.exe a.out conftest a.* conftest.* b.out
+ do
+ test -f "$ac_file" || continue
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.o | *.obj )
+! ;;
+! conftest.$ac_ext )
+! # This is the source file.
+ ;;
+ [ab].out )
+ # We found the default executable, but exeext='' is most
+ # certainly right.
+ break;;
+ *.* )
+! ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'`
+! # FIXME: I believe we export ac_cv_exeext for Libtool,
+! # but it would be cool to find out if it's true. Does anybody
+! # maintain Libtool? --akim.
+! export ac_cv_exeext
+ break;;
+ * )
+ break;;
+ esac
+ done
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! { { echo "$as_me:$LINENO: error: C compiler cannot create executables
+ See \`config.log' for more details." >&5
+! echo "$as_me: error: C compiler cannot create executables
+ See \`config.log' for more details." >&2;}
+ { (exit 77); exit 77; }; }
+ fi
+
+ ac_exeext=$ac_cv_exeext
+- echo "$as_me:$LINENO: result: $ac_file" >&5
+- echo "${ECHO_T}$ac_file" >&6
+
+! # Check the compiler produces executables we can run. If not, either
+ # the compiler is broken, or we cross compile.
+! echo "$as_me:$LINENO: checking whether the C compiler works" >&5
+! echo $ECHO_N "checking whether the C compiler works... $ECHO_C" >&6
+ # FIXME: These cross compiler hacks should be removed for Autoconf 3.0
+ # If not cross compiling, check that we can run a simple program.
+ if test "$cross_compiling" != yes; then
+ if { ac_try='./$ac_file'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ cross_compiling=no
+ else
+ if test "$cross_compiling" = maybe; then
+ cross_compiling=yes
+ else
+! { { echo "$as_me:$LINENO: error: cannot run C compiled programs.
+ If you meant to cross compile, use \`--host'.
+ See \`config.log' for more details." >&5
+! echo "$as_me: error: cannot run C compiled programs.
+ If you meant to cross compile, use \`--host'.
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+ fi
+ fi
+! echo "$as_me:$LINENO: result: yes" >&5
+! echo "${ECHO_T}yes" >&6
+
+! rm -f a.out a.exe conftest$ac_cv_exeext b.out
+ ac_clean_files=$ac_clean_files_save
+! # Check the compiler produces executables we can run. If not, either
+ # the compiler is broken, or we cross compile.
+! echo "$as_me:$LINENO: checking whether we are cross compiling" >&5
+! echo $ECHO_N "checking whether we are cross compiling... $ECHO_C" >&6
+! echo "$as_me:$LINENO: result: $cross_compiling" >&5
+! echo "${ECHO_T}$cross_compiling" >&6
+!
+! echo "$as_me:$LINENO: checking for suffix of executables" >&5
+! echo $ECHO_N "checking for suffix of executables... $ECHO_C" >&6
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+ # If both `conftest.exe' and `conftest' are `present' (well, observable)
+ # catch `conftest.exe'. For instance with Cygwin, `ls conftest' will
+--- 2422,2567 ----
+ }
+ _ACEOF
+ ac_clean_files_save=$ac_clean_files
+! ac_clean_files="$ac_clean_files a.out a.out.dSYM a.exe b.out"
+ # Try to create an executable without -o first, disregard a.out.
+ # It will help us diagnose broken compilers, and finding out an intuition
+ # of exeext.
+! { $as_echo "$as_me:$LINENO: checking for C compiler default output file name" >&5
+! $as_echo_n "checking for C compiler default output file name... " >&6; }
+! ac_link_default=`$as_echo "$ac_link" | sed 's/ -o *conftest[^ ]*//'`
+!
+! # The possible output files:
+! ac_files="a.out conftest.exe conftest a.exe a_out.exe b.out conftest.*"
+!
+! ac_rmfiles=
+! for ac_file in $ac_files
+! do
+! case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj ) ;;
+! * ) ac_rmfiles="$ac_rmfiles $ac_file";;
+! esac
+! done
+! rm -f $ac_rmfiles
+!
+! if { (ac_try="$ac_link_default"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link_default") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+! # Autoconf-2.13 could set the ac_cv_exeext variable to `no'.
+! # So ignore a value of `no', otherwise this would lead to `EXEEXT = no'
+! # in a Makefile. We should not override ac_cv_exeext if it was cached,
+! # so that the user can short-circuit this test for compilers unknown to
+! # Autoconf.
+! for ac_file in $ac_files ''
+ do
+ test -f "$ac_file" || continue
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj )
+ ;;
+ [ab].out )
+ # We found the default executable, but exeext='' is most
+ # certainly right.
+ break;;
+ *.* )
+! if test "${ac_cv_exeext+set}" = set && test "$ac_cv_exeext" != no;
+! then :; else
+! ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'`
+! fi
+! # We set ac_cv_exeext here because the later test for it is not
+! # safe: cross compilers may not add the suffix if given an `-o'
+! # argument, so we may need to know it at that point already.
+! # Even if this section looks crufty: it has the advantage of
+! # actually working.
+ break;;
+ * )
+ break;;
+ esac
+ done
++ test "$ac_cv_exeext" = no && ac_cv_exeext=
++
+ else
+! ac_file=''
+! fi
+!
+! { $as_echo "$as_me:$LINENO: result: $ac_file" >&5
+! $as_echo "$ac_file" >&6; }
+! if test -z "$ac_file"; then
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! { { $as_echo "$as_me:$LINENO: error: C compiler cannot create executables
+ See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: C compiler cannot create executables
+ See \`config.log' for more details." >&2;}
+ { (exit 77); exit 77; }; }
+ fi
+
+ ac_exeext=$ac_cv_exeext
+
+! # Check that the compiler produces executables we can run. If not, either
+ # the compiler is broken, or we cross compile.
+! { $as_echo "$as_me:$LINENO: checking whether the C compiler works" >&5
+! $as_echo_n "checking whether the C compiler works... " >&6; }
+ # FIXME: These cross compiler hacks should be removed for Autoconf 3.0
+ # If not cross compiling, check that we can run a simple program.
+ if test "$cross_compiling" != yes; then
+ if { ac_try='./$ac_file'
+! { (case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_try") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ cross_compiling=no
+ else
+ if test "$cross_compiling" = maybe; then
+ cross_compiling=yes
+ else
+! { { $as_echo "$as_me:$LINENO: error: cannot run C compiled programs.
+ If you meant to cross compile, use \`--host'.
+ See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: cannot run C compiled programs.
+ If you meant to cross compile, use \`--host'.
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+ fi
+ fi
+! { $as_echo "$as_me:$LINENO: result: yes" >&5
+! $as_echo "yes" >&6; }
+
+! rm -f -r a.out a.out.dSYM a.exe conftest$ac_cv_exeext b.out
+ ac_clean_files=$ac_clean_files_save
+! # Check that the compiler produces executables we can run. If not, either
+ # the compiler is broken, or we cross compile.
+! { $as_echo "$as_me:$LINENO: checking whether we are cross compiling" >&5
+! $as_echo_n "checking whether we are cross compiling... " >&6; }
+! { $as_echo "$as_me:$LINENO: result: $cross_compiling" >&5
+! $as_echo "$cross_compiling" >&6; }
+!
+! { $as_echo "$as_me:$LINENO: checking for suffix of executables" >&5
+! $as_echo_n "checking for suffix of executables... " >&6; }
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+ # If both `conftest.exe' and `conftest' are `present' (well, observable)
+ # catch `conftest.exe'. For instance with Cygwin, `ls conftest' will
+***************
+*** 1902,1933 ****
+ for ac_file in conftest.exe conftest conftest.*; do
+ test -f "$ac_file" || continue
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.o | *.obj ) ;;
+ *.* ) ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'`
+- export ac_cv_exeext
+ break;;
+ * ) break;;
+ esac
+ done
+ else
+! { { echo "$as_me:$LINENO: error: cannot compute suffix of executables: cannot compile and link
+ See \`config.log' for more details." >&5
+! echo "$as_me: error: cannot compute suffix of executables: cannot compile and link
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+ rm -f conftest$ac_cv_exeext
+! echo "$as_me:$LINENO: result: $ac_cv_exeext" >&5
+! echo "${ECHO_T}$ac_cv_exeext" >&6
+
+ rm -f conftest.$ac_ext
+ EXEEXT=$ac_cv_exeext
+ ac_exeext=$EXEEXT
+! echo "$as_me:$LINENO: checking for suffix of object files" >&5
+! echo $ECHO_N "checking for suffix of object files... $ECHO_C" >&6
+ if test "${ac_cv_objext+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 2570,2600 ----
+ for ac_file in conftest.exe conftest conftest.*; do
+ test -f "$ac_file" || continue
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM | *.o | *.obj ) ;;
+ *.* ) ac_cv_exeext=`expr "$ac_file" : '[^.]*\(\..*\)'`
+ break;;
+ * ) break;;
+ esac
+ done
+ else
+! { { $as_echo "$as_me:$LINENO: error: cannot compute suffix of executables: cannot compile and link
+ See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: cannot compute suffix of executables: cannot compile and link
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+ rm -f conftest$ac_cv_exeext
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_exeext" >&5
+! $as_echo "$ac_cv_exeext" >&6; }
+
+ rm -f conftest.$ac_ext
+ EXEEXT=$ac_cv_exeext
+ ac_exeext=$EXEEXT
+! { $as_echo "$as_me:$LINENO: checking for suffix of object files" >&5
+! $as_echo_n "checking for suffix of object files... " >&6; }
+ if test "${ac_cv_objext+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 1945,1983 ****
+ }
+ _ACEOF
+ rm -f conftest.o conftest.obj
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+! for ac_file in `(ls conftest.o conftest.obj; ls conftest.*) 2>/dev/null`; do
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg ) ;;
+ *) ac_cv_objext=`expr "$ac_file" : '.*\.\(.*\)'`
+ break;;
+ esac
+ done
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! { { echo "$as_me:$LINENO: error: cannot compute suffix of object files: cannot compile
+ See \`config.log' for more details." >&5
+! echo "$as_me: error: cannot compute suffix of object files: cannot compile
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+ rm -f conftest.$ac_cv_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_objext" >&5
+! echo "${ECHO_T}$ac_cv_objext" >&6
+ OBJEXT=$ac_cv_objext
+ ac_objext=$OBJEXT
+! echo "$as_me:$LINENO: checking whether we are using the GNU C compiler" >&5
+! echo $ECHO_N "checking whether we are using the GNU C compiler... $ECHO_C" >&6
+ if test "${ac_cv_c_compiler_gnu+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 2612,2657 ----
+ }
+ _ACEOF
+ rm -f conftest.o conftest.obj
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; then
+! for ac_file in conftest.o conftest.obj conftest.*; do
+! test -f "$ac_file" || continue;
+ case $ac_file in
+! *.$ac_ext | *.xcoff | *.tds | *.d | *.pdb | *.xSYM | *.bb | *.bbg | *.map | *.inf | *.dSYM ) ;;
+ *) ac_cv_objext=`expr "$ac_file" : '.*\.\(.*\)'`
+ break;;
+ esac
+ done
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! { { $as_echo "$as_me:$LINENO: error: cannot compute suffix of object files: cannot compile
+ See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: cannot compute suffix of object files: cannot compile
+ See \`config.log' for more details." >&2;}
+ { (exit 1); exit 1; }; }
+ fi
+
+ rm -f conftest.$ac_cv_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_objext" >&5
+! $as_echo "$ac_cv_objext" >&6; }
+ OBJEXT=$ac_cv_objext
+ ac_objext=$OBJEXT
+! { $as_echo "$as_me:$LINENO: checking whether we are using the GNU C compiler" >&5
+! $as_echo_n "checking whether we are using the GNU C compiler... " >&6; }
+ if test "${ac_cv_c_compiler_gnu+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 1998,2047 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_compiler_gnu=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_compiler_gnu=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ ac_cv_c_compiler_gnu=$ac_compiler_gnu
+
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_c_compiler_gnu" >&5
+! echo "${ECHO_T}$ac_cv_c_compiler_gnu" >&6
+! GCC=`test $ac_compiler_gnu = yes && echo yes`
+ ac_test_CFLAGS=${CFLAGS+set}
+ ac_save_CFLAGS=$CFLAGS
+! CFLAGS="-g"
+! echo "$as_me:$LINENO: checking whether $CC accepts -g" >&5
+! echo $ECHO_N "checking whether $CC accepts -g... $ECHO_C" >&6
+ if test "${ac_cv_prog_cc_g+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 2672,2725 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_compiler_gnu=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_compiler_gnu=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ ac_cv_c_compiler_gnu=$ac_compiler_gnu
+
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_c_compiler_gnu" >&5
+! $as_echo "$ac_cv_c_compiler_gnu" >&6; }
+! if test $ac_compiler_gnu = yes; then
+! GCC=yes
+! else
+! GCC=
+! fi
+ ac_test_CFLAGS=${CFLAGS+set}
+ ac_save_CFLAGS=$CFLAGS
+! { $as_echo "$as_me:$LINENO: checking whether $CC accepts -g" >&5
+! $as_echo_n "checking whether $CC accepts -g... " >&6; }
+ if test "${ac_cv_prog_cc_g+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_save_c_werror_flag=$ac_c_werror_flag
+! ac_c_werror_flag=yes
+! ac_cv_prog_cc_g=no
+! CFLAGS="-g"
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 2057,2094 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_prog_cc_g=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_prog_cc_g=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_prog_cc_g" >&5
+! echo "${ECHO_T}$ac_cv_prog_cc_g" >&6
+ if test "$ac_test_CFLAGS" = set; then
+ CFLAGS=$ac_save_CFLAGS
+ elif test $ac_cv_prog_cc_g = yes; then
+--- 2735,2855 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_prog_cc_g=yes
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! CFLAGS=""
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+!
+! int
+! main ()
+! {
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_c_werror_flag=$ac_save_c_werror_flag
+! CFLAGS="-g"
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+!
+! int
+! main ()
+! {
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_prog_cc_g=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! ac_c_werror_flag=$ac_save_c_werror_flag
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_prog_cc_g" >&5
+! $as_echo "$ac_cv_prog_cc_g" >&6; }
+ if test "$ac_test_CFLAGS" = set; then
+ CFLAGS=$ac_save_CFLAGS
+ elif test $ac_cv_prog_cc_g = yes; then
+***************
+*** 2104,2115 ****
+ CFLAGS=
+ fi
+ fi
+! echo "$as_me:$LINENO: checking for $CC option to accept ANSI C" >&5
+! echo $ECHO_N "checking for $CC option to accept ANSI C... $ECHO_C" >&6
+! if test "${ac_cv_prog_cc_stdc+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! ac_cv_prog_cc_stdc=no
+ ac_save_CC=$CC
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 2865,2876 ----
+ CFLAGS=
+ fi
+ fi
+! { $as_echo "$as_me:$LINENO: checking for $CC option to accept ISO C89" >&5
+! $as_echo_n "checking for $CC option to accept ISO C89... " >&6; }
+! if test "${ac_cv_prog_cc_c89+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_prog_cc_c89=no
+ ac_save_CC=$CC
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 2143,2154 ****
+ /* OSF 4.0 Compaq cc is some sort of almost-ANSI by default. It has
+ function prototypes and stuff, but not '\xHH' hex character constants.
+ These don't provoke an error unfortunately, instead are silently treated
+! as 'x'. The following induces an error, until -std1 is added to get
+ proper ANSI mode. Curiously '\x00'!='x' always comes out true, for an
+ array size at least. It's necessary to write '\x00'==0 to get something
+! that's true only with -std1. */
+ int osf4_cc_array ['\x00' == 0 ? 1 : -1];
+
+ int test (int i, double x);
+ struct s1 {int (*f) (int a);};
+ struct s2 {int (*f) (double a);};
+--- 2904,2920 ----
+ /* OSF 4.0 Compaq cc is some sort of almost-ANSI by default. It has
+ function prototypes and stuff, but not '\xHH' hex character constants.
+ These don't provoke an error unfortunately, instead are silently treated
+! as 'x'. The following induces an error, until -std is added to get
+ proper ANSI mode. Curiously '\x00'!='x' always comes out true, for an
+ array size at least. It's necessary to write '\x00'==0 to get something
+! that's true only with -std. */
+ int osf4_cc_array ['\x00' == 0 ? 1 : -1];
+
++ /* IBM C 6 for AIX is almost-ANSI by default, but it replaces macro parameters
++ inside strings and character constants. */
++ #define FOO(x) 'x'
++ int xlc6_cc_array[FOO(a) == 'x' ? 1 : -1];
++
+ int test (int i, double x);
+ struct s1 {int (*f) (int a);};
+ struct s2 {int (*f) (double a);};
+***************
+*** 2163,2412 ****
+ return 0;
+ }
+ _ACEOF
+! # Don't try gcc -ansi; that turns off useful extensions and
+! # breaks some systems' header files.
+! # AIX -qlanglvl=ansi
+! # Ultrix and OSF/1 -std1
+! # HP-UX 10.20 and later -Ae
+! # HP-UX older versions -Aa -D_HPUX_SOURCE
+! # SVR4 -Xc -D__EXTENSIONS__
+! for ac_arg in "" -qlanglvl=ansi -std1 -Ae "-Aa -D_HPUX_SOURCE" "-Xc -D__EXTENSIONS__"
+ do
+ CC="$ac_save_CC $ac_arg"
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_prog_cc_stdc=$ac_arg
+! break
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ fi
+! rm -f conftest.err conftest.$ac_objext
+ done
+! rm -f conftest.$ac_ext conftest.$ac_objext
+ CC=$ac_save_CC
+
+ fi
+!
+! case "x$ac_cv_prog_cc_stdc" in
+! x|xno)
+! echo "$as_me:$LINENO: result: none needed" >&5
+! echo "${ECHO_T}none needed" >&6 ;;
+ *)
+! echo "$as_me:$LINENO: result: $ac_cv_prog_cc_stdc" >&5
+! echo "${ECHO_T}$ac_cv_prog_cc_stdc" >&6
+! CC="$CC $ac_cv_prog_cc_stdc" ;;
+ esac
+
+! # Some people use a C++ compiler to compile C. Since we use `exit',
+! # in C++ we need to declare it. In case someone uses the same compiler
+! # for both compiling C and C++ we need to have the C++ compiler decide
+! # the declaration of exit, since it's the most demanding environment.
+! cat >conftest.$ac_ext <<_ACEOF
+! #ifndef __cplusplus
+! choke me
+! #endif
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! for ac_declaration in \
+! '' \
+! 'extern "C" void std::exit (int) throw (); using std::exit;' \
+! 'extern "C" void std::exit (int); using std::exit;' \
+! 'extern "C" void exit (int) throw ();' \
+! 'extern "C" void exit (int);' \
+! 'void exit (int);'
+! do
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_declaration
+! #include <stdlib.h>
+! int
+! main ()
+! {
+! exit (42);
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! :
+ else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
+! continue
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_declaration
+! int
+! main ()
+! {
+! exit (42);
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! break
+! else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! done
+! rm -f conftest*
+! if test -n "$ac_declaration"; then
+! echo '#ifdef __cplusplus' >>confdefs.h
+! echo $ac_declaration >>confdefs.h
+! echo '#endif' >>confdefs.h
+! fi
+!
+! else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! ac_ext=c
+! ac_cpp='$CPP $CPPFLAGS'
+! ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+! ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+! ac_compiler_gnu=$ac_cv_c_compiler_gnu
+!
+!
+! # Put a plausible default for CC_FOR_BUILD in Makefile.
+! if test "x$cross_compiling" = "xno"; then
+! CC_FOR_BUILD='$(CC)'
+! else
+! CC_FOR_BUILD=gcc
+! fi
+! CFLAGS_FOR_BUILD=${CFLAGS_FOR_BUILD-${CFLAGS}}
+!
+! ALL_LINGUAS=
+! # If we haven't got the data from the intl directory,
+! # assume NLS is disabled.
+! USE_NLS=no
+! LIBINTL=
+! LIBINTL_DEP=
+! INCINTL=
+! XGETTEXT=
+! GMSGFMT=
+! POSUB=
+!
+! if test -f ../../intl/config.intl; then
+! . ../../intl/config.intl
+! fi
+! echo "$as_me:$LINENO: checking whether NLS is requested" >&5
+! echo $ECHO_N "checking whether NLS is requested... $ECHO_C" >&6
+! if test x"$USE_NLS" != xyes; then
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+! else
+! echo "$as_me:$LINENO: result: yes" >&5
+! echo "${ECHO_T}yes" >&6
+!
+! cat >>confdefs.h <<\_ACEOF
+! #define ENABLE_NLS 1
+ _ACEOF
+
+
+! echo "$as_me:$LINENO: checking for catalogs to be installed" >&5
+! echo $ECHO_N "checking for catalogs to be installed... $ECHO_C" >&6
+ # Look for .po and .gmo files in the source directory.
+ CATALOGS=
+ XLINGUAS=
+--- 2929,3031 ----
+ return 0;
+ }
+ _ACEOF
+! for ac_arg in '' -qlanglvl=extc89 -qlanglvl=ansi -std \
+! -Ae "-Aa -D_HPUX_SOURCE" "-Xc -D__EXTENSIONS__"
+ do
+ CC="$ac_save_CC $ac_arg"
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_prog_cc_c89=$ac_arg
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
++
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext
+! test "x$ac_cv_prog_cc_c89" != "xno" && break
+ done
+! rm -f conftest.$ac_ext
+ CC=$ac_save_CC
+
+ fi
+! # AC_CACHE_VAL
+! case "x$ac_cv_prog_cc_c89" in
+! x)
+! { $as_echo "$as_me:$LINENO: result: none needed" >&5
+! $as_echo "none needed" >&6; } ;;
+! xno)
+! { $as_echo "$as_me:$LINENO: result: unsupported" >&5
+! $as_echo "unsupported" >&6; } ;;
+ *)
+! CC="$CC $ac_cv_prog_cc_c89"
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_prog_cc_c89" >&5
+! $as_echo "$ac_cv_prog_cc_c89" >&6; } ;;
+ esac
+
+!
+! ac_ext=c
+! ac_cpp='$CPP $CPPFLAGS'
+! ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+! ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+! ac_compiler_gnu=$ac_cv_c_compiler_gnu
+!
+!
+! # Put a plausible default for CC_FOR_BUILD in Makefile.
+! if test "x$cross_compiling" = "xno"; then
+! CC_FOR_BUILD='$(CC)'
+ else
+! CC_FOR_BUILD=gcc
+! fi
+! CFLAGS_FOR_BUILD=${CFLAGS_FOR_BUILD-${CFLAGS}}
+
+! ALL_LINGUAS=
+! # If we haven't got the data from the intl directory,
+! # assume NLS is disabled.
+! USE_NLS=no
+! LIBINTL=
+! LIBINTL_DEP=
+! INCINTL=
+! XGETTEXT=
+! GMSGFMT=
+! POSUB=
+!
+! if test -f ../../intl/config.intl; then
+! . ../../intl/config.intl
+ fi
+! { $as_echo "$as_me:$LINENO: checking whether NLS is requested" >&5
+! $as_echo_n "checking whether NLS is requested... " >&6; }
+! if test x"$USE_NLS" != xyes; then
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+! else
+! { $as_echo "$as_me:$LINENO: result: yes" >&5
+! $as_echo "yes" >&6; }
+!
+! cat >>confdefs.h <<\_ACEOF
+! #define ENABLE_NLS 1
+ _ACEOF
+
+
+! { $as_echo "$as_me:$LINENO: checking for catalogs to be installed" >&5
+! $as_echo_n "checking for catalogs to be installed... " >&6; }
+ # Look for .po and .gmo files in the source directory.
+ CATALOGS=
+ XLINGUAS=
+***************
+*** 2437,2444 ****
+ fi
+ done
+ LINGUAS="$XLINGUAS"
+! echo "$as_me:$LINENO: result: $LINGUAS" >&5
+! echo "${ECHO_T}$LINGUAS" >&6
+
+
+ DATADIRNAME=share
+--- 3056,3063 ----
+ fi
+ done
+ LINGUAS="$XLINGUAS"
+! { $as_echo "$as_me:$LINENO: result: $LINGUAS" >&5
+! $as_echo "$LINGUAS" >&6; }
+
+
+ DATADIRNAME=share
+***************
+*** 2452,2466 ****
+ fi
+
+
+! # Check whether --enable-sim-alignment or --disable-sim-alignment was given.
+ if test "${enable_sim_alignment+set}" = set; then
+! enableval="$enable_sim_alignment"
+! case "${enableval}" in
+ yes | strict | STRICT) sim_alignment="-DWITH_ALIGNMENT=STRICT_ALIGNMENT";;
+ no | nonstrict | NONSTRICT) sim_alignment="-DWITH_ALIGNMENT=NONSTRICT_ALIGNMENT";;
+ 0 | default | DEFAULT) sim_alignment="-DWITH_ALIGNMENT=0";;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-alignment\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-alignment\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_alignment="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_alignment" != x""; then
+--- 3071,3084 ----
+ fi
+
+
+! # Check whether --enable-sim-alignment was given.
+ if test "${enable_sim_alignment+set}" = set; then
+! enableval=$enable_sim_alignment; case "${enableval}" in
+ yes | strict | STRICT) sim_alignment="-DWITH_ALIGNMENT=STRICT_ALIGNMENT";;
+ no | nonstrict | NONSTRICT) sim_alignment="-DWITH_ALIGNMENT=NONSTRICT_ALIGNMENT";;
+ 0 | default | DEFAULT) sim_alignment="-DWITH_ALIGNMENT=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-alignment\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-alignment\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_alignment="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_alignment" != x""; then
+***************
+*** 2468,2483 ****
+ fi
+ else
+ sim_alignment=""
+! fi;
+
+! # Check whether --enable-sim-assert or --disable-sim-assert was given.
+ if test "${enable_sim_assert+set}" = set; then
+! enableval="$enable_sim_assert"
+! case "${enableval}" in
+ yes) sim_assert="-DWITH_ASSERT=1";;
+ no) sim_assert="-DWITH_ASSERT=0";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-assert does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-assert does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_assert="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_assert" != x""; then
+--- 3086,3101 ----
+ fi
+ else
+ sim_alignment=""
+! fi
+
+!
+! # Check whether --enable-sim-assert was given.
+ if test "${enable_sim_assert+set}" = set; then
+! enableval=$enable_sim_assert; case "${enableval}" in
+ yes) sim_assert="-DWITH_ASSERT=1";;
+ no) sim_assert="-DWITH_ASSERT=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-assert does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-assert does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_assert="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_assert" != x""; then
+***************
+*** 2485,2499 ****
+ fi
+ else
+ sim_assert=""
+! fi;
+
+! # Check whether --enable-sim-bitsize or --disable-sim-bitsize was given.
+ if test "${enable_sim_bitsize+set}" = set; then
+! enableval="$enable_sim_bitsize"
+! case "${enableval}" in
+ 32|64) sim_bitsize="-DWITH_TARGET_WORD_BITSIZE=$enableval";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-bitsize was given $enableval. Expected 32 or 64\"" >&5
+! echo "$as_me: error: \"--enable-sim-bitsize was given $enableval. Expected 32 or 64\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_bitsize="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_bitsize" != x""; then
+--- 3103,3117 ----
+ fi
+ else
+ sim_assert=""
+! fi
+
+!
+! # Check whether --enable-sim-bitsize was given.
+ if test "${enable_sim_bitsize+set}" = set; then
+! enableval=$enable_sim_bitsize; case "${enableval}" in
+ 32|64) sim_bitsize="-DWITH_TARGET_WORD_BITSIZE=$enableval";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-bitsize was given $enableval. Expected 32 or 64\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-bitsize was given $enableval. Expected 32 or 64\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_bitsize="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_bitsize" != x""; then
+***************
+*** 2501,2516 ****
+ fi
+ else
+ sim_bitsize=""
+! fi;
+
+! # Check whether --enable-sim-bswap or --disable-sim-bswap was given.
+ if test "${enable_sim_bswap+set}" = set; then
+! enableval="$enable_sim_bswap"
+! case "${enableval}" in
+ yes) sim_bswap="-DWITH_BSWAP=1";;
+ no) sim_bswap="-DWITH_BSWAP=0";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-bswap does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-bswap does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_bswap="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_bswap" != x""; then
+--- 3119,3134 ----
+ fi
+ else
+ sim_bitsize=""
+! fi
+
+!
+! # Check whether --enable-sim-bswap was given.
+ if test "${enable_sim_bswap+set}" = set; then
+! enableval=$enable_sim_bswap; case "${enableval}" in
+ yes) sim_bswap="-DWITH_BSWAP=1";;
+ no) sim_bswap="-DWITH_BSWAP=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-bswap does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-bswap does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_bswap="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_bswap" != x""; then
+***************
+*** 2518,2529 ****
+ fi
+ else
+ sim_bswap=""
+! fi;
+
+! # Check whether --enable-sim-cflags or --disable-sim-cflags was given.
+ if test "${enable_sim_cflags+set}" = set; then
+! enableval="$enable_sim_cflags"
+! case "${enableval}" in
+ yes) sim_cflags="-O2 -fomit-frame-pointer";;
+ no) sim_cflags="";;
+ *) sim_cflags=`echo "${enableval}" | sed -e "s/,/ /g"`;;
+--- 3136,3147 ----
+ fi
+ else
+ sim_bswap=""
+! fi
+
+!
+! # Check whether --enable-sim-cflags was given.
+ if test "${enable_sim_cflags+set}" = set; then
+! enableval=$enable_sim_cflags; case "${enableval}" in
+ yes) sim_cflags="-O2 -fomit-frame-pointer";;
+ no) sim_cflags="";;
+ *) sim_cflags=`echo "${enableval}" | sed -e "s/,/ /g"`;;
+***************
+*** 2533,2554 ****
+ fi
+ else
+ sim_cflags=""
+! fi;
+
+! # Check whether --enable-sim-config or --disable-sim-config was given.
+ if test "${enable_sim_config+set}" = set; then
+! enableval="$enable_sim_config"
+! case "${enableval}" in
+! yes|no) { { echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-config=file\"" >&5
+! echo "$as_me: error: \"No value supplied for --enable-sim-config=file\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ *) if test -f "${srcdir}/${enableval}"; then
+ sim_config="${enableval}";
+ elif test -f "${srcdir}/${enableval}-config.h"; then
+ sim_config="${enableval}-config.h"
+ else
+! { { echo "$as_me:$LINENO: error: \"Config file $enableval was not found\"" >&5
+! echo "$as_me: error: \"Config file $enableval was not found\"" >&2;}
+ { (exit 1); exit 1; }; };
+ sim_config=std-config.h
+ fi;;
+--- 3151,3172 ----
+ fi
+ else
+ sim_cflags=""
+! fi
+
+!
+! # Check whether --enable-sim-config was given.
+ if test "${enable_sim_config+set}" = set; then
+! enableval=$enable_sim_config; case "${enableval}" in
+! yes|no) { { $as_echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-config=file\"" >&5
+! $as_echo "$as_me: error: \"No value supplied for --enable-sim-config=file\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ *) if test -f "${srcdir}/${enableval}"; then
+ sim_config="${enableval}";
+ elif test -f "${srcdir}/${enableval}-config.h"; then
+ sim_config="${enableval}-config.h"
+ else
+! { { $as_echo "$as_me:$LINENO: error: \"Config file $enableval was not found\"" >&5
+! $as_echo "$as_me: error: \"Config file $enableval was not found\"" >&2;}
+ { (exit 1); exit 1; }; };
+ sim_config=std-config.h
+ fi;;
+***************
+*** 2561,2578 ****
+ if test x"$silent" != x"yes"; then
+ echo "Setting config flags = $sim_config" 6>&1
+ fi
+! fi;
+
+! # Check whether --enable-sim-decode-mechanism or --disable-sim-decode-mechanism was given.
+ if test "${enable_sim_decode_mechanism+set}" = set; then
+! enableval="$enable_sim_decode_mechanism"
+! case "${enableval}" in
+! yes|no) { { echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-decode-mechanism=file\"" >&5
+! echo "$as_me: error: \"No value supplied for --enable-sim-decode-mechanism=file\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ array|switch|padded-switch|goto-switch) sim_decode_mechanism="-T ${enableval}";;
+! *) { { echo "$as_me:$LINENO: error: \"File $enableval is not an opcode rules file\"" >&5
+! echo "$as_me: error: \"File $enableval is not an opcode rules file\"" >&2;}
+ { (exit 1); exit 1; }; };
+ sim_decode_mechanism="switch";;
+ esac
+--- 3179,3196 ----
+ if test x"$silent" != x"yes"; then
+ echo "Setting config flags = $sim_config" 6>&1
+ fi
+! fi
+
+!
+! # Check whether --enable-sim-decode-mechanism was given.
+ if test "${enable_sim_decode_mechanism+set}" = set; then
+! enableval=$enable_sim_decode_mechanism; case "${enableval}" in
+! yes|no) { { $as_echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-decode-mechanism=file\"" >&5
+! $as_echo "$as_me: error: \"No value supplied for --enable-sim-decode-mechanism=file\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ array|switch|padded-switch|goto-switch) sim_decode_mechanism="-T ${enableval}";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"File $enableval is not an opcode rules file\"" >&5
+! $as_echo "$as_me: error: \"File $enableval is not an opcode rules file\"" >&2;}
+ { (exit 1); exit 1; }; };
+ sim_decode_mechanism="switch";;
+ esac
+***************
+*** 2584,2597 ****
+ if test x"$silent" != x"yes"; then
+ echo "Setting decode mechanism flags = $sim_decode_mechanism"
+ fi
+! fi;
+
+! # Check whether --enable-sim-default-model or --disable-sim-default-model was given.
+ if test "${enable_sim_default_model+set}" = set; then
+! enableval="$enable_sim_default_model"
+! case "${enableval}" in
+! yes|no) { { echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-default-model=model\"" >&5
+! echo "$as_me: error: \"No value supplied for --enable-sim-default-model=model\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ *) sim_default_model="-DWITH_DEFAULT_MODEL=${enableval}";;
+ esac
+--- 3202,3215 ----
+ if test x"$silent" != x"yes"; then
+ echo "Setting decode mechanism flags = $sim_decode_mechanism"
+ fi
+! fi
+
+!
+! # Check whether --enable-sim-default-model was given.
+ if test "${enable_sim_default_model+set}" = set; then
+! enableval=$enable_sim_default_model; case "${enableval}" in
+! yes|no) { { $as_echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-default-model=model\"" >&5
+! $as_echo "$as_me: error: \"No value supplied for --enable-sim-default-model=model\"" >&2;}
+ { (exit 1); exit 1; }; };;
+ *) sim_default_model="-DWITH_DEFAULT_MODEL=${enableval}";;
+ esac
+***************
+*** 2600,2615 ****
+ fi
+ else
+ sim_default_model=""
+! fi;
+
+! # Check whether --enable-sim-duplicate or --disable-sim-duplicate was given.
+ if test "${enable_sim_duplicate+set}" = set; then
+! enableval="$enable_sim_duplicate"
+! case "${enableval}" in
+ yes) sim_dup="-E";;
+ no) sim_dup="";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-duplicate does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-duplicate does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_dup="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_dup" != x""; then
+--- 3218,3233 ----
+ fi
+ else
+ sim_default_model=""
+! fi
+
+!
+! # Check whether --enable-sim-duplicate was given.
+ if test "${enable_sim_duplicate+set}" = set; then
+! enableval=$enable_sim_duplicate; case "${enableval}" in
+ yes) sim_dup="-E";;
+ no) sim_dup="";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-duplicate does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-duplicate does not take a value\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_dup="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_dup" != x""; then
+***************
+*** 2620,2631 ****
+ if test x"$silent" != x"yes"; then
+ echo "Setting duplicate flags = $sim_dup" 6>&1
+ fi
+! fi;
+
+! # Check whether --enable-sim-endian or --disable-sim-endian was given.
+ if test "${enable_sim_endian+set}" = set; then
+! enableval="$enable_sim_endian"
+! case "${enableval}" in
+ yes) case "$target" in
+ *powerpc-*) sim_endian="-DWITH_TARGET_BYTE_ORDER=BIG_ENDIAN";;
+ *powerpcle-*) sim_endian="-DWITH_TARGET_BYTE_ORDER=LITTLE_ENDIAN";;
+--- 3238,3249 ----
+ if test x"$silent" != x"yes"; then
+ echo "Setting duplicate flags = $sim_dup" 6>&1
+ fi
+! fi
+
+!
+! # Check whether --enable-sim-endian was given.
+ if test "${enable_sim_endian+set}" = set; then
+! enableval=$enable_sim_endian; case "${enableval}" in
+ yes) case "$target" in
+ *powerpc-*) sim_endian="-DWITH_TARGET_BYTE_ORDER=BIG_ENDIAN";;
+ *powerpcle-*) sim_endian="-DWITH_TARGET_BYTE_ORDER=LITTLE_ENDIAN";;
+***************
+*** 2634,2641 ****
+ no) sim_endian="-DWITH_TARGET_BYTE_ORDER=0";;
+ b*|B*) sim_endian="-DWITH_TARGET_BYTE_ORDER=BIG_ENDIAN";;
+ l*|L*) sim_endian="-DWITH_TARGET_BYTE_ORDER=LITTLE_ENDIAN";;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-endian\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval for --enable-sim-endian\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_endian="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_endian" != x""; then
+--- 3252,3259 ----
+ no) sim_endian="-DWITH_TARGET_BYTE_ORDER=0";;
+ b*|B*) sim_endian="-DWITH_TARGET_BYTE_ORDER=BIG_ENDIAN";;
+ l*|L*) sim_endian="-DWITH_TARGET_BYTE_ORDER=LITTLE_ENDIAN";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-endian\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval for --enable-sim-endian\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_endian="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_endian" != x""; then
+***************
+*** 2643,2660 ****
+ fi
+ else
+ sim_endian=""
+! fi;
+
+! # Check whether --enable-sim-env or --disable-sim-env was given.
+ if test "${enable_sim_env+set}" = set; then
+! enableval="$enable_sim_env"
+! case "${enableval}" in
+ operating | os | oea) sim_env="-DWITH_ENVIRONMENT=OPERATING_ENVIRONMENT";;
+ virtual | vea) sim_env="-DWITH_ENVIRONMENT=VIRTUAL_ENVIRONMENT";;
+ user | uea) sim_env="-DWITH_ENVIRONMENT=USER_ENVIRONMENT";;
+ no) sim_env="-DWITH_ENVIRONMENT=0";;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-env\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-env\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_env="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_env" != x""; then
+--- 3261,3278 ----
+ fi
+ else
+ sim_endian=""
+! fi
+
+!
+! # Check whether --enable-sim-env was given.
+ if test "${enable_sim_env+set}" = set; then
+! enableval=$enable_sim_env; case "${enableval}" in
+ operating | os | oea) sim_env="-DWITH_ENVIRONMENT=OPERATING_ENVIRONMENT";;
+ virtual | vea) sim_env="-DWITH_ENVIRONMENT=VIRTUAL_ENVIRONMENT";;
+ user | uea) sim_env="-DWITH_ENVIRONMENT=USER_ENVIRONMENT";;
+ no) sim_env="-DWITH_ENVIRONMENT=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-env\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-env\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_env="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_env" != x""; then
+***************
+*** 2662,2675 ****
+ fi
+ else
+ sim_env=""
+! fi;
+
+! # Check whether --enable-sim-filter or --disable-sim-filter was given.
+ if test "${enable_sim_filter+set}" = set; then
+! enableval="$enable_sim_filter"
+! case "${enableval}" in
+! yes) { { echo "$as_me:$LINENO: error: \"--enable-sim-filter must be specified with a rule to filter or no\"" >&5
+! echo "$as_me: error: \"--enable-sim-filter must be specified with a rule to filter or no\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_filter="";;
+ no) sim_filter="";;
+ *) sim_filter="-F $enableval";;
+--- 3280,3293 ----
+ fi
+ else
+ sim_env=""
+! fi
+
+!
+! # Check whether --enable-sim-filter was given.
+ if test "${enable_sim_filter+set}" = set; then
+! enableval=$enable_sim_filter; case "${enableval}" in
+! yes) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-filter must be specified with a rule to filter or no\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-filter must be specified with a rule to filter or no\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_filter="";;
+ no) sim_filter="";;
+ *) sim_filter="-F $enableval";;
+***************
+*** 2682,2699 ****
+ if test x"$silent" != x"yes"; then
+ echo "Setting filter flags = $sim_filter" 6>&1
+ fi
+! fi;
+
+! # Check whether --enable-sim-float or --disable-sim-float was given.
+ if test "${enable_sim_float+set}" = set; then
+! enableval="$enable_sim_float"
+! case "${enableval}" in
+ yes | hard) sim_float="-DWITH_FLOATING_POINT=HARD_FLOATING_POINT";;
+ no | soft) sim_float="-DWITH_FLOATING_POINT=SOFT_FLOATING_POINT";;
+ altivec) sim_float="-DWITH_ALTIVEC" ; sim_filter="${sim_filter},av" ;;
+ *spe*|*simd*) sim_float="-DWITH_E500" ; sim_filter="${sim_filter},e500" ;;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-float\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-float\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_float="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_float" != x""; then
+--- 3300,3317 ----
+ if test x"$silent" != x"yes"; then
+ echo "Setting filter flags = $sim_filter" 6>&1
+ fi
+! fi
+
+!
+! # Check whether --enable-sim-float was given.
+ if test "${enable_sim_float+set}" = set; then
+! enableval=$enable_sim_float; case "${enableval}" in
+ yes | hard) sim_float="-DWITH_FLOATING_POINT=HARD_FLOATING_POINT";;
+ no | soft) sim_float="-DWITH_FLOATING_POINT=SOFT_FLOATING_POINT";;
+ altivec) sim_float="-DWITH_ALTIVEC" ; sim_filter="${sim_filter},av" ;;
+ *spe*|*simd*) sim_float="-DWITH_E500" ; sim_filter="${sim_filter},e500" ;;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-float\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-float\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_float="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_float" != x""; then
+***************
+*** 2707,2722 ****
+ *) sim_float=""
+ esac
+
+! fi;
+
+! # Check whether --enable-sim-hardware or --disable-sim-hardware was given.
+ if test "${enable_sim_hardware+set}" = set; then
+! enableval="$enable_sim_hardware"
+! hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide"
+ case "${enableval}" in
+ yes) ;;
+! no) { { echo "$as_me:$LINENO: error: \"List of hardware must be specified for --enable-sim-hardware\"" >&5
+! echo "$as_me: error: \"List of hardware must be specified for --enable-sim-hardware\"" >&2;}
+ { (exit 1); exit 1; }; }; hardware="";;
+ ,*) hardware="${hardware}${enableval}";;
+ *,) hardware="${enableval}${hardware}";;
+--- 3325,3340 ----
+ *) sim_float=""
+ esac
+
+! fi
+!
+
+! # Check whether --enable-sim-hardware was given.
+ if test "${enable_sim_hardware+set}" = set; then
+! enableval=$enable_sim_hardware; hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide,ethtap"
+ case "${enableval}" in
+ yes) ;;
+! no) { { $as_echo "$as_me:$LINENO: error: \"List of hardware must be specified for --enable-sim-hardware\"" >&5
+! $as_echo "$as_me: error: \"List of hardware must be specified for --enable-sim-hardware\"" >&2;}
+ { (exit 1); exit 1; }; }; hardware="";;
+ ,*) hardware="${hardware}${enableval}";;
+ *,) hardware="${enableval}${hardware}";;
+***************
+*** 2728,2748 ****
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+ fi
+ else
+! hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide"
+ sim_hw_src=`echo $hardware | sed -e 's/,/.c hw_/g' -e 's/^/hw_/' -e s'/$/.c/'`
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes"; then
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+ fi
+! fi;
+
+! # Check whether --enable-sim-hostbitsize or --disable-sim-hostbitsize was given.
+ if test "${enable_sim_hostbitsize+set}" = set; then
+! enableval="$enable_sim_hostbitsize"
+! case "${enableval}" in
+ 32|64) sim_hostbitsize="-DWITH_HOST_WORD_BITSIZE=$enableval";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-hostbitsize was given $enableval. Expected 32 or 64\"" >&5
+! echo "$as_me: error: \"--enable-sim-hostbitsize was given $enableval. Expected 32 or 64\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_hostbitsize="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_hostbitsize" != x""; then
+--- 3346,3366 ----
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+ fi
+ else
+! hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide,ethtap"
+ sim_hw_src=`echo $hardware | sed -e 's/,/.c hw_/g' -e 's/^/hw_/' -e s'/$/.c/'`
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes"; then
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+ fi
+! fi
+
+!
+! # Check whether --enable-sim-hostbitsize was given.
+ if test "${enable_sim_hostbitsize+set}" = set; then
+! enableval=$enable_sim_hostbitsize; case "${enableval}" in
+ 32|64) sim_hostbitsize="-DWITH_HOST_WORD_BITSIZE=$enableval";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-hostbitsize was given $enableval. Expected 32 or 64\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-hostbitsize was given $enableval. Expected 32 or 64\"" >&2;}
+ { (exit 1); exit 1; }; }; sim_hostbitsize="";;
+ esac
+ if test x"$silent" != x"yes" && test x"$sim_hostbitsize" != x""; then
+***************
+*** 2750,4005 ****
+ fi
+ else
+ sim_hostbitsize=""
+! fi;
+
+
+- # Check whether --enable-sim-hostendian or --disable-sim-hostendian was given.
+- if test "${enable_sim_hostendian+set}" = set; then
+- enableval="$enable_sim_hostendian"
+- case "${enableval}" in
+- no) sim_hostendian="-DWITH_HOST_BYTE_ORDER=0";;
+- b*|B*) sim_hostendian="-DWITH_HOST_BYTE_ORDER=BIG_ENDIAN";;
+- l*|L*) sim_hostendian="-DWITH_HOST_BYTE_ORDER=LITTLE_ENDIAN";;
+- *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-hostendian\"" >&5
+- echo "$as_me: error: \"Unknown value $enableval for --enable-sim-hostendian\"" >&2;}
+- { (exit 1); exit 1; }; }; sim_hostendian="";;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_hostendian" != x""; then
+- echo "Setting hostendian flags = $sim_hostendian" 6>&1
+- fi
+- else
+
+! if test "x$cross_compiling" = "xno"; then
+! echo "$as_me:$LINENO: checking whether byte ordering is bigendian" >&5
+! echo $ECHO_N "checking whether byte ordering is bigendian... $ECHO_C" >&6
+! if test "${ac_cv_c_bigendian+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! # See if sys/param.h defines the BYTE_ORDER macro.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #include <sys/types.h>
+! #include <sys/param.h>
+!
+! int
+! main ()
+! {
+! #if !BYTE_ORDER || !BIG_ENDIAN || !LITTLE_ENDIAN
+! bogus endian macros
+ #endif
+!
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! # It does; now see whether it defined to BIG_ENDIAN or not.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #include <sys/types.h>
+! #include <sys/param.h>
+!
+! int
+! main ()
+! {
+! #if BYTE_ORDER != BIG_ENDIAN
+! not big endian
+! #endif
+!
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_c_bigendian=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_c_bigendian=no
+ fi
+- rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+- else
+- echo "$as_me: failed program was:" >&5
+- sed 's/^/| /' conftest.$ac_ext >&5
+
+! # It does not; compile a test program.
+! if test "$cross_compiling" = yes; then
+! # try to guess the endianness by grepping values into an object file
+! ac_cv_c_bigendian=unknown
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! short ascii_mm[] = { 0x4249, 0x4765, 0x6E44, 0x6961, 0x6E53, 0x7953, 0 };
+! short ascii_ii[] = { 0x694C, 0x5454, 0x656C, 0x6E45, 0x6944, 0x6E61, 0 };
+! void _ascii () { char *s = (char *) ascii_mm; s = (char *) ascii_ii; }
+! short ebcdic_ii[] = { 0x89D3, 0xE3E3, 0x8593, 0x95C5, 0x89C4, 0x9581, 0 };
+! short ebcdic_mm[] = { 0xC2C9, 0xC785, 0x95C4, 0x8981, 0x95E2, 0xA8E2, 0 };
+! void _ebcdic () { char *s = (char *) ebcdic_mm; s = (char *) ebcdic_ii; }
+! int
+! main ()
+! {
+! _ascii (); _ebcdic ();
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! if grep BIGenDianSyS conftest.$ac_objext >/dev/null ; then
+! ac_cv_c_bigendian=yes
+! fi
+! if grep LiTTleEnDian conftest.$ac_objext >/dev/null ; then
+! if test "$ac_cv_c_bigendian" = unknown; then
+! ac_cv_c_bigendian=no
+! else
+! # finding both strings is unlikely to happen, but who knows?
+! ac_cv_c_bigendian=unknown
+! fi
+! fi
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! int
+! main ()
+! {
+! /* Are we little or big endian? From Harbison&Steele. */
+! union
+! {
+! long l;
+! char c[sizeof (long)];
+! } u;
+! u.l = 1;
+! exit (u.c[sizeof (long) - 1] == 1);
+! }
+ _ACEOF
+! rm -f conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_c_bigendian=no
+ else
+! echo "$as_me: program exited with status $ac_status" >&5
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ( exit $ac_status )
+! ac_cv_c_bigendian=yes
+! fi
+! rm -f core *.core gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+! fi
+! fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+- echo "$as_me:$LINENO: result: $ac_cv_c_bigendian" >&5
+- echo "${ECHO_T}$ac_cv_c_bigendian" >&6
+- case $ac_cv_c_bigendian in
+- yes)
+
+! cat >>confdefs.h <<\_ACEOF
+! #define WORDS_BIGENDIAN 1
+! _ACEOF
+! ;;
+! no)
+! ;;
+! *)
+! { { echo "$as_me:$LINENO: error: unknown endianness
+! presetting ac_cv_c_bigendian=no (or yes) will help" >&5
+! echo "$as_me: error: unknown endianness
+! presetting ac_cv_c_bigendian=no (or yes) will help" >&2;}
+! { (exit 1); exit 1; }; } ;;
+! esac
+
+! if test $ac_cv_c_bigendian = yes; then
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=BIG_ENDIAN"
+! else
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=LITTLE_ENDIAN"
+! fi
+ else
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=0"
+ fi
+- fi;
+
+! # Check whether --enable-sim-icache or --disable-sim-icache was given.
+! if test "${enable_sim_icache+set}" = set; then
+! enableval="$enable_sim_icache"
+! icache="-R"
+! case "${enableval}" in
+! yes) icache="1024"; sim_icache="-I $icache";;
+! no) sim_icache="-R";;
+! *) icache=1024
+! sim_icache="-"
+! for x in `echo "${enableval}" | sed -e "s/,/ /g"`; do
+! case "$x" in
+! define) sim_icache="${sim_icache}R";;
+! semantic) sim_icache="${sim_icache}C";;
+! insn) sim_icache="${sim_icache}S";;
+! 0*|1*|2*|3*|4*|5*|6*|7*|8*|9*) icache=$x;;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $x for --enable-sim-icache\"" >&5
+! echo "$as_me: error: \"Unknown value $x for --enable-sim-icache\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_icache="";;
+! esac
+! done
+! sim_icache="${sim_icache}I $icache";;
+ esac
+! if test x"$silent" != x"yes" && test x"$icache" != x""; then
+! echo "Setting instruction cache size to $icache ($sim_icache)"
+! fi
+ else
+! sim_icache="-CSRI 1024"
+! if test x"$silent" != x"yes"; then
+! echo "Setting instruction cache size to 1024 ($sim_icache)"
+ fi
+- fi;
+
+- # Check whether --enable-sim-inline or --disable-sim-inline was given.
+- if test "${enable_sim_inline+set}" = set; then
+- enableval="$enable_sim_inline"
+- sim_inline=""
+- case "$enableval" in
+- no) sim_inline="-DDEFAULT_INLINE=0";;
+- 0) sim_inline="-DDEFAULT_INLINE=0";;
+- yes | 2) sim_inline="-DDEFAULT_INLINE=ALL_INLINE";;
+- 1) sim_inline="-DDEFAULT_INLINE=PSIM_INLINE_LOCALS";;
+- *) for x in `echo "$enableval" | sed -e "s/,/ /g"`; do
+- new_flag=""
+- case "$x" in
+- *_INLINE=*) new_flag="-D$x";;
+- *=*) new_flag=`echo "$x" | sed -e "s/=/_INLINE=/" -e "s/^/-D/"`;;
+- *_INLINE) new_flag="-D$x=ALL_INLINE";;
+- *) new_flag="-D$x""_INLINE=ALL_INLINE";;
+- esac
+- if test x"$sim_inline" = x""; then
+- sim_inline="$new_flag"
+- else
+- sim_inline="$sim_inline $new_flag"
+- fi
+- done;;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_inline" != x""; then
+- echo "Setting inline flags = $sim_inline" 6>&1
+ fi
+ else
+! if test x"$GCC" != ""; then
+! sim_inline="-DDEFAULT_INLINE=PSIM_INLINE_LOCALS"
+! if test x"$silent" != x"yes"; then
+! echo "Setting inline flags = $sim_inline" 6>&1
+ fi
+ else
+! sim_inline=""
+ fi
+- fi;
+
+! # Check whether --enable-sim-jump or --disable-sim-jump was given.
+! if test "${enable_sim_jump+set}" = set; then
+! enableval="$enable_sim_jump"
+! case "${enableval}" in
+! yes) sim_jump="-J";;
+! no) sim_jump="";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-jump does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-jump does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_jump="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_jump" != x""; then
+! echo "Setting jump flag = $sim_jump" 6>&1
+ fi
+ else
+! sim_jump=""
+! if test x"$silent" != x"yes"; then
+! echo "Setting jump flag = $sim_jump" 6>&1
+! fi
+! fi;
+
+! # Check whether --enable-sim-line-nr or --disable-sim-line-nr was given.
+! if test "${enable_sim_line_nr+set}" = set; then
+! enableval="$enable_sim_line_nr"
+! case "${enableval}" in
+! yes) sim_line_nr="";;
+! no) sim_line_nr="-L";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-line-nr does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-line-nr does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_line_nr="";;
+ esac
+! if test x"$silent" != x"yes" && test x"$sim_line_nr" != x""; then
+! echo "Setting warning flags = $sim_line_nr" 6>&1
+! fi
+ else
+! sim_line_nr=""
+! fi;
+
+! # Check whether --enable-sim-model or --disable-sim-model was given.
+! if test "${enable_sim_model+set}" = set; then
+! enableval="$enable_sim_model"
+! case "${enableval}" in
+! yes|no) { { echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-model=model\"" >&5
+! echo "$as_me: error: \"No value supplied for --enable-sim-model=model\"" >&2;}
+! { (exit 1); exit 1; }; };;
+! *) sim_model="-DWITH_MODEL=${enableval}";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_model" != x""; then
+! echo "Setting model flags = $sim_model" 6>&1
+ fi
+ else
+! sim_model=""
+! fi;
+
+- # Check whether --enable-sim-model-issue or --disable-sim-model-issue was given.
+- if test "${enable_sim_model_issue+set}" = set; then
+- enableval="$enable_sim_model_issue"
+- case "${enableval}" in
+- yes) sim_model_issue="-DWITH_MODEL_ISSUE=MODEL_ISSUE_PROCESS";;
+- no) sim_model_issue="-DWITH_MODEL_ISSUE=MODEL_ISSUE_IGNORE";;
+- *) { { echo "$as_me:$LINENO: error: \"--enable-sim-model-issue does not take a value\"" >&5
+- echo "$as_me: error: \"--enable-sim-model-issue does not take a value\"" >&2;}
+- { (exit 1); exit 1; }; }; sim_model_issue="";;
+- esac
+- if test x"$silent" != x"yes"; then
+- echo "Setting model-issue flags = $sim_model_issue" 6>&1
+ fi
+ else
+! sim_model_issue=""
+! fi;
+
+- # Check whether --enable-sim-monitor or --disable-sim-monitor was given.
+- if test "${enable_sim_monitor+set}" = set; then
+- enableval="$enable_sim_monitor"
+- case "${enableval}" in
+- yes) sim_monitor="-DWITH_MON='MONITOR_INSTRUCTION_ISSUE | MONITOR_LOAD_STORE_UNIT'";;
+- no) sim_monitor="-DWITH_MON=0";;
+- instruction) sim_monitor="-DWITH_MON=MONITOR_INSTRUCTION_ISSUE";;
+- memory) sim_monitor="-DWITH_MON=MONITOR_LOAD_STORE_UNIT";;
+- *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-mon\"" >&5
+- echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-mon\"" >&2;}
+- { (exit 1); exit 1; }; }; sim_env="";;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_monitor" != x""; then
+- echo "Setting monitor flags = $sim_monitor" 6>&1
+ fi
+ else
+! sim_monitor=""
+! fi;
+
+! # Check whether --enable-sim-opcode or --disable-sim-opcode was given.
+! if test "${enable_sim_opcode+set}" = set; then
+! enableval="$enable_sim_opcode"
+! case "${enableval}" in
+! yes|no) { { echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-opcode=file\"" >&5
+! echo "$as_me: error: \"No value supplied for --enable-sim-opcode=file\"" >&2;}
+! { (exit 1); exit 1; }; };;
+! *) if test -f "${srcdir}/${enableval}"; then
+! sim_opcode="${enableval}"
+! elif test -f "${srcdir}/dc-${enableval}"; then
+! sim_opcode="dc-${enableval}"
+! else
+! { { echo "$as_me:$LINENO: error: \"File $enableval is not an opcode rules file\"" >&5
+! echo "$as_me: error: \"File $enableval is not an opcode rules file\"" >&2;}
+! { (exit 1); exit 1; }; };
+! sim_opcode="dc-complex"
+! fi;;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_opcode" != x""; then
+! echo "Setting opcode flags = $sim_opcode" 6>&1
+ fi
+! else
+! sim_opcode="dc-complex"
+! if test x"$silent" != x"yes"; then
+! echo "Setting opcode flags = $sim_opcode"
+ fi
+- fi;
+
+! # Check whether --enable-sim-packages or --disable-sim-packages was given.
+! if test "${enable_sim_packages+set}" = set; then
+! enableval="$enable_sim_packages"
+! packages=disklabel
+! case "${enableval}" in
+! yes) ;;
+! no) { { echo "$as_me:$LINENO: error: \"List of packages must be specified for --enable-sim-packages\"" >&5
+! echo "$as_me: error: \"List of packages must be specified for --enable-sim-packages\"" >&2;}
+! { (exit 1); exit 1; }; }; packages="";;
+! ,*) packages="${packages}${enableval}";;
+! *,) packages="${enableval}${packages}";;
+! *) packages="${enableval}"'';;
+! esac
+! sim_pk_src=`echo $packages | sed -e 's/,/.c pk_/g' -e 's/^/pk_/' -e 's/$/.c/'`
+! sim_pk_obj=`echo $sim_pk_src | sed -e 's/\.c/.o/g'`
+! if test x"$silent" != x"yes" && test x"$packages" != x""; then
+! echo "Setting packages to $sim_pk_src, $sim_pk_obj"
+ fi
+- else
+- packages=disklabel
+- sim_pk_src=`echo $packages | sed -e 's/,/.c pk_/g' -e 's/^/pk_/' -e 's/$/.c/'`
+- sim_pk_obj=`echo $sim_pk_src | sed -e 's/\.c/.o/g'`
+- if test x"$silent" != x"yes"; then
+- echo "Setting packages to $sim_pk_src, $sim_pk_obj"
+ fi
+! fi;
+
+! # Check whether --enable-sim-regparm or --disable-sim-regparm was given.
+! if test "${enable_sim_regparm+set}" = set; then
+! enableval="$enable_sim_regparm"
+! case "${enableval}" in
+! 0*|1*|2*|3*|4*|5*|6*|7*|8*|9*) sim_regparm="-DWITH_REGPARM=${enableval}";;
+! no) sim_regparm="" ;;
+! yes) sim_regparm="-DWITH_REGPARM=3";;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-regparm\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval for --enable-sim-regparm\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_regparm="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_regparm" != x""; then
+! echo "Setting regparm flags = $sim_regparm" 6>&1
+! fi
+! else
+! sim_regparm=""
+! fi;
+
+- # Check whether --enable-sim-reserved-bits or --disable-sim-reserved-bits was given.
+- if test "${enable_sim_reserved_bits+set}" = set; then
+- enableval="$enable_sim_reserved_bits"
+- case "${enableval}" in
+- yes) sim_reserved="-DWITH_RESERVED_BITS=1";;
+- no) sim_reserved="-DWITH_RESERVED_BITS=0";;
+- *) { { echo "$as_me:$LINENO: error: \"--enable-sim-reserved-bits does not take a value\"" >&5
+- echo "$as_me: error: \"--enable-sim-reserved-bits does not take a value\"" >&2;}
+- { (exit 1); exit 1; }; }; sim_reserved="";;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_reserved" != x""; then
+- echo "Setting reserved flags = $sim_reserved" 6>&1
+ fi
+- else
+- sim_reserved=""
+- fi;
+
+! # Check whether --enable-sim-smp or --disable-sim-smp was given.
+! if test "${enable_sim_smp+set}" = set; then
+! enableval="$enable_sim_smp"
+! case "${enableval}" in
+! yes) sim_smp="-DWITH_SMP=5" ; sim_igen_smp="-N 5";;
+! no) sim_smp="-DWITH_SMP=0" ; sim_igen_smp="-N 0";;
+! *) sim_smp="-DWITH_SMP=$enableval" ; sim_igen_smp="-N $enableval";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_smp" != x""; then
+! echo "Setting smp flags = $sim_smp" 6>&1
+! fi
+! else
+! sim_smp="-DWITH_SMP=5" ; sim_igen_smp="-N 5"
+! if test x"$silent" != x"yes"; then
+! echo "Setting smp flags = $sim_smp" 6>&1
+! fi
+! fi;
+
+- # Check whether --enable-sim-stdcall or --disable-sim-stdcall was given.
+- if test "${enable_sim_stdcall+set}" = set; then
+- enableval="$enable_sim_stdcall"
+- case "${enableval}" in
+- no) sim_stdcall="" ;;
+- std*) sim_stdcall="-DWITH_STDCALL=1";;
+- yes) sim_stdcall="-DWITH_STDCALL=1";;
+- *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-stdcall\"" >&5
+- echo "$as_me: error: \"Unknown value $enableval for --enable-sim-stdcall\"" >&2;}
+- { (exit 1); exit 1; }; }; sim_stdcall="";;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_stdcall" != x""; then
+- echo "Setting function call flags = $sim_stdcall" 6>&1
+- fi
+- else
+- sim_stdcall=""
+- fi;
+
+! # Check whether --enable-sim-stdio or --disable-sim-stdio was given.
+! if test "${enable_sim_stdio+set}" = set; then
+! enableval="$enable_sim_stdio"
+! case "${enableval}" in
+! yes) sim_stdio="-DWITH_STDIO=DO_USE_STDIO";;
+! no) sim_stdio="-DWITH_STDIO=DONT_USE_STDIO";;
+! *) { { echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-stdio\"" >&5
+! echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-stdio\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_stdio="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_stdio" != x""; then
+! echo "Setting stdio flags = $sim_stdio" 6>&1
+! fi
+ else
+! sim_stdio=""
+! fi;
+
+! # Check whether --enable-sim-switch or --disable-sim-switch was given.
+! if test "${enable_sim_switch+set}" = set; then
+! enableval="$enable_sim_switch"
+! case "${enableval}" in
+! yes) sim_switch="-s";;
+! no) sim_switch="";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-switch does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-switch does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_switch="";;
+ esac
+! if test x"$silent" != x"yes" && test x"$sim_switch" != x""; then
+! echo "Setting switch flags = $sim_switch" 6>&1
+! fi
+ else
+! sim_switch="";
+! if test x"$silent" != x"yes"; then
+! echo "Setting switch flags = $sim_switch" 6>&1
+! fi
+! fi;
+
+! # Check whether --enable-sim-timebase or --disable-sim-timebase was given.
+! if test "${enable_sim_timebase+set}" = set; then
+! enableval="$enable_sim_timebase"
+! case "${enableval}" in
+! yes) sim_timebase="-DWITH_TIME_BASE=1";;
+! no) sim_timebase="-DWITH_TIME_BASE=0";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-timebase does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-timebase does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_timebase="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_timebase" != x""; then
+! echo "Setting timebase flags = $sim_timebase" 6>&1
+ fi
+- else
+- sim_timebase=""
+- fi;
+
+! # Check whether --enable-sim-trace or --disable-sim-trace was given.
+! if test "${enable_sim_trace+set}" = set; then
+! enableval="$enable_sim_trace"
+! case "${enableval}" in
+! yes) sim_trace="-DWITH_TRACE=1";;
+! no) sim_trace="-DWITH_TRACE=0";;
+! *) { { echo "$as_me:$LINENO: error: \"--enable-sim-trace does not take a value\"" >&5
+! echo "$as_me: error: \"--enable-sim-trace does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_trace="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_trace" != x""; then
+! echo "Setting trace flags = $sim_trace" 6>&1
+ fi
+! else
+! sim_trace=""
+! fi;
+
+- # Check whether --enable-sim-warnings or --disable-sim-warnings was given.
+- if test "${enable_sim_warnings+set}" = set; then
+- enableval="$enable_sim_warnings"
+- case "${enableval}" in
+- yes) sim_warnings="-Werror -Wall -Wpointer-arith -Wmissing-prototypes -Wmissing-declarations ";;
+- no) sim_warnings="-w";;
+- *) sim_warnings=`echo "${enableval}" | sed -e "s/,/ /g"`;;
+- esac
+- if test x"$silent" != x"yes" && test x"$sim_warnings" != x""; then
+- echo "Setting warning flags = $sim_warnings" 6>&1
+ fi
+- else
+- sim_warnings=""
+- fi;
+
+! # Check whether --enable-sim-xor-endian or --disable-sim-xor-endian was given.
+! if test "${enable_sim_xor_endian+set}" = set; then
+! enableval="$enable_sim_xor_endian"
+! case "${enableval}" in
+! yes) sim_xor_endian="-DWITH_XOR_ENDIAN=8";;
+! no) sim_xor_endian="-DWITH_XOR_ENDIAN=0";;
+! *) sim_xor_endian="-DWITH_XOR_ENDIAN=$enableval";;
+ esac
+! if test x"$silent" != x"yes" && test x"$sim_xor_endian" != x""; then
+! echo "Setting xor-endian flag = $sim_xor_endian" 6>&1
+ fi
+ else
+- sim_xor_endian=""
+- fi;
+
+! # Make sure we can run config.sub.
+! $ac_config_sub sun4 >/dev/null 2>&1 ||
+! { { echo "$as_me:$LINENO: error: cannot run $ac_config_sub" >&5
+! echo "$as_me: error: cannot run $ac_config_sub" >&2;}
+! { (exit 1); exit 1; }; }
+
+! echo "$as_me:$LINENO: checking build system type" >&5
+! echo $ECHO_N "checking build system type... $ECHO_C" >&6
+! if test "${ac_cv_build+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! ac_cv_build_alias=$build_alias
+! test -z "$ac_cv_build_alias" &&
+! ac_cv_build_alias=`$ac_config_guess`
+! test -z "$ac_cv_build_alias" &&
+! { { echo "$as_me:$LINENO: error: cannot guess build type; you must specify one" >&5
+! echo "$as_me: error: cannot guess build type; you must specify one" >&2;}
+! { (exit 1); exit 1; }; }
+! ac_cv_build=`$ac_config_sub $ac_cv_build_alias` ||
+! { { echo "$as_me:$LINENO: error: $ac_config_sub $ac_cv_build_alias failed" >&5
+! echo "$as_me: error: $ac_config_sub $ac_cv_build_alias failed" >&2;}
+! { (exit 1); exit 1; }; }
+
+! fi
+! echo "$as_me:$LINENO: result: $ac_cv_build" >&5
+! echo "${ECHO_T}$ac_cv_build" >&6
+! build=$ac_cv_build
+! build_cpu=`echo $ac_cv_build | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\1/'`
+! build_vendor=`echo $ac_cv_build | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\2/'`
+! build_os=`echo $ac_cv_build | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\3/'`
+
+
+! echo "$as_me:$LINENO: checking host system type" >&5
+! echo $ECHO_N "checking host system type... $ECHO_C" >&6
+! if test "${ac_cv_host+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! ac_cv_host_alias=$host_alias
+! test -z "$ac_cv_host_alias" &&
+! ac_cv_host_alias=$ac_cv_build_alias
+! ac_cv_host=`$ac_config_sub $ac_cv_host_alias` ||
+! { { echo "$as_me:$LINENO: error: $ac_config_sub $ac_cv_host_alias failed" >&5
+! echo "$as_me: error: $ac_config_sub $ac_cv_host_alias failed" >&2;}
+! { (exit 1); exit 1; }; }
+
+ fi
+- echo "$as_me:$LINENO: result: $ac_cv_host" >&5
+- echo "${ECHO_T}$ac_cv_host" >&6
+- host=$ac_cv_host
+- host_cpu=`echo $ac_cv_host | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\1/'`
+- host_vendor=`echo $ac_cv_host | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\2/'`
+- host_os=`echo $ac_cv_host | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\3/'`
+
+!
+! echo "$as_me:$LINENO: checking target system type" >&5
+! echo $ECHO_N "checking target system type... $ECHO_C" >&6
+! if test "${ac_cv_target+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! ac_cv_target_alias=$target_alias
+! test "x$ac_cv_target_alias" = "x" &&
+! ac_cv_target_alias=$ac_cv_host_alias
+! ac_cv_target=`$ac_config_sub $ac_cv_target_alias` ||
+! { { echo "$as_me:$LINENO: error: $ac_config_sub $ac_cv_target_alias failed" >&5
+! echo "$as_me: error: $ac_config_sub $ac_cv_target_alias failed" >&2;}
+! { (exit 1); exit 1; }; }
+
+ fi
+- echo "$as_me:$LINENO: result: $ac_cv_target" >&5
+- echo "${ECHO_T}$ac_cv_target" >&6
+- target=$ac_cv_target
+- target_cpu=`echo $ac_cv_target | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\1/'`
+- target_vendor=`echo $ac_cv_target | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\2/'`
+- target_os=`echo $ac_cv_target | sed 's/^\([^-]*\)-\([^-]*\)-\(.*\)$/\3/'`
+
+
+! # The aliases save the names the user supplied, while $host etc.
+! # will get canonicalized.
+! test -n "$target_alias" &&
+! test "$program_prefix$program_suffix$program_transform_name" = \
+! NONENONEs,x,x, &&
+! program_prefix=${target_alias}-
+! test "$program_prefix" != NONE &&
+! program_transform_name="s,^,$program_prefix,;$program_transform_name"
+! # Use a double $ so make ignores it.
+! test "$program_suffix" != NONE &&
+! program_transform_name="s,\$,$program_suffix,;$program_transform_name"
+! # Double any \ or $. echo might interpret backslashes.
+! # By default was `s,x,x', remove it if useless.
+! cat <<\_ACEOF >conftest.sed
+! s/[\\$]/&&/g;s/;s,x,x,$//
+ _ACEOF
+! program_transform_name=`echo $program_transform_name | sed -f conftest.sed`
+! rm conftest.sed
+!
+!
+! . ${srcdir}/../../bfd/configure.host
+
+! case ${host} in
+! *mingw32*)
+
+! cat >>confdefs.h <<\_ACEOF
+! #define USE_WIN32API 1
+ _ACEOF
+!
+! ;;
+ esac
+
+! ac_config_headers="$ac_config_headers config.h:config.in"
+
+
+- ac_ext=c
+- ac_cpp='$CPP $CPPFLAGS'
+- ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+- ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+- ac_compiler_gnu=$ac_cv_c_compiler_gnu
+- echo "$as_me:$LINENO: checking how to run the C preprocessor" >&5
+- echo $ECHO_N "checking how to run the C preprocessor... $ECHO_C" >&6
+- # On Suns, sometimes $CPP names a directory.
+- if test -n "$CPP" && test -d "$CPP"; then
+- CPP=
+ fi
+! if test -z "$CPP"; then
+! if test "${ac_cv_prog_CPP+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! # Double quotes because CPP needs to be expanded
+! for CPP in "$CC -E" "$CC -E -traditional-cpp" "/lib/cpp"
+! do
+! ac_preproc_ok=false
+! for ac_c_preproc_warn_flag in '' yes
+! do
+! # Use a header file that comes with gcc, so configuring glibc
+! # with a fresh cross-compiler works.
+! # Prefer <limits.h> to <assert.h> if __STDC__ is defined, since
+! # <limits.h> exists even on freestanding compilers.
+! # On the NeXT, cc -E runs the code through the compiler's parser,
+! # not just through cpp. "Syntax error" is here to catch this case.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #ifdef __STDC__
+! # include <limits.h>
+! #else
+! # include <assert.h>
+! #endif
+! Syntax error
+ _ACEOF
+! if { (eval echo "$as_me:$LINENO: \"$ac_cpp conftest.$ac_ext\"") >&5
+! (eval $ac_cpp conftest.$ac_ext) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null; then
+! if test -s conftest.err; then
+! ac_cpp_err=$ac_c_preproc_warn_flag
+! ac_cpp_err=$ac_cpp_err$ac_c_werror_flag
+! else
+! ac_cpp_err=
+! fi
+! else
+! ac_cpp_err=yes
+! fi
+! if test -z "$ac_cpp_err"; then
+! :
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! # Broken: fails on valid input.
+! continue
+ fi
+- rm -f conftest.err conftest.$ac_ext
+
+! # OK, works on sane cases. Now check whether non-existent headers
+! # can be detected and how.
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #include <ac_nonexistent.h>
+ _ACEOF
+! if { (eval echo "$as_me:$LINENO: \"$ac_cpp conftest.$ac_ext\"") >&5
+! (eval $ac_cpp conftest.$ac_ext) 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null; then
+! if test -s conftest.err; then
+! ac_cpp_err=$ac_c_preproc_warn_flag
+! ac_cpp_err=$ac_cpp_err$ac_c_werror_flag
+ else
+! ac_cpp_err=
+ fi
+ else
+! ac_cpp_err=yes
+ fi
+- if test -z "$ac_cpp_err"; then
+- # Broken: success on invalid input.
+- continue
+ else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! # Passes both tests.
+! ac_preproc_ok=:
+! break
+ fi
+- rm -f conftest.err conftest.$ac_ext
+
+! done
+! # Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped.
+! rm -f conftest.err conftest.$ac_ext
+! if $ac_preproc_ok; then
+! break
+ fi
+
+- done
+- ac_cv_prog_CPP=$CPP
+
+ fi
+- CPP=$ac_cv_prog_CPP
+ else
+! ac_cv_prog_CPP=$CPP
+ fi
+- echo "$as_me:$LINENO: result: $CPP" >&5
+- echo "${ECHO_T}$CPP" >&6
+- ac_preproc_ok=false
+- for ac_c_preproc_warn_flag in '' yes
+- do
+- # Use a header file that comes with gcc, so configuring glibc
+- # with a fresh cross-compiler works.
+- # Prefer <limits.h> to <assert.h> if __STDC__ is defined, since
+- # <limits.h> exists even on freestanding compilers.
+- # On the NeXT, cc -E runs the code through the compiler's parser,
+- # not just through cpp. "Syntax error" is here to catch this case.
+- cat >conftest.$ac_ext <<_ACEOF
+- /* confdefs.h. */
+- _ACEOF
+- cat confdefs.h >>conftest.$ac_ext
+- cat >>conftest.$ac_ext <<_ACEOF
+- /* end confdefs.h. */
+- #ifdef __STDC__
+- # include <limits.h>
+- #else
+- # include <assert.h>
+- #endif
+- Syntax error
+- _ACEOF
+- if { (eval echo "$as_me:$LINENO: \"$ac_cpp conftest.$ac_ext\"") >&5
+- (eval $ac_cpp conftest.$ac_ext) 2>conftest.er1
+- ac_status=$?
+- grep -v '^ *+' conftest.er1 >conftest.err
+- rm -f conftest.er1
+- cat conftest.err >&5
+- echo "$as_me:$LINENO: \$? = $ac_status" >&5
+- (exit $ac_status); } >/dev/null; then
+- if test -s conftest.err; then
+- ac_cpp_err=$ac_c_preproc_warn_flag
+- ac_cpp_err=$ac_cpp_err$ac_c_werror_flag
+- else
+- ac_cpp_err=
+- fi
+- else
+- ac_cpp_err=yes
+ fi
+- if test -z "$ac_cpp_err"; then
+- :
+- else
+- echo "$as_me: failed program was:" >&5
+- sed 's/^/| /' conftest.$ac_ext >&5
+
+- # Broken: fails on valid input.
+- continue
+- fi
+- rm -f conftest.err conftest.$ac_ext
+
+! # OK, works on sane cases. Now check whether non-existent headers
+! # can be detected and how.
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <ac_nonexistent.h>
+! _ACEOF
+! if { (eval echo "$as_me:$LINENO: \"$ac_cpp conftest.$ac_ext\"") >&5
+! (eval $ac_cpp conftest.$ac_ext) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null; then
+! if test -s conftest.err; then
+! ac_cpp_err=$ac_c_preproc_warn_flag
+! ac_cpp_err=$ac_cpp_err$ac_c_werror_flag
+! else
+! ac_cpp_err=
+! fi
+! else
+! ac_cpp_err=yes
+ fi
+- if test -z "$ac_cpp_err"; then
+- # Broken: success on invalid input.
+- continue
+ else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! # Passes both tests.
+! ac_preproc_ok=:
+! break
+ fi
+- rm -f conftest.err conftest.$ac_ext
+
+! done
+! # Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped.
+! rm -f conftest.err conftest.$ac_ext
+! if $ac_preproc_ok; then
+! :
+ else
+! { { echo "$as_me:$LINENO: error: C preprocessor \"$CPP\" fails sanity check
+! See \`config.log' for more details." >&5
+! echo "$as_me: error: C preprocessor \"$CPP\" fails sanity check
+! See \`config.log' for more details." >&2;}
+! { (exit 1); exit 1; }; }
+ fi
+
+- ac_ext=c
+- ac_cpp='$CPP $CPPFLAGS'
+- ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+- ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+- ac_compiler_gnu=$ac_cv_c_compiler_gnu
+-
+
+! echo "$as_me:$LINENO: checking for egrep" >&5
+! echo $ECHO_N "checking for egrep... $ECHO_C" >&6
+! if test "${ac_cv_prog_egrep+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! if echo a | (grep -E '(a|b)') >/dev/null 2>&1
+! then ac_cv_prog_egrep='grep -E'
+! else ac_cv_prog_egrep='egrep'
+! fi
+ fi
+- echo "$as_me:$LINENO: result: $ac_cv_prog_egrep" >&5
+- echo "${ECHO_T}$ac_cv_prog_egrep" >&6
+- EGREP=$ac_cv_prog_egrep
+
+
+! echo "$as_me:$LINENO: checking for ANSI C header files" >&5
+! echo $ECHO_N "checking for ANSI C header files... $ECHO_C" >&6
+! if test "${ac_cv_header_stdc+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <stdlib.h>
+! #include <stdarg.h>
+! #include <string.h>
+! #include <float.h>
+
+- int
+- main ()
+- {
+
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_header_stdc=yes
+ else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_header_stdc=no
+ fi
+- rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+
+- if test $ac_cv_header_stdc = yes; then
+- # SunOS 4.x string.h does not declare mem*, contrary to ANSI.
+- cat >conftest.$ac_ext <<_ACEOF
+- /* confdefs.h. */
+- _ACEOF
+- cat confdefs.h >>conftest.$ac_ext
+- cat >>conftest.$ac_ext <<_ACEOF
+- /* end confdefs.h. */
+- #include <string.h>
+
+! _ACEOF
+! if (eval "$ac_cpp conftest.$ac_ext") 2>&5 |
+! $EGREP "memchr" >/dev/null 2>&1; then
+! :
+ else
+! ac_cv_header_stdc=no
+ fi
+- rm -f conftest*
+-
+ fi
+
+- if test $ac_cv_header_stdc = yes; then
+- # ISC 2.0.2 stdlib.h does not declare free, contrary to ANSI.
+- cat >conftest.$ac_ext <<_ACEOF
+- /* confdefs.h. */
+- _ACEOF
+- cat confdefs.h >>conftest.$ac_ext
+- cat >>conftest.$ac_ext <<_ACEOF
+- /* end confdefs.h. */
+- #include <stdlib.h>
+
+! _ACEOF
+! if (eval "$ac_cpp conftest.$ac_ext") 2>&5 |
+! $EGREP "free" >/dev/null 2>&1; then
+! :
+ else
+! ac_cv_header_stdc=no
+ fi
+- rm -f conftest*
+
+- fi
+
+! if test $ac_cv_header_stdc = yes; then
+! # /bin/cc in Irix-4.0.5 gets non-ANSI ctype macros unless using -ansi.
+! if test "$cross_compiling" = yes; then
+! :
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <ctype.h>
+! #if ((' ' & 0x0FF) == 0x020)
+! # define ISLOWER(c) ('a' <= (c) && (c) <= 'z')
+! # define TOUPPER(c) (ISLOWER(c) ? 'A' + ((c) - 'a') : (c))
+! #else
+! # define ISLOWER(c) \
+! (('a' <= (c) && (c) <= 'i') \
+! || ('j' <= (c) && (c) <= 'r') \
+! || ('s' <= (c) && (c) <= 'z'))
+! # define TOUPPER(c) (ISLOWER(c) ? ((c) | 0x40) : (c))
+! #endif
+
+- #define XOR(e, f) (((e) && !(f)) || (!(e) && (f)))
+- int
+- main ()
+- {
+- int i;
+- for (i = 0; i < 256; i++)
+- if (XOR (islower (i), ISLOWER (i))
+- || toupper (i) != TOUPPER (i))
+- exit(2);
+- exit (0);
+- }
+- _ACEOF
+- rm -f conftest$ac_exeext
+- if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+- (eval $ac_link) 2>&5
+- ac_status=$?
+- echo "$as_me:$LINENO: \$? = $ac_status" >&5
+- (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+- { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+- (eval $ac_try) 2>&5
+- ac_status=$?
+- echo "$as_me:$LINENO: \$? = $ac_status" >&5
+- (exit $ac_status); }; }; then
+- :
+- else
+- echo "$as_me: program exited with status $ac_status" >&5
+- echo "$as_me: failed program was:" >&5
+- sed 's/^/| /' conftest.$ac_ext >&5
+
+! ( exit $ac_status )
+! ac_cv_header_stdc=no
+ fi
+! rm -f core *.core gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
+ fi
+ fi
+- echo "$as_me:$LINENO: result: $ac_cv_header_stdc" >&5
+- echo "${ECHO_T}$ac_cv_header_stdc" >&6
+- if test $ac_cv_header_stdc = yes; then
+
+! cat >>confdefs.h <<\_ACEOF
+! #define STDC_HEADERS 1
+! _ACEOF
+
+ fi
+
+- # On IRIX 5.3, sys/types and inttypes.h are conflicting.
+
+
+
+
+
+
+
+
+
+! for ac_header in sys/types.h sys/stat.h stdlib.h string.h memory.h strings.h \
+! inttypes.h stdint.h unistd.h
+! do
+! as_ac_Header=`echo "ac_cv_header_$ac_header" | $as_tr_sh`
+! echo "$as_me:$LINENO: checking for $ac_header" >&5
+! echo $ECHO_N "checking for $ac_header... $ECHO_C" >&6
+! if eval "test \"\${$as_ac_Header+set}\" = set"; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+
+! #include <$ac_header>
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! eval "$as_ac_Header=yes"
+! else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
+! eval "$as_ac_Header=no"
+! fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! fi
+! echo "$as_me:$LINENO: result: `eval echo '${'$as_ac_Header'}'`" >&5
+! echo "${ECHO_T}`eval echo '${'$as_ac_Header'}'`" >&6
+! if test `eval echo '${'$as_ac_Header'}'` = yes; then
+! cat >>confdefs.h <<_ACEOF
+! #define `echo "HAVE_$ac_header" | $as_tr_cpp` 1
+ _ACEOF
+
+! fi
+!
+! done
+
+
+
+! echo "$as_me:$LINENO: checking for struct stat.st_blksize" >&5
+! echo $ECHO_N "checking for struct stat.st_blksize... $ECHO_C" >&6
+ if test "${ac_cv_member_struct_stat_st_blksize+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 3368,4921 ----
+ fi
+ else
+ sim_hostbitsize=""
+! fi
+
+
+
+! ac_ext=c
+! ac_cpp='$CPP $CPPFLAGS'
+! ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+! ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+! ac_compiler_gnu=$ac_cv_c_compiler_gnu
+! { $as_echo "$as_me:$LINENO: checking how to run the C preprocessor" >&5
+! $as_echo_n "checking how to run the C preprocessor... " >&6; }
+! # On Suns, sometimes $CPP names a directory.
+! if test -n "$CPP" && test -d "$CPP"; then
+! CPP=
+! fi
+! if test -z "$CPP"; then
+! if test "${ac_cv_prog_CPP+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! # Double quotes because CPP needs to be expanded
+! for CPP in "$CC -E" "$CC -E -traditional-cpp" "/lib/cpp"
+! do
+! ac_preproc_ok=false
+! for ac_c_preproc_warn_flag in '' yes
+! do
+! # Use a header file that comes with gcc, so configuring glibc
+! # with a fresh cross-compiler works.
+! # Prefer <limits.h> to <assert.h> if __STDC__ is defined, since
+! # <limits.h> exists even on freestanding compilers.
+! # On the NeXT, cc -E runs the code through the compiler's parser,
+! # not just through cpp. "Syntax error" is here to catch this case.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #ifdef __STDC__
+! # include <limits.h>
+! #else
+! # include <assert.h>
+ #endif
+! Syntax error
+ _ACEOF
+! if { (ac_try="$ac_cpp conftest.$ac_ext"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_cpp conftest.$ac_ext") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null && {
+! test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! }; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! # Broken: fails on valid input.
+! continue
+! fi
+!
+! rm -f conftest.err conftest.$ac_ext
+!
+! # OK, works on sane cases. Now check whether nonexistent headers
+! # can be detected and how.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #include <ac_nonexistent.h>
+ _ACEOF
+! if { (ac_try="$ac_cpp conftest.$ac_ext"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_cpp conftest.$ac_ext") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null && {
+! test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! }; then
+! # Broken: success on invalid input.
+! continue
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! # Passes both tests.
+! ac_preproc_ok=:
+! break
+ fi
+
+! rm -f conftest.err conftest.$ac_ext
+!
+! done
+! # Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped.
+! rm -f conftest.err conftest.$ac_ext
+! if $ac_preproc_ok; then
+! break
+! fi
+!
+! done
+! ac_cv_prog_CPP=$CPP
+!
+! fi
+! CPP=$ac_cv_prog_CPP
+! else
+! ac_cv_prog_CPP=$CPP
+! fi
+! { $as_echo "$as_me:$LINENO: result: $CPP" >&5
+! $as_echo "$CPP" >&6; }
+! ac_preproc_ok=false
+! for ac_c_preproc_warn_flag in '' yes
+! do
+! # Use a header file that comes with gcc, so configuring glibc
+! # with a fresh cross-compiler works.
+! # Prefer <limits.h> to <assert.h> if __STDC__ is defined, since
+! # <limits.h> exists even on freestanding compilers.
+! # On the NeXT, cc -E runs the code through the compiler's parser,
+! # not just through cpp. "Syntax error" is here to catch this case.
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #ifdef __STDC__
+! # include <limits.h>
+! #else
+! # include <assert.h>
+! #endif
+! Syntax error
+ _ACEOF
+! if { (ac_try="$ac_cpp conftest.$ac_ext"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_cpp conftest.$ac_ext") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null && {
+! test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! }; then
+! :
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
++ # Broken: fails on valid input.
++ continue
+ fi
+!
+! rm -f conftest.err conftest.$ac_ext
+!
+! # OK, works on sane cases. Now check whether nonexistent headers
+! # can be detected and how.
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! #include <ac_nonexistent.h>
+ _ACEOF
+! if { (ac_try="$ac_cpp conftest.$ac_ext"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_cpp conftest.$ac_ext") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null && {
+! test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! }; then
+! # Broken: success on invalid input.
+! continue
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! # Passes both tests.
+! ac_preproc_ok=:
+! break
+ fi
+
+! rm -f conftest.err conftest.$ac_ext
+
+! done
+! # Because of `break', _AC_PREPROC_IFELSE's cleaning code was skipped.
+! rm -f conftest.err conftest.$ac_ext
+! if $ac_preproc_ok; then
+! :
+ else
+! { { $as_echo "$as_me:$LINENO: error: C preprocessor \"$CPP\" fails sanity check
+! See \`config.log' for more details." >&5
+! $as_echo "$as_me: error: C preprocessor \"$CPP\" fails sanity check
+! See \`config.log' for more details." >&2;}
+! { (exit 1); exit 1; }; }
+ fi
+
+! ac_ext=c
+! ac_cpp='$CPP $CPPFLAGS'
+! ac_compile='$CC -c $CFLAGS $CPPFLAGS conftest.$ac_ext >&5'
+! ac_link='$CC -o conftest$ac_exeext $CFLAGS $CPPFLAGS $LDFLAGS conftest.$ac_ext $LIBS >&5'
+! ac_compiler_gnu=$ac_cv_c_compiler_gnu
+!
+!
+! { $as_echo "$as_me:$LINENO: checking for grep that handles long lines and -e" >&5
+! $as_echo_n "checking for grep that handles long lines and -e... " >&6; }
+! if test "${ac_cv_path_GREP+set}" = set; then
+! $as_echo_n "(cached) " >&6
+! else
+! if test -z "$GREP"; then
+! ac_path_GREP_found=false
+! # Loop through the user's path and test for each of PROGNAME-LIST
+! as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+! for as_dir in $PATH$PATH_SEPARATOR/usr/xpg4/bin
+! do
+! IFS=$as_save_IFS
+! test -z "$as_dir" && as_dir=.
+! for ac_prog in grep ggrep; do
+! for ac_exec_ext in '' $ac_executable_extensions; do
+! ac_path_GREP="$as_dir/$ac_prog$ac_exec_ext"
+! { test -f "$ac_path_GREP" && $as_test_x "$ac_path_GREP"; } || continue
+! # Check for GNU ac_path_GREP and select it if it is found.
+! # Check for GNU $ac_path_GREP
+! case `"$ac_path_GREP" --version 2>&1` in
+! *GNU*)
+! ac_cv_path_GREP="$ac_path_GREP" ac_path_GREP_found=:;;
+! *)
+! ac_count=0
+! $as_echo_n 0123456789 >"conftest.in"
+! while :
+! do
+! cat "conftest.in" "conftest.in" >"conftest.tmp"
+! mv "conftest.tmp" "conftest.in"
+! cp "conftest.in" "conftest.nl"
+! $as_echo 'GREP' >> "conftest.nl"
+! "$ac_path_GREP" -e 'GREP$' -e '-(cannot match)-' < "conftest.nl" >"conftest.out" 2>/dev/null || break
+! diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break
+! ac_count=`expr $ac_count + 1`
+! if test $ac_count -gt ${ac_path_GREP_max-0}; then
+! # Best one so far, save it but keep looking for a better one
+! ac_cv_path_GREP="$ac_path_GREP"
+! ac_path_GREP_max=$ac_count
+! fi
+! # 10*(2^10) chars as input seems more than enough
+! test $ac_count -gt 10 && break
+! done
+! rm -f conftest.in conftest.tmp conftest.nl conftest.out;;
+ esac
+!
+! $ac_path_GREP_found && break 3
+! done
+! done
+! done
+! IFS=$as_save_IFS
+! if test -z "$ac_cv_path_GREP"; then
+! { { $as_echo "$as_me:$LINENO: error: no acceptable grep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" >&5
+! $as_echo "$as_me: error: no acceptable grep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" >&2;}
+! { (exit 1); exit 1; }; }
+! fi
+ else
+! ac_cv_path_GREP=$GREP
+ fi
+
+ fi
++ { $as_echo "$as_me:$LINENO: result: $ac_cv_path_GREP" >&5
++ $as_echo "$ac_cv_path_GREP" >&6; }
++ GREP="$ac_cv_path_GREP"
++
++
++ { $as_echo "$as_me:$LINENO: checking for egrep" >&5
++ $as_echo_n "checking for egrep... " >&6; }
++ if test "${ac_cv_path_EGREP+set}" = set; then
++ $as_echo_n "(cached) " >&6
+ else
+! if echo a | $GREP -E '(a|b)' >/dev/null 2>&1
+! then ac_cv_path_EGREP="$GREP -E"
+! else
+! if test -z "$EGREP"; then
+! ac_path_EGREP_found=false
+! # Loop through the user's path and test for each of PROGNAME-LIST
+! as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+! for as_dir in $PATH$PATH_SEPARATOR/usr/xpg4/bin
+! do
+! IFS=$as_save_IFS
+! test -z "$as_dir" && as_dir=.
+! for ac_prog in egrep; do
+! for ac_exec_ext in '' $ac_executable_extensions; do
+! ac_path_EGREP="$as_dir/$ac_prog$ac_exec_ext"
+! { test -f "$ac_path_EGREP" && $as_test_x "$ac_path_EGREP"; } || continue
+! # Check for GNU ac_path_EGREP and select it if it is found.
+! # Check for GNU $ac_path_EGREP
+! case `"$ac_path_EGREP" --version 2>&1` in
+! *GNU*)
+! ac_cv_path_EGREP="$ac_path_EGREP" ac_path_EGREP_found=:;;
+! *)
+! ac_count=0
+! $as_echo_n 0123456789 >"conftest.in"
+! while :
+! do
+! cat "conftest.in" "conftest.in" >"conftest.tmp"
+! mv "conftest.tmp" "conftest.in"
+! cp "conftest.in" "conftest.nl"
+! $as_echo 'EGREP' >> "conftest.nl"
+! "$ac_path_EGREP" 'EGREP$' < "conftest.nl" >"conftest.out" 2>/dev/null || break
+! diff "conftest.out" "conftest.nl" >/dev/null 2>&1 || break
+! ac_count=`expr $ac_count + 1`
+! if test $ac_count -gt ${ac_path_EGREP_max-0}; then
+! # Best one so far, save it but keep looking for a better one
+! ac_cv_path_EGREP="$ac_path_EGREP"
+! ac_path_EGREP_max=$ac_count
+! fi
+! # 10*(2^10) chars as input seems more than enough
+! test $ac_count -gt 10 && break
+! done
+! rm -f conftest.in conftest.tmp conftest.nl conftest.out;;
+! esac
+!
+! $ac_path_EGREP_found && break 3
+! done
+! done
+! done
+! IFS=$as_save_IFS
+! if test -z "$ac_cv_path_EGREP"; then
+! { { $as_echo "$as_me:$LINENO: error: no acceptable egrep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" >&5
+! $as_echo "$as_me: error: no acceptable egrep could be found in $PATH$PATH_SEPARATOR/usr/xpg4/bin" >&2;}
+! { (exit 1); exit 1; }; }
+ fi
+ else
+! ac_cv_path_EGREP=$EGREP
+ fi
+
+! fi
+ fi
++ { $as_echo "$as_me:$LINENO: result: $ac_cv_path_EGREP" >&5
++ $as_echo "$ac_cv_path_EGREP" >&6; }
++ EGREP="$ac_cv_path_EGREP"
++
++
++ { $as_echo "$as_me:$LINENO: checking for ANSI C header files" >&5
++ $as_echo_n "checking for ANSI C header files... " >&6; }
++ if test "${ac_cv_header_stdc+set}" = set; then
++ $as_echo_n "(cached) " >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <stdlib.h>
+! #include <stdarg.h>
+! #include <string.h>
+! #include <float.h>
+
+! int
+! main ()
+! {
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+ esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_header_stdc=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_header_stdc=no
+ fi
++
++ rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
++
++ if test $ac_cv_header_stdc = yes; then
++ # SunOS 4.x string.h does not declare mem*, contrary to ANSI.
++ cat >conftest.$ac_ext <<_ACEOF
++ /* confdefs.h. */
++ _ACEOF
++ cat confdefs.h >>conftest.$ac_ext
++ cat >>conftest.$ac_ext <<_ACEOF
++ /* end confdefs.h. */
++ #include <string.h>
++
++ _ACEOF
++ if (eval "$ac_cpp conftest.$ac_ext") 2>&5 |
++ $EGREP "memchr" >/dev/null 2>&1; then
++ :
+ else
+! ac_cv_header_stdc=no
+! fi
+! rm -f conftest*
+
+ fi
++
++ if test $ac_cv_header_stdc = yes; then
++ # ISC 2.0.2 stdlib.h does not declare free, contrary to ANSI.
++ cat >conftest.$ac_ext <<_ACEOF
++ /* confdefs.h. */
++ _ACEOF
++ cat confdefs.h >>conftest.$ac_ext
++ cat >>conftest.$ac_ext <<_ACEOF
++ /* end confdefs.h. */
++ #include <stdlib.h>
++
++ _ACEOF
++ if (eval "$ac_cpp conftest.$ac_ext") 2>&5 |
++ $EGREP "free" >/dev/null 2>&1; then
++ :
+ else
+! ac_cv_header_stdc=no
+! fi
+! rm -f conftest*
+
+ fi
++
++ if test $ac_cv_header_stdc = yes; then
++ # /bin/cc in Irix-4.0.5 gets non-ANSI ctype macros unless using -ansi.
++ if test "$cross_compiling" = yes; then
++ :
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <ctype.h>
+! #include <stdlib.h>
+! #if ((' ' & 0x0FF) == 0x020)
+! # define ISLOWER(c) ('a' <= (c) && (c) <= 'z')
+! # define TOUPPER(c) (ISLOWER(c) ? 'A' + ((c) - 'a') : (c))
+! #else
+! # define ISLOWER(c) \
+! (('a' <= (c) && (c) <= 'i') \
+! || ('j' <= (c) && (c) <= 'r') \
+! || ('s' <= (c) && (c) <= 'z'))
+! # define TOUPPER(c) (ISLOWER(c) ? ((c) | 0x40) : (c))
+! #endif
+
+! #define XOR(e, f) (((e) && !(f)) || (!(e) && (f)))
+! int
+! main ()
+! {
+! int i;
+! for (i = 0; i < 256; i++)
+! if (XOR (islower (i), ISLOWER (i))
+! || toupper (i) != TOUPPER (i))
+! return 2;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>&5
+! ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_try") 2>&5
+! ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! :
+! else
+! $as_echo "$as_me: program exited with status $ac_status" >&5
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ( exit $ac_status )
+! ac_cv_header_stdc=no
+ fi
+! rm -rf conftest.dSYM
+! rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
+
+!
+ fi
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_header_stdc" >&5
+! $as_echo "$ac_cv_header_stdc" >&6; }
+! if test $ac_cv_header_stdc = yes; then
+
+! cat >>confdefs.h <<\_ACEOF
+! #define STDC_HEADERS 1
+! _ACEOF
+
+ fi
+
+! # On IRIX 5.3, sys/types and inttypes.h are conflicting.
+
+
+!
+!
+!
+!
+!
+!
+!
+! for ac_header in sys/types.h sys/stat.h stdlib.h string.h memory.h strings.h \
+! inttypes.h stdint.h unistd.h
+! do
+! as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh`
+! { $as_echo "$as_me:$LINENO: checking for $ac_header" >&5
+! $as_echo_n "checking for $ac_header... " >&6; }
+! if { as_var=$as_ac_Header; eval "test \"\${$as_var+set}\" = set"; }; then
+! $as_echo_n "(cached) " >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+
+! #include <$ac_header>
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+ esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! eval "$as_ac_Header=yes"
+ else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
+! eval "$as_ac_Header=no"
+ fi
+
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! ac_res=`eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'`
+! { $as_echo "$as_me:$LINENO: result: $ac_res" >&5
+! $as_echo "$ac_res" >&6; }
+! if test `eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'` = yes; then
+! cat >>confdefs.h <<_ACEOF
+! #define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1
+! _ACEOF
+
+ fi
+
+! done
+!
+!
+! # Check whether --enable-sim-hostendian was given.
+! if test "${enable_sim_hostendian+set}" = set; then
+! enableval=$enable_sim_hostendian; case "${enableval}" in
+! no) sim_hostendian="-DWITH_HOST_BYTE_ORDER=0";;
+! b*|B*) sim_hostendian="-DWITH_HOST_BYTE_ORDER=BIG_ENDIAN";;
+! l*|L*) sim_hostendian="-DWITH_HOST_BYTE_ORDER=LITTLE_ENDIAN";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-hostendian\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval for --enable-sim-hostendian\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_hostendian="";;
+ esac
+! if test x"$silent" != x"yes" && test x"$sim_hostendian" != x""; then
+! echo "Setting hostendian flags = $sim_hostendian" 6>&1
+ fi
+ else
+
+! if test "x$cross_compiling" = "xno"; then
+
+! { $as_echo "$as_me:$LINENO: checking whether byte ordering is bigendian" >&5
+! $as_echo_n "checking whether byte ordering is bigendian... " >&6; }
+! if test "${ac_cv_c_bigendian+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_c_bigendian=unknown
+
+! if test $ac_cv_c_bigendian = unknown; then
+! # See if sys/param.h defines the BYTE_ORDER macro.
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <sys/types.h>
+! #include <sys/param.h>
+
++ int
++ main ()
++ {
++ #if ! (defined BYTE_ORDER && defined BIG_ENDIAN \
++ && defined LITTLE_ENDIAN && BYTE_ORDER && BIG_ENDIAN \
++ && LITTLE_ENDIAN)
++ bogus endian macros
++ #endif
+
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! # It does; now see whether it defined to BIG_ENDIAN or not.
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <sys/types.h>
+! #include <sys/param.h>
+!
+! int
+! main ()
+! {
+! #if BYTE_ORDER != BIG_ENDIAN
+! not big endian
+! #endif
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_c_bigendian=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
++ ac_cv_c_bigendian=no
+ fi
+
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+
+ fi
+
++ rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
++ fi
++ if test $ac_cv_c_bigendian = unknown; then
++ # See if <limits.h> defines _LITTLE_ENDIAN or _BIG_ENDIAN (e.g., Solaris).
++ cat >conftest.$ac_ext <<_ACEOF
++ /* confdefs.h. */
++ _ACEOF
++ cat confdefs.h >>conftest.$ac_ext
++ cat >>conftest.$ac_ext <<_ACEOF
++ /* end confdefs.h. */
++ #include <limits.h>
+
+! int
+! main ()
+! {
+! #if ! (defined _LITTLE_ENDIAN || defined _BIG_ENDIAN)
+! bogus endian macros
+! #endif
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! # It does; now see whether it defined to _BIG_ENDIAN or not.
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+ _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <limits.h>
+
+! int
+! main ()
+! {
+! #ifndef _BIG_ENDIAN
+! not big endian
+! #endif
+
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+ esac
++ eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
++ $as_echo "$ac_try_echo") >&5
++ (eval "$ac_compile") 2>conftest.er1
++ ac_status=$?
++ grep -v '^ *+' conftest.er1 >conftest.err
++ rm -f conftest.er1
++ cat conftest.err >&5
++ $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
++ (exit $ac_status); } && {
++ test -z "$ac_c_werror_flag" ||
++ test ! -s conftest.err
++ } && test -s conftest.$ac_objext; then
++ ac_cv_c_bigendian=yes
++ else
++ $as_echo "$as_me: failed program was:" >&5
++ sed 's/^/| /' conftest.$ac_ext >&5
++
++ ac_cv_c_bigendian=no
++ fi
+
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+
+
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! fi
+! if test $ac_cv_c_bigendian = unknown; then
+! # Compile a test program.
+! if test "$cross_compiling" = yes; then
+! # Try to guess by grepping values from an object file.
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! short int ascii_mm[] =
+! { 0x4249, 0x4765, 0x6E44, 0x6961, 0x6E53, 0x7953, 0 };
+! short int ascii_ii[] =
+! { 0x694C, 0x5454, 0x656C, 0x6E45, 0x6944, 0x6E61, 0 };
+! int use_ascii (int i) {
+! return ascii_mm[i] + ascii_ii[i];
+! }
+! short int ebcdic_ii[] =
+! { 0x89D3, 0xE3E3, 0x8593, 0x95C5, 0x89C4, 0x9581, 0 };
+! short int ebcdic_mm[] =
+! { 0xC2C9, 0xC785, 0x95C4, 0x8981, 0x95E2, 0xA8E2, 0 };
+! int use_ebcdic (int i) {
+! return ebcdic_mm[i] + ebcdic_ii[i];
+! }
+! extern int foo;
+!
+! int
+! main ()
+! {
+! return use_ascii (foo) == use_ebcdic (foo);
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! if grep BIGenDianSyS conftest.$ac_objext >/dev/null; then
+! ac_cv_c_bigendian=yes
+! fi
+! if grep LiTTleEnDian conftest.$ac_objext >/dev/null ; then
+! if test "$ac_cv_c_bigendian" = unknown; then
+! ac_cv_c_bigendian=no
+! else
+! # finding both strings is unlikely to happen, but who knows?
+! ac_cv_c_bigendian=unknown
+! fi
+! fi
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+ fi
+
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+!
+! /* Are we little or big endian? From Harbison&Steele. */
+! union
+! {
+! long int l;
+! char c[sizeof (long int)];
+! } u;
+! u.l = 1;
+! return u.c[sizeof (long int) - 1] == 1;
+!
+! ;
+! return 0;
+! }
+ _ACEOF
+! rm -f conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_try") 2>&5
+! ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_c_bigendian=no
+! else
+! $as_echo "$as_me: program exited with status $ac_status" >&5
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ( exit $ac_status )
+! ac_cv_c_bigendian=yes
+! fi
+! rm -rf conftest.dSYM
+! rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+! fi
+!
+!
+! fi
+! fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_c_bigendian" >&5
+! $as_echo "$ac_cv_c_bigendian" >&6; }
+! case $ac_cv_c_bigendian in #(
+! yes)
+! cat >>confdefs.h <<\_ACEOF
+! #define WORDS_BIGENDIAN 1
+! _ACEOF
+! ;; #(
+! no)
+! ;; #(
+! universal)
+! ;; #(
+! *)
+! { { $as_echo "$as_me:$LINENO: error: unknown endianness
+! presetting ac_cv_c_bigendian=no (or yes) will help" >&5
+! $as_echo "$as_me: error: unknown endianness
+! presetting ac_cv_c_bigendian=no (or yes) will help" >&2;}
+! { (exit 1); exit 1; }; } ;;
+! esac
+!
+! if test $ac_cv_c_bigendian = yes; then
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=BIG_ENDIAN"
+ else
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=LITTLE_ENDIAN"
+ fi
+ else
+! sim_hostendian="-DWITH_HOST_BYTE_ORDER=0"
+! fi
+! fi
+!
+!
+! # Check whether --enable-sim-icache was given.
+! if test "${enable_sim_icache+set}" = set; then
+! enableval=$enable_sim_icache; icache="-R"
+! case "${enableval}" in
+! yes) icache="1024"; sim_icache="-I $icache";;
+! no) sim_icache="-R";;
+! *) icache=1024
+! sim_icache="-"
+! for x in `echo "${enableval}" | sed -e "s/,/ /g"`; do
+! case "$x" in
+! define) sim_icache="${sim_icache}R";;
+! semantic) sim_icache="${sim_icache}C";;
+! insn) sim_icache="${sim_icache}S";;
+! 0*|1*|2*|3*|4*|5*|6*|7*|8*|9*) icache=$x;;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $x for --enable-sim-icache\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $x for --enable-sim-icache\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_icache="";;
+! esac
+! done
+! sim_icache="${sim_icache}I $icache";;
+! esac
+! if test x"$silent" != x"yes" && test x"$icache" != x""; then
+! echo "Setting instruction cache size to $icache ($sim_icache)"
+! fi
+! else
+! sim_icache="-CSRI 1024"
+! if test x"$silent" != x"yes"; then
+! echo "Setting instruction cache size to 1024 ($sim_icache)"
+! fi
+! fi
+!
+!
+! # Check whether --enable-sim-inline was given.
+! if test "${enable_sim_inline+set}" = set; then
+! enableval=$enable_sim_inline; sim_inline=""
+! case "$enableval" in
+! no) sim_inline="-DDEFAULT_INLINE=0";;
+! 0) sim_inline="-DDEFAULT_INLINE=0";;
+! yes | 2) sim_inline="-DDEFAULT_INLINE=ALL_INLINE";;
+! 1) sim_inline="-DDEFAULT_INLINE=PSIM_INLINE_LOCALS";;
+! *) for x in `echo "$enableval" | sed -e "s/,/ /g"`; do
+! new_flag=""
+! case "$x" in
+! *_INLINE=*) new_flag="-D$x";;
+! *=*) new_flag=`echo "$x" | sed -e "s/=/_INLINE=/" -e "s/^/-D/"`;;
+! *_INLINE) new_flag="-D$x=ALL_INLINE";;
+! *) new_flag="-D$x""_INLINE=ALL_INLINE";;
+! esac
+! if test x"$sim_inline" = x""; then
+! sim_inline="$new_flag"
+! else
+! sim_inline="$sim_inline $new_flag"
+! fi
+! done;;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_inline" != x""; then
+! echo "Setting inline flags = $sim_inline" 6>&1
+! fi
+! else
+! if test x"$GCC" != ""; then
+! sim_inline="-DDEFAULT_INLINE=PSIM_INLINE_LOCALS"
+! if test x"$silent" != x"yes"; then
+! echo "Setting inline flags = $sim_inline" 6>&1
+! fi
+! else
+! sim_inline=""
+! fi
+! fi
+!
+!
+! # Check whether --enable-sim-jump was given.
+! if test "${enable_sim_jump+set}" = set; then
+! enableval=$enable_sim_jump; case "${enableval}" in
+! yes) sim_jump="-J";;
+! no) sim_jump="";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-jump does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-jump does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_jump="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_jump" != x""; then
+! echo "Setting jump flag = $sim_jump" 6>&1
+! fi
+! else
+! sim_jump=""
+! if test x"$silent" != x"yes"; then
+! echo "Setting jump flag = $sim_jump" 6>&1
+! fi
+! fi
+!
+!
+! # Check whether --enable-sim-line-nr was given.
+! if test "${enable_sim_line_nr+set}" = set; then
+! enableval=$enable_sim_line_nr; case "${enableval}" in
+! yes) sim_line_nr="";;
+! no) sim_line_nr="-L";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-line-nr does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-line-nr does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_line_nr="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_line_nr" != x""; then
+! echo "Setting warning flags = $sim_line_nr" 6>&1
+! fi
+! else
+! sim_line_nr=""
+! fi
+!
+!
+! # Check whether --enable-sim-model was given.
+! if test "${enable_sim_model+set}" = set; then
+! enableval=$enable_sim_model; case "${enableval}" in
+! yes|no) { { $as_echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-model=model\"" >&5
+! $as_echo "$as_me: error: \"No value supplied for --enable-sim-model=model\"" >&2;}
+! { (exit 1); exit 1; }; };;
+! *) sim_model="-DWITH_MODEL=${enableval}";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_model" != x""; then
+! echo "Setting model flags = $sim_model" 6>&1
+! fi
+! else
+! sim_model=""
+! fi
+!
+!
+! # Check whether --enable-sim-model-issue was given.
+! if test "${enable_sim_model_issue+set}" = set; then
+! enableval=$enable_sim_model_issue; case "${enableval}" in
+! yes) sim_model_issue="-DWITH_MODEL_ISSUE=MODEL_ISSUE_PROCESS";;
+! no) sim_model_issue="-DWITH_MODEL_ISSUE=MODEL_ISSUE_IGNORE";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-model-issue does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-model-issue does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_model_issue="";;
+! esac
+! if test x"$silent" != x"yes"; then
+! echo "Setting model-issue flags = $sim_model_issue" 6>&1
+! fi
+! else
+! sim_model_issue=""
+! fi
+!
+!
+! # Check whether --enable-sim-monitor was given.
+! if test "${enable_sim_monitor+set}" = set; then
+! enableval=$enable_sim_monitor; case "${enableval}" in
+! yes) sim_monitor="-DWITH_MON='MONITOR_INSTRUCTION_ISSUE | MONITOR_LOAD_STORE_UNIT'";;
+! no) sim_monitor="-DWITH_MON=0";;
+! instruction) sim_monitor="-DWITH_MON=MONITOR_INSTRUCTION_ISSUE";;
+! memory) sim_monitor="-DWITH_MON=MONITOR_LOAD_STORE_UNIT";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-mon\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-mon\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_env="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_monitor" != x""; then
+! echo "Setting monitor flags = $sim_monitor" 6>&1
+ fi
+ else
+! sim_monitor=""
+ fi
+
+!
+! # Check whether --enable-sim-opcode was given.
+! if test "${enable_sim_opcode+set}" = set; then
+! enableval=$enable_sim_opcode; case "${enableval}" in
+! yes|no) { { $as_echo "$as_me:$LINENO: error: \"No value supplied for --enable-sim-opcode=file\"" >&5
+! $as_echo "$as_me: error: \"No value supplied for --enable-sim-opcode=file\"" >&2;}
+! { (exit 1); exit 1; }; };;
+! *) if test -f "${srcdir}/${enableval}"; then
+! sim_opcode="${enableval}"
+! elif test -f "${srcdir}/dc-${enableval}"; then
+! sim_opcode="dc-${enableval}"
+! else
+! { { $as_echo "$as_me:$LINENO: error: \"File $enableval is not an opcode rules file\"" >&5
+! $as_echo "$as_me: error: \"File $enableval is not an opcode rules file\"" >&2;}
+! { (exit 1); exit 1; }; };
+! sim_opcode="dc-complex"
+! fi;;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_opcode" != x""; then
+! echo "Setting opcode flags = $sim_opcode" 6>&1
+! fi
+! else
+! sim_opcode="dc-complex"
+! if test x"$silent" != x"yes"; then
+! echo "Setting opcode flags = $sim_opcode"
+! fi
+ fi
+
+
++ # Check whether --enable-sim-packages was given.
++ if test "${enable_sim_packages+set}" = set; then
++ enableval=$enable_sim_packages; packages=disklabel
++ case "${enableval}" in
++ yes) ;;
++ no) { { $as_echo "$as_me:$LINENO: error: \"List of packages must be specified for --enable-sim-packages\"" >&5
++ $as_echo "$as_me: error: \"List of packages must be specified for --enable-sim-packages\"" >&2;}
++ { (exit 1); exit 1; }; }; packages="";;
++ ,*) packages="${packages}${enableval}";;
++ *,) packages="${enableval}${packages}";;
++ *) packages="${enableval}"'';;
++ esac
++ sim_pk_src=`echo $packages | sed -e 's/,/.c pk_/g' -e 's/^/pk_/' -e 's/$/.c/'`
++ sim_pk_obj=`echo $sim_pk_src | sed -e 's/\.c/.o/g'`
++ if test x"$silent" != x"yes" && test x"$packages" != x""; then
++ echo "Setting packages to $sim_pk_src, $sim_pk_obj"
+ fi
+ else
+! packages=disklabel
+! sim_pk_src=`echo $packages | sed -e 's/,/.c pk_/g' -e 's/^/pk_/' -e 's/$/.c/'`
+! sim_pk_obj=`echo $sim_pk_src | sed -e 's/\.c/.o/g'`
+! if test x"$silent" != x"yes"; then
+! echo "Setting packages to $sim_pk_src, $sim_pk_obj"
+ fi
+ fi
+
+
+! # Check whether --enable-sim-regparm was given.
+! if test "${enable_sim_regparm+set}" = set; then
+! enableval=$enable_sim_regparm; case "${enableval}" in
+! 0*|1*|2*|3*|4*|5*|6*|7*|8*|9*) sim_regparm="-DWITH_REGPARM=${enableval}";;
+! no) sim_regparm="" ;;
+! yes) sim_regparm="-DWITH_REGPARM=3";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-regparm\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval for --enable-sim-regparm\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_regparm="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_regparm" != x""; then
+! echo "Setting regparm flags = $sim_regparm" 6>&1
+ fi
+ else
+! sim_regparm=""
+ fi
+
+!
+! # Check whether --enable-sim-reserved-bits was given.
+! if test "${enable_sim_reserved_bits+set}" = set; then
+! enableval=$enable_sim_reserved_bits; case "${enableval}" in
+! yes) sim_reserved="-DWITH_RESERVED_BITS=1";;
+! no) sim_reserved="-DWITH_RESERVED_BITS=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-reserved-bits does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-reserved-bits does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_reserved="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_reserved" != x""; then
+! echo "Setting reserved flags = $sim_reserved" 6>&1
+! fi
+ else
+! sim_reserved=""
+ fi
+
+
+! # Check whether --enable-sim-smp was given.
+! if test "${enable_sim_smp+set}" = set; then
+! enableval=$enable_sim_smp; case "${enableval}" in
+! yes) sim_smp="-DWITH_SMP=5" ; sim_igen_smp="-N 5";;
+! no) sim_smp="-DWITH_SMP=0" ; sim_igen_smp="-N 0";;
+! *) sim_smp="-DWITH_SMP=$enableval" ; sim_igen_smp="-N $enableval";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_smp" != x""; then
+! echo "Setting smp flags = $sim_smp" 6>&1
+! fi
+! else
+! sim_smp="-DWITH_SMP=5" ; sim_igen_smp="-N 5"
+! if test x"$silent" != x"yes"; then
+! echo "Setting smp flags = $sim_smp" 6>&1
+! fi
+ fi
+
+
+! # Check whether --enable-sim-stdcall was given.
+! if test "${enable_sim_stdcall+set}" = set; then
+! enableval=$enable_sim_stdcall; case "${enableval}" in
+! no) sim_stdcall="" ;;
+! std*) sim_stdcall="-DWITH_STDCALL=1";;
+! yes) sim_stdcall="-DWITH_STDCALL=1";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval for --enable-sim-stdcall\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval for --enable-sim-stdcall\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_stdcall="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_stdcall" != x""; then
+! echo "Setting function call flags = $sim_stdcall" 6>&1
+! fi
+ else
+! sim_stdcall=""
+! fi
+
+
+! # Check whether --enable-sim-stdio was given.
+! if test "${enable_sim_stdio+set}" = set; then
+! enableval=$enable_sim_stdio; case "${enableval}" in
+! yes) sim_stdio="-DWITH_STDIO=DO_USE_STDIO";;
+! no) sim_stdio="-DWITH_STDIO=DONT_USE_STDIO";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"Unknown value $enableval passed to --enable-sim-stdio\"" >&5
+! $as_echo "$as_me: error: \"Unknown value $enableval passed to --enable-sim-stdio\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_stdio="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_stdio" != x""; then
+! echo "Setting stdio flags = $sim_stdio" 6>&1
+! fi
+ else
+! sim_stdio=""
+ fi
+
+
+! # Check whether --enable-sim-switch was given.
+! if test "${enable_sim_switch+set}" = set; then
+! enableval=$enable_sim_switch; case "${enableval}" in
+! yes) sim_switch="-s";;
+! no) sim_switch="";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-switch does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-switch does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_switch="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_switch" != x""; then
+! echo "Setting switch flags = $sim_switch" 6>&1
+! fi
+ else
+! sim_switch="";
+! if test x"$silent" != x"yes"; then
+! echo "Setting switch flags = $sim_switch" 6>&1
+ fi
+ fi
+
+
+! # Check whether --enable-sim-timebase was given.
+! if test "${enable_sim_timebase+set}" = set; then
+! enableval=$enable_sim_timebase; case "${enableval}" in
+! yes) sim_timebase="-DWITH_TIME_BASE=1";;
+! no) sim_timebase="-DWITH_TIME_BASE=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-timebase does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-timebase does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_timebase="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_timebase" != x""; then
+! echo "Setting timebase flags = $sim_timebase" 6>&1
+! fi
+ else
+! sim_timebase=""
+ fi
+
+
+! # Check whether --enable-sim-trace was given.
+! if test "${enable_sim_trace+set}" = set; then
+! enableval=$enable_sim_trace; case "${enableval}" in
+! yes) sim_trace="-DWITH_TRACE=1";;
+! no) sim_trace="-DWITH_TRACE=0";;
+! *) { { $as_echo "$as_me:$LINENO: error: \"--enable-sim-trace does not take a value\"" >&5
+! $as_echo "$as_me: error: \"--enable-sim-trace does not take a value\"" >&2;}
+! { (exit 1); exit 1; }; }; sim_trace="";;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_trace" != x""; then
+! echo "Setting trace flags = $sim_trace" 6>&1
+! fi
+ else
+! sim_trace=""
+! fi
+
+
+! # Check whether --enable-sim-warnings was given.
+! if test "${enable_sim_warnings+set}" = set; then
+! enableval=$enable_sim_warnings; case "${enableval}" in
+! yes) sim_warnings="-Werror -Wall -Wpointer-arith -Wmissing-prototypes -Wmissing-declarations ";;
+! no) sim_warnings="-w";;
+! *) sim_warnings=`echo "${enableval}" | sed -e "s/,/ /g"`;;
+! esac
+! if test x"$silent" != x"yes" && test x"$sim_warnings" != x""; then
+! echo "Setting warning flags = $sim_warnings" 6>&1
+ fi
+! else
+! sim_warnings=""
+ fi
++
++
++ # Check whether --enable-sim-xor-endian was given.
++ if test "${enable_sim_xor_endian+set}" = set; then
++ enableval=$enable_sim_xor_endian; case "${enableval}" in
++ yes) sim_xor_endian="-DWITH_XOR_ENDIAN=8";;
++ no) sim_xor_endian="-DWITH_XOR_ENDIAN=0";;
++ *) sim_xor_endian="-DWITH_XOR_ENDIAN=$enableval";;
++ esac
++ if test x"$silent" != x"yes" && test x"$sim_xor_endian" != x""; then
++ echo "Setting xor-endian flag = $sim_xor_endian" 6>&1
+ fi
++ else
++ sim_xor_endian=""
+ fi
+
+!
+! # Make sure we can run config.sub.
+! $SHELL "$ac_aux_dir/config.sub" sun4 >/dev/null 2>&1 ||
+! { { $as_echo "$as_me:$LINENO: error: cannot run $SHELL $ac_aux_dir/config.sub" >&5
+! $as_echo "$as_me: error: cannot run $SHELL $ac_aux_dir/config.sub" >&2;}
+! { (exit 1); exit 1; }; }
+!
+! { $as_echo "$as_me:$LINENO: checking build system type" >&5
+! $as_echo_n "checking build system type... " >&6; }
+! if test "${ac_cv_build+set}" = set; then
+! $as_echo_n "(cached) " >&6
+! else
+! ac_build_alias=$build_alias
+! test "x$ac_build_alias" = x &&
+! ac_build_alias=`$SHELL "$ac_aux_dir/config.guess"`
+! test "x$ac_build_alias" = x &&
+! { { $as_echo "$as_me:$LINENO: error: cannot guess build type; you must specify one" >&5
+! $as_echo "$as_me: error: cannot guess build type; you must specify one" >&2;}
+! { (exit 1); exit 1; }; }
+! ac_cv_build=`$SHELL "$ac_aux_dir/config.sub" $ac_build_alias` ||
+! { { $as_echo "$as_me:$LINENO: error: $SHELL $ac_aux_dir/config.sub $ac_build_alias failed" >&5
+! $as_echo "$as_me: error: $SHELL $ac_aux_dir/config.sub $ac_build_alias failed" >&2;}
+! { (exit 1); exit 1; }; }
+
+ fi
++ { $as_echo "$as_me:$LINENO: result: $ac_cv_build" >&5
++ $as_echo "$ac_cv_build" >&6; }
++ case $ac_cv_build in
++ *-*-*) ;;
++ *) { { $as_echo "$as_me:$LINENO: error: invalid value of canonical build" >&5
++ $as_echo "$as_me: error: invalid value of canonical build" >&2;}
++ { (exit 1); exit 1; }; };;
++ esac
++ build=$ac_cv_build
++ ac_save_IFS=$IFS; IFS='-'
++ set x $ac_cv_build
++ shift
++ build_cpu=$1
++ build_vendor=$2
++ shift; shift
++ # Remember, the first character of IFS is used to create $*,
++ # except with old shells:
++ build_os=$*
++ IFS=$ac_save_IFS
++ case $build_os in *\ *) build_os=`echo "$build_os" | sed 's/ /-/g'`;; esac
+
+
++ { $as_echo "$as_me:$LINENO: checking host system type" >&5
++ $as_echo_n "checking host system type... " >&6; }
++ if test "${ac_cv_host+set}" = set; then
++ $as_echo_n "(cached) " >&6
++ else
++ if test "x$host_alias" = x; then
++ ac_cv_host=$ac_cv_build
++ else
++ ac_cv_host=`$SHELL "$ac_aux_dir/config.sub" $host_alias` ||
++ { { $as_echo "$as_me:$LINENO: error: $SHELL $ac_aux_dir/config.sub $host_alias failed" >&5
++ $as_echo "$as_me: error: $SHELL $ac_aux_dir/config.sub $host_alias failed" >&2;}
++ { (exit 1); exit 1; }; }
++ fi
+
++ fi
++ { $as_echo "$as_me:$LINENO: result: $ac_cv_host" >&5
++ $as_echo "$ac_cv_host" >&6; }
++ case $ac_cv_host in
++ *-*-*) ;;
++ *) { { $as_echo "$as_me:$LINENO: error: invalid value of canonical host" >&5
++ $as_echo "$as_me: error: invalid value of canonical host" >&2;}
++ { (exit 1); exit 1; }; };;
++ esac
++ host=$ac_cv_host
++ ac_save_IFS=$IFS; IFS='-'
++ set x $ac_cv_host
++ shift
++ host_cpu=$1
++ host_vendor=$2
++ shift; shift
++ # Remember, the first character of IFS is used to create $*,
++ # except with old shells:
++ host_os=$*
++ IFS=$ac_save_IFS
++ case $host_os in *\ *) host_os=`echo "$host_os" | sed 's/ /-/g'`;; esac
+
+
++ { $as_echo "$as_me:$LINENO: checking target system type" >&5
++ $as_echo_n "checking target system type... " >&6; }
++ if test "${ac_cv_target+set}" = set; then
++ $as_echo_n "(cached) " >&6
++ else
++ if test "x$target_alias" = x; then
++ ac_cv_target=$ac_cv_host
++ else
++ ac_cv_target=`$SHELL "$ac_aux_dir/config.sub" $target_alias` ||
++ { { $as_echo "$as_me:$LINENO: error: $SHELL $ac_aux_dir/config.sub $target_alias failed" >&5
++ $as_echo "$as_me: error: $SHELL $ac_aux_dir/config.sub $target_alias failed" >&2;}
++ { (exit 1); exit 1; }; }
++ fi
+
++ fi
++ { $as_echo "$as_me:$LINENO: result: $ac_cv_target" >&5
++ $as_echo "$ac_cv_target" >&6; }
++ case $ac_cv_target in
++ *-*-*) ;;
++ *) { { $as_echo "$as_me:$LINENO: error: invalid value of canonical target" >&5
++ $as_echo "$as_me: error: invalid value of canonical target" >&2;}
++ { (exit 1); exit 1; }; };;
++ esac
++ target=$ac_cv_target
++ ac_save_IFS=$IFS; IFS='-'
++ set x $ac_cv_target
++ shift
++ target_cpu=$1
++ target_vendor=$2
++ shift; shift
++ # Remember, the first character of IFS is used to create $*,
++ # except with old shells:
++ target_os=$*
++ IFS=$ac_save_IFS
++ case $target_os in *\ *) target_os=`echo "$target_os" | sed 's/ /-/g'`;; esac
+
+
++ # The aliases save the names the user supplied, while $host etc.
++ # will get canonicalized.
++ test -n "$target_alias" &&
++ test "$program_prefix$program_suffix$program_transform_name" = \
++ NONENONEs,x,x, &&
++ program_prefix=${target_alias}-
++ test "$program_prefix" != NONE &&
++ program_transform_name="s&^&$program_prefix&;$program_transform_name"
++ # Use a double $ so make ignores it.
++ test "$program_suffix" != NONE &&
++ program_transform_name="s&\$&$program_suffix&;$program_transform_name"
++ # Double any \ or $.
++ # By default was `s,x,x', remove it if useless.
++ ac_script='s/[\\$]/&&/g;s/;s,x,x,$//'
++ program_transform_name=`$as_echo "$program_transform_name" | sed "$ac_script"`
+
+
+! . ${srcdir}/../../bfd/configure.host
+
+! case ${host} in
+! *mingw32*)
+
+! cat >>confdefs.h <<\_ACEOF
+! #define USE_WIN32API 1
+ _ACEOF
+
+! ;;
+! esac
+
++ ac_config_headers="$ac_config_headers config.h:config.in"
+
+
+! { $as_echo "$as_me:$LINENO: checking for struct stat.st_blksize" >&5
+! $as_echo_n "checking for struct stat.st_blksize... " >&6; }
+ if test "${ac_cv_member_struct_stat_st_blksize+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4019,4051 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_blksize=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 4935,4963 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_blksize=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4063,4102 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_blksize=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_blksize=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_blksize" >&5
+! echo "${ECHO_T}$ac_cv_member_struct_stat_st_blksize" >&6
+ if test $ac_cv_member_struct_stat_st_blksize = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+--- 4975,5012 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_blksize=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_blksize=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_blksize" >&5
+! $as_echo "$ac_cv_member_struct_stat_st_blksize" >&6; }
+ if test $ac_cv_member_struct_stat_st_blksize = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+***************
+*** 4111,4120 ****
+ fi
+
+
+! echo "$as_me:$LINENO: checking for struct stat.st_blocks" >&5
+! echo $ECHO_N "checking for struct stat.st_blocks... $ECHO_C" >&6
+ if test "${ac_cv_member_struct_stat_st_blocks+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5021,5030 ----
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: checking for struct stat.st_blocks" >&5
+! $as_echo_n "checking for struct stat.st_blocks... " >&6; }
+ if test "${ac_cv_member_struct_stat_st_blocks+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4134,4166 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_blocks=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5044,5072 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_blocks=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4178,4217 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_blocks=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_blocks=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_blocks" >&5
+! echo "${ECHO_T}$ac_cv_member_struct_stat_st_blocks" >&6
+ if test $ac_cv_member_struct_stat_st_blocks = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+--- 5084,5121 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_blocks=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_blocks=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_blocks" >&5
+! $as_echo "$ac_cv_member_struct_stat_st_blocks" >&6; }
+ if test $ac_cv_member_struct_stat_st_blocks = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+***************
+*** 4224,4245 ****
+ _ACEOF
+
+ else
+! case $LIBOBJS in
+! "fileblocks.$ac_objext" | \
+! *" fileblocks.$ac_objext" | \
+! "fileblocks.$ac_objext "* | \
+ *" fileblocks.$ac_objext "* ) ;;
+! *) LIBOBJS="$LIBOBJS fileblocks.$ac_objext" ;;
+ esac
+
+ fi
+
+
+!
+! echo "$as_me:$LINENO: checking for struct stat.st_rdev" >&5
+! echo $ECHO_N "checking for struct stat.st_rdev... $ECHO_C" >&6
+ if test "${ac_cv_member_struct_stat_st_rdev+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5128,5146 ----
+ _ACEOF
+
+ else
+! case " $LIBOBJS " in
+ *" fileblocks.$ac_objext "* ) ;;
+! *) LIBOBJS="$LIBOBJS fileblocks.$ac_objext"
+! ;;
+ esac
+
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: checking for struct stat.st_rdev" >&5
+! $as_echo_n "checking for struct stat.st_rdev... " >&6; }
+ if test "${ac_cv_member_struct_stat_st_rdev+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4259,4291 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_rdev=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5160,5188 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_rdev=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4303,4342 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_stat_st_rdev=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_rdev=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_rdev" >&5
+! echo "${ECHO_T}$ac_cv_member_struct_stat_st_rdev" >&6
+ if test $ac_cv_member_struct_stat_st_rdev = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+--- 5200,5237 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_stat_st_rdev=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_stat_st_rdev=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_member_struct_stat_st_rdev" >&5
+! $as_echo "$ac_cv_member_struct_stat_st_rdev" >&6; }
+ if test $ac_cv_member_struct_stat_st_rdev = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+***************
+*** 4351,4360 ****
+ fi
+
+
+! echo "$as_me:$LINENO: checking whether struct tm is in sys/time.h or time.h" >&5
+! echo $ECHO_N "checking whether struct tm is in sys/time.h or time.h... $ECHO_C" >&6
+ if test "${ac_cv_struct_tm+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5246,5255 ----
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: checking whether struct tm is in sys/time.h or time.h" >&5
+! $as_echo_n "checking whether struct tm is in sys/time.h or time.h... " >&6; }
+ if test "${ac_cv_struct_tm+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4368,4411 ****
+ int
+ main ()
+ {
+! struct tm *tp; tp->tm_sec;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_struct_tm=time.h
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_struct_tm=sys/time.h
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_struct_tm" >&5
+! echo "${ECHO_T}$ac_cv_struct_tm" >&6
+ if test $ac_cv_struct_tm = sys/time.h; then
+
+ cat >>confdefs.h <<\_ACEOF
+--- 5263,5305 ----
+ int
+ main ()
+ {
+! struct tm tm;
+! int *p = &tm.tm_sec;
+! return !p;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_struct_tm=time.h
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_struct_tm=sys/time.h
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_struct_tm" >&5
+! $as_echo "$ac_cv_struct_tm" >&6; }
+ if test $ac_cv_struct_tm = sys/time.h; then
+
+ cat >>confdefs.h <<\_ACEOF
+***************
+*** 4414,4423 ****
+
+ fi
+
+! echo "$as_me:$LINENO: checking for struct tm.tm_zone" >&5
+! echo $ECHO_N "checking for struct tm.tm_zone... $ECHO_C" >&6
+ if test "${ac_cv_member_struct_tm_tm_zone+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5308,5317 ----
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for struct tm.tm_zone" >&5
+! $as_echo_n "checking for struct tm.tm_zone... " >&6; }
+ if test "${ac_cv_member_struct_tm_tm_zone+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4440,4472 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_tm_tm_zone=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5334,5362 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_tm_tm_zone=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4487,4526 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_member_struct_tm_tm_zone=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_tm_tm_zone=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_member_struct_tm_tm_zone" >&5
+! echo "${ECHO_T}$ac_cv_member_struct_tm_tm_zone" >&6
+ if test $ac_cv_member_struct_tm_tm_zone = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+--- 5377,5414 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_member_struct_tm_tm_zone=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_member_struct_tm_tm_zone=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_member_struct_tm_tm_zone" >&5
+! $as_echo "$ac_cv_member_struct_tm_tm_zone" >&6; }
+ if test $ac_cv_member_struct_tm_tm_zone = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+***************
+*** 4537,4546 ****
+ _ACEOF
+
+ else
+! echo "$as_me:$LINENO: checking for tzname" >&5
+! echo $ECHO_N "checking for tzname... $ECHO_C" >&6
+ if test "${ac_cv_var_tzname+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5425,5504 ----
+ _ACEOF
+
+ else
+! { $as_echo "$as_me:$LINENO: checking whether tzname is declared" >&5
+! $as_echo_n "checking whether tzname is declared... " >&6; }
+! if test "${ac_cv_have_decl_tzname+set}" = set; then
+! $as_echo_n "(cached) " >&6
+! else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <time.h>
+!
+! int
+! main ()
+! {
+! #ifndef tzname
+! (void) tzname;
+! #endif
+!
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_have_decl_tzname=yes
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_have_decl_tzname=no
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_have_decl_tzname" >&5
+! $as_echo "$ac_cv_have_decl_tzname" >&6; }
+! if test $ac_cv_have_decl_tzname = yes; then
+!
+! cat >>confdefs.h <<_ACEOF
+! #define HAVE_DECL_TZNAME 1
+! _ACEOF
+!
+!
+! else
+! cat >>confdefs.h <<_ACEOF
+! #define HAVE_DECL_TZNAME 0
+! _ACEOF
+!
+!
+! fi
+!
+!
+! { $as_echo "$as_me:$LINENO: checking for tzname" >&5
+! $as_echo_n "checking for tzname... " >&6; }
+ if test "${ac_cv_var_tzname+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4549,4600 ****
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+ #include <time.h>
+! #ifndef tzname /* For SGI. */
+! extern char *tzname[]; /* RS6000 and others reject char **tzname. */
+ #endif
+
+ int
+ main ()
+ {
+! atoi(*tzname);
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_var_tzname=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_var_tzname=no
+ fi
+! rm -f conftest.err conftest.$ac_objext \
+ conftest$ac_exeext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_var_tzname" >&5
+! echo "${ECHO_T}$ac_cv_var_tzname" >&6
+ if test $ac_cv_var_tzname = yes; then
+
+ cat >>confdefs.h <<\_ACEOF
+--- 5507,5559 ----
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+ #include <time.h>
+! #if !HAVE_DECL_TZNAME
+! extern char *tzname[];
+ #endif
+
+ int
+ main ()
+ {
+! return tzname[0][0];
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest$ac_exeext && {
+! test "$cross_compiling" = yes ||
+! $as_test_x conftest$ac_exeext
+! }; then
+ ac_cv_var_tzname=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_var_tzname=no
+ fi
+!
+! rm -rf conftest.dSYM
+! rm -f core conftest.err conftest.$ac_objext conftest_ipa8_conftest.oo \
+ conftest$ac_exeext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_var_tzname" >&5
+! $as_echo "$ac_cv_var_tzname" >&6; }
+ if test $ac_cv_var_tzname = yes; then
+
+ cat >>confdefs.h <<\_ACEOF
+***************
+*** 4605,4614 ****
+ fi
+
+
+! echo "$as_me:$LINENO: checking for uid_t in sys/types.h" >&5
+! echo $ECHO_N "checking for uid_t in sys/types.h... $ECHO_C" >&6
+ if test "${ac_cv_type_uid_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5564,5573 ----
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: checking for uid_t in sys/types.h" >&5
+! $as_echo_n "checking for uid_t in sys/types.h... " >&6; }
+ if test "${ac_cv_type_uid_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4628,4635 ****
+ rm -f conftest*
+
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_uid_t" >&5
+! echo "${ECHO_T}$ac_cv_type_uid_t" >&6
+ if test $ac_cv_type_uid_t = no; then
+
+ cat >>confdefs.h <<\_ACEOF
+--- 5587,5594 ----
+ rm -f conftest*
+
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_uid_t" >&5
+! $as_echo "$ac_cv_type_uid_t" >&6; }
+ if test $ac_cv_type_uid_t = no; then
+
+ cat >>confdefs.h <<\_ACEOF
+***************
+*** 4643,4652 ****
+
+ fi
+
+! echo "$as_me:$LINENO: checking type of array argument to getgroups" >&5
+! echo $ECHO_N "checking type of array argument to getgroups... $ECHO_C" >&6
+ if test "${ac_cv_type_getgroups+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test "$cross_compiling" = yes; then
+ ac_cv_type_getgroups=cross
+--- 5602,5611 ----
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking type of array argument to getgroups" >&5
+! $as_echo_n "checking type of array argument to getgroups... " >&6; }
+ if test "${ac_cv_type_getgroups+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test "$cross_compiling" = yes; then
+ ac_cv_type_getgroups=cross
+***************
+*** 4658,4664 ****
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+ /* Thanks to Mike Rendell for this test. */
+! #include <sys/types.h>
+ #define NGID 256
+ #undef MAX
+ #define MAX(x, y) ((x) > (y) ? (x) : (y))
+--- 5617,5623 ----
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+ /* Thanks to Mike Rendell for this test. */
+! $ac_includes_default
+ #define NGID 256
+ #undef MAX
+ #define MAX(x, y) ((x) > (y) ? (x) : (y))
+***************
+*** 4668,4674 ****
+ {
+ gid_t gidset[NGID];
+ int i, n;
+! union { gid_t gval; long lval; } val;
+
+ val.lval = -1;
+ for (i = 0; i < NGID; i++)
+--- 5627,5633 ----
+ {
+ gid_t gidset[NGID];
+ int i, n;
+! union { gid_t gval; long int lval; } val;
+
+ val.lval = -1;
+ for (i = 0; i < NGID; i++)
+***************
+*** 4676,4707 ****
+ n = getgroups (sizeof (gidset) / MAX (sizeof (int), sizeof (gid_t)) - 1,
+ gidset);
+ /* Exit non-zero if getgroups seems to require an array of ints. This
+! happens when gid_t is short but getgroups modifies an array of ints. */
+! exit ((n > 0 && gidset[n] != val.gval) ? 1 : 0);
+ }
+ _ACEOF
+ rm -f conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ ac_cv_type_getgroups=gid_t
+ else
+! echo "$as_me: program exited with status $ac_status" >&5
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ( exit $ac_status )
+ ac_cv_type_getgroups=int
+ fi
+! rm -f core *.core gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
+ if test $ac_cv_type_getgroups = cross; then
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 5635,5681 ----
+ n = getgroups (sizeof (gidset) / MAX (sizeof (int), sizeof (gid_t)) - 1,
+ gidset);
+ /* Exit non-zero if getgroups seems to require an array of ints. This
+! happens when gid_t is short int but getgroups modifies an array
+! of ints. */
+! return n > 0 && gidset[n] != val.gval;
+ }
+ _ACEOF
+ rm -f conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_try") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ ac_cv_type_getgroups=gid_t
+ else
+! $as_echo "$as_me: program exited with status $ac_status" >&5
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ( exit $ac_status )
+ ac_cv_type_getgroups=int
+ fi
+! rm -rf conftest.dSYM
+! rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
++
++
+ if test $ac_cv_type_getgroups = cross; then
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4722,4741 ****
+
+ fi
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_getgroups" >&5
+! echo "${ECHO_T}$ac_cv_type_getgroups" >&6
+
+ cat >>confdefs.h <<_ACEOF
+ #define GETGROUPS_T $ac_cv_type_getgroups
+ _ACEOF
+
+
+! echo "$as_me:$LINENO: checking for mode_t" >&5
+! echo $ECHO_N "checking for mode_t... $ECHO_C" >&6
+ if test "${ac_cv_type_mode_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5696,5716 ----
+
+ fi
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_getgroups" >&5
+! $as_echo "$ac_cv_type_getgroups" >&6; }
+
+ cat >>confdefs.h <<_ACEOF
+ #define GETGROUPS_T $ac_cv_type_getgroups
+ _ACEOF
+
+
+! { $as_echo "$as_me:$LINENO: checking for mode_t" >&5
+! $as_echo_n "checking for mode_t... " >&6; }
+ if test "${ac_cv_type_mode_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_type_mode_t=no
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4745,4791 ****
+ int
+ main ()
+ {
+- if ((mode_t *) 0)
+- return 0;
+ if (sizeof (mode_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_mode_t=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_mode_t=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_mode_t" >&5
+! echo "${ECHO_T}$ac_cv_type_mode_t" >&6
+ if test $ac_cv_type_mode_t = yes; then
+ :
+ else
+--- 5720,5803 ----
+ int
+ main ()
+ {
+ if (sizeof (mode_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+! if (sizeof ((mode_t)))
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_mode_t=yes
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+!
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_mode_t" >&5
+! $as_echo "$ac_cv_type_mode_t" >&6; }
+ if test $ac_cv_type_mode_t = yes; then
+ :
+ else
+***************
+*** 4796,4807 ****
+
+ fi
+
+! echo "$as_me:$LINENO: checking for off_t" >&5
+! echo $ECHO_N "checking for off_t... $ECHO_C" >&6
+ if test "${ac_cv_type_off_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5808,5820 ----
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for off_t" >&5
+! $as_echo_n "checking for off_t... " >&6; }
+ if test "${ac_cv_type_off_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_type_off_t=no
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4811,4873 ****
+ int
+ main ()
+ {
+- if ((off_t *) 0)
+- return 0;
+ if (sizeof (off_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_off_t=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_off_t=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_off_t" >&5
+! echo "${ECHO_T}$ac_cv_type_off_t" >&6
+ if test $ac_cv_type_off_t = yes; then
+ :
+ else
+
+ cat >>confdefs.h <<_ACEOF
+! #define off_t long
+ _ACEOF
+
+ fi
+
+! echo "$as_me:$LINENO: checking for pid_t" >&5
+! echo $ECHO_N "checking for pid_t... $ECHO_C" >&6
+ if test "${ac_cv_type_pid_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 5824,5924 ----
+ int
+ main ()
+ {
+ if (sizeof (off_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+! if (sizeof ((off_t)))
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_type_off_t=yes
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_off_t" >&5
+! $as_echo "$ac_cv_type_off_t" >&6; }
+ if test $ac_cv_type_off_t = yes; then
+ :
+ else
+
+ cat >>confdefs.h <<_ACEOF
+! #define off_t long int
+ _ACEOF
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for pid_t" >&5
+! $as_echo_n "checking for pid_t... " >&6; }
+ if test "${ac_cv_type_pid_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_type_pid_t=no
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 4877,4923 ****
+ int
+ main ()
+ {
+- if ((pid_t *) 0)
+- return 0;
+ if (sizeof (pid_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_pid_t=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_pid_t=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_pid_t" >&5
+! echo "${ECHO_T}$ac_cv_type_pid_t" >&6
+ if test $ac_cv_type_pid_t = yes; then
+ :
+ else
+--- 5928,6011 ----
+ int
+ main ()
+ {
+ if (sizeof (pid_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+! if (sizeof ((pid_t)))
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_type_pid_t=yes
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_pid_t" >&5
+! $as_echo "$ac_cv_type_pid_t" >&6; }
+ if test $ac_cv_type_pid_t = yes; then
+ :
+ else
+***************
+*** 4928,4937 ****
+
+ fi
+
+! echo "$as_me:$LINENO: checking return type of signal handlers" >&5
+! echo $ECHO_N "checking return type of signal handlers... $ECHO_C" >&6
+ if test "${ac_cv_type_signal+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6016,6025 ----
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking return type of signal handlers" >&5
+! $as_echo_n "checking return type of signal handlers... " >&6; }
+ if test "${ac_cv_type_signal+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 4941,5008 ****
+ /* end confdefs.h. */
+ #include <sys/types.h>
+ #include <signal.h>
+- #ifdef signal
+- # undef signal
+- #endif
+- #ifdef __cplusplus
+- extern "C" void (*signal (int, void (*)(int)))(int);
+- #else
+- void (*signal ()) ();
+- #endif
+
+ int
+ main ()
+ {
+! int i;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_signal=void
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_signal=int
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_signal" >&5
+! echo "${ECHO_T}$ac_cv_type_signal" >&6
+
+ cat >>confdefs.h <<_ACEOF
+ #define RETSIGTYPE $ac_cv_type_signal
+ _ACEOF
+
+
+! echo "$as_me:$LINENO: checking for size_t" >&5
+! echo $ECHO_N "checking for size_t... $ECHO_C" >&6
+ if test "${ac_cv_type_size_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 6029,6086 ----
+ /* end confdefs.h. */
+ #include <sys/types.h>
+ #include <signal.h>
+
+ int
+ main ()
+ {
+! return *(signal (0, 0)) (0) == 1;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! ac_cv_type_signal=int
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_signal=void
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_signal" >&5
+! $as_echo "$ac_cv_type_signal" >&6; }
+
+ cat >>confdefs.h <<_ACEOF
+ #define RETSIGTYPE $ac_cv_type_signal
+ _ACEOF
+
+
+! { $as_echo "$as_me:$LINENO: checking for size_t" >&5
+! $as_echo_n "checking for size_t... " >&6; }
+ if test "${ac_cv_type_size_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_type_size_t=no
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 5012,5072 ****
+ int
+ main ()
+ {
+- if ((size_t *) 0)
+- return 0;
+ if (sizeof (size_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_size_t=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_size_t=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_size_t" >&5
+! echo "${ECHO_T}$ac_cv_type_size_t" >&6
+ if test $ac_cv_type_size_t = yes; then
+ :
+ else
+
+ cat >>confdefs.h <<_ACEOF
+! #define size_t unsigned
+ _ACEOF
+
+ fi
+
+! echo "$as_me:$LINENO: checking for uid_t in sys/types.h" >&5
+! echo $ECHO_N "checking for uid_t in sys/types.h... $ECHO_C" >&6
+ if test "${ac_cv_type_uid_t+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6090,6187 ----
+ int
+ main ()
+ {
+ if (sizeof (size_t))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+! if (sizeof ((size_t)))
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_type_size_t=yes
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_size_t" >&5
+! $as_echo "$ac_cv_type_size_t" >&6; }
+ if test $ac_cv_type_size_t = yes; then
+ :
+ else
+
+ cat >>confdefs.h <<_ACEOF
+! #define size_t unsigned int
+ _ACEOF
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for uid_t in sys/types.h" >&5
+! $as_echo_n "checking for uid_t in sys/types.h... " >&6; }
+ if test "${ac_cv_type_uid_t+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5086,5093 ****
+ rm -f conftest*
+
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_uid_t" >&5
+! echo "${ECHO_T}$ac_cv_type_uid_t" >&6
+ if test $ac_cv_type_uid_t = no; then
+
+ cat >>confdefs.h <<\_ACEOF
+--- 6201,6208 ----
+ rm -f conftest*
+
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_uid_t" >&5
+! $as_echo "$ac_cv_type_uid_t" >&6; }
+ if test $ac_cv_type_uid_t = no; then
+
+ cat >>confdefs.h <<\_ACEOF
+***************
+*** 5154,5164 ****
+
+ for ac_func in access cfgetispeed cfgetospeed cfsetispeed cfsetospeed chdir chmod chown dup dup2 fchmod fchown fcntl fstat fstatfs getdirentries getegid geteuid getgid getpid getppid getrusage gettimeofday getuid ioctl kill link lseek lstat mkdir pipe readlink rmdir setreuid setregid stat sigprocmask stat symlink tcgetattr tcsetattr tcsendbreak tcdrain tcflush tcflow tcgetpgrp tcsetpgrp time umask unlink
+ do
+! as_ac_var=`echo "ac_cv_func_$ac_func" | $as_tr_sh`
+! echo "$as_me:$LINENO: checking for $ac_func" >&5
+! echo $ECHO_N "checking for $ac_func... $ECHO_C" >&6
+! if eval "test \"\${$as_ac_var+set}\" = set"; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6269,6279 ----
+
+ for ac_func in access cfgetispeed cfgetospeed cfsetispeed cfsetospeed chdir chmod chown dup dup2 fchmod fchown fcntl fstat fstatfs getdirentries getegid geteuid getgid getpid getppid getrusage gettimeofday getuid ioctl kill link lseek lstat mkdir pipe readlink rmdir setreuid setregid stat sigprocmask stat symlink tcgetattr tcsetattr tcsendbreak tcdrain tcflush tcflow tcgetpgrp tcsetpgrp time umask unlink
+ do
+! as_ac_var=`$as_echo "ac_cv_func_$ac_func" | $as_tr_sh`
+! { $as_echo "$as_me:$LINENO: checking for $ac_func" >&5
+! $as_echo_n "checking for $ac_func... " >&6; }
+! if { as_var=$as_ac_var; eval "test \"\${$as_var+set}\" = set"; }; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5183,5253 ****
+
+ #undef $ac_func
+
+! /* Override any gcc2 internal prototype to avoid an error. */
+ #ifdef __cplusplus
+ extern "C"
+- {
+ #endif
+- /* We use char because int might match the return type of a gcc2
+- builtin and then its argument prototype would still apply. */
+ char $ac_func ();
+ /* The GNU C library defines this for functions which it implements
+ to always fail with ENOSYS. Some functions are actually named
+ something starting with __ and the normal name is an alias. */
+! #if defined (__stub_$ac_func) || defined (__stub___$ac_func)
+ choke me
+- #else
+- char (*f) () = $ac_func;
+- #endif
+- #ifdef __cplusplus
+- }
+ #endif
+
+ int
+ main ()
+ {
+! return f != $ac_func;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ eval "$as_ac_var=yes"
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! eval "$as_ac_var=no"
+ fi
+! rm -f conftest.err conftest.$ac_objext \
+ conftest$ac_exeext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: `eval echo '${'$as_ac_var'}'`" >&5
+! echo "${ECHO_T}`eval echo '${'$as_ac_var'}'`" >&6
+! if test `eval echo '${'$as_ac_var'}'` = yes; then
+ cat >>confdefs.h <<_ACEOF
+! #define `echo "HAVE_$ac_func" | $as_tr_cpp` 1
+ _ACEOF
+
+ fi
+--- 6298,6366 ----
+
+ #undef $ac_func
+
+! /* Override any GCC internal prototype to avoid an error.
+! Use char because int might match the return type of a GCC
+! builtin and then its argument prototype would still apply. */
+ #ifdef __cplusplus
+ extern "C"
+ #endif
+ char $ac_func ();
+ /* The GNU C library defines this for functions which it implements
+ to always fail with ENOSYS. Some functions are actually named
+ something starting with __ and the normal name is an alias. */
+! #if defined __stub_$ac_func || defined __stub___$ac_func
+ choke me
+ #endif
+
+ int
+ main ()
+ {
+! return $ac_func ();
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest$ac_exeext && {
+! test "$cross_compiling" = yes ||
+! $as_test_x conftest$ac_exeext
+! }; then
+ eval "$as_ac_var=yes"
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! eval "$as_ac_var=no"
+ fi
+!
+! rm -rf conftest.dSYM
+! rm -f core conftest.err conftest.$ac_objext conftest_ipa8_conftest.oo \
+ conftest$ac_exeext conftest.$ac_ext
+ fi
+! ac_res=`eval 'as_val=${'$as_ac_var'}
+! $as_echo "$as_val"'`
+! { $as_echo "$as_me:$LINENO: result: $ac_res" >&5
+! $as_echo "$ac_res" >&6; }
+! if test `eval 'as_val=${'$as_ac_var'}
+! $as_echo "$as_val"'` = yes; then
+ cat >>confdefs.h <<_ACEOF
+! #define `$as_echo "HAVE_$ac_func" | $as_tr_cpp` 1
+ _ACEOF
+
+ fi
+***************
+*** 5274,5292 ****
+
+ for ac_header in fcntl.h stdlib.h string.h strings.h sys/ioctl.h sys/mount.h sys/param.h sys/resource.h sys/stat.h sys/termio.h sys/termios.h sys/time.h sys/times.h sys/types.h time.h unistd.h sys/vfs.h sys/statfs.h
+ do
+! as_ac_Header=`echo "ac_cv_header_$ac_header" | $as_tr_sh`
+! if eval "test \"\${$as_ac_Header+set}\" = set"; then
+! echo "$as_me:$LINENO: checking for $ac_header" >&5
+! echo $ECHO_N "checking for $ac_header... $ECHO_C" >&6
+! if eval "test \"\${$as_ac_Header+set}\" = set"; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! fi
+! echo "$as_me:$LINENO: result: `eval echo '${'$as_ac_Header'}'`" >&5
+! echo "${ECHO_T}`eval echo '${'$as_ac_Header'}'`" >&6
+ else
+ # Is the header compilable?
+! echo "$as_me:$LINENO: checking $ac_header usability" >&5
+! echo $ECHO_N "checking $ac_header usability... $ECHO_C" >&6
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+--- 6387,6407 ----
+
+ for ac_header in fcntl.h stdlib.h string.h strings.h sys/ioctl.h sys/mount.h sys/param.h sys/resource.h sys/stat.h sys/termio.h sys/termios.h sys/time.h sys/times.h sys/types.h time.h unistd.h sys/vfs.h sys/statfs.h
+ do
+! as_ac_Header=`$as_echo "ac_cv_header_$ac_header" | $as_tr_sh`
+! if { as_var=$as_ac_Header; eval "test \"\${$as_var+set}\" = set"; }; then
+! { $as_echo "$as_me:$LINENO: checking for $ac_header" >&5
+! $as_echo_n "checking for $ac_header... " >&6; }
+! if { as_var=$as_ac_Header; eval "test \"\${$as_var+set}\" = set"; }; then
+! $as_echo_n "(cached) " >&6
+! fi
+! ac_res=`eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'`
+! { $as_echo "$as_me:$LINENO: result: $ac_res" >&5
+! $as_echo "$ac_res" >&6; }
+ else
+ # Is the header compilable?
+! { $as_echo "$as_me:$LINENO: checking $ac_header usability" >&5
+! $as_echo_n "checking $ac_header usability... " >&6; }
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+***************
+*** 5297,5337 ****
+ #include <$ac_header>
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_header_compiler=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_header_compiler=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! echo "$as_me:$LINENO: result: $ac_header_compiler" >&5
+! echo "${ECHO_T}$ac_header_compiler" >&6
+
+ # Is the header present?
+! echo "$as_me:$LINENO: checking $ac_header presence" >&5
+! echo $ECHO_N "checking $ac_header presence... $ECHO_C" >&6
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+--- 6412,6449 ----
+ #include <$ac_header>
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_header_compiler=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_header_compiler=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+! { $as_echo "$as_me:$LINENO: result: $ac_header_compiler" >&5
+! $as_echo "$ac_header_compiler" >&6; }
+
+ # Is the header present?
+! { $as_echo "$as_me:$LINENO: checking $ac_header presence" >&5
+! $as_echo_n "checking $ac_header presence... " >&6; }
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+***************
+*** 5340,5420 ****
+ /* end confdefs.h. */
+ #include <$ac_header>
+ _ACEOF
+! if { (eval echo "$as_me:$LINENO: \"$ac_cpp conftest.$ac_ext\"") >&5
+! (eval $ac_cpp conftest.$ac_ext) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null; then
+! if test -s conftest.err; then
+! ac_cpp_err=$ac_c_preproc_warn_flag
+! ac_cpp_err=$ac_cpp_err$ac_c_werror_flag
+! else
+! ac_cpp_err=
+! fi
+! else
+! ac_cpp_err=yes
+! fi
+! if test -z "$ac_cpp_err"; then
+ ac_header_preproc=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ac_header_preproc=no
+ fi
+ rm -f conftest.err conftest.$ac_ext
+! echo "$as_me:$LINENO: result: $ac_header_preproc" >&5
+! echo "${ECHO_T}$ac_header_preproc" >&6
+
+ # So? What about this header?
+ case $ac_header_compiler:$ac_header_preproc:$ac_c_preproc_warn_flag in
+ yes:no: )
+! { echo "$as_me:$LINENO: WARNING: $ac_header: accepted by the compiler, rejected by the preprocessor!" >&5
+! echo "$as_me: WARNING: $ac_header: accepted by the compiler, rejected by the preprocessor!" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: proceeding with the compiler's result" >&5
+! echo "$as_me: WARNING: $ac_header: proceeding with the compiler's result" >&2;}
+ ac_header_preproc=yes
+ ;;
+ no:yes:* )
+! { echo "$as_me:$LINENO: WARNING: $ac_header: present but cannot be compiled" >&5
+! echo "$as_me: WARNING: $ac_header: present but cannot be compiled" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: check for missing prerequisite headers?" >&5
+! echo "$as_me: WARNING: $ac_header: check for missing prerequisite headers?" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: see the Autoconf documentation" >&5
+! echo "$as_me: WARNING: $ac_header: see the Autoconf documentation" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: section \"Present But Cannot Be Compiled\"" >&5
+! echo "$as_me: WARNING: $ac_header: section \"Present But Cannot Be Compiled\"" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: proceeding with the preprocessor's result" >&5
+! echo "$as_me: WARNING: $ac_header: proceeding with the preprocessor's result" >&2;}
+! { echo "$as_me:$LINENO: WARNING: $ac_header: in the future, the compiler will take precedence" >&5
+! echo "$as_me: WARNING: $ac_header: in the future, the compiler will take precedence" >&2;}
+! (
+! cat <<\_ASBOX
+! ## ------------------------------------------ ##
+! ## Report this to the AC_PACKAGE_NAME lists. ##
+! ## ------------------------------------------ ##
+! _ASBOX
+! ) |
+! sed "s/^/$as_me: WARNING: /" >&2
+ ;;
+ esac
+! echo "$as_me:$LINENO: checking for $ac_header" >&5
+! echo $ECHO_N "checking for $ac_header... $ECHO_C" >&6
+! if eval "test \"\${$as_ac_Header+set}\" = set"; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ eval "$as_ac_Header=\$ac_header_preproc"
+ fi
+! echo "$as_me:$LINENO: result: `eval echo '${'$as_ac_Header'}'`" >&5
+! echo "${ECHO_T}`eval echo '${'$as_ac_Header'}'`" >&6
+
+ fi
+! if test `eval echo '${'$as_ac_Header'}'` = yes; then
+ cat >>confdefs.h <<_ACEOF
+! #define `echo "HAVE_$ac_header" | $as_tr_cpp` 1
+ _ACEOF
+
+ fi
+--- 6452,6528 ----
+ /* end confdefs.h. */
+ #include <$ac_header>
+ _ACEOF
+! if { (ac_try="$ac_cpp conftest.$ac_ext"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_cpp conftest.$ac_ext") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } >/dev/null && {
+! test -z "$ac_c_preproc_warn_flag$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! }; then
+ ac_header_preproc=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ac_header_preproc=no
+ fi
++
+ rm -f conftest.err conftest.$ac_ext
+! { $as_echo "$as_me:$LINENO: result: $ac_header_preproc" >&5
+! $as_echo "$ac_header_preproc" >&6; }
+
+ # So? What about this header?
+ case $ac_header_compiler:$ac_header_preproc:$ac_c_preproc_warn_flag in
+ yes:no: )
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: accepted by the compiler, rejected by the preprocessor!" >&5
+! $as_echo "$as_me: WARNING: $ac_header: accepted by the compiler, rejected by the preprocessor!" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: proceeding with the compiler's result" >&5
+! $as_echo "$as_me: WARNING: $ac_header: proceeding with the compiler's result" >&2;}
+ ac_header_preproc=yes
+ ;;
+ no:yes:* )
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: present but cannot be compiled" >&5
+! $as_echo "$as_me: WARNING: $ac_header: present but cannot be compiled" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: check for missing prerequisite headers?" >&5
+! $as_echo "$as_me: WARNING: $ac_header: check for missing prerequisite headers?" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: see the Autoconf documentation" >&5
+! $as_echo "$as_me: WARNING: $ac_header: see the Autoconf documentation" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: section \"Present But Cannot Be Compiled\"" >&5
+! $as_echo "$as_me: WARNING: $ac_header: section \"Present But Cannot Be Compiled\"" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: proceeding with the preprocessor's result" >&5
+! $as_echo "$as_me: WARNING: $ac_header: proceeding with the preprocessor's result" >&2;}
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_header: in the future, the compiler will take precedence" >&5
+! $as_echo "$as_me: WARNING: $ac_header: in the future, the compiler will take precedence" >&2;}
+!
+ ;;
+ esac
+! { $as_echo "$as_me:$LINENO: checking for $ac_header" >&5
+! $as_echo_n "checking for $ac_header... " >&6; }
+! if { as_var=$as_ac_Header; eval "test \"\${$as_var+set}\" = set"; }; then
+! $as_echo_n "(cached) " >&6
+ else
+ eval "$as_ac_Header=\$ac_header_preproc"
+ fi
+! ac_res=`eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'`
+! { $as_echo "$as_me:$LINENO: result: $ac_res" >&5
+! $as_echo "$ac_res" >&6; }
+
+ fi
+! if test `eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'` = yes; then
+ cat >>confdefs.h <<_ACEOF
+! #define `$as_echo "HAVE_$ac_header" | $as_tr_cpp` 1
+ _ACEOF
+
+ fi
+***************
+*** 5426,5635 ****
+
+
+
+! ac_header_dirent=no
+! for ac_hdr in dirent.h sys/ndir.h sys/dir.h ndir.h; do
+! as_ac_Header=`echo "ac_cv_header_dirent_$ac_hdr" | $as_tr_sh`
+! echo "$as_me:$LINENO: checking for $ac_hdr that defines DIR" >&5
+! echo $ECHO_N "checking for $ac_hdr that defines DIR... $ECHO_C" >&6
+! if eval "test \"\${$as_ac_Header+set}\" = set"; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! #include <sys/types.h>
+! #include <$ac_hdr>
+!
+! int
+! main ()
+! {
+! if ((DIR *) 0)
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! eval "$as_ac_Header=yes"
+! else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! eval "$as_ac_Header=no"
+! fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+! fi
+! echo "$as_me:$LINENO: result: `eval echo '${'$as_ac_Header'}'`" >&5
+! echo "${ECHO_T}`eval echo '${'$as_ac_Header'}'`" >&6
+! if test `eval echo '${'$as_ac_Header'}'` = yes; then
+! cat >>confdefs.h <<_ACEOF
+! #define `echo "HAVE_$ac_hdr" | $as_tr_cpp` 1
+! _ACEOF
+!
+! ac_header_dirent=$ac_hdr; break
+! fi
+!
+! done
+! # Two versions of opendir et al. are in -ldir and -lx on SCO Xenix.
+! if test $ac_header_dirent = dirent.h; then
+! echo "$as_me:$LINENO: checking for library containing opendir" >&5
+! echo $ECHO_N "checking for library containing opendir... $ECHO_C" >&6
+! if test "${ac_cv_search_opendir+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+! else
+! ac_func_search_save_LIBS=$LIBS
+! ac_cv_search_opendir=no
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+!
+! /* Override any gcc2 internal prototype to avoid an error. */
+! #ifdef __cplusplus
+! extern "C"
+! #endif
+! /* We use char because int might match the return type of a gcc2
+! builtin and then its argument prototype would still apply. */
+! char opendir ();
+! int
+! main ()
+! {
+! opendir ();
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+! ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_search_opendir="none required"
+! else
+! echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! fi
+! rm -f conftest.err conftest.$ac_objext \
+! conftest$ac_exeext conftest.$ac_ext
+! if test "$ac_cv_search_opendir" = no; then
+! for ac_lib in dir; do
+! LIBS="-l$ac_lib $ac_func_search_save_LIBS"
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+
+- /* Override any gcc2 internal prototype to avoid an error. */
+- #ifdef __cplusplus
+- extern "C"
+- #endif
+- /* We use char because int might match the return type of a gcc2
+- builtin and then its argument prototype would still apply. */
+- char opendir ();
+ int
+ main ()
+ {
+! opendir ();
+ ;
+ return 0;
+ }
+ _ACEOF
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_search_opendir="-l$ac_lib"
+! break
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ fi
+! rm -f conftest.err conftest.$ac_objext \
+! conftest$ac_exeext conftest.$ac_ext
+! done
+! fi
+! LIBS=$ac_func_search_save_LIBS
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_search_opendir" >&5
+! echo "${ECHO_T}$ac_cv_search_opendir" >&6
+! if test "$ac_cv_search_opendir" != no; then
+! test "$ac_cv_search_opendir" = "none required" || LIBS="$ac_cv_search_opendir $LIBS"
+
+ fi
+
+! else
+! echo "$as_me:$LINENO: checking for library containing opendir" >&5
+! echo $ECHO_N "checking for library containing opendir... $ECHO_C" >&6
+ if test "${ac_cv_search_opendir+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ ac_func_search_save_LIBS=$LIBS
+- ac_cv_search_opendir=no
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+--- 6534,6615 ----
+
+
+
+! ac_header_dirent=no
+! for ac_hdr in dirent.h sys/ndir.h sys/dir.h ndir.h; do
+! as_ac_Header=`$as_echo "ac_cv_header_dirent_$ac_hdr" | $as_tr_sh`
+! { $as_echo "$as_me:$LINENO: checking for $ac_hdr that defines DIR" >&5
+! $as_echo_n "checking for $ac_hdr that defines DIR... " >&6; }
+! if { as_var=$as_ac_Header; eval "test \"\${$as_var+set}\" = set"; }; then
+! $as_echo_n "(cached) " >&6
+! else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
++ #include <sys/types.h>
++ #include <$ac_hdr>
+
+ int
+ main ()
+ {
+! if ((DIR *) 0)
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! eval "$as_ac_Header=yes"
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
++ eval "$as_ac_Header=no"
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! ac_res=`eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'`
+! { $as_echo "$as_me:$LINENO: result: $ac_res" >&5
+! $as_echo "$ac_res" >&6; }
+! if test `eval 'as_val=${'$as_ac_Header'}
+! $as_echo "$as_val"'` = yes; then
+! cat >>confdefs.h <<_ACEOF
+! #define `$as_echo "HAVE_$ac_hdr" | $as_tr_cpp` 1
+! _ACEOF
+
++ ac_header_dirent=$ac_hdr; break
+ fi
+
+! done
+! # Two versions of opendir et al. are in -ldir and -lx on SCO Xenix.
+! if test $ac_header_dirent = dirent.h; then
+! { $as_echo "$as_me:$LINENO: checking for library containing opendir" >&5
+! $as_echo_n "checking for library containing opendir... " >&6; }
+ if test "${ac_cv_search_opendir+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ ac_func_search_save_LIBS=$LIBS
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+***************
+*** 5637,5751 ****
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+
+! /* Override any gcc2 internal prototype to avoid an error. */
+ #ifdef __cplusplus
+ extern "C"
+ #endif
+- /* We use char because int might match the return type of a gcc2
+- builtin and then its argument prototype would still apply. */
+ char opendir ();
+ int
+ main ()
+ {
+! opendir ();
+ ;
+ return 0;
+ }
+ _ACEOF
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_search_opendir="none required"
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ fi
+! rm -f conftest.err conftest.$ac_objext \
+! conftest$ac_exeext conftest.$ac_ext
+! if test "$ac_cv_search_opendir" = no; then
+! for ac_lib in x; do
+! LIBS="-l$ac_lib $ac_func_search_save_LIBS"
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+
+! /* Override any gcc2 internal prototype to avoid an error. */
+ #ifdef __cplusplus
+ extern "C"
+ #endif
+- /* We use char because int might match the return type of a gcc2
+- builtin and then its argument prototype would still apply. */
+ char opendir ();
+ int
+ main ()
+ {
+! opendir ();
+ ;
+ return 0;
+ }
+ _ACEOF
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_search_opendir="-l$ac_lib"
+! break
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ fi
+! rm -f conftest.err conftest.$ac_objext \
+! conftest$ac_exeext conftest.$ac_ext
+! done
+ fi
+ LIBS=$ac_func_search_save_LIBS
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_search_opendir" >&5
+! echo "${ECHO_T}$ac_cv_search_opendir" >&6
+! if test "$ac_cv_search_opendir" != no; then
+! test "$ac_cv_search_opendir" = "none required" || LIBS="$ac_cv_search_opendir $LIBS"
+
+ fi
+
+--- 6617,6781 ----
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+
+! /* Override any GCC internal prototype to avoid an error.
+! Use char because int might match the return type of a GCC
+! builtin and then its argument prototype would still apply. */
+ #ifdef __cplusplus
+ extern "C"
+ #endif
+ char opendir ();
+ int
+ main ()
+ {
+! return opendir ();
+ ;
+ return 0;
+ }
+ _ACEOF
+! for ac_lib in '' dir; do
+! if test -z "$ac_lib"; then
+! ac_res="none required"
+! else
+! ac_res=-l$ac_lib
+! LIBS="-l$ac_lib $ac_func_search_save_LIBS"
+! fi
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest$ac_exeext && {
+! test "$cross_compiling" = yes ||
+! $as_test_x conftest$ac_exeext
+! }; then
+! ac_cv_search_opendir=$ac_res
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
++
+ fi
+!
+! rm -rf conftest.dSYM
+! rm -f core conftest.err conftest.$ac_objext conftest_ipa8_conftest.oo \
+! conftest$ac_exeext
+! if test "${ac_cv_search_opendir+set}" = set; then
+! break
+! fi
+! done
+! if test "${ac_cv_search_opendir+set}" = set; then
+! :
+! else
+! ac_cv_search_opendir=no
+! fi
+! rm conftest.$ac_ext
+! LIBS=$ac_func_search_save_LIBS
+! fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_search_opendir" >&5
+! $as_echo "$ac_cv_search_opendir" >&6; }
+! ac_res=$ac_cv_search_opendir
+! if test "$ac_res" != no; then
+! test "$ac_res" = "none required" || LIBS="$ac_res $LIBS"
+!
+! fi
+!
+! else
+! { $as_echo "$as_me:$LINENO: checking for library containing opendir" >&5
+! $as_echo_n "checking for library containing opendir... " >&6; }
+! if test "${ac_cv_search_opendir+set}" = set; then
+! $as_echo_n "(cached) " >&6
+! else
+! ac_func_search_save_LIBS=$LIBS
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+ cat >>conftest.$ac_ext <<_ACEOF
+ /* end confdefs.h. */
+
+! /* Override any GCC internal prototype to avoid an error.
+! Use char because int might match the return type of a GCC
+! builtin and then its argument prototype would still apply. */
+ #ifdef __cplusplus
+ extern "C"
+ #endif
+ char opendir ();
+ int
+ main ()
+ {
+! return opendir ();
+ ;
+ return 0;
+ }
+ _ACEOF
+! for ac_lib in '' x; do
+! if test -z "$ac_lib"; then
+! ac_res="none required"
+! else
+! ac_res=-l$ac_lib
+! LIBS="-l$ac_lib $ac_func_search_save_LIBS"
+! fi
+! rm -f conftest.$ac_objext conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest$ac_exeext && {
+! test "$cross_compiling" = yes ||
+! $as_test_x conftest$ac_exeext
+! }; then
+! ac_cv_search_opendir=$ac_res
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
++
+ fi
+!
+! rm -rf conftest.dSYM
+! rm -f core conftest.err conftest.$ac_objext conftest_ipa8_conftest.oo \
+! conftest$ac_exeext
+! if test "${ac_cv_search_opendir+set}" = set; then
+! break
+ fi
++ done
++ if test "${ac_cv_search_opendir+set}" = set; then
++ :
++ else
++ ac_cv_search_opendir=no
++ fi
++ rm conftest.$ac_ext
+ LIBS=$ac_func_search_save_LIBS
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_search_opendir" >&5
+! $as_echo "$ac_cv_search_opendir" >&6; }
+! ac_res=$ac_cv_search_opendir
+! if test "$ac_res" != no; then
+! test "$ac_res" = "none required" || LIBS="$ac_res $LIBS"
+
+ fi
+
+***************
+*** 5753,5762 ****
+
+
+ sim_termio=""
+! echo "$as_me:$LINENO: checking for struct termios" >&5
+! echo $ECHO_N "checking for struct termios... $ECHO_C" >&6
+ if test "${ac_cv_termios_struct+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6783,6792 ----
+
+
+ sim_termio=""
+! { $as_echo "$as_me:$LINENO: checking for struct termios" >&5
+! $as_echo_n "checking for struct termios... " >&6; }
+ if test "${ac_cv_termios_struct+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5780,5827 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_termios_struct=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termios_struct=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! echo "$as_me:$LINENO: result: $ac_cv_termios_struct" >&5
+! echo "${ECHO_T}$ac_cv_termios_struct" >&6
+ if test $ac_cv_termios_struct = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIOS_STRUCTURE"
+ fi
+
+ if test "$ac_cv_termios_struct" = "yes"; then
+! echo "$as_me:$LINENO: checking for c_line field in struct termios" >&5
+! echo $ECHO_N "checking for c_line field in struct termios... $ECHO_C" >&6
+ if test "${ac_cv_termios_cline+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6810,6854 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_termios_struct=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termios_struct=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_termios_struct" >&5
+! $as_echo "$ac_cv_termios_struct" >&6; }
+ if test $ac_cv_termios_struct = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIOS_STRUCTURE"
+ fi
+
+ if test "$ac_cv_termios_struct" = "yes"; then
+! { $as_echo "$as_me:$LINENO: checking for c_line field in struct termios" >&5
+! $as_echo_n "checking for c_line field in struct termios... " >&6; }
+ if test "${ac_cv_termios_cline+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5840,5879 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_termios_cline=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termios_cline=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+
+! echo "$as_me:$LINENO: result: $ac_cv_termios_cline" >&5
+! echo "${ECHO_T}$ac_cv_termios_cline" >&6
+ if test $ac_cv_termios_cline = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIOS_CLINE"
+ fi
+--- 6867,6903 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_termios_cline=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termios_cline=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_termios_cline" >&5
+! $as_echo "$ac_cv_termios_cline" >&6; }
+ if test $ac_cv_termios_cline = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIOS_CLINE"
+ fi
+***************
+*** 5882,5891 ****
+ fi
+
+ if test "$ac_cv_termios_struct" != "yes"; then
+! echo "$as_me:$LINENO: checking for struct termio" >&5
+! echo $ECHO_N "checking for struct termio... $ECHO_C" >&6
+ if test "${ac_cv_termio_struct+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6906,6915 ----
+ fi
+
+ if test "$ac_cv_termios_struct" != "yes"; then
+! { $as_echo "$as_me:$LINENO: checking for struct termio" >&5
+! $as_echo_n "checking for struct termio... " >&6; }
+ if test "${ac_cv_termio_struct+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5909,5947 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_termio_struct=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termio_struct=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! echo "$as_me:$LINENO: result: $ac_cv_termio_struct" >&5
+! echo "${ECHO_T}$ac_cv_termio_struct" >&6
+ if test $ac_cv_termio_struct = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIO_STRUCTURE"
+ fi
+--- 6933,6968 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_termio_struct=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termio_struct=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_termio_struct" >&5
+! $as_echo "$ac_cv_termio_struct" >&6; }
+ if test $ac_cv_termio_struct = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIO_STRUCTURE"
+ fi
+***************
+*** 5950,5959 ****
+ fi
+
+ if test "$ac_cv_termio_struct" = "yes"; then
+! echo "$as_me:$LINENO: checking for c_line field in struct termio" >&5
+! echo $ECHO_N "checking for c_line field in struct termio... $ECHO_C" >&6
+ if test "${ac_cv_termio_cline+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 6971,6980 ----
+ fi
+
+ if test "$ac_cv_termio_struct" = "yes"; then
+! { $as_echo "$as_me:$LINENO: checking for c_line field in struct termio" >&5
+! $as_echo_n "checking for c_line field in struct termio... " >&6; }
+ if test "${ac_cv_termio_cline+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 5972,6011 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_termio_cline=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termio_cline=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+
+! echo "$as_me:$LINENO: result: $ac_cv_termio_cline" >&5
+! echo "${ECHO_T}$ac_cv_termio_cline" >&6
+ if test $ac_cv_termio_cline = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIO_CLINE"
+ fi
+--- 6993,7029 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_termio_cline=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_termio_cline=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_termio_cline" >&5
+! $as_echo "$ac_cv_termio_cline" >&6; }
+ if test $ac_cv_termio_cline = yes; then
+ sim_termio="$sim_termio -DHAVE_TERMIO_CLINE"
+ fi
+***************
+*** 6013,6022 ****
+ ac_cv_termio_cline=no
+ fi
+
+! echo "$as_me:$LINENO: checking for struct statfs" >&5
+! echo $ECHO_N "checking for struct statfs... $ECHO_C" >&6
+ if test "${ac_cv_struct_statfs+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+--- 7031,7040 ----
+ ac_cv_termio_cline=no
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for struct statfs" >&5
+! $as_echo_n "checking for struct statfs... " >&6; }
+ if test "${ac_cv_struct_statfs+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+***************
+*** 6046,6084 ****
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+ ac_cv_struct_statfs=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_struct_statfs=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! echo "$as_me:$LINENO: result: $ac_cv_struct_statfs" >&5
+! echo "${ECHO_T}$ac_cv_struct_statfs" >&6
+ if test $ac_cv_struct_statfs = yes; then
+
+ cat >>confdefs.h <<\_ACEOF
+--- 7064,7099 ----
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+ ac_cv_struct_statfs=yes
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_struct_statfs=no
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_struct_statfs" >&5
+! $as_echo "$ac_cv_struct_statfs" >&6; }
+ if test $ac_cv_struct_statfs = yes; then
+
+ cat >>confdefs.h <<\_ACEOF
+***************
+*** 6087,6098 ****
+
+ fi
+
+! echo "$as_me:$LINENO: checking for long long" >&5
+! echo $ECHO_N "checking for long long... $ECHO_C" >&6
+ if test "${ac_cv_type_long_long+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+--- 7102,7114 ----
+
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for long long" >&5
+! $as_echo_n "checking for long long... " >&6; }
+ if test "${ac_cv_type_long_long+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+! ac_cv_type_long_long=no
+! cat >conftest.$ac_ext <<_ACEOF
+ /* confdefs.h. */
+ _ACEOF
+ cat confdefs.h >>conftest.$ac_ext
+***************
+*** 6102,6148 ****
+ int
+ main ()
+ {
+- if ((long long *) 0)
+- return 0;
+ if (sizeof (long long))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (eval echo "$as_me:$LINENO: \"$ac_compile\"") >&5
+! (eval $ac_compile) 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } &&
+! { ac_try='test -z "$ac_c_werror_flag"
+! || test ! -s conftest.err'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+! ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; } &&
+! { ac_try='test -s conftest.$ac_objext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); }; }; then
+! ac_cv_type_long_long=yes
+ else
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+! ac_cv_type_long_long=no
+ fi
+! rm -f conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! echo "$as_me:$LINENO: result: $ac_cv_type_long_long" >&5
+! echo "${ECHO_T}$ac_cv_type_long_long" >&6
+ if test $ac_cv_type_long_long = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+--- 7118,7201 ----
+ int
+ main ()
+ {
+ if (sizeof (long long))
+! return 0;
+ ;
+ return 0;
+ }
+ _ACEOF
+ rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+ grep -v '^ *+' conftest.er1 >conftest.err
+ rm -f conftest.er1
+ cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! cat >conftest.$ac_ext <<_ACEOF
+! /* confdefs.h. */
+! _ACEOF
+! cat confdefs.h >>conftest.$ac_ext
+! cat >>conftest.$ac_ext <<_ACEOF
+! /* end confdefs.h. */
+! $ac_includes_default
+! int
+! main ()
+! {
+! if (sizeof ((long long)))
+! return 0;
+! ;
+! return 0;
+! }
+! _ACEOF
+! rm -f conftest.$ac_objext
+! if { (ac_try="$ac_compile"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_compile") 2>conftest.er1
+ ac_status=$?
+! grep -v '^ *+' conftest.er1 >conftest.err
+! rm -f conftest.er1
+! cat conftest.err >&5
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+! (exit $ac_status); } && {
+! test -z "$ac_c_werror_flag" ||
+! test ! -s conftest.err
+! } && test -s conftest.$ac_objext; then
+! :
+! else
+! $as_echo "$as_me: failed program was:" >&5
+! sed 's/^/| /' conftest.$ac_ext >&5
+!
+! ac_cv_type_long_long=yes
+! fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ else
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+!
+ fi
+!
+! rm -f core conftest.err conftest.$ac_objext conftest.$ac_ext
+ fi
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_type_long_long" >&5
+! $as_echo "$ac_cv_type_long_long" >&6; }
+ if test $ac_cv_type_long_long = yes; then
+
+ cat >>confdefs.h <<_ACEOF
+***************
+*** 6154,6163 ****
+
+
+ sim_devzero=""
+! echo "$as_me:$LINENO: checking for /dev/zero" >&5
+! echo $ECHO_N "checking for /dev/zero... $ECHO_C" >&6
+ if test "${ac_cv_devzero+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test "$cross_compiling" = yes; then
+ ac_cv_devzero=no
+--- 7207,7216 ----
+
+
+ sim_devzero=""
+! { $as_echo "$as_me:$LINENO: checking for /dev/zero" >&5
+! $as_echo_n "checking for /dev/zero... " >&6; }
+ if test "${ac_cv_devzero+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test "$cross_compiling" = yes; then
+ ac_cv_devzero=no
+***************
+*** 6186,6250 ****
+ }
+ _ACEOF
+ rm -f conftest$ac_exeext
+! if { (eval echo "$as_me:$LINENO: \"$ac_link\"") >&5
+! (eval $ac_link) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (eval echo "$as_me:$LINENO: \"$ac_try\"") >&5
+! (eval $ac_try) 2>&5
+ ac_status=$?
+! echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ ac_cv_devzero=yes
+ else
+! echo "$as_me: program exited with status $ac_status" >&5
+! echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ( exit $ac_status )
+ ac_cv_devzero=no
+ fi
+! rm -f core *.core gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
+ fi
+
+! echo "$as_me:$LINENO: result: $ac_cv_devzero" >&5
+! echo "${ECHO_T}$ac_cv_devzero" >&6
+ if test $ac_cv_devzero = yes; then
+ sim_devzero="-DHAVE_DEVZERO"
+ else
+ sim_devzero=""
+ fi
+
+! echo "$as_me:$LINENO: checking for common simulator directory" >&5
+! echo $ECHO_N "checking for common simulator directory... $ECHO_C" >&6
+ if test -f "${srcdir}/../common/callback.c"; then
+! echo "$as_me:$LINENO: result: yes" >&5
+! echo "${ECHO_T}yes" >&6
+ sim_callback="callback.o targ-map.o"
+ sim_targ_vals="targ-vals.h targ-map.c targ-vals.def"
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ sim_callback=""
+ sim_targ_vals=""
+ fi
+
+! echo "$as_me:$LINENO: checking for common simulator directory fpu implementation" >&5
+! echo $ECHO_N "checking for common simulator directory fpu implementation... $ECHO_C" >&6
+ if test -f "${srcdir}/../common/sim-fpu.c"; then
+! echo "$as_me:$LINENO: result: yes" >&5
+! echo "${ECHO_T}yes" >&6
+ sim_fpu_cflags="-DHAVE_COMMON_FPU -I../common -I${srcdir}/../common"
+ sim_fpu="sim-fpu.o"
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ sim_fpu_cflags=
+ sim_fpu=
+ fi
+
+
+
+
+--- 7239,7346 ----
+ }
+ _ACEOF
+ rm -f conftest$ac_exeext
+! if { (ac_try="$ac_link"
+! case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_link") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); } && { ac_try='./conftest$ac_exeext'
+! { (case "(($ac_try" in
+! *\"* | *\`* | *\\*) ac_try_echo=\$ac_try;;
+! *) ac_try_echo=$ac_try;;
+! esac
+! eval ac_try_echo="\"\$as_me:$LINENO: $ac_try_echo\""
+! $as_echo "$ac_try_echo") >&5
+! (eval "$ac_try") 2>&5
+ ac_status=$?
+! $as_echo "$as_me:$LINENO: \$? = $ac_status" >&5
+ (exit $ac_status); }; }; then
+ ac_cv_devzero=yes
+ else
+! $as_echo "$as_me: program exited with status $ac_status" >&5
+! $as_echo "$as_me: failed program was:" >&5
+ sed 's/^/| /' conftest.$ac_ext >&5
+
+ ( exit $ac_status )
+ ac_cv_devzero=no
+ fi
+! rm -rf conftest.dSYM
+! rm -f core *.core core.conftest.* gmon.out bb.out conftest$ac_exeext conftest.$ac_objext conftest.$ac_ext
+ fi
++
++
+ fi
+
+! { $as_echo "$as_me:$LINENO: result: $ac_cv_devzero" >&5
+! $as_echo "$ac_cv_devzero" >&6; }
+ if test $ac_cv_devzero = yes; then
+ sim_devzero="-DHAVE_DEVZERO"
+ else
+ sim_devzero=""
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for common simulator directory" >&5
+! $as_echo_n "checking for common simulator directory... " >&6; }
+ if test -f "${srcdir}/../common/callback.c"; then
+! { $as_echo "$as_me:$LINENO: result: yes" >&5
+! $as_echo "yes" >&6; }
+ sim_callback="callback.o targ-map.o"
+ sim_targ_vals="targ-vals.h targ-map.c targ-vals.def"
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ sim_callback=""
+ sim_targ_vals=""
+ fi
+
+! { $as_echo "$as_me:$LINENO: checking for common simulator directory fpu implementation" >&5
+! $as_echo_n "checking for common simulator directory fpu implementation... " >&6; }
+ if test -f "${srcdir}/../common/sim-fpu.c"; then
+! { $as_echo "$as_me:$LINENO: result: yes" >&5
+! $as_echo "yes" >&6; }
+ sim_fpu_cflags="-DHAVE_COMMON_FPU -I../common -I${srcdir}/../common"
+ sim_fpu="sim-fpu.o"
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ sim_fpu_cflags=
+ sim_fpu=
+ fi
+
++ case ${host_os} in
++ *linux*)
++ sim_async_io_src=async_io.c
++ sim_async_io_obj=async_io.o
++ ;;
++ *)
++ { $as_echo "$as_me:$LINENO: Removing 'ethtap' device on non-linux host" >&5
++ $as_echo "$as_me: Removing 'ethtap' device on non-linux host" >&6;}
++ sim_hw_src=`echo $sim_hw_src | sed -e 's/hw_ethtap.c//g'`
++ sim_hw_obj=`echo $sim_hw_obj | sed -e 's/hw_ethtap.o//g'`
++ if test x"$silent" != x"yes"; then
++ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
++ fi
++ sim_async_io_src=
++ sim_async_io_obj=
++ ;;
++ esac
++ case ${sim_hw_src} in
++ *hw_ethtap*)
++
++ cat >>confdefs.h <<\_ACEOF
++ #define HAVE_ETHTAP 1
++ _ACEOF
++
++ ;;
++ *)
++ ;;
++ esac
++
+
+
+
+***************
+*** 6256,6265 ****
+ if test -n "$ac_tool_prefix"; then
+ # Extract the first word of "${ac_tool_prefix}ranlib", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}ranlib; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_RANLIB+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$RANLIB"; then
+ ac_cv_prog_RANLIB="$RANLIB" # Let the user override the test.
+--- 7352,7361 ----
+ if test -n "$ac_tool_prefix"; then
+ # Extract the first word of "${ac_tool_prefix}ranlib", so it can be a program name with args.
+ set dummy ${ac_tool_prefix}ranlib; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_RANLIB+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$RANLIB"; then
+ ac_cv_prog_RANLIB="$RANLIB" # Let the user override the test.
+***************
+*** 6270,6303 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_RANLIB="${ac_tool_prefix}ranlib"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+ fi
+ fi
+ RANLIB=$ac_cv_prog_RANLIB
+ if test -n "$RANLIB"; then
+! echo "$as_me:$LINENO: result: $RANLIB" >&5
+! echo "${ECHO_T}$RANLIB" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+ fi
+ if test -z "$ac_cv_prog_RANLIB"; then
+ ac_ct_RANLIB=$RANLIB
+ # Extract the first word of "ranlib", so it can be a program name with args.
+ set dummy ranlib; ac_word=$2
+! echo "$as_me:$LINENO: checking for $ac_word" >&5
+! echo $ECHO_N "checking for $ac_word... $ECHO_C" >&6
+ if test "${ac_cv_prog_ac_ct_RANLIB+set}" = set; then
+! echo $ECHO_N "(cached) $ECHO_C" >&6
+ else
+ if test -n "$ac_ct_RANLIB"; then
+ ac_cv_prog_ac_ct_RANLIB="$ac_ct_RANLIB" # Let the user override the test.
+--- 7366,7401 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_RANLIB="${ac_tool_prefix}ranlib"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ RANLIB=$ac_cv_prog_RANLIB
+ if test -n "$RANLIB"; then
+! { $as_echo "$as_me:$LINENO: result: $RANLIB" >&5
+! $as_echo "$RANLIB" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
++
+ fi
+ if test -z "$ac_cv_prog_RANLIB"; then
+ ac_ct_RANLIB=$RANLIB
+ # Extract the first word of "ranlib", so it can be a program name with args.
+ set dummy ranlib; ac_word=$2
+! { $as_echo "$as_me:$LINENO: checking for $ac_word" >&5
+! $as_echo_n "checking for $ac_word... " >&6; }
+ if test "${ac_cv_prog_ac_ct_RANLIB+set}" = set; then
+! $as_echo_n "(cached) " >&6
+ else
+ if test -n "$ac_ct_RANLIB"; then
+ ac_cv_prog_ac_ct_RANLIB="$ac_ct_RANLIB" # Let the user override the test.
+***************
+*** 6308,6334 ****
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if $as_executable_p "$as_dir/$ac_word$ac_exec_ext"; then
+ ac_cv_prog_ac_ct_RANLIB="ranlib"
+! echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
+
+- test -z "$ac_cv_prog_ac_ct_RANLIB" && ac_cv_prog_ac_ct_RANLIB=":"
+ fi
+ fi
+ ac_ct_RANLIB=$ac_cv_prog_ac_ct_RANLIB
+ if test -n "$ac_ct_RANLIB"; then
+! echo "$as_me:$LINENO: result: $ac_ct_RANLIB" >&5
+! echo "${ECHO_T}$ac_ct_RANLIB" >&6
+ else
+! echo "$as_me:$LINENO: result: no" >&5
+! echo "${ECHO_T}no" >&6
+ fi
+
+! RANLIB=$ac_ct_RANLIB
+ else
+ RANLIB="$ac_cv_prog_RANLIB"
+ fi
+--- 7406,7446 ----
+ IFS=$as_save_IFS
+ test -z "$as_dir" && as_dir=.
+ for ac_exec_ext in '' $ac_executable_extensions; do
+! if { test -f "$as_dir/$ac_word$ac_exec_ext" && $as_test_x "$as_dir/$ac_word$ac_exec_ext"; }; then
+ ac_cv_prog_ac_ct_RANLIB="ranlib"
+! $as_echo "$as_me:$LINENO: found $as_dir/$ac_word$ac_exec_ext" >&5
+ break 2
+ fi
+ done
+ done
++ IFS=$as_save_IFS
+
+ fi
+ fi
+ ac_ct_RANLIB=$ac_cv_prog_ac_ct_RANLIB
+ if test -n "$ac_ct_RANLIB"; then
+! { $as_echo "$as_me:$LINENO: result: $ac_ct_RANLIB" >&5
+! $as_echo "$ac_ct_RANLIB" >&6; }
+ else
+! { $as_echo "$as_me:$LINENO: result: no" >&5
+! $as_echo "no" >&6; }
+ fi
+
+! if test "x$ac_ct_RANLIB" = x; then
+! RANLIB=":"
+! else
+! case $cross_compiling:$ac_tool_warned in
+! yes:)
+! { $as_echo "$as_me:$LINENO: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&5
+! $as_echo "$as_me: WARNING: In the future, Autoconf will not detect cross-tools
+! whose name does not start with the host triplet. If you think this
+! configuration is useful to you, please write to autoconf@gnu.org." >&2;}
+! ac_tool_warned=yes ;;
+! esac
+! RANLIB=$ac_ct_RANLIB
+! fi
+ else
+ RANLIB="$ac_cv_prog_RANLIB"
+ fi
+***************
+*** 6378,6385 ****
+
+
+
+! ac_config_files="$ac_config_files Makefile"
+! ac_config_commands="$ac_config_commands default"
+ cat >confcache <<\_ACEOF
+ # This file is a shell script that caches the results of configure
+ # tests run on this system so they can be shared between configure
+--- 7490,7501 ----
+
+
+
+!
+!
+! ac_config_files="$ac_config_files Makefile"
+!
+! ac_config_commands="$ac_config_commands default"
+!
+ cat >confcache <<\_ACEOF
+ # This file is a shell script that caches the results of configure
+ # tests run on this system so they can be shared between configure
+***************
+*** 6398,6436 ****
+
+ # The following way of writing the cache mishandles newlines in values,
+ # but we know of no workaround that is simple, portable, and efficient.
+! # So, don't put newlines in cache variables' values.
+ # Ultrix sh set writes to stderr and can't be redirected directly,
+ # and sets the high bit in the cache file unless we assign to the vars.
+! {
+ (set) 2>&1 |
+! case `(ac_space=' '; set | grep ac_space) 2>&1` in
+! *ac_space=\ *)
+ # `set' does not quote correctly, so add quotes (double-quote
+ # substitution turns \\\\ into \\, and sed turns \\ into \).
+ sed -n \
+ "s/'/'\\\\''/g;
+ s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='\\2'/p"
+! ;;
+ *)
+ # `set' quotes correctly as required by POSIX, so do not add quotes.
+! sed -n \
+! "s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1=\\2/p"
+ ;;
+! esac;
+! } |
+ sed '
+ t clear
+! : clear
+ s/^\([^=]*\)=\(.*[{}].*\)$/test "${\1+set}" = set || &/
+ t end
+! /^ac_cv_env/!s/^\([^=]*\)=\(.*\)$/\1=${\1=\2}/
+! : end' >>confcache
+! if diff $cache_file confcache >/dev/null 2>&1; then :; else
+! if test -w $cache_file; then
+! test "x$cache_file" != "x/dev/null" && echo "updating cache $cache_file"
+ cat confcache >$cache_file
+ else
+! echo "not updating unwritable cache $cache_file"
+ fi
+ fi
+ rm -f confcache
+--- 7514,7572 ----
+
+ # The following way of writing the cache mishandles newlines in values,
+ # but we know of no workaround that is simple, portable, and efficient.
+! # So, we kill variables containing newlines.
+ # Ultrix sh set writes to stderr and can't be redirected directly,
+ # and sets the high bit in the cache file unless we assign to the vars.
+! (
+! for ac_var in `(set) 2>&1 | sed -n 's/^\([a-zA-Z_][a-zA-Z0-9_]*\)=.*/\1/p'`; do
+! eval ac_val=\$$ac_var
+! case $ac_val in #(
+! *${as_nl}*)
+! case $ac_var in #(
+! *_cv_*) { $as_echo "$as_me:$LINENO: WARNING: Cache variable $ac_var contains a newline." >&5
+! $as_echo "$as_me: WARNING: Cache variable $ac_var contains a newline." >&2;} ;;
+! esac
+! case $ac_var in #(
+! _ | IFS | as_nl) ;; #(
+! BASH_ARGV | BASH_SOURCE) eval $ac_var= ;; #(
+! *) $as_unset $ac_var ;;
+! esac ;;
+! esac
+! done
+!
+ (set) 2>&1 |
+! case $as_nl`(ac_space=' '; set) 2>&1` in #(
+! *${as_nl}ac_space=\ *)
+ # `set' does not quote correctly, so add quotes (double-quote
+ # substitution turns \\\\ into \\, and sed turns \\ into \).
+ sed -n \
+ "s/'/'\\\\''/g;
+ s/^\\([_$as_cr_alnum]*_cv_[_$as_cr_alnum]*\\)=\\(.*\\)/\\1='\\2'/p"
+! ;; #(
+ *)
+ # `set' quotes correctly as required by POSIX, so do not add quotes.
+! sed -n "/^[_$as_cr_alnum]*_cv_[_$as_cr_alnum]*=/p"
+ ;;
+! esac |
+! sort
+! ) |
+ sed '
++ /^ac_cv_env_/b end
+ t clear
+! :clear
+ s/^\([^=]*\)=\(.*[{}].*\)$/test "${\1+set}" = set || &/
+ t end
+! s/^\([^=]*\)=\(.*\)$/\1=${\1=\2}/
+! :end' >>confcache
+! if diff "$cache_file" confcache >/dev/null 2>&1; then :; else
+! if test -w "$cache_file"; then
+! test "x$cache_file" != "x/dev/null" &&
+! { $as_echo "$as_me:$LINENO: updating cache $cache_file" >&5
+! $as_echo "$as_me: updating cache $cache_file" >&6;}
+ cat confcache >$cache_file
+ else
+! { $as_echo "$as_me:$LINENO: not updating unwritable cache $cache_file" >&5
+! $as_echo "$as_me: not updating unwritable cache $cache_file" >&6;}
+ fi
+ fi
+ rm -f confcache
+***************
+*** 6439,6470 ****
+ # Let make expand exec_prefix.
+ test "x$exec_prefix" = xNONE && exec_prefix='${prefix}'
+
+- # VPATH may cause trouble with some makes, so we remove $(srcdir),
+- # ${srcdir} and @srcdir@ from VPATH if srcdir is ".", strip leading and
+- # trailing colons and then remove the whole line if VPATH becomes empty
+- # (actually we leave an empty line to preserve line numbers).
+- if test "x$srcdir" = x.; then
+- ac_vpsub='/^[ ]*VPATH[ ]*=/{
+- s/:*\$(srcdir):*/:/;
+- s/:*\${srcdir}:*/:/;
+- s/:*@srcdir@:*/:/;
+- s/^\([^=]*=[ ]*\):*/\1/;
+- s/:*$//;
+- s/^[^=]*=[ ]*$//;
+- }'
+- fi
+-
+ DEFS=-DHAVE_CONFIG_H
+
+ ac_libobjs=
+ ac_ltlibobjs=
+ for ac_i in : $LIBOBJS; do test "x$ac_i" = x: && continue
+ # 1. Remove the extension, and $U if already installed.
+! ac_i=`echo "$ac_i" |
+! sed 's/\$U\././;s/\.o$//;s/\.obj$//'`
+! # 2. Add them.
+! ac_libobjs="$ac_libobjs $ac_i\$U.$ac_objext"
+! ac_ltlibobjs="$ac_ltlibobjs $ac_i"'$U.lo'
+ done
+ LIBOBJS=$ac_libobjs
+
+--- 7575,7592 ----
+ # Let make expand exec_prefix.
+ test "x$exec_prefix" = xNONE && exec_prefix='${prefix}'
+
+ DEFS=-DHAVE_CONFIG_H
+
+ ac_libobjs=
+ ac_ltlibobjs=
+ for ac_i in : $LIBOBJS; do test "x$ac_i" = x: && continue
+ # 1. Remove the extension, and $U if already installed.
+! ac_script='s/\$U\././;s/\.o$//;s/\.obj$//'
+! ac_i=`$as_echo "$ac_i" | sed "$ac_script"`
+! # 2. Prepend LIBOBJDIR. When used with automake>=1.10 LIBOBJDIR
+! # will be set to the directory where LIBOBJS objects are built.
+! ac_libobjs="$ac_libobjs \${LIBOBJDIR}$ac_i\$U.$ac_objext"
+! ac_ltlibobjs="$ac_ltlibobjs \${LIBOBJDIR}$ac_i"'$U.lo'
+ done
+ LIBOBJS=$ac_libobjs
+
+***************
+*** 6473,6483 ****
+
+
+ : ${CONFIG_STATUS=./config.status}
+ ac_clean_files_save=$ac_clean_files
+ ac_clean_files="$ac_clean_files $CONFIG_STATUS"
+! { echo "$as_me:$LINENO: creating $CONFIG_STATUS" >&5
+! echo "$as_me: creating $CONFIG_STATUS" >&6;}
+! cat >$CONFIG_STATUS <<_ACEOF
+ #! $SHELL
+ # Generated by $as_me.
+ # Run this file to recreate the current configuration.
+--- 7595,7606 ----
+
+
+ : ${CONFIG_STATUS=./config.status}
++ ac_write_fail=0
+ ac_clean_files_save=$ac_clean_files
+ ac_clean_files="$ac_clean_files $CONFIG_STATUS"
+! { $as_echo "$as_me:$LINENO: creating $CONFIG_STATUS" >&5
+! $as_echo "$as_me: creating $CONFIG_STATUS" >&6;}
+! cat >$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+ #! $SHELL
+ # Generated by $as_me.
+ # Run this file to recreate the current configuration.
+***************
+*** 6490,6511 ****
+ SHELL=\${CONFIG_SHELL-$SHELL}
+ _ACEOF
+
+! cat >>$CONFIG_STATUS <<\_ACEOF
+ ## --------------------- ##
+ ## M4sh Initialization. ##
+ ## --------------------- ##
+
+! # Be Bourne compatible
+ if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+ emulate sh
+ NULLCMD=:
+! # Zsh 3.x and 4.x performs word splitting on ${1+"$@"}, which
+ # is contrary to our usage. Disable this feature.
+ alias -g '${1+"$@"}'='"$@"'
+! elif test -n "${BASH_VERSION+set}" && (set -o posix) >/dev/null 2>&1; then
+! set -o posix
+ fi
+- DUALCASE=1; export DUALCASE # for MKS sh
+
+ # Support unset when possible.
+ if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then
+--- 7613,7690 ----
+ SHELL=\${CONFIG_SHELL-$SHELL}
+ _ACEOF
+
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+ ## --------------------- ##
+ ## M4sh Initialization. ##
+ ## --------------------- ##
+
+! # Be more Bourne compatible
+! DUALCASE=1; export DUALCASE # for MKS sh
+ if test -n "${ZSH_VERSION+set}" && (emulate sh) >/dev/null 2>&1; then
+ emulate sh
+ NULLCMD=:
+! # Pre-4.2 versions of Zsh do word splitting on ${1+"$@"}, which
+ # is contrary to our usage. Disable this feature.
+ alias -g '${1+"$@"}'='"$@"'
+! setopt NO_GLOB_SUBST
+! else
+! case `(set -o) 2>/dev/null` in
+! *posix*) set -o posix ;;
+! esac
+!
+! fi
+!
+!
+!
+!
+! # PATH needs CR
+! # Avoid depending upon Character Ranges.
+! as_cr_letters='abcdefghijklmnopqrstuvwxyz'
+! as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ'
+! as_cr_Letters=$as_cr_letters$as_cr_LETTERS
+! as_cr_digits='0123456789'
+! as_cr_alnum=$as_cr_Letters$as_cr_digits
+!
+! as_nl='
+! '
+! export as_nl
+! # Printing a long string crashes Solaris 7 /usr/bin/printf.
+! as_echo='\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\\'
+! as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo
+! as_echo=$as_echo$as_echo$as_echo$as_echo$as_echo$as_echo
+! if (test "X`printf %s $as_echo`" = "X$as_echo") 2>/dev/null; then
+! as_echo='printf %s\n'
+! as_echo_n='printf %s'
+! else
+! if test "X`(/usr/ucb/echo -n -n $as_echo) 2>/dev/null`" = "X-n $as_echo"; then
+! as_echo_body='eval /usr/ucb/echo -n "$1$as_nl"'
+! as_echo_n='/usr/ucb/echo -n'
+! else
+! as_echo_body='eval expr "X$1" : "X\\(.*\\)"'
+! as_echo_n_body='eval
+! arg=$1;
+! case $arg in
+! *"$as_nl"*)
+! expr "X$arg" : "X\\(.*\\)$as_nl";
+! arg=`expr "X$arg" : ".*$as_nl\\(.*\\)"`;;
+! esac;
+! expr "X$arg" : "X\\(.*\\)" | tr -d "$as_nl"
+! '
+! export as_echo_n_body
+! as_echo_n='sh -c $as_echo_n_body as_echo'
+! fi
+! export as_echo_body
+! as_echo='sh -c $as_echo_body as_echo'
+! fi
+!
+! # The user is always right.
+! if test "${PATH_SEPARATOR+set}" != set; then
+! PATH_SEPARATOR=:
+! (PATH='/bin;/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 && {
+! (PATH='/bin:/bin'; FPATH=$PATH; sh -c :) >/dev/null 2>&1 ||
+! PATH_SEPARATOR=';'
+! }
+ fi
+
+ # Support unset when possible.
+ if ( (MAIL=60; unset MAIL) || exit) >/dev/null 2>&1; then
+***************
+*** 6515,6547 ****
+ fi
+
+
+ # Work around bugs in pre-3.0 UWIN ksh.
+! $as_unset ENV MAIL MAILPATH
+ PS1='$ '
+ PS2='> '
+ PS4='+ '
+
+ # NLS nuisances.
+! for as_var in \
+! LANG LANGUAGE LC_ADDRESS LC_ALL LC_COLLATE LC_CTYPE LC_IDENTIFICATION \
+! LC_MEASUREMENT LC_MESSAGES LC_MONETARY LC_NAME LC_NUMERIC LC_PAPER \
+! LC_TELEPHONE LC_TIME
+! do
+! if (set +x; test -z "`(eval $as_var=C; export $as_var) 2>&1`"); then
+! eval $as_var=C; export $as_var
+! else
+! $as_unset $as_var
+! fi
+! done
+
+ # Required to use basename.
+! if expr a : '\(a\)' >/dev/null 2>&1; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+! if (basename /) >/dev/null 2>&1 && test "X`basename / 2>&1`" = "X/"; then
+ as_basename=basename
+ else
+ as_basename=false
+--- 7694,7753 ----
+ fi
+
+
++ # IFS
++ # We need space, tab and new line, in precisely that order. Quoting is
++ # there to prevent editors from complaining about space-tab.
++ # (If _AS_PATH_WALK were called with IFS unset, it would disable word
++ # splitting by setting IFS to empty value.)
++ IFS=" "" $as_nl"
++
++ # Find who we are. Look in the path if we contain no directory separator.
++ case $0 in
++ *[\\/]* ) as_myself=$0 ;;
++ *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
++ for as_dir in $PATH
++ do
++ IFS=$as_save_IFS
++ test -z "$as_dir" && as_dir=.
++ test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break
++ done
++ IFS=$as_save_IFS
++
++ ;;
++ esac
++ # We did not find ourselves, most probably we were run as `sh COMMAND'
++ # in which case we are not to be found in the path.
++ if test "x$as_myself" = x; then
++ as_myself=$0
++ fi
++ if test ! -f "$as_myself"; then
++ $as_echo "$as_myself: error: cannot find myself; rerun with an absolute file name" >&2
++ { (exit 1); exit 1; }
++ fi
++
+ # Work around bugs in pre-3.0 UWIN ksh.
+! for as_var in ENV MAIL MAILPATH
+! do ($as_unset $as_var) >/dev/null 2>&1 && $as_unset $as_var
+! done
+ PS1='$ '
+ PS2='> '
+ PS4='+ '
+
+ # NLS nuisances.
+! LC_ALL=C
+! export LC_ALL
+! LANGUAGE=C
+! export LANGUAGE
+
+ # Required to use basename.
+! if expr a : '\(a\)' >/dev/null 2>&1 &&
+! test "X`expr 00001 : '.*\(...\)'`" = X001; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+! if (basename -- /) >/dev/null 2>&1 && test "X`basename -- / 2>&1`" = "X/"; then
+ as_basename=basename
+ else
+ as_basename=false
+***************
+*** 6549,6707 ****
+
+
+ # Name of the executable.
+! as_me=`$as_basename "$0" ||
+ $as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \
+ X"$0" : 'X\(//\)$' \| \
+! X"$0" : 'X\(/\)$' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X/"$0" |
+! sed '/^.*\/\([^/][^/]*\)\/*$/{ s//\1/; q; }
+! /^X\/\(\/\/\)$/{ s//\1/; q; }
+! /^X\/\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+!
+!
+! # PATH needs CR, and LINENO needs CR and PATH.
+! # Avoid depending upon Character Ranges.
+! as_cr_letters='abcdefghijklmnopqrstuvwxyz'
+! as_cr_LETTERS='ABCDEFGHIJKLMNOPQRSTUVWXYZ'
+! as_cr_Letters=$as_cr_letters$as_cr_LETTERS
+! as_cr_digits='0123456789'
+! as_cr_alnum=$as_cr_Letters$as_cr_digits
+!
+! # The user is always right.
+! if test "${PATH_SEPARATOR+set}" != set; then
+! echo "#! /bin/sh" >conf$$.sh
+! echo "exit 0" >>conf$$.sh
+! chmod +x conf$$.sh
+! if (PATH="/nonexistent;."; conf$$.sh) >/dev/null 2>&1; then
+! PATH_SEPARATOR=';'
+! else
+! PATH_SEPARATOR=:
+! fi
+! rm -f conf$$.sh
+! fi
+
+
+- as_lineno_1=$LINENO
+- as_lineno_2=$LINENO
+- as_lineno_3=`(expr $as_lineno_1 + 1) 2>/dev/null`
+- test "x$as_lineno_1" != "x$as_lineno_2" &&
+- test "x$as_lineno_3" = "x$as_lineno_2" || {
+- # Find who we are. Look in the path if we contain no path at all
+- # relative or not.
+- case $0 in
+- *[\\/]* ) as_myself=$0 ;;
+- *) as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+- for as_dir in $PATH
+- do
+- IFS=$as_save_IFS
+- test -z "$as_dir" && as_dir=.
+- test -r "$as_dir/$0" && as_myself=$as_dir/$0 && break
+- done
+
+- ;;
+- esac
+- # We did not find ourselves, most probably we were run as `sh COMMAND'
+- # in which case we are not to be found in the path.
+- if test "x$as_myself" = x; then
+- as_myself=$0
+- fi
+- if test ! -f "$as_myself"; then
+- { { echo "$as_me:$LINENO: error: cannot find myself; rerun with an absolute path" >&5
+- echo "$as_me: error: cannot find myself; rerun with an absolute path" >&2;}
+- { (exit 1); exit 1; }; }
+- fi
+- case $CONFIG_SHELL in
+- '')
+- as_save_IFS=$IFS; IFS=$PATH_SEPARATOR
+- for as_dir in /bin$PATH_SEPARATOR/usr/bin$PATH_SEPARATOR$PATH
+- do
+- IFS=$as_save_IFS
+- test -z "$as_dir" && as_dir=.
+- for as_base in sh bash ksh sh5; do
+- case $as_dir in
+- /*)
+- if ("$as_dir/$as_base" -c '
+ as_lineno_1=$LINENO
+ as_lineno_2=$LINENO
+- as_lineno_3=`(expr $as_lineno_1 + 1) 2>/dev/null`
+ test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x$as_lineno_3" = "x$as_lineno_2" ') 2>/dev/null; then
+! $as_unset BASH_ENV || test "${BASH_ENV+set}" != set || { BASH_ENV=; export BASH_ENV; }
+! $as_unset ENV || test "${ENV+set}" != set || { ENV=; export ENV; }
+! CONFIG_SHELL=$as_dir/$as_base
+! export CONFIG_SHELL
+! exec "$CONFIG_SHELL" "$0" ${1+"$@"}
+! fi;;
+! esac
+! done
+! done
+! ;;
+! esac
+
+ # Create $as_me.lineno as a copy of $as_myself, but with $LINENO
+ # uniformly replaced by the line number. The first 'sed' inserts a
+! # line-number line before each line; the second 'sed' does the real
+! # work. The second script uses 'N' to pair each line-number line
+! # with the numbered line, and appends trailing '-' during
+! # substitution so that $LINENO is not a special case at line end.
+ # (Raja R Harinath suggested sed '=', and Paul Eggert wrote the
+! # second 'sed' script. Blame Lee E. McMahon for sed's syntax. :-)
+! sed '=' <$as_myself |
+ sed '
+ N
+! s,$,-,
+! : loop
+! s,^\(['$as_cr_digits']*\)\(.*\)[$]LINENO\([^'$as_cr_alnum'_]\),\1\2\1\3,
+ t loop
+! s,-$,,
+! s,^['$as_cr_digits']*\n,,
+ ' >$as_me.lineno &&
+! chmod +x $as_me.lineno ||
+! { { echo "$as_me:$LINENO: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&5
+! echo "$as_me: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&2;}
+ { (exit 1); exit 1; }; }
+
+ # Don't try to exec as it changes $[0], causing all sort of problems
+ # (the dirname of $[0] is not the place where we might find the
+! # original and so on. Autoconf is especially sensible to this).
+! . ./$as_me.lineno
+ # Exit status is that of the last command.
+ exit
+ }
+
+
+! case `echo "testing\c"; echo 1,2,3`,`echo -n testing; echo 1,2,3` in
+! *c*,-n*) ECHO_N= ECHO_C='
+! ' ECHO_T=' ' ;;
+! *c*,* ) ECHO_N=-n ECHO_C= ECHO_T= ;;
+! *) ECHO_N= ECHO_C='\c' ECHO_T= ;;
+! esac
+
+! if expr a : '\(a\)' >/dev/null 2>&1; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+ rm -f conf$$ conf$$.exe conf$$.file
+! echo >conf$$.file
+! if ln -s conf$$.file conf$$ 2>/dev/null; then
+! # We could just check for DJGPP; but this test a) works b) is more generic
+! # and c) will remain valid once DJGPP supports symlinks (DJGPP 2.04).
+! if test -f conf$$.exe; then
+! # Don't use ln at all; we don't have any links
+! as_ln_s='cp -p'
+! else
+ as_ln_s='ln -s'
+ fi
+- elif ln conf$$.file conf$$ 2>/dev/null; then
+- as_ln_s=ln
+ else
+ as_ln_s='cp -p'
+ fi
+! rm -f conf$$ conf$$.exe conf$$.file
+
+ if mkdir -p . 2>/dev/null; then
+ as_mkdir_p=:
+--- 7755,7876 ----
+
+
+ # Name of the executable.
+! as_me=`$as_basename -- "$0" ||
+ $as_expr X/"$0" : '.*/\([^/][^/]*\)/*$' \| \
+ X"$0" : 'X\(//\)$' \| \
+! X"$0" : 'X\(/\)' \| . 2>/dev/null ||
+! $as_echo X/"$0" |
+! sed '/^.*\/\([^/][^/]*\)\/*$/{
+! s//\1/
+! q
+! }
+! /^X\/\(\/\/\)$/{
+! s//\1/
+! q
+! }
+! /^X\/\(\/\).*/{
+! s//\1/
+! q
+! }
+! s/.*/./; q'`
+!
+! # CDPATH.
+! $as_unset CDPATH
+
+
+
+ as_lineno_1=$LINENO
+ as_lineno_2=$LINENO
+ test "x$as_lineno_1" != "x$as_lineno_2" &&
+! test "x`expr $as_lineno_1 + 1`" = "x$as_lineno_2" || {
+
+ # Create $as_me.lineno as a copy of $as_myself, but with $LINENO
+ # uniformly replaced by the line number. The first 'sed' inserts a
+! # line-number line after each line using $LINENO; the second 'sed'
+! # does the real work. The second script uses 'N' to pair each
+! # line-number line with the line containing $LINENO, and appends
+! # trailing '-' during substitution so that $LINENO is not a special
+! # case at line end.
+ # (Raja R Harinath suggested sed '=', and Paul Eggert wrote the
+! # scripts with optimization help from Paolo Bonzini. Blame Lee
+! # E. McMahon (1931-1989) for sed's syntax. :-)
+! sed -n '
+! p
+! /[$]LINENO/=
+! ' <$as_myself |
+ sed '
++ s/[$]LINENO.*/&-/
++ t lineno
++ b
++ :lineno
+ N
+! :loop
+! s/[$]LINENO\([^'$as_cr_alnum'_].*\n\)\(.*\)/\2\1\2/
+ t loop
+! s/-\n.*//
+ ' >$as_me.lineno &&
+! chmod +x "$as_me.lineno" ||
+! { $as_echo "$as_me: error: cannot create $as_me.lineno; rerun with a POSIX shell" >&2
+ { (exit 1); exit 1; }; }
+
+ # Don't try to exec as it changes $[0], causing all sort of problems
+ # (the dirname of $[0] is not the place where we might find the
+! # original and so on. Autoconf is especially sensitive to this).
+! . "./$as_me.lineno"
+ # Exit status is that of the last command.
+ exit
+ }
+
+
+! if (as_dir=`dirname -- /` && test "X$as_dir" = X/) >/dev/null 2>&1; then
+! as_dirname=dirname
+! else
+! as_dirname=false
+! fi
+
+! ECHO_C= ECHO_N= ECHO_T=
+! case `echo -n x` in
+! -n*)
+! case `echo 'x\c'` in
+! *c*) ECHO_T=' ';; # ECHO_T is single tab character.
+! *) ECHO_C='\c';;
+! esac;;
+! *)
+! ECHO_N='-n';;
+! esac
+! if expr a : '\(a\)' >/dev/null 2>&1 &&
+! test "X`expr 00001 : '.*\(...\)'`" = X001; then
+ as_expr=expr
+ else
+ as_expr=false
+ fi
+
+ rm -f conf$$ conf$$.exe conf$$.file
+! if test -d conf$$.dir; then
+! rm -f conf$$.dir/conf$$.file
+! else
+! rm -f conf$$.dir
+! mkdir conf$$.dir 2>/dev/null
+! fi
+! if (echo >conf$$.file) 2>/dev/null; then
+! if ln -s conf$$.file conf$$ 2>/dev/null; then
+ as_ln_s='ln -s'
++ # ... but there are two gotchas:
++ # 1) On MSYS, both `ln -s file dir' and `ln file dir' fail.
++ # 2) DJGPP < 2.04 has no symlinks; `ln -s' creates a wrapper executable.
++ # In both cases, we have to default to `cp -p'.
++ ln -s conf$$.file conf$$.dir 2>/dev/null && test ! -f conf$$.exe ||
++ as_ln_s='cp -p'
++ elif ln conf$$.file conf$$ 2>/dev/null; then
++ as_ln_s=ln
++ else
++ as_ln_s='cp -p'
+ fi
+ else
+ as_ln_s='cp -p'
+ fi
+! rm -f conf$$ conf$$.exe conf$$.dir/conf$$.file conf$$.file
+! rmdir conf$$.dir 2>/dev/null
+
+ if mkdir -p . 2>/dev/null; then
+ as_mkdir_p=:
+***************
+*** 6710,6716 ****
+ as_mkdir_p=false
+ fi
+
+! as_executable_p="test -f"
+
+ # Sed expression to map a string onto a valid CPP name.
+ as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'"
+--- 7879,7906 ----
+ as_mkdir_p=false
+ fi
+
+! if test -x / >/dev/null 2>&1; then
+! as_test_x='test -x'
+! else
+! if ls -dL / >/dev/null 2>&1; then
+! as_ls_L_option=L
+! else
+! as_ls_L_option=
+! fi
+! as_test_x='
+! eval sh -c '\''
+! if test -d "$1"; then
+! test -d "$1/.";
+! else
+! case $1 in
+! -*)set "./$1";;
+! esac;
+! case `ls -ld'$as_ls_L_option' "$1" 2>/dev/null` in
+! ???[sx]*):;;*)false;;esac;fi
+! '\'' sh
+! '
+! fi
+! as_executable_p=$as_test_x
+
+ # Sed expression to map a string onto a valid CPP name.
+ as_tr_cpp="eval sed 'y%*$as_cr_letters%P$as_cr_LETTERS%;s%[^_$as_cr_alnum]%_%g'"
+***************
+*** 6719,6749 ****
+ as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'"
+
+
+- # IFS
+- # We need space, tab and new line, in precisely that order.
+- as_nl='
+- '
+- IFS=" $as_nl"
+-
+- # CDPATH.
+- $as_unset CDPATH
+-
+ exec 6>&1
+
+! # Open the log real soon, to keep \$[0] and so on meaningful, and to
+ # report actual input values of CONFIG_FILES etc. instead of their
+! # values after options handling. Logging --version etc. is OK.
+! exec 5>>config.log
+! {
+! echo
+! sed 'h;s/./-/g;s/^.../## /;s/...$/ ##/;p;x;p;x' <<_ASBOX
+! ## Running $as_me. ##
+! _ASBOX
+! } >&5
+! cat >&5 <<_CSEOF
+!
+ This file was extended by $as_me, which was
+! generated by GNU Autoconf 2.59. Invocation command line was
+
+ CONFIG_FILES = $CONFIG_FILES
+ CONFIG_HEADERS = $CONFIG_HEADERS
+--- 7909,7922 ----
+ as_tr_sh="eval sed 'y%*+%pp%;s%[^_$as_cr_alnum]%_%g'"
+
+
+ exec 6>&1
+
+! # Save the log message, to keep $[0] and so on meaningful, and to
+ # report actual input values of CONFIG_FILES etc. instead of their
+! # values after options handling.
+! ac_log="
+ This file was extended by $as_me, which was
+! generated by GNU Autoconf 2.62. Invocation command line was
+
+ CONFIG_FILES = $CONFIG_FILES
+ CONFIG_HEADERS = $CONFIG_HEADERS
+***************
+*** 6751,6780 ****
+ CONFIG_COMMANDS = $CONFIG_COMMANDS
+ $ $0 $@
+
+! _CSEOF
+! echo "on `(hostname || uname -n) 2>/dev/null | sed 1q`" >&5
+! echo >&5
+ _ACEOF
+
+ # Files that config.status was made for.
+! if test -n "$ac_config_files"; then
+! echo "config_files=\"$ac_config_files\"" >>$CONFIG_STATUS
+! fi
+!
+! if test -n "$ac_config_headers"; then
+! echo "config_headers=\"$ac_config_headers\"" >>$CONFIG_STATUS
+! fi
+
+! if test -n "$ac_config_links"; then
+! echo "config_links=\"$ac_config_links\"" >>$CONFIG_STATUS
+! fi
+!
+! if test -n "$ac_config_commands"; then
+! echo "config_commands=\"$ac_config_commands\"" >>$CONFIG_STATUS
+! fi
+!
+! cat >>$CONFIG_STATUS <<\_ACEOF
+
+ ac_cs_usage="\
+ \`$as_me' instantiates files from templates according to the
+ current configuration.
+--- 7924,7943 ----
+ CONFIG_COMMANDS = $CONFIG_COMMANDS
+ $ $0 $@
+
+! on `(hostname || uname -n) 2>/dev/null | sed 1q`
+! "
+!
+ _ACEOF
+
++ cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+ # Files that config.status was made for.
+! config_files="$ac_config_files"
+! config_headers="$ac_config_headers"
+! config_commands="$ac_config_commands"
+
+! _ACEOF
+
++ cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+ ac_cs_usage="\
+ \`$as_me' instantiates files from templates according to the
+ current configuration.
+***************
+*** 6782,6795 ****
+ Usage: $0 [OPTIONS] [FILE]...
+
+ -h, --help print this help, then exit
+! -V, --version print version number, then exit
+ -q, --quiet do not print progress messages
+ -d, --debug don't remove temporary files
+ --recheck update $as_me by reconfiguring in the same conditions
+ --file=FILE[:TEMPLATE]
+! instantiate the configuration file FILE
+ --header=FILE[:TEMPLATE]
+! instantiate the configuration header FILE
+
+ Configuration files:
+ $config_files
+--- 7945,7958 ----
+ Usage: $0 [OPTIONS] [FILE]...
+
+ -h, --help print this help, then exit
+! -V, --version print version number and configuration settings, then exit
+ -q, --quiet do not print progress messages
+ -d, --debug don't remove temporary files
+ --recheck update $as_me by reconfiguring in the same conditions
+ --file=FILE[:TEMPLATE]
+! instantiate the configuration file FILE
+ --header=FILE[:TEMPLATE]
+! instantiate the configuration header FILE
+
+ Configuration files:
+ $config_files
+***************
+*** 6801,6883 ****
+ $config_commands
+
+ Report bugs to <bug-autoconf@gnu.org>."
+- _ACEOF
+
+! cat >>$CONFIG_STATUS <<_ACEOF
+ ac_cs_version="\\
+ config.status
+! configured by $0, generated by GNU Autoconf 2.59,
+! with options \\"`echo "$ac_configure_args" | sed 's/[\\""\`\$]/\\\\&/g'`\\"
+
+! Copyright (C) 2003 Free Software Foundation, Inc.
+ This config.status script is free software; the Free Software Foundation
+ gives unlimited permission to copy, distribute and modify it."
+! srcdir=$srcdir
+! INSTALL="$INSTALL"
+ _ACEOF
+
+! cat >>$CONFIG_STATUS <<\_ACEOF
+! # If no file are specified by the user, then we need to provide default
+! # value. By we need to know if files were specified by the user.
+ ac_need_defaults=:
+ while test $# != 0
+ do
+ case $1 in
+ --*=*)
+! ac_option=`expr "x$1" : 'x\([^=]*\)='`
+! ac_optarg=`expr "x$1" : 'x[^=]*=\(.*\)'`
+ ac_shift=:
+ ;;
+! -*)
+ ac_option=$1
+ ac_optarg=$2
+ ac_shift=shift
+ ;;
+- *) # This is not an option, so the user has probably given explicit
+- # arguments.
+- ac_option=$1
+- ac_need_defaults=false;;
+ esac
+
+ case $ac_option in
+ # Handling of the options.
+- _ACEOF
+- cat >>$CONFIG_STATUS <<\_ACEOF
+ -recheck | --recheck | --rechec | --reche | --rech | --rec | --re | --r)
+ ac_cs_recheck=: ;;
+! --version | --vers* | -V )
+! echo "$ac_cs_version"; exit 0 ;;
+! --he | --h)
+! # Conflict between --help and --header
+! { { echo "$as_me:$LINENO: error: ambiguous option: $1
+! Try \`$0 --help' for more information." >&5
+! echo "$as_me: error: ambiguous option: $1
+! Try \`$0 --help' for more information." >&2;}
+! { (exit 1); exit 1; }; };;
+! --help | --hel | -h )
+! echo "$ac_cs_usage"; exit 0 ;;
+! --debug | --d* | -d )
+ debug=: ;;
+ --file | --fil | --fi | --f )
+ $ac_shift
+! CONFIG_FILES="$CONFIG_FILES $ac_optarg"
+ ac_need_defaults=false;;
+ --header | --heade | --head | --hea )
+ $ac_shift
+! CONFIG_HEADERS="$CONFIG_HEADERS $ac_optarg"
+ ac_need_defaults=false;;
+ -q | -quiet | --quiet | --quie | --qui | --qu | --q \
+ | -silent | --silent | --silen | --sile | --sil | --si | --s)
+ ac_cs_silent=: ;;
+
+ # This is an error.
+! -*) { { echo "$as_me:$LINENO: error: unrecognized option: $1
+! Try \`$0 --help' for more information." >&5
+! echo "$as_me: error: unrecognized option: $1
+! Try \`$0 --help' for more information." >&2;}
+ { (exit 1); exit 1; }; } ;;
+
+! *) ac_config_targets="$ac_config_targets $1" ;;
+
+ esac
+ shift
+--- 7964,8045 ----
+ $config_commands
+
+ Report bugs to <bug-autoconf@gnu.org>."
+
+! _ACEOF
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+ ac_cs_version="\\
+ config.status
+! configured by $0, generated by GNU Autoconf 2.62,
+! with options \\"`$as_echo "$ac_configure_args" | sed 's/^ //; s/[\\""\`\$]/\\\\&/g'`\\"
+
+! Copyright (C) 2008 Free Software Foundation, Inc.
+ This config.status script is free software; the Free Software Foundation
+ gives unlimited permission to copy, distribute and modify it."
+!
+! ac_pwd='$ac_pwd'
+! srcdir='$srcdir'
+! INSTALL='$INSTALL'
+! test -n "\$AWK" || AWK=awk
+ _ACEOF
+
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+! # The default lists apply if the user does not specify any file.
+ ac_need_defaults=:
+ while test $# != 0
+ do
+ case $1 in
+ --*=*)
+! ac_option=`expr "X$1" : 'X\([^=]*\)='`
+! ac_optarg=`expr "X$1" : 'X[^=]*=\(.*\)'`
+ ac_shift=:
+ ;;
+! *)
+ ac_option=$1
+ ac_optarg=$2
+ ac_shift=shift
+ ;;
+ esac
+
+ case $ac_option in
+ # Handling of the options.
+ -recheck | --recheck | --rechec | --reche | --rech | --rec | --re | --r)
+ ac_cs_recheck=: ;;
+! --version | --versio | --versi | --vers | --ver | --ve | --v | -V )
+! $as_echo "$ac_cs_version"; exit ;;
+! --debug | --debu | --deb | --de | --d | -d )
+ debug=: ;;
+ --file | --fil | --fi | --f )
+ $ac_shift
+! case $ac_optarg in
+! *\'*) ac_optarg=`$as_echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"` ;;
+! esac
+! CONFIG_FILES="$CONFIG_FILES '$ac_optarg'"
+ ac_need_defaults=false;;
+ --header | --heade | --head | --hea )
+ $ac_shift
+! case $ac_optarg in
+! *\'*) ac_optarg=`$as_echo "$ac_optarg" | sed "s/'/'\\\\\\\\''/g"` ;;
+! esac
+! CONFIG_HEADERS="$CONFIG_HEADERS '$ac_optarg'"
+ ac_need_defaults=false;;
++ --he | --h)
++ # Conflict between --help and --header
++ { $as_echo "$as_me: error: ambiguous option: $1
++ Try \`$0 --help' for more information." >&2
++ { (exit 1); exit 1; }; };;
++ --help | --hel | -h )
++ $as_echo "$ac_cs_usage"; exit ;;
+ -q | -quiet | --quiet | --quie | --qui | --qu | --q \
+ | -silent | --silent | --silen | --sile | --sil | --si | --s)
+ ac_cs_silent=: ;;
+
+ # This is an error.
+! -*) { $as_echo "$as_me: error: unrecognized option: $1
+! Try \`$0 --help' for more information." >&2
+ { (exit 1); exit 1; }; } ;;
+
+! *) ac_config_targets="$ac_config_targets $1"
+! ac_need_defaults=false ;;
+
+ esac
+ shift
+***************
+*** 6891,6922 ****
+ fi
+
+ _ACEOF
+! cat >>$CONFIG_STATUS <<_ACEOF
+ if \$ac_cs_recheck; then
+! echo "running $SHELL $0 " $ac_configure_args \$ac_configure_extra_args " --no-create --no-recursion" >&6
+! exec $SHELL $0 $ac_configure_args \$ac_configure_extra_args --no-create --no-recursion
+ fi
+
+ _ACEOF
+
+
+
+!
+!
+! cat >>$CONFIG_STATUS <<\_ACEOF
+ for ac_config_target in $ac_config_targets
+ do
+! case "$ac_config_target" in
+! # Handling of arguments.
+! "Makefile" ) CONFIG_FILES="$CONFIG_FILES Makefile" ;;
+! "default" ) CONFIG_COMMANDS="$CONFIG_COMMANDS default" ;;
+! "config.h" ) CONFIG_HEADERS="$CONFIG_HEADERS config.h:config.in" ;;
+! *) { { echo "$as_me:$LINENO: error: invalid argument: $ac_config_target" >&5
+! echo "$as_me: error: invalid argument: $ac_config_target" >&2;}
+ { (exit 1); exit 1; }; };;
+ esac
+ done
+
+ # If the user did not use the arguments to specify the items to instantiate,
+ # then the envvar interface is used. Set only those that are not.
+ # We use the long form for the default assignment because of an extremely
+--- 8053,8100 ----
+ fi
+
+ _ACEOF
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+ if \$ac_cs_recheck; then
+! set X '$SHELL' '$0' $ac_configure_args \$ac_configure_extra_args --no-create --no-recursion
+! shift
+! \$as_echo "running CONFIG_SHELL=$SHELL \$*" >&6
+! CONFIG_SHELL='$SHELL'
+! export CONFIG_SHELL
+! exec "\$@"
+ fi
+
+ _ACEOF
++ cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
++ exec 5>>config.log
++ {
++ echo
++ sed 'h;s/./-/g;s/^.../## /;s/...$/ ##/;p;x;p;x' <<_ASBOX
++ ## Running $as_me. ##
++ _ASBOX
++ $as_echo "$ac_log"
++ } >&5
+
++ _ACEOF
++ cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
++ _ACEOF
+
++ cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+
+! # Handling of arguments.
+ for ac_config_target in $ac_config_targets
+ do
+! case $ac_config_target in
+! "config.h") CONFIG_HEADERS="$CONFIG_HEADERS config.h:config.in" ;;
+! "Makefile") CONFIG_FILES="$CONFIG_FILES Makefile" ;;
+! "default") CONFIG_COMMANDS="$CONFIG_COMMANDS default" ;;
+!
+! *) { { $as_echo "$as_me:$LINENO: error: invalid argument: $ac_config_target" >&5
+! $as_echo "$as_me: error: invalid argument: $ac_config_target" >&2;}
+ { (exit 1); exit 1; }; };;
+ esac
+ done
+
++
+ # If the user did not use the arguments to specify the items to instantiate,
+ # then the envvar interface is used. Set only those that are not.
+ # We use the long form for the default assignment because of an extremely
+***************
+*** 6928,7685 ****
+ fi
+
+ # Have a temporary directory for convenience. Make it in the build tree
+! # simply because there is no reason to put it here, and in addition,
+ # creating and moving files from /tmp can sometimes cause problems.
+! # Create a temporary directory, and hook for its removal unless debugging.
+ $debug ||
+ {
+! trap 'exit_status=$?; rm -rf $tmp && exit $exit_status' 0
+ trap '{ (exit 1); exit 1; }' 1 2 13 15
+ }
+-
+ # Create a (secure) tmp directory for tmp files.
+
+ {
+! tmp=`(umask 077 && mktemp -d -q "./confstatXXXXXX") 2>/dev/null` &&
+ test -n "$tmp" && test -d "$tmp"
+ } ||
+ {
+! tmp=./confstat$$-$RANDOM
+! (umask 077 && mkdir $tmp)
+ } ||
+ {
+! echo "$me: cannot create a temporary directory in ." >&2
+ { (exit 1); exit 1; }
+ }
+
+ _ACEOF
+
+- cat >>$CONFIG_STATUS <<_ACEOF
+
+! #
+! # CONFIG_FILES section.
+! #
+
+! # No need to generate the scripts if there are no CONFIG_FILES.
+! # This happens for instance when ./config.status config.h
+! if test -n "\$CONFIG_FILES"; then
+! # Protect against being on the right side of a sed subst in config.status.
+! sed 's/,@/@@/; s/@,/@@/; s/,;t t\$/@;t t/; /@;t t\$/s/[\\\\&,]/\\\\&/g;
+! s/@@/,@/; s/@@/@,/; s/@;t t\$/,;t t/' >\$tmp/subs.sed <<\\CEOF
+! s,@sim_environment@,$sim_environment,;t t
+! s,@sim_alignment@,$sim_alignment,;t t
+! s,@sim_assert@,$sim_assert,;t t
+! s,@sim_bitsize@,$sim_bitsize,;t t
+! s,@sim_endian@,$sim_endian,;t t
+! s,@sim_hostendian@,$sim_hostendian,;t t
+! s,@sim_float@,$sim_float,;t t
+! s,@sim_scache@,$sim_scache,;t t
+! s,@sim_default_model@,$sim_default_model,;t t
+! s,@sim_hw_cflags@,$sim_hw_cflags,;t t
+! s,@sim_hw_objs@,$sim_hw_objs,;t t
+! s,@sim_hw@,$sim_hw,;t t
+! s,@sim_inline@,$sim_inline,;t t
+! s,@sim_packages@,$sim_packages,;t t
+! s,@sim_regparm@,$sim_regparm,;t t
+! s,@sim_reserved_bits@,$sim_reserved_bits,;t t
+! s,@sim_smp@,$sim_smp,;t t
+! s,@sim_stdcall@,$sim_stdcall,;t t
+! s,@sim_xor_endian@,$sim_xor_endian,;t t
+! s,@WARN_CFLAGS@,$WARN_CFLAGS,;t t
+! s,@WERROR_CFLAGS@,$WERROR_CFLAGS,;t t
+! s,@SHELL@,$SHELL,;t t
+! s,@PATH_SEPARATOR@,$PATH_SEPARATOR,;t t
+! s,@PACKAGE_NAME@,$PACKAGE_NAME,;t t
+! s,@PACKAGE_TARNAME@,$PACKAGE_TARNAME,;t t
+! s,@PACKAGE_VERSION@,$PACKAGE_VERSION,;t t
+! s,@PACKAGE_STRING@,$PACKAGE_STRING,;t t
+! s,@PACKAGE_BUGREPORT@,$PACKAGE_BUGREPORT,;t t
+! s,@exec_prefix@,$exec_prefix,;t t
+! s,@prefix@,$prefix,;t t
+! s,@program_transform_name@,$program_transform_name,;t t
+! s,@bindir@,$bindir,;t t
+! s,@sbindir@,$sbindir,;t t
+! s,@libexecdir@,$libexecdir,;t t
+! s,@datadir@,$datadir,;t t
+! s,@sysconfdir@,$sysconfdir,;t t
+! s,@sharedstatedir@,$sharedstatedir,;t t
+! s,@localstatedir@,$localstatedir,;t t
+! s,@libdir@,$libdir,;t t
+! s,@includedir@,$includedir,;t t
+! s,@oldincludedir@,$oldincludedir,;t t
+! s,@infodir@,$infodir,;t t
+! s,@mandir@,$mandir,;t t
+! s,@build_alias@,$build_alias,;t t
+! s,@host_alias@,$host_alias,;t t
+! s,@target_alias@,$target_alias,;t t
+! s,@DEFS@,$DEFS,;t t
+! s,@ECHO_C@,$ECHO_C,;t t
+! s,@ECHO_N@,$ECHO_N,;t t
+! s,@ECHO_T@,$ECHO_T,;t t
+! s,@LIBS@,$LIBS,;t t
+! s,@INSTALL_PROGRAM@,$INSTALL_PROGRAM,;t t
+! s,@INSTALL_SCRIPT@,$INSTALL_SCRIPT,;t t
+! s,@INSTALL_DATA@,$INSTALL_DATA,;t t
+! s,@CC@,$CC,;t t
+! s,@CFLAGS@,$CFLAGS,;t t
+! s,@LDFLAGS@,$LDFLAGS,;t t
+! s,@CPPFLAGS@,$CPPFLAGS,;t t
+! s,@ac_ct_CC@,$ac_ct_CC,;t t
+! s,@EXEEXT@,$EXEEXT,;t t
+! s,@OBJEXT@,$OBJEXT,;t t
+! s,@USE_NLS@,$USE_NLS,;t t
+! s,@LIBINTL@,$LIBINTL,;t t
+! s,@LIBINTL_DEP@,$LIBINTL_DEP,;t t
+! s,@INCINTL@,$INCINTL,;t t
+! s,@XGETTEXT@,$XGETTEXT,;t t
+! s,@GMSGFMT@,$GMSGFMT,;t t
+! s,@POSUB@,$POSUB,;t t
+! s,@CATALOGS@,$CATALOGS,;t t
+! s,@DATADIRNAME@,$DATADIRNAME,;t t
+! s,@INSTOBJEXT@,$INSTOBJEXT,;t t
+! s,@GENCAT@,$GENCAT,;t t
+! s,@CATOBJEXT@,$CATOBJEXT,;t t
+! s,@build@,$build,;t t
+! s,@build_cpu@,$build_cpu,;t t
+! s,@build_vendor@,$build_vendor,;t t
+! s,@build_os@,$build_os,;t t
+! s,@host@,$host,;t t
+! s,@host_cpu@,$host_cpu,;t t
+! s,@host_vendor@,$host_vendor,;t t
+! s,@host_os@,$host_os,;t t
+! s,@target@,$target,;t t
+! s,@target_cpu@,$target_cpu,;t t
+! s,@target_vendor@,$target_vendor,;t t
+! s,@target_os@,$target_os,;t t
+! s,@CPP@,$CPP,;t t
+! s,@EGREP@,$EGREP,;t t
+! s,@LIBOBJS@,$LIBOBJS,;t t
+! s,@CC_FOR_BUILD@,$CC_FOR_BUILD,;t t
+! s,@CFLAGS_FOR_BUILD@,$CFLAGS_FOR_BUILD,;t t
+! s,@HDEFINES@,$HDEFINES,;t t
+! s,@AR@,$AR,;t t
+! s,@RANLIB@,$RANLIB,;t t
+! s,@ac_ct_RANLIB@,$ac_ct_RANLIB,;t t
+! s,@sim_cflags@,$sim_cflags,;t t
+! s,@sim_warnings@,$sim_warnings,;t t
+! s,@sim_line_nr@,$sim_line_nr,;t t
+! s,@sim_config@,$sim_config,;t t
+! s,@sim_opcode@,$sim_opcode,;t t
+! s,@sim_switch@,$sim_switch,;t t
+! s,@sim_dup@,$sim_dup,;t t
+! s,@sim_decode_mechanism@,$sim_decode_mechanism,;t t
+! s,@sim_jump@,$sim_jump,;t t
+! s,@sim_filter@,$sim_filter,;t t
+! s,@sim_icache@,$sim_icache,;t t
+! s,@sim_hw_src@,$sim_hw_src,;t t
+! s,@sim_hw_obj@,$sim_hw_obj,;t t
+! s,@sim_pk_src@,$sim_pk_src,;t t
+! s,@sim_pk_obj@,$sim_pk_obj,;t t
+! s,@sim_bswap@,$sim_bswap,;t t
+! s,@sim_igen_smp@,$sim_igen_smp,;t t
+! s,@sim_hostbitsize@,$sim_hostbitsize,;t t
+! s,@sim_env@,$sim_env,;t t
+! s,@sim_timebase@,$sim_timebase,;t t
+! s,@sim_trace@,$sim_trace,;t t
+! s,@sim_reserved@,$sim_reserved,;t t
+! s,@sim_monitor@,$sim_monitor,;t t
+! s,@sim_model@,$sim_model,;t t
+! s,@sim_model_issue@,$sim_model_issue,;t t
+! s,@sim_stdio@,$sim_stdio,;t t
+! s,@sim_termio@,$sim_termio,;t t
+! s,@sim_devzero@,$sim_devzero,;t t
+! s,@sim_callback@,$sim_callback,;t t
+! s,@sim_targ_vals@,$sim_targ_vals,;t t
+! s,@sim_fpu_cflags@,$sim_fpu_cflags,;t t
+! s,@sim_fpu@,$sim_fpu,;t t
+! s,@LTLIBOBJS@,$LTLIBOBJS,;t t
+! CEOF
+!
+! _ACEOF
+!
+! cat >>$CONFIG_STATUS <<\_ACEOF
+! # Split the substitutions into bite-sized pieces for seds with
+! # small command number limits, like on Digital OSF/1 and HP-UX.
+! ac_max_sed_lines=48
+! ac_sed_frag=1 # Number of current file.
+! ac_beg=1 # First line for current file.
+! ac_end=$ac_max_sed_lines # Line after last line for current file.
+! ac_more_lines=:
+! ac_sed_cmds=
+! while $ac_more_lines; do
+! if test $ac_beg -gt 1; then
+! sed "1,${ac_beg}d; ${ac_end}q" $tmp/subs.sed >$tmp/subs.frag
+! else
+! sed "${ac_end}q" $tmp/subs.sed >$tmp/subs.frag
+! fi
+! if test ! -s $tmp/subs.frag; then
+! ac_more_lines=false
+! else
+! # The purpose of the label and of the branching condition is to
+! # speed up the sed processing (if there are no `@' at all, there
+! # is no need to browse any of the substitutions).
+! # These are the two extra sed commands mentioned above.
+! (echo ':t
+! /@[a-zA-Z_][a-zA-Z_0-9]*@/!b' && cat $tmp/subs.frag) >$tmp/subs-$ac_sed_frag.sed
+! if test -z "$ac_sed_cmds"; then
+! ac_sed_cmds="sed -f $tmp/subs-$ac_sed_frag.sed"
+! else
+! ac_sed_cmds="$ac_sed_cmds | sed -f $tmp/subs-$ac_sed_frag.sed"
+! fi
+! ac_sed_frag=`expr $ac_sed_frag + 1`
+! ac_beg=$ac_end
+! ac_end=`expr $ac_end + $ac_max_sed_lines`
+! fi
+! done
+! if test -z "$ac_sed_cmds"; then
+! ac_sed_cmds=cat
+ fi
+! fi # test -n "$CONFIG_FILES"
+
+ _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF
+! for ac_file in : $CONFIG_FILES; do test "x$ac_file" = x: && continue
+! # Support "outfile[:infile[:infile...]]", defaulting infile="outfile.in".
+! case $ac_file in
+! - | *:- | *:-:* ) # input from stdin
+! cat >$tmp/stdin
+! ac_file_in=`echo "$ac_file" | sed 's,[^:]*:,,'`
+! ac_file=`echo "$ac_file" | sed 's,:.*,,'` ;;
+! *:* ) ac_file_in=`echo "$ac_file" | sed 's,[^:]*:,,'`
+! ac_file=`echo "$ac_file" | sed 's,:.*,,'` ;;
+! * ) ac_file_in=$ac_file.in ;;
+ esac
+
+! # Compute @srcdir@, @top_srcdir@, and @INSTALL@ for subdirectories.
+! ac_dir=`(dirname "$ac_file") 2>/dev/null ||
+ $as_expr X"$ac_file" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+ X"$ac_file" : 'X\(//\)[^/]' \| \
+ X"$ac_file" : 'X\(//\)$' \| \
+! X"$ac_file" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$ac_file" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+! { if $as_mkdir_p; then
+! mkdir -p "$ac_dir"
+! else
+! as_dir="$ac_dir"
+ as_dirs=
+! while test ! -d "$as_dir"; do
+! as_dirs="$as_dir $as_dirs"
+! as_dir=`(dirname "$as_dir") 2>/dev/null ||
+ $as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+ X"$as_dir" : 'X\(//\)[^/]' \| \
+ X"$as_dir" : 'X\(//\)$' \| \
+! X"$as_dir" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$as_dir" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+ done
+! test ! -n "$as_dirs" || mkdir $as_dirs
+! fi || { { echo "$as_me:$LINENO: error: cannot create directory \"$ac_dir\"" >&5
+! echo "$as_me: error: cannot create directory \"$ac_dir\"" >&2;}
+ { (exit 1); exit 1; }; }; }
+-
+ ac_builddir=.
+
+! if test "$ac_dir" != .; then
+! ac_dir_suffix=/`echo "$ac_dir" | sed 's,^\.[\\/],,'`
+! # A "../" for each directory in $ac_dir_suffix.
+! ac_top_builddir=`echo "$ac_dir_suffix" | sed 's,/[^\\/]*,../,g'`
+! else
+! ac_dir_suffix= ac_top_builddir=
+! fi
+
+ case $srcdir in
+! .) # No --srcdir option. We are building in place.
+ ac_srcdir=.
+! if test -z "$ac_top_builddir"; then
+! ac_top_srcdir=.
+! else
+! ac_top_srcdir=`echo $ac_top_builddir | sed 's,/$,,'`
+! fi ;;
+! [\\/]* | ?:[\\/]* ) # Absolute path.
+ ac_srcdir=$srcdir$ac_dir_suffix;
+! ac_top_srcdir=$srcdir ;;
+! *) # Relative path.
+! ac_srcdir=$ac_top_builddir$srcdir$ac_dir_suffix
+! ac_top_srcdir=$ac_top_builddir$srcdir ;;
+! esac
+
+- # Do not use `cd foo && pwd` to compute absolute paths, because
+- # the directories may not exist.
+- case `pwd` in
+- .) ac_abs_builddir="$ac_dir";;
+- *)
+- case "$ac_dir" in
+- .) ac_abs_builddir=`pwd`;;
+- [\\/]* | ?:[\\/]* ) ac_abs_builddir="$ac_dir";;
+- *) ac_abs_builddir=`pwd`/"$ac_dir";;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_top_builddir=${ac_top_builddir}.;;
+- *)
+- case ${ac_top_builddir}. in
+- .) ac_abs_top_builddir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_top_builddir=${ac_top_builddir}.;;
+- *) ac_abs_top_builddir=$ac_abs_builddir/${ac_top_builddir}.;;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_srcdir=$ac_srcdir;;
+- *)
+- case $ac_srcdir in
+- .) ac_abs_srcdir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_srcdir=$ac_srcdir;;
+- *) ac_abs_srcdir=$ac_abs_builddir/$ac_srcdir;;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_top_srcdir=$ac_top_srcdir;;
+- *)
+- case $ac_top_srcdir in
+- .) ac_abs_top_srcdir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_top_srcdir=$ac_top_srcdir;;
+- *) ac_abs_top_srcdir=$ac_abs_builddir/$ac_top_srcdir;;
+- esac;;
+- esac
+
+
+ case $INSTALL in
+ [\\/$]* | ?:[\\/]* ) ac_INSTALL=$INSTALL ;;
+! *) ac_INSTALL=$ac_top_builddir$INSTALL ;;
+ esac
+
+! if test x"$ac_file" != x-; then
+! { echo "$as_me:$LINENO: creating $ac_file" >&5
+! echo "$as_me: creating $ac_file" >&6;}
+! rm -f "$ac_file"
+! fi
+! # Let's still pretend it is `configure' which instantiates (i.e., don't
+! # use $as_me), people would be surprised to read:
+! # /* config.h. Generated by config.status. */
+! if test x"$ac_file" = x-; then
+! configure_input=
+! else
+! configure_input="$ac_file. "
+! fi
+! configure_input=$configure_input"Generated from `echo $ac_file_in |
+! sed 's,.*/,,'` by configure."
+!
+! # First look for the input files in the build tree, otherwise in the
+! # src tree.
+! ac_file_inputs=`IFS=:
+! for f in $ac_file_in; do
+! case $f in
+! -) echo $tmp/stdin ;;
+! [\\/$]*)
+! # Absolute (can't be DOS-style, as IFS=:)
+! test -f "$f" || { { echo "$as_me:$LINENO: error: cannot find input file: $f" >&5
+! echo "$as_me: error: cannot find input file: $f" >&2;}
+! { (exit 1); exit 1; }; }
+! echo "$f";;
+! *) # Relative
+! if test -f "$f"; then
+! # Build tree
+! echo "$f"
+! elif test -f "$srcdir/$f"; then
+! # Source tree
+! echo "$srcdir/$f"
+! else
+! # /dev/null tree
+! { { echo "$as_me:$LINENO: error: cannot find input file: $f" >&5
+! echo "$as_me: error: cannot find input file: $f" >&2;}
+! { (exit 1); exit 1; }; }
+! fi;;
+! esac
+! done` || { (exit 1); exit 1; }
+ _ACEOF
+! cat >>$CONFIG_STATUS <<_ACEOF
+! sed "$ac_vpsub
+ $extrasub
+ _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF
+ :t
+ /@[a-zA-Z_][a-zA-Z_0-9]*@/!b
+! s,@configure_input@,$configure_input,;t t
+! s,@srcdir@,$ac_srcdir,;t t
+! s,@abs_srcdir@,$ac_abs_srcdir,;t t
+! s,@top_srcdir@,$ac_top_srcdir,;t t
+! s,@abs_top_srcdir@,$ac_abs_top_srcdir,;t t
+! s,@builddir@,$ac_builddir,;t t
+! s,@abs_builddir@,$ac_abs_builddir,;t t
+! s,@top_builddir@,$ac_top_builddir,;t t
+! s,@abs_top_builddir@,$ac_abs_top_builddir,;t t
+! s,@INSTALL@,$ac_INSTALL,;t t
+! " $ac_file_inputs | (eval "$ac_sed_cmds") >$tmp/out
+! rm -f $tmp/stdin
+! if test x"$ac_file" != x-; then
+! mv $tmp/out $ac_file
+! else
+! cat $tmp/out
+! rm -f $tmp/out
+! fi
+!
+! done
+! _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF
+!
+! #
+! # CONFIG_HEADER section.
+! #
+
+! # These sed commands are passed to sed as "A NAME B NAME C VALUE D", where
+! # NAME is the cpp macro being defined and VALUE is the value it is being given.
+! #
+! # ac_d sets the value in "#define NAME VALUE" lines.
+! ac_dA='s,^\([ ]*\)#\([ ]*define[ ][ ]*\)'
+! ac_dB='[ ].*$,\1#\2'
+! ac_dC=' '
+! ac_dD=',;t'
+! # ac_u turns "#undef NAME" without trailing blanks into "#define NAME VALUE".
+! ac_uA='s,^\([ ]*\)#\([ ]*\)undef\([ ][ ]*\)'
+! ac_uB='$,\1#\2define\3'
+! ac_uC=' '
+! ac_uD=',;t'
+
+! for ac_file in : $CONFIG_HEADERS; do test "x$ac_file" = x: && continue
+! # Support "outfile[:infile[:infile...]]", defaulting infile="outfile.in".
+ case $ac_file in
+! - | *:- | *:-:* ) # input from stdin
+! cat >$tmp/stdin
+! ac_file_in=`echo "$ac_file" | sed 's,[^:]*:,,'`
+! ac_file=`echo "$ac_file" | sed 's,:.*,,'` ;;
+! *:* ) ac_file_in=`echo "$ac_file" | sed 's,[^:]*:,,'`
+! ac_file=`echo "$ac_file" | sed 's,:.*,,'` ;;
+! * ) ac_file_in=$ac_file.in ;;
+! esac
+!
+! test x"$ac_file" != x- && { echo "$as_me:$LINENO: creating $ac_file" >&5
+! echo "$as_me: creating $ac_file" >&6;}
+!
+! # First look for the input files in the build tree, otherwise in the
+! # src tree.
+! ac_file_inputs=`IFS=:
+! for f in $ac_file_in; do
+! case $f in
+! -) echo $tmp/stdin ;;
+! [\\/$]*)
+! # Absolute (can't be DOS-style, as IFS=:)
+! test -f "$f" || { { echo "$as_me:$LINENO: error: cannot find input file: $f" >&5
+! echo "$as_me: error: cannot find input file: $f" >&2;}
+ { (exit 1); exit 1; }; }
+! # Do quote $f, to prevent DOS paths from being IFS'd.
+! echo "$f";;
+! *) # Relative
+! if test -f "$f"; then
+! # Build tree
+! echo "$f"
+! elif test -f "$srcdir/$f"; then
+! # Source tree
+! echo "$srcdir/$f"
+! else
+! # /dev/null tree
+! { { echo "$as_me:$LINENO: error: cannot find input file: $f" >&5
+! echo "$as_me: error: cannot find input file: $f" >&2;}
+! { (exit 1); exit 1; }; }
+! fi;;
+! esac
+! done` || { (exit 1); exit 1; }
+! # Remove the trailing spaces.
+! sed 's/[ ]*$//' $ac_file_inputs >$tmp/in
+!
+! _ACEOF
+!
+! # Transform confdefs.h into two sed scripts, `conftest.defines' and
+! # `conftest.undefs', that substitutes the proper values into
+! # config.h.in to produce config.h. The first handles `#define'
+! # templates, and the second `#undef' templates.
+! # And first: Protect against being on the right side of a sed subst in
+! # config.status. Protect against being in an unquoted here document
+! # in config.status.
+! rm -f conftest.defines conftest.undefs
+! # Using a here document instead of a string reduces the quoting nightmare.
+! # Putting comments in sed scripts is not portable.
+! #
+! # `end' is used to avoid that the second main sed command (meant for
+! # 0-ary CPP macros) applies to n-ary macro definitions.
+! # See the Autoconf documentation for `clear'.
+! cat >confdef2sed.sed <<\_ACEOF
+! s/[\\&,]/\\&/g
+! s,[\\$`],\\&,g
+! t clear
+! : clear
+! s,^[ ]*#[ ]*define[ ][ ]*\([^ (][^ (]*\)\(([^)]*)\)[ ]*\(.*\)$,${ac_dA}\1${ac_dB}\1\2${ac_dC}\3${ac_dD},gp
+! t end
+! s,^[ ]*#[ ]*define[ ][ ]*\([^ ][^ ]*\)[ ]*\(.*\)$,${ac_dA}\1${ac_dB}\1${ac_dC}\2${ac_dD},gp
+! : end
+! _ACEOF
+! # If some macros were called several times there might be several times
+! # the same #defines, which is useless. Nevertheless, we may not want to
+! # sort them, since we want the *last* AC-DEFINE to be honored.
+! uniq confdefs.h | sed -n -f confdef2sed.sed >conftest.defines
+! sed 's/ac_d/ac_u/g' conftest.defines >conftest.undefs
+! rm -f confdef2sed.sed
+!
+! # This sed command replaces #undef with comments. This is necessary, for
+! # example, in the case of _POSIX_SOURCE, which is predefined and required
+! # on some systems where configure will not decide to define it.
+! cat >>conftest.undefs <<\_ACEOF
+! s,^[ ]*#[ ]*undef[ ][ ]*[a-zA-Z_][a-zA-Z_0-9]*,/* & */,
+! _ACEOF
+!
+! # Break up conftest.defines because some shells have a limit on the size
+! # of here documents, and old seds have small limits too (100 cmds).
+! echo ' # Handle all the #define templates only if necessary.' >>$CONFIG_STATUS
+! echo ' if grep "^[ ]*#[ ]*define" $tmp/in >/dev/null; then' >>$CONFIG_STATUS
+! echo ' # If there are no defines, we may have an empty if/fi' >>$CONFIG_STATUS
+! echo ' :' >>$CONFIG_STATUS
+! rm -f conftest.tail
+! while grep . conftest.defines >/dev/null
+! do
+! # Write a limited-size here document to $tmp/defines.sed.
+! echo ' cat >$tmp/defines.sed <<CEOF' >>$CONFIG_STATUS
+! # Speed up: don't consider the non `#define' lines.
+! echo '/^[ ]*#[ ]*define/!b' >>$CONFIG_STATUS
+! # Work around the forget-to-reset-the-flag bug.
+! echo 't clr' >>$CONFIG_STATUS
+! echo ': clr' >>$CONFIG_STATUS
+! sed ${ac_max_here_lines}q conftest.defines >>$CONFIG_STATUS
+! echo 'CEOF
+! sed -f $tmp/defines.sed $tmp/in >$tmp/out
+! rm -f $tmp/in
+! mv $tmp/out $tmp/in
+! ' >>$CONFIG_STATUS
+! sed 1,${ac_max_here_lines}d conftest.defines >conftest.tail
+! rm -f conftest.defines
+! mv conftest.tail conftest.defines
+! done
+! rm -f conftest.defines
+! echo ' fi # grep' >>$CONFIG_STATUS
+! echo >>$CONFIG_STATUS
+!
+! # Break up conftest.undefs because some shells have a limit on the size
+! # of here documents, and old seds have small limits too (100 cmds).
+! echo ' # Handle all the #undef templates' >>$CONFIG_STATUS
+! rm -f conftest.tail
+! while grep . conftest.undefs >/dev/null
+! do
+! # Write a limited-size here document to $tmp/undefs.sed.
+! echo ' cat >$tmp/undefs.sed <<CEOF' >>$CONFIG_STATUS
+! # Speed up: don't consider the non `#undef'
+! echo '/^[ ]*#[ ]*undef/!b' >>$CONFIG_STATUS
+! # Work around the forget-to-reset-the-flag bug.
+! echo 't clr' >>$CONFIG_STATUS
+! echo ': clr' >>$CONFIG_STATUS
+! sed ${ac_max_here_lines}q conftest.undefs >>$CONFIG_STATUS
+! echo 'CEOF
+! sed -f $tmp/undefs.sed $tmp/in >$tmp/out
+! rm -f $tmp/in
+! mv $tmp/out $tmp/in
+! ' >>$CONFIG_STATUS
+! sed 1,${ac_max_here_lines}d conftest.undefs >conftest.tail
+! rm -f conftest.undefs
+! mv conftest.tail conftest.undefs
+! done
+! rm -f conftest.undefs
+!
+! cat >>$CONFIG_STATUS <<\_ACEOF
+! # Let's still pretend it is `configure' which instantiates (i.e., don't
+! # use $as_me), people would be surprised to read:
+! # /* config.h. Generated by config.status. */
+! if test x"$ac_file" = x-; then
+! echo "/* Generated by configure. */" >$tmp/config.h
+! else
+! echo "/* $ac_file. Generated by configure. */" >$tmp/config.h
+! fi
+! cat $tmp/in >>$tmp/config.h
+! rm -f $tmp/in
+ if test x"$ac_file" != x-; then
+! if diff $ac_file $tmp/config.h >/dev/null 2>&1; then
+! { echo "$as_me:$LINENO: $ac_file is unchanged" >&5
+! echo "$as_me: $ac_file is unchanged" >&6;}
+ else
+! ac_dir=`(dirname "$ac_file") 2>/dev/null ||
+! $as_expr X"$ac_file" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$ac_file" : 'X\(//\)[^/]' \| \
+! X"$ac_file" : 'X\(//\)$' \| \
+! X"$ac_file" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$ac_file" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+! { if $as_mkdir_p; then
+! mkdir -p "$ac_dir"
+! else
+! as_dir="$ac_dir"
+! as_dirs=
+! while test ! -d "$as_dir"; do
+! as_dirs="$as_dir $as_dirs"
+! as_dir=`(dirname "$as_dir") 2>/dev/null ||
+! $as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$as_dir" : 'X\(//\)[^/]' \| \
+! X"$as_dir" : 'X\(//\)$' \| \
+! X"$as_dir" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$as_dir" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+! done
+! test ! -n "$as_dirs" || mkdir $as_dirs
+! fi || { { echo "$as_me:$LINENO: error: cannot create directory \"$ac_dir\"" >&5
+! echo "$as_me: error: cannot create directory \"$ac_dir\"" >&2;}
+! { (exit 1); exit 1; }; }; }
+!
+! rm -f $ac_file
+! mv $tmp/config.h $ac_file
+ fi
+ else
+! cat $tmp/config.h
+! rm -f $tmp/config.h
+ fi
+! done
+! _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF
+!
+! #
+! # CONFIG_COMMANDS section.
+! #
+! for ac_file in : $CONFIG_COMMANDS; do test "x$ac_file" = x: && continue
+! ac_dest=`echo "$ac_file" | sed 's,:.*,,'`
+! ac_source=`echo "$ac_file" | sed 's,[^:]*:,,'`
+! ac_dir=`(dirname "$ac_dest") 2>/dev/null ||
+! $as_expr X"$ac_dest" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$ac_dest" : 'X\(//\)[^/]' \| \
+! X"$ac_dest" : 'X\(//\)$' \| \
+! X"$ac_dest" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$ac_dest" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+! { if $as_mkdir_p; then
+! mkdir -p "$ac_dir"
+! else
+! as_dir="$ac_dir"
+! as_dirs=
+! while test ! -d "$as_dir"; do
+! as_dirs="$as_dir $as_dirs"
+! as_dir=`(dirname "$as_dir") 2>/dev/null ||
+! $as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+! X"$as_dir" : 'X\(//\)[^/]' \| \
+! X"$as_dir" : 'X\(//\)$' \| \
+! X"$as_dir" : 'X\(/\)' \| \
+! . : '\(.\)' 2>/dev/null ||
+! echo X"$as_dir" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{ s//\1/; q; }
+! /^X\(\/\/\)[^/].*/{ s//\1/; q; }
+! /^X\(\/\/\)$/{ s//\1/; q; }
+! /^X\(\/\).*/{ s//\1/; q; }
+! s/.*/./; q'`
+! done
+! test ! -n "$as_dirs" || mkdir $as_dirs
+! fi || { { echo "$as_me:$LINENO: error: cannot create directory \"$ac_dir\"" >&5
+! echo "$as_me: error: cannot create directory \"$ac_dir\"" >&2;}
+! { (exit 1); exit 1; }; }; }
+!
+! ac_builddir=.
+!
+! if test "$ac_dir" != .; then
+! ac_dir_suffix=/`echo "$ac_dir" | sed 's,^\.[\\/],,'`
+! # A "../" for each directory in $ac_dir_suffix.
+! ac_top_builddir=`echo "$ac_dir_suffix" | sed 's,/[^\\/]*,../,g'`
+! else
+! ac_dir_suffix= ac_top_builddir=
+! fi
+
+! case $srcdir in
+! .) # No --srcdir option. We are building in place.
+! ac_srcdir=.
+! if test -z "$ac_top_builddir"; then
+! ac_top_srcdir=.
+! else
+! ac_top_srcdir=`echo $ac_top_builddir | sed 's,/$,,'`
+! fi ;;
+! [\\/]* | ?:[\\/]* ) # Absolute path.
+! ac_srcdir=$srcdir$ac_dir_suffix;
+! ac_top_srcdir=$srcdir ;;
+! *) # Relative path.
+! ac_srcdir=$ac_top_builddir$srcdir$ac_dir_suffix
+! ac_top_srcdir=$ac_top_builddir$srcdir ;;
+! esac
+
+- # Do not use `cd foo && pwd` to compute absolute paths, because
+- # the directories may not exist.
+- case `pwd` in
+- .) ac_abs_builddir="$ac_dir";;
+- *)
+- case "$ac_dir" in
+- .) ac_abs_builddir=`pwd`;;
+- [\\/]* | ?:[\\/]* ) ac_abs_builddir="$ac_dir";;
+- *) ac_abs_builddir=`pwd`/"$ac_dir";;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_top_builddir=${ac_top_builddir}.;;
+- *)
+- case ${ac_top_builddir}. in
+- .) ac_abs_top_builddir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_top_builddir=${ac_top_builddir}.;;
+- *) ac_abs_top_builddir=$ac_abs_builddir/${ac_top_builddir}.;;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_srcdir=$ac_srcdir;;
+- *)
+- case $ac_srcdir in
+- .) ac_abs_srcdir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_srcdir=$ac_srcdir;;
+- *) ac_abs_srcdir=$ac_abs_builddir/$ac_srcdir;;
+- esac;;
+- esac
+- case $ac_abs_builddir in
+- .) ac_abs_top_srcdir=$ac_top_srcdir;;
+- *)
+- case $ac_top_srcdir in
+- .) ac_abs_top_srcdir=$ac_abs_builddir;;
+- [\\/]* | ?:[\\/]* ) ac_abs_top_srcdir=$ac_top_srcdir;;
+- *) ac_abs_top_srcdir=$ac_abs_builddir/$ac_top_srcdir;;
+- esac;;
+- esac
+
+
+- { echo "$as_me:$LINENO: executing $ac_dest commands" >&5
+- echo "$as_me: executing $ac_dest commands" >&6;}
+- case $ac_dest in
+- default ) case x$CONFIG_HEADERS in xconfig.h:config.in) echo > stamp-h ;; esac ;;
+ esac
+! done
+! _ACEOF
+
+- cat >>$CONFIG_STATUS <<\_ACEOF
+
+ { (exit 0); exit 0; }
+ _ACEOF
+ chmod +x $CONFIG_STATUS
+ ac_clean_files=$ac_clean_files_save
+
+
+ # configure is writing to config.log, and then calls config.status.
+ # config.status does its own redirection, appending to config.log.
+--- 8106,8721 ----
+ fi
+
+ # Have a temporary directory for convenience. Make it in the build tree
+! # simply because there is no reason against having it here, and in addition,
+ # creating and moving files from /tmp can sometimes cause problems.
+! # Hook for its removal unless debugging.
+! # Note that there is a small window in which the directory will not be cleaned:
+! # after its creation but before its name has been assigned to `$tmp'.
+ $debug ||
+ {
+! tmp=
+! trap 'exit_status=$?
+! { test -z "$tmp" || test ! -d "$tmp" || rm -fr "$tmp"; } && exit $exit_status
+! ' 0
+ trap '{ (exit 1); exit 1; }' 1 2 13 15
+ }
+ # Create a (secure) tmp directory for tmp files.
+
+ {
+! tmp=`(umask 077 && mktemp -d "./confXXXXXX") 2>/dev/null` &&
+ test -n "$tmp" && test -d "$tmp"
+ } ||
+ {
+! tmp=./conf$$-$RANDOM
+! (umask 077 && mkdir "$tmp")
+ } ||
+ {
+! $as_echo "$as_me: cannot create a temporary directory in ." >&2
+ { (exit 1); exit 1; }
+ }
+
++ # Set up the scripts for CONFIG_FILES section.
++ # No need to generate them if there are no CONFIG_FILES.
++ # This happens for instance with `./config.status config.h'.
++ if test -n "$CONFIG_FILES"; then
++
++
++ ac_cr=' '
++ ac_cs_awk_cr=`$AWK 'BEGIN { print "a\rb" }' </dev/null 2>/dev/null`
++ if test "$ac_cs_awk_cr" = "a${ac_cr}b"; then
++ ac_cs_awk_cr='\\r'
++ else
++ ac_cs_awk_cr=$ac_cr
++ fi
++
++ echo 'BEGIN {' >"$tmp/subs1.awk" &&
+ _ACEOF
+
+
+! {
+! echo "cat >conf$$subs.awk <<_ACEOF" &&
+! echo "$ac_subst_vars" | sed 's/.*/&!$&$ac_delim/' &&
+! echo "_ACEOF"
+! } >conf$$subs.sh ||
+! { { $as_echo "$as_me:$LINENO: error: could not make $CONFIG_STATUS" >&5
+! $as_echo "$as_me: error: could not make $CONFIG_STATUS" >&2;}
+! { (exit 1); exit 1; }; }
+! ac_delim_num=`echo "$ac_subst_vars" | grep -c '$'`
+! ac_delim='%!_!# '
+! for ac_last_try in false false false false false :; do
+! . ./conf$$subs.sh ||
+! { { $as_echo "$as_me:$LINENO: error: could not make $CONFIG_STATUS" >&5
+! $as_echo "$as_me: error: could not make $CONFIG_STATUS" >&2;}
+! { (exit 1); exit 1; }; }
+
+! if test `sed -n "s/.*$ac_delim\$/X/p" conf$$subs.awk | grep -c X` = $ac_delim_num; then
+! break
+! elif $ac_last_try; then
+! { { $as_echo "$as_me:$LINENO: error: could not make $CONFIG_STATUS" >&5
+! $as_echo "$as_me: error: could not make $CONFIG_STATUS" >&2;}
+! { (exit 1); exit 1; }; }
+! else
+! ac_delim="$ac_delim!$ac_delim _$ac_delim!! "
+ fi
+! done
+! rm -f conf$$subs.sh
+
++ cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
++ cat >>"\$tmp/subs1.awk" <<\\_ACAWK &&
+ _ACEOF
+! sed -n '
+! h
+! s/^/S["/; s/!.*/"]=/
+! p
+! g
+! s/^[^!]*!//
+! :repl
+! t repl
+! s/'"$ac_delim"'$//
+! t delim
+! :nl
+! h
+! s/\(.\{148\}\).*/\1/
+! t more1
+! s/["\\]/\\&/g; s/^/"/; s/$/\\n"\\/
+! p
+! n
+! b repl
+! :more1
+! s/["\\]/\\&/g; s/^/"/; s/$/"\\/
+! p
+! g
+! s/.\{148\}//
+! t nl
+! :delim
+! h
+! s/\(.\{148\}\).*/\1/
+! t more2
+! s/["\\]/\\&/g; s/^/"/; s/$/"/
+! p
+! b
+! :more2
+! s/["\\]/\\&/g; s/^/"/; s/$/"\\/
+! p
+! g
+! s/.\{148\}//
+! t delim
+! ' <conf$$subs.awk | sed '
+! /^[^""]/{
+! N
+! s/\n//
+! }
+! ' >>$CONFIG_STATUS || ac_write_fail=1
+! rm -f conf$$subs.awk
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+! _ACAWK
+! cat >>"\$tmp/subs1.awk" <<_ACAWK &&
+! for (key in S) S_is_set[key] = 1
+! FS = ""
+!
+! }
+! {
+! line = $ 0
+! nfields = split(line, field, "@")
+! substed = 0
+! len = length(field[1])
+! for (i = 2; i < nfields; i++) {
+! key = field[i]
+! keylen = length(key)
+! if (S_is_set[key]) {
+! value = S[key]
+! line = substr(line, 1, len) "" value "" substr(line, len + keylen + 3)
+! len += length(value) + length(field[++i])
+! substed = 1
+! } else
+! len += 1 + keylen
+! }
+!
+! print line
+! }
+!
+! _ACAWK
+! _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+! if sed "s/$ac_cr//" < /dev/null > /dev/null 2>&1; then
+! sed "s/$ac_cr\$//; s/$ac_cr/$ac_cs_awk_cr/g"
+! else
+! cat
+! fi < "$tmp/subs1.awk" > "$tmp/subs.awk" \
+! || { { $as_echo "$as_me:$LINENO: error: could not setup config files machinery" >&5
+! $as_echo "$as_me: error: could not setup config files machinery" >&2;}
+! { (exit 1); exit 1; }; }
+! _ACEOF
+!
+! # VPATH may cause trouble with some makes, so we remove $(srcdir),
+! # ${srcdir} and @srcdir@ from VPATH if srcdir is ".", strip leading and
+! # trailing colons and then remove the whole line if VPATH becomes empty
+! # (actually we leave an empty line to preserve line numbers).
+! if test "x$srcdir" = x.; then
+! ac_vpsub='/^[ ]*VPATH[ ]*=/{
+! s/:*\$(srcdir):*/:/
+! s/:*\${srcdir}:*/:/
+! s/:*@srcdir@:*/:/
+! s/^\([^=]*=[ ]*\):*/\1/
+! s/:*$//
+! s/^[^=]*=[ ]*$//
+! }'
+! fi
+!
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+! fi # test -n "$CONFIG_FILES"
+!
+! # Set up the scripts for CONFIG_HEADERS section.
+! # No need to generate them if there are no CONFIG_HEADERS.
+! # This happens for instance with `./config.status Makefile'.
+! if test -n "$CONFIG_HEADERS"; then
+! cat >"$tmp/defines.awk" <<\_ACAWK ||
+! BEGIN {
+! _ACEOF
+!
+! # Transform confdefs.h into an awk script `defines.awk', embedded as
+! # here-document in config.status, that substitutes the proper values into
+! # config.h.in to produce config.h.
+!
+! # Create a delimiter string that does not exist in confdefs.h, to ease
+! # handling of long lines.
+! ac_delim='%!_!# '
+! for ac_last_try in false false :; do
+! ac_t=`sed -n "/$ac_delim/p" confdefs.h`
+! if test -z "$ac_t"; then
+! break
+! elif $ac_last_try; then
+! { { $as_echo "$as_me:$LINENO: error: could not make $CONFIG_HEADERS" >&5
+! $as_echo "$as_me: error: could not make $CONFIG_HEADERS" >&2;}
+! { (exit 1); exit 1; }; }
+! else
+! ac_delim="$ac_delim!$ac_delim _$ac_delim!! "
+! fi
+! done
+!
+! # For the awk script, D is an array of macro values keyed by name,
+! # likewise P contains macro parameters if any. Preserve backslash
+! # newline sequences.
+!
+! ac_word_re=[_$as_cr_Letters][_$as_cr_alnum]*
+! sed -n '
+! s/.\{148\}/&'"$ac_delim"'/g
+! t rset
+! :rset
+! s/^[ ]*#[ ]*define[ ][ ]*/ /
+! t def
+! d
+! :def
+! s/\\$//
+! t bsnl
+! s/["\\]/\\&/g
+! s/^ \('"$ac_word_re"'\)\(([^()]*)\)[ ]*\(.*\)/P["\1"]="\2"\
+! D["\1"]=" \3"/p
+! s/^ \('"$ac_word_re"'\)[ ]*\(.*\)/D["\1"]=" \2"/p
+! d
+! :bsnl
+! s/["\\]/\\&/g
+! s/^ \('"$ac_word_re"'\)\(([^()]*)\)[ ]*\(.*\)/P["\1"]="\2"\
+! D["\1"]=" \3\\\\\\n"\\/p
+! t cont
+! s/^ \('"$ac_word_re"'\)[ ]*\(.*\)/D["\1"]=" \2\\\\\\n"\\/p
+! t cont
+! d
+! :cont
+! n
+! s/.\{148\}/&'"$ac_delim"'/g
+! t clear
+! :clear
+! s/\\$//
+! t bsnlc
+! s/["\\]/\\&/g; s/^/"/; s/$/"/p
+! d
+! :bsnlc
+! s/["\\]/\\&/g; s/^/"/; s/$/\\\\\\n"\\/p
+! b cont
+! ' <confdefs.h | sed '
+! s/'"$ac_delim"'/"\\\
+! "/g' >>$CONFIG_STATUS || ac_write_fail=1
+!
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+! for (key in D) D_is_set[key] = 1
+! FS = ""
+! }
+! /^[\t ]*#[\t ]*(define|undef)[\t ]+$ac_word_re([\t (]|\$)/ {
+! line = \$ 0
+! split(line, arg, " ")
+! if (arg[1] == "#") {
+! defundef = arg[2]
+! mac1 = arg[3]
+! } else {
+! defundef = substr(arg[1], 2)
+! mac1 = arg[2]
+! }
+! split(mac1, mac2, "(") #)
+! macro = mac2[1]
+! if (D_is_set[macro]) {
+! # Preserve the white space surrounding the "#".
+! prefix = substr(line, 1, index(line, defundef) - 1)
+! print prefix "define", macro P[macro] D[macro]
+! next
+! } else {
+! # Replace #undef with comments. This is necessary, for example,
+! # in the case of _POSIX_SOURCE, which is predefined and required
+! # on some systems where configure will not decide to define it.
+! if (defundef == "undef") {
+! print "/*", line, "*/"
+! next
+! }
+! }
+! }
+! { print }
+! _ACAWK
+! _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+! { { $as_echo "$as_me:$LINENO: error: could not setup config headers machinery" >&5
+! $as_echo "$as_me: error: could not setup config headers machinery" >&2;}
+! { (exit 1); exit 1; }; }
+! fi # test -n "$CONFIG_HEADERS"
+!
+!
+! eval set X " :F $CONFIG_FILES :H $CONFIG_HEADERS :C $CONFIG_COMMANDS"
+! shift
+! for ac_tag
+! do
+! case $ac_tag in
+! :[FHLC]) ac_mode=$ac_tag; continue;;
+! esac
+! case $ac_mode$ac_tag in
+! :[FHL]*:*);;
+! :L* | :C*:*) { { $as_echo "$as_me:$LINENO: error: Invalid tag $ac_tag." >&5
+! $as_echo "$as_me: error: Invalid tag $ac_tag." >&2;}
+! { (exit 1); exit 1; }; };;
+! :[FH]-) ac_tag=-:-;;
+! :[FH]*) ac_tag=$ac_tag:$ac_tag.in;;
+! esac
+! ac_save_IFS=$IFS
+! IFS=:
+! set x $ac_tag
+! IFS=$ac_save_IFS
+! shift
+! ac_file=$1
+! shift
+!
+! case $ac_mode in
+! :L) ac_source=$1;;
+! :[FH])
+! ac_file_inputs=
+! for ac_f
+! do
+! case $ac_f in
+! -) ac_f="$tmp/stdin";;
+! *) # Look for the file first in the build tree, then in the source tree
+! # (if the path is not absolute). The absolute path cannot be DOS-style,
+! # because $ac_f cannot contain `:'.
+! test -f "$ac_f" ||
+! case $ac_f in
+! [\\/$]*) false;;
+! *) test -f "$srcdir/$ac_f" && ac_f="$srcdir/$ac_f";;
+! esac ||
+! { { $as_echo "$as_me:$LINENO: error: cannot find input file: $ac_f" >&5
+! $as_echo "$as_me: error: cannot find input file: $ac_f" >&2;}
+! { (exit 1); exit 1; }; };;
+! esac
+! case $ac_f in *\'*) ac_f=`$as_echo "$ac_f" | sed "s/'/'\\\\\\\\''/g"`;; esac
+! ac_file_inputs="$ac_file_inputs '$ac_f'"
+! done
+!
+! # Let's still pretend it is `configure' which instantiates (i.e., don't
+! # use $as_me), people would be surprised to read:
+! # /* config.h. Generated by config.status. */
+! configure_input='Generated from '`
+! $as_echo "$*" | sed 's|^[^:]*/||;s|:[^:]*/|, |g'
+! `' by configure.'
+! if test x"$ac_file" != x-; then
+! configure_input="$ac_file. $configure_input"
+! { $as_echo "$as_me:$LINENO: creating $ac_file" >&5
+! $as_echo "$as_me: creating $ac_file" >&6;}
+! fi
+! # Neutralize special characters interpreted by sed in replacement strings.
+! case $configure_input in #(
+! *\&* | *\|* | *\\* )
+! ac_sed_conf_input=`$as_echo "$configure_input" |
+! sed 's/[\\\\&|]/\\\\&/g'`;; #(
+! *) ac_sed_conf_input=$configure_input;;
+! esac
+!
+! case $ac_tag in
+! *:-:* | *:-) cat >"$tmp/stdin" \
+! || { { $as_echo "$as_me:$LINENO: error: could not create $ac_file" >&5
+! $as_echo "$as_me: error: could not create $ac_file" >&2;}
+! { (exit 1); exit 1; }; } ;;
+! esac
+! ;;
+ esac
+
+! ac_dir=`$as_dirname -- "$ac_file" ||
+ $as_expr X"$ac_file" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+ X"$ac_file" : 'X\(//\)[^/]' \| \
+ X"$ac_file" : 'X\(//\)$' \| \
+! X"$ac_file" : 'X\(/\)' \| . 2>/dev/null ||
+! $as_echo X"$ac_file" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)[^/].*/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\).*/{
+! s//\1/
+! q
+! }
+! s/.*/./; q'`
+! { as_dir="$ac_dir"
+! case $as_dir in #(
+! -*) as_dir=./$as_dir;;
+! esac
+! test -d "$as_dir" || { $as_mkdir_p && mkdir -p "$as_dir"; } || {
+ as_dirs=
+! while :; do
+! case $as_dir in #(
+! *\'*) as_qdir=`$as_echo "$as_dir" | sed "s/'/'\\\\\\\\''/g"`;; #'(
+! *) as_qdir=$as_dir;;
+! esac
+! as_dirs="'$as_qdir' $as_dirs"
+! as_dir=`$as_dirname -- "$as_dir" ||
+ $as_expr X"$as_dir" : 'X\(.*[^/]\)//*[^/][^/]*/*$' \| \
+ X"$as_dir" : 'X\(//\)[^/]' \| \
+ X"$as_dir" : 'X\(//\)$' \| \
+! X"$as_dir" : 'X\(/\)' \| . 2>/dev/null ||
+! $as_echo X"$as_dir" |
+! sed '/^X\(.*[^/]\)\/\/*[^/][^/]*\/*$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)[^/].*/{
+! s//\1/
+! q
+! }
+! /^X\(\/\/\)$/{
+! s//\1/
+! q
+! }
+! /^X\(\/\).*/{
+! s//\1/
+! q
+! }
+! s/.*/./; q'`
+! test -d "$as_dir" && break
+ done
+! test -z "$as_dirs" || eval "mkdir $as_dirs"
+! } || test -d "$as_dir" || { { $as_echo "$as_me:$LINENO: error: cannot create directory $as_dir" >&5
+! $as_echo "$as_me: error: cannot create directory $as_dir" >&2;}
+ { (exit 1); exit 1; }; }; }
+ ac_builddir=.
+
+! case "$ac_dir" in
+! .) ac_dir_suffix= ac_top_builddir_sub=. ac_top_build_prefix= ;;
+! *)
+! ac_dir_suffix=/`$as_echo "$ac_dir" | sed 's|^\.[\\/]||'`
+! # A ".." for each directory in $ac_dir_suffix.
+! ac_top_builddir_sub=`$as_echo "$ac_dir_suffix" | sed 's|/[^\\/]*|/..|g;s|/||'`
+! case $ac_top_builddir_sub in
+! "") ac_top_builddir_sub=. ac_top_build_prefix= ;;
+! *) ac_top_build_prefix=$ac_top_builddir_sub/ ;;
+! esac ;;
+! esac
+! ac_abs_top_builddir=$ac_pwd
+! ac_abs_builddir=$ac_pwd$ac_dir_suffix
+! # for backward compatibility:
+! ac_top_builddir=$ac_top_build_prefix
+
+ case $srcdir in
+! .) # We are building in place.
+ ac_srcdir=.
+! ac_top_srcdir=$ac_top_builddir_sub
+! ac_abs_top_srcdir=$ac_pwd ;;
+! [\\/]* | ?:[\\/]* ) # Absolute name.
+ ac_srcdir=$srcdir$ac_dir_suffix;
+! ac_top_srcdir=$srcdir
+! ac_abs_top_srcdir=$srcdir ;;
+! *) # Relative name.
+! ac_srcdir=$ac_top_build_prefix$srcdir$ac_dir_suffix
+! ac_top_srcdir=$ac_top_build_prefix$srcdir
+! ac_abs_top_srcdir=$ac_pwd/$srcdir ;;
+! esac
+! ac_abs_srcdir=$ac_abs_top_srcdir$ac_dir_suffix
+
+
++ case $ac_mode in
++ :F)
++ #
++ # CONFIG_FILE
++ #
+
+ case $INSTALL in
+ [\\/$]* | ?:[\\/]* ) ac_INSTALL=$INSTALL ;;
+! *) ac_INSTALL=$ac_top_build_prefix$INSTALL ;;
+ esac
++ _ACEOF
+
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+! # If the template does not know about datarootdir, expand it.
+! # FIXME: This hack should be removed a few years after 2.60.
+! ac_datarootdir_hack=; ac_datarootdir_seen=
+!
+! ac_sed_dataroot='
+! /datarootdir/ {
+! p
+! q
+! }
+! /@datadir@/p
+! /@docdir@/p
+! /@infodir@/p
+! /@localedir@/p
+! /@mandir@/p
+! '
+! case `eval "sed -n \"\$ac_sed_dataroot\" $ac_file_inputs"` in
+! *datarootdir*) ac_datarootdir_seen=yes;;
+! *@datadir@*|*@docdir@*|*@infodir@*|*@localedir@*|*@mandir@*)
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_file_inputs seems to ignore the --datarootdir setting" >&5
+! $as_echo "$as_me: WARNING: $ac_file_inputs seems to ignore the --datarootdir setting" >&2;}
+! _ACEOF
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+! ac_datarootdir_hack='
+! s&@datadir@&$datadir&g
+! s&@docdir@&$docdir&g
+! s&@infodir@&$infodir&g
+! s&@localedir@&$localedir&g
+! s&@mandir@&$mandir&g
+! s&\\\${datarootdir}&$datarootdir&g' ;;
+! esac
+ _ACEOF
+!
+! # Neutralize VPATH when `$srcdir' = `.'.
+! # Shell code in configure.ac might set extrasub.
+! # FIXME: do we really want to maintain this feature?
+! cat >>$CONFIG_STATUS <<_ACEOF || ac_write_fail=1
+! ac_sed_extra="$ac_vpsub
+ $extrasub
+ _ACEOF
+! cat >>$CONFIG_STATUS <<\_ACEOF || ac_write_fail=1
+ :t
+ /@[a-zA-Z_][a-zA-Z_0-9]*@/!b
+! s|@configure_input@|$ac_sed_conf_input|;t t
+! s&@top_builddir@&$ac_top_builddir_sub&;t t
+! s&@top_build_prefix@&$ac_top_build_prefix&;t t
+! s&@srcdir@&$ac_srcdir&;t t
+! s&@abs_srcdir@&$ac_abs_srcdir&;t t
+! s&@top_srcdir@&$ac_top_srcdir&;t t
+! s&@abs_top_srcdir@&$ac_abs_top_srcdir&;t t
+! s&@builddir@&$ac_builddir&;t t
+! s&@abs_builddir@&$ac_abs_builddir&;t t
+! s&@abs_top_builddir@&$ac_abs_top_builddir&;t t
+! s&@INSTALL@&$ac_INSTALL&;t t
+! $ac_datarootdir_hack
+! "
+! eval sed \"\$ac_sed_extra\" "$ac_file_inputs" | $AWK -f "$tmp/subs.awk" >$tmp/out \
+! || { { $as_echo "$as_me:$LINENO: error: could not create $ac_file" >&5
+! $as_echo "$as_me: error: could not create $ac_file" >&2;}
+! { (exit 1); exit 1; }; }
+
+! test -z "$ac_datarootdir_hack$ac_datarootdir_seen" &&
+! { ac_out=`sed -n '/\${datarootdir}/p' "$tmp/out"`; test -n "$ac_out"; } &&
+! { ac_out=`sed -n '/^[ ]*datarootdir[ ]*:*=/p' "$tmp/out"`; test -z "$ac_out"; } &&
+! { $as_echo "$as_me:$LINENO: WARNING: $ac_file contains a reference to the variable \`datarootdir'
+! which seems to be undefined. Please make sure it is defined." >&5
+! $as_echo "$as_me: WARNING: $ac_file contains a reference to the variable \`datarootdir'
+! which seems to be undefined. Please make sure it is defined." >&2;}
+
+! rm -f "$tmp/stdin"
+ case $ac_file in
+! -) cat "$tmp/out" && rm -f "$tmp/out";;
+! *) rm -f "$ac_file" && mv "$tmp/out" "$ac_file";;
+! esac \
+! || { { $as_echo "$as_me:$LINENO: error: could not create $ac_file" >&5
+! $as_echo "$as_me: error: could not create $ac_file" >&2;}
+ { (exit 1); exit 1; }; }
+! ;;
+! :H)
+! #
+! # CONFIG_HEADER
+! #
+ if test x"$ac_file" != x-; then
+! {
+! $as_echo "/* $configure_input */" \
+! && eval '$AWK -f "$tmp/defines.awk"' "$ac_file_inputs"
+! } >"$tmp/config.h" \
+! || { { $as_echo "$as_me:$LINENO: error: could not create $ac_file" >&5
+! $as_echo "$as_me: error: could not create $ac_file" >&2;}
+! { (exit 1); exit 1; }; }
+! if diff "$ac_file" "$tmp/config.h" >/dev/null 2>&1; then
+! { $as_echo "$as_me:$LINENO: $ac_file is unchanged" >&5
+! $as_echo "$as_me: $ac_file is unchanged" >&6;}
+ else
+! rm -f "$ac_file"
+! mv "$tmp/config.h" "$ac_file" \
+! || { { $as_echo "$as_me:$LINENO: error: could not create $ac_file" >&5
+! $as_echo "$as_me: error: could not create $ac_file" >&2;}
+! { (exit 1); exit 1; }; }
+ fi
+ else
+! $as_echo "/* $configure_input */" \
+! && eval '$AWK -f "$tmp/defines.awk"' "$ac_file_inputs" \
+! || { { $as_echo "$as_me:$LINENO: error: could not create -" >&5
+! $as_echo "$as_me: error: could not create -" >&2;}
+! { (exit 1); exit 1; }; }
+ fi
+! ;;
+
+! :C) { $as_echo "$as_me:$LINENO: executing $ac_file commands" >&5
+! $as_echo "$as_me: executing $ac_file commands" >&6;}
+! ;;
+! esac
+
+
++ case $ac_file$ac_mode in
++ "default":C) case x$CONFIG_HEADERS in xconfig.h:config.in) echo > stamp-h ;; esac ;;
+
+ esac
+! done # for ac_tag
+
+
+ { (exit 0); exit 0; }
+ _ACEOF
+ chmod +x $CONFIG_STATUS
+ ac_clean_files=$ac_clean_files_save
+
++ test $ac_write_fail = 0 ||
++ { { $as_echo "$as_me:$LINENO: error: write failure creating $CONFIG_STATUS" >&5
++ $as_echo "$as_me: error: write failure creating $CONFIG_STATUS" >&2;}
++ { (exit 1); exit 1; }; }
++
+
+ # configure is writing to config.log, and then calls config.status.
+ # config.status does its own redirection, appending to config.log.
+***************
+*** 7701,7704 ****
+--- 8737,8744 ----
+ # would make configure fail if this is the last instruction.
+ $ac_cs_success || { (exit 1); exit 1; }
+ fi
++ if test -n "$ac_unrecognized_opts" && test "$enable_option_checking" != no; then
++ { $as_echo "$as_me:$LINENO: WARNING: Unrecognized options: $ac_unrecognized_opts" >&5
++ $as_echo "$as_me: WARNING: Unrecognized options: $ac_unrecognized_opts" >&2;}
++ fi
+
+diff -crN gdb-6.8.orig/sim/ppc/configure.ac gdb-6.8/sim/ppc/configure.ac
+*** gdb-6.8.orig/sim/ppc/configure.ac 2008-03-14 14:35:27.000000000 -0700
+--- gdb-6.8/sim/ppc/configure.ac 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 212,218 ****
+
+ AC_ARG_ENABLE(sim-hardware,
+ [ --enable-sim-hardware=list Specify the hardware to be included in the build.],
+! [hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide"
+ case "${enableval}" in
+ yes) ;;
+ no) AC_MSG_ERROR("List of hardware must be specified for --enable-sim-hardware"); hardware="";;
+--- 212,218 ----
+
+ AC_ARG_ENABLE(sim-hardware,
+ [ --enable-sim-hardware=list Specify the hardware to be included in the build.],
+! [hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide,ethtap"
+ case "${enableval}" in
+ yes) ;;
+ no) AC_MSG_ERROR("List of hardware must be specified for --enable-sim-hardware"); hardware="";;
+***************
+*** 224,230 ****
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes" && test x"$hardware" != x""; then
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+! fi],[hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide"
+ sim_hw_src=`echo $hardware | sed -e 's/,/.c hw_/g' -e 's/^/hw_/' -e s'/$/.c/'`
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes"; then
+--- 224,230 ----
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes" && test x"$hardware" != x""; then
+ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
+! fi],[hardware="cpu,memory,nvram,iobus,htab,disk,trace,register,vm,init,core,pal,com,eeprom,opic,glue,phb,ide,ethtap"
+ sim_hw_src=`echo $hardware | sed -e 's/,/.c hw_/g' -e 's/^/hw_/' -e s'/$/.c/'`
+ sim_hw_obj=`echo $sim_hw_src | sed -e 's/\.c/.o/g'`
+ if test x"$silent" != x"yes"; then
+***************
+*** 744,749 ****
+--- 744,774 ----
+ sim_fpu=
+ fi
+
++ dnl async_io and ethtap only available on linux for now
++ case ${host_os} in
++ *linux*)
++ sim_async_io_src=async_io.c
++ sim_async_io_obj=async_io.o
++ ;;
++ *)
++ AC_MSG_NOTICE([Removing 'ethtap' device on non-linux host])
++ sim_hw_src=`echo $sim_hw_src | sed -e 's/hw_ethtap[.]c//g'`
++ sim_hw_obj=`echo $sim_hw_obj | sed -e 's/hw_ethtap[.]o//g'`
++ if test x"$silent" != x"yes"; then
++ echo "Setting hardware to $sim_hw_src, $sim_hw_obj"
++ fi
++ sim_async_io_src=
++ sim_async_io_obj=
++ ;;
++ esac
++ case ${sim_hw_src} in
++ *hw_ethtap*)
++ AC_DEFINE(HAVE_ETHTAP, 1, [Define if ethtap device is built (linux host only)])
++ ;;
++ *)
++ ;;
++ esac
++
+ dnl Check for exe extension
+ AC_EXEEXT
+
+***************
+*** 798,803 ****
+--- 823,830 ----
+ AC_SUBST(sim_targ_vals)
+ AC_SUBST(sim_fpu_cflags)
+ AC_SUBST(sim_fpu)
++ AC_SUBST(sim_async_io_src)
++ AC_SUBST(sim_async_io_obj)
+
+ AC_OUTPUT(Makefile,
+ [case x$CONFIG_HEADERS in xconfig.h:config.in) echo > stamp-h ;; esac])
+diff -crN gdb-6.8.orig/sim/ppc/crc32.c gdb-6.8/sim/ppc/crc32.c
+*** gdb-6.8.orig/sim/ppc/crc32.c 1969-12-31 16:00:00.000000000 -0800
+--- gdb-6.8/sim/ppc/crc32.c 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 0 ****
+--- 1,75 ----
++ /* Simple, table-driven 'ethernet' CRC32.
++ *
++ * Assumes bytes are transmitted as little-endian bit-stream.
++ *
++ * Written by T. Straumann, released into public domain.
++ *
++ */
++ #include <inttypes.h>
++
++ #define CRCPOLY_LE 0xedb88320
++
++ static uint32_t crc32tbl[256] = {0};
++
++ uint32_t
++ crc32_le(uint32_t crc, uint8_t *buf, unsigned len)
++ {
++ uint8_t i;
++ while (len--) {
++ i = crc ^ *buf++;
++ crc = (crc >> 8) ^ crc32tbl[i];
++ }
++ return crc;
++ }
++
++ uint32_t
++ crc32_le_eth(uint8_t *buf, unsigned len)
++ {
++ return crc32_le(-1,buf,len) ^ (-1);
++ }
++
++ static void crc32_inittab()
++ {
++ uint32_t i,j;
++ for ( i=0; i<256; i++ ) {
++
++ uint32_t crc = i;
++
++ for ( j=0; j<8; j++ )
++ crc = (crc>>1) ^ ((crc&1) ? CRCPOLY_LE : 0);
++
++ crc32tbl[i] = crc;
++ }
++ }
++
++ #if DO_MAIN_TEST
++
++ #include <stdio.h>
++ #include <string.h>
++
++ int main(int argc, char **argv)
++ {
++ char tst[9+4+4]={0};
++ char *str;
++ int i;
++ uint32_t crc;
++
++ crc32_inittab();
++
++ strcpy(tst,"123456789");
++
++ str = argc > 1 ? argv[1] : tst;
++
++ crc=crc32_le_eth(str,strlen(str));
++ printf("CRC-LE: 0x%08x (%u)\n", crc, crc);
++
++ if ( str == tst ) {
++ if ( crc != 0xCBF43926 ) {
++ printf("Should be 0xCBF43926\n");
++ } else {
++ printf("Test OK\n");
++ }
++ }
++ return 0;
++ }
++ #endif
+diff -crN gdb-6.8.orig/sim/ppc/debug.c gdb-6.8/sim/ppc/debug.c
+*** gdb-6.8.orig/sim/ppc/debug.c 1999-04-15 18:35:08.000000000 -0700
+--- gdb-6.8/sim/ppc/debug.c 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 60,65 ****
+--- 60,68 ----
+ { trace_eeprom_device, "eeprom-device" },
+ { trace_file_device, "file-device" },
+ { trace_glue_device, "glue-device" },
++ #ifdef HAVE_ETHTAP
++ { trace_ethtap_device, "ethtap-device" },
++ #endif
+ { trace_halt_device, "halt-device" },
+ { trace_htab_device, "htab-device" },
+ { trace_icu_device, "icu-device" },
+diff -crN gdb-6.8.orig/sim/ppc/debug.h gdb-6.8/sim/ppc/debug.h
+*** gdb-6.8.orig/sim/ppc/debug.h 1999-04-15 18:35:08.000000000 -0700
+--- gdb-6.8/sim/ppc/debug.h 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 42,47 ****
+--- 42,50 ----
+ trace_eeprom_device,
+ trace_file_device,
+ trace_glue_device,
++ #ifdef HAVE_ETHTAP
++ trace_ethtap_device,
++ #endif
+ trace_halt_device,
+ trace_htab_device,
+ trace_icu_device,
+diff -crN gdb-6.8.orig/sim/ppc/hw_ethtap.c gdb-6.8/sim/ppc/hw_ethtap.c
+*** gdb-6.8.orig/sim/ppc/hw_ethtap.c 1969-12-31 16:00:00.000000000 -0800
+--- gdb-6.8/sim/ppc/hw_ethtap.c 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 0 ****
+--- 1,745 ----
++ /* This file is part of the program psim.
++
++ Copyright (C) 1994-1996, Andrew Cagney <cagney@highland.com.au>
++
++ 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.
++
++ This file was written by Till Straumann, 2008.
++
++ */
++
++ #ifndef _HW_ETHTAP_C_
++ #define _HW_ETHTAP_C_
++
++ #include "crc32.c"
++
++ #include "device_table.h"
++
++ #include "psim.h"
++ #include "events.h"
++ #include "async_io.h"
++
++ #include <unistd.h>
++ #include <fcntl.h>
++ #include <signal.h>
++ #include <errno.h>
++ #include <poll.h>
++ #include <stdlib.h>
++
++ #include <sys/ioctl.h>
++ #include <net/if.h>
++ #include <linux/if_tun.h>
++
++ #undef DEBUG_RX_RAW
++
++ /* DEVICE
++
++
++ ethtap -- a trivial ethernet interface that directs all traffic
++ to a 'tap' interface on the host computer (a 'tap' interface
++ requires a special host-os driver which routes packets written
++ to / read from a device special file to a 'soft' network interface
++ on the host. Such a driver is e.g., available on linux (tun/tap)).
++
++ NOTE: you normally need superuser privileges to create a 'tap'
++ interface on the host, i.e., you need these privileges to run psim.
++ Alternatively (linux), the sysadmin can create a 'persistent'
++ 'tap' device and assign it to a specific user (tuncfg -u <user>).
++ In this case, the <user> must also have read/write access to
++ the /dev/net/tun device (it is not a problem to make this
++ device node world-read-writeable because ordinary users
++ lack the CAP_NET capability and may not create new 'tap'
++ devices even if they are granted write-access to /dev/net/tun
++ (RTM).
++
++ DESCRIPTION
++
++ The ethtap device is a very simple emulation of a ethernet
++ chip. It does not implement a real FIFO or descriptor rings
++ but 'cheats' by relying on the fact that PSIM is a single-threaded,
++ monolithic program:
++
++ The device contains two register pairs (one for RX, one for TX)
++ which serve as a '1-element' descriptor list.
++
++ The register pairs consist of a 'buffer-address' and
++ 'buffer-size/status' register. The 'buffer-address' register
++ must always be written first. When the 'buffer-size' register is
++ written buffer 'ownership' is transferred to ethtap and
++ the user must wait for ethtap changing a status-bit in the
++ 'size' register before accessing the buffer again.
++
++ However, because psim is single-threaded this synchronization
++ is really simple: E.g., during transmission the driver writes
++ a buffer address to the tx-buffer-address register and then
++ writes the 'size' register. At this point, the ethtap device
++ uses DMA to copy the buffer to an internal area. Because
++ psim does not use a separate thread for DMA this means that
++ when the write operation to the 'size' register completes the
++ DMA is already complete -- very unlike real-life...
++
++ Packet reception is equally simple: the user writes a buffer
++ address and a size to the rx register pair. If data is
++ available then writing the 'size' register triggers a DMA
++ operation which is complete when the write-register operation
++ returns. If, however, no data is available then ethtap
++ retains ownership of the buffer (RX_STA_RDY bit is NOT set)
++ and the user must wait for data to arrive (e.g., by using
++ interrupts).
++
++
++ PROPERTIES
++
++
++ reg = <address> <size> (required)
++
++ Specify the address (within the parent bus) that this device is to
++ live. The address must be 4 byte aligned.
++
++ tun-device = <string> (optional)
++ name of the 'tun' device to open; defaults to "/dev/net/tun"
++
++ tap-if-name = <string> (optional)
++ name of the 'tap' interface (on the host) to use; defaults to
++ "tap0"
++
++ hw-address = <string> (optional)
++ ethernet address of this device; a string of the format, e.g.,
++ "00:00:3a:12:34:56"
++
++ enable-crc = <boolean> (optional)
++ compute crc32 and append to packet received by this device.
++ The driver must be prepared to handle (and maybe check)
++ the crc32 -- the number of received bytes contains the
++ 4 bytes used by the crc.
++ CRC generation is ultimately controlled by the CRCEN bit
++ in the CSR; this property just defines the initial setting.
++ Defaults to 'false'.
++
++ EXAMPLES
++
++
++ Enable tracing of the device:
++
++ | -t ethtap-device \
++
++
++ Create source, bitwize-and, and sink glue devices. Since the
++ device at address <<0x10000>> is of size <<8>> it will have two
++ output interrupt ports.
++
++ | -o '/iobus@0xf0000000/ethtap@0x10000/reg 0x10000 0x40' \
++ | -o '/iobus@0xf0000000/ethtap@0x10000/tun-device "/dev/net/tun"' \
++ | -o '/iobus@0xf0000000/ethtap@0x10000/tap-ifname "tap0"' \
++ | -o '/iobus@0xf0000000/ethtap@0x10000/hw-address "00:00:00:22:11:00"' \
++ | -o '/iobus@0xf0000000/ethtap@0x10000/enable-crc false'
++
++
++ BUGS/LIMITATIONS
++
++ This device only works on host-oses with tun/tap support and
++ usually requires psim to be executed with appropriate privileges
++ or a properly setup 'persistent' tap-device.
++
++ This device works only on host-oses with
++
++ */
++
++ #define TX_BUFSZ 2048
++ #define RX_BUFSZ 2048
++
++ #define HW_VERSION 1
++
++ /* Register indices */
++ #define TST_VAL_REG 0
++ #define TST_TX_BUF_REG 1
++ #define TST_TX_STA_REG 2
++ #define TST_VER_REG 3
++
++ #define TST_RX_BUF_REG 4
++ #define TST_RX_STA_REG 5
++ #define TST_IEN_REG 6
++ #define TST_IRQ_REG 7
++
++ #define TST_MACA0_REG 8
++ #define TST_MACA1_REG 9
++
++ #define TST_CSR_REG 10
++
++ #define TST_NUM_REGS 16 /* must be power of 2 */
++
++ #define TST_TX_CNT_MSK 0xffff
++ #define TST_TX_STA_LST (1<<16) /* last chunk */
++ #define TST_TX_STA_DONE (1<<31) /* TX done */
++
++ #define TST_TX_ERR_NOSPC (1<<20) /* buffer too small */
++ #define TST_TX_ERR_DMA (1<<21) /* DMA error */
++ #define TST_TX_ERR_NOFD (1<<22) /* no file descriptor */
++ #define TST_TX_ERR_WR (1<<23) /* file write error */
++
++ #define TST_TX_ERR_MSK (0xffff0000 & ~(TST_TX_STA_LST|TST_TX_STA_DONE))
++
++ #define TST_RX_CNT_MSK 0xffff
++ #define TST_RX_STA_RDY (1<<31) /* data available */
++
++
++ #define TST_RX_ERR_NOSPC (1<<20) /* buffer too small */
++ #define TST_RX_ERR_DMA (1<<21) /* DMA error */
++ #define TST_RX_ERR_RD (1<<23) /* file read error */
++
++ #define TST_RX_IRQ (1<<0)
++
++ #define TST_CSR_PROM (1<<0) /* promiscuous */
++ #define TST_CSR_CRCEN (1<<1) /* enable CRC */
++
++ typedef struct _hw_ethtap_device {
++ int space;
++ unsigned_word base,bound;
++ unsigned_4 val;
++ unsigned_4 tx_base;
++ unsigned_4 tx_sta;
++ unsigned_4 tx_idx;
++ unsigned_4 rx_base;
++ unsigned_4 rx_sta;
++ unsigned_4 ien;
++ unsigned_4 ipend;
++ unsigned_4 ilast;
++ unsigned_4 csr;
++ int tx_fd, tx_ad;
++ int rx_fd, rx_ad;
++ int rx_space;
++ const char *ifnam;
++ int rx_len;
++ unsigned_1 enaddr[8];
++ unsigned_1 tx_buf[TX_BUFSZ];
++ unsigned_1 rx_buf[RX_BUFSZ];
++ device *next;
++ } hw_ethtap_device;
++
++ static device *thedevs = 0;
++
++ static void update_irq(device *me, hw_ethtap_device *ethtap)
++ {
++ unsigned_4 inew = ethtap->ien & ethtap->ipend;
++ if ( inew != ethtap->ilast ) {
++ device_interrupt_event(me, 0, inew ? 0 : 1, NULL, 0);
++ ethtap->ilast = inew;
++ }
++ }
++
++ static int
++ filter_dest(hw_ethtap_device *ethtap)
++ {
++ int i,sum,match;
++
++ for ( match=1, sum = i = 0; i<6; i++ ) {
++ if ( ethtap->rx_buf[i] != ethtap->enaddr[i] )
++ match=0;
++ sum += ethtap->rx_buf[i];
++ }
++
++ /* match broadcast addr is equivalent to sum == 6*255 */
++
++ return ( !match && sum != 6*255 );
++ }
++
++ static int
++ fill_rxbuf(device *me, hw_ethtap_device *ethtap)
++ {
++ int got;
++ uint32_t crc;
++
++ if ( ethtap->rx_len ) {
++ device_error(me, "Internal Error; rx_len should be zero\n");
++ }
++
++ got = hwAsyncIoRead(ethtap->rx_ad, ethtap->rx_buf, RX_BUFSZ);
++
++ if ( ( ethtap->csr & TST_CSR_CRCEN ) && got > 0 ) {
++ crc = H2BE_4(crc32_le_eth(ethtap->rx_buf, got));
++
++ memcpy(ethtap->rx_buf+got, &crc, sizeof(crc));
++
++ got += sizeof(crc);
++ }
++
++
++ #ifdef DEBUG_RX_RAW
++ {
++ int i;
++
++ printf("#VVVVVVVV#\n");
++ for ( i=0; i<got; ) {
++ printf("%02X ",ethtap->rx_buf[i]);
++ if ( 0 == (++i & 0xf) )
++ fputc('\n',stdout);
++ }
++ if ( i & 0xf )
++ fputc('\n',stdout);
++ printf("#^^^^^^^^#\n");
++ }
++ #endif
++
++ if ( got >= 0 && ! ( ethtap->csr & TST_CSR_PROM ) ) {
++ /* filter destination */
++ if ( got < 6 || filter_dest(ethtap) )
++ return -1;
++ }
++
++ ethtap->rx_len = got;
++
++ return 0;
++ }
++
++
++ static void
++ rx_input(void *me)
++ {
++ hw_ethtap_device *ethtap = (hw_ethtap_device*)device_data(me);
++ int cnt = ethtap->rx_sta & TST_RX_CNT_MSK;
++ int got;
++ int lvl;
++
++ /* could and should filter HW address even if
++ * no buffer is available; not doing so is
++ * simpler, however...
++ */
++
++ if ( cnt ) {
++
++ if ( ethtap->rx_sta & TST_RX_STA_RDY )
++ device_error(me, "rx_input: INTERNAL ERROR; should not get here with DONE set\n");
++
++ lvl = hwAsyncIoBlock();
++
++ got = ethtap->rx_len;
++ ethtap->rx_len = 0;
++
++ if ( got > 0 ) {
++ if ( cnt < got ) {
++ ethtap->rx_sta |= TST_RX_ERR_NOSPC;
++ got = cnt;
++ }
++ if ( got != device_dma_write_buffer(device_parent(me), ethtap->rx_buf, ethtap->rx_space, ethtap->rx_base, got, 0) ) {
++ ethtap->rx_sta |= TST_RX_ERR_DMA;
++ } else {
++ ethtap->rx_sta = TST_RX_STA_RDY | got;
++ }
++ } else if ( 0 == got || EAGAIN == errno ) {
++ /* no more data */
++ ethtap->ipend &= ~TST_RX_IRQ;
++ } else {
++ ethtap->rx_sta |= TST_RX_ERR_RD;
++ }
++ update_irq( me, ethtap );
++
++ if ( (ethtap->ipend & TST_RX_IRQ) ) {
++ /* try to read more data */
++ fill_rxbuf(me, ethtap);
++ }
++
++ hwAsyncIoUnblock(lvl);
++ }
++ }
++
++ static void
++ hw_ethtap_cb(int fd, unsigned reasonBitmask, void *uarg)
++ {
++ hw_ethtap_device *p;
++ device *me = uarg;
++
++ p = (hw_ethtap_device*)device_data(me);
++
++ if ( ! (reasonBitmask & ASYNC_IO_READ_POSSIBLE) ) {
++ return;
++ }
++
++ if ( ! (p->ipend & TST_RX_IRQ) ) {
++
++ if ( fill_rxbuf(me, p) )
++ return;
++
++ p->ipend |= TST_RX_IRQ;
++ event_queue_schedule_after_signal(
++ psim_event_queue(device_system(me)),
++ 1LL /* now */,
++ rx_input,
++ me);
++ }
++ }
++
++ #define DFLT_TUN_NAM "/dev/net/tun"
++
++ static void
++ hw_ethtap_device_init_data(device *me)
++ {
++ struct ifreq ifr;
++ int status;
++ const char *tun_nam = DFLT_TUN_NAM;
++ reg_property_spec unit;
++ hw_ethtap_device *ethtap = (hw_ethtap_device*)device_data(me);
++ int space;
++ unsigned_word address;
++ unsigned size;
++ int reg;
++
++ reg = 0;
++ do {
++
++ /* find and decode the reg property -- skipping 0-sized pairs */
++ if (!device_find_reg_array_property(me, "reg", reg++, &unit))
++ device_error(me, "missing or invalid reg entry %d", reg);
++
++ } while (
++ ! device_address_to_attach_address(device_parent(me), &unit.address,
++ &space, &address, me) ||
++ ! device_size_to_attach_size(device_parent(me), &unit.size, &size, me));
++
++ ethtap->base = address;
++ ethtap->bound = address+size;
++ ethtap->space = space;
++
++ DTRACE(ethtap, ("initializing addresses (space, base[size] - %d, (0x%x[0x%x])\n", space, address, size));
++
++ ethtap->val = 0xaffecafe;
++
++ if ( ethtap->rx_fd >= 0 ) {
++ if ( (status = hwAsyncIoUnregister(ethtap->rx_ad, hw_ethtap_cb, me)) ) {
++ device_error(me, "hwAsyncIoUnregister(unregister rx_ad) failed: %i\n", status);
++ }
++ close(ethtap->rx_fd);
++ }
++
++ #ifdef TEST_PIPE
++ if ( ethtap->tx_fd >= 0 ) {
++ #ifdef TEST_POLLSTUFF
++ if ( (status = hwAsyncIoUnregister(ethtap->tx_ad, hw_ethtap_cb, me)) ) {
++ device_error(me, "hwAsyncIoUnregister(unregister tx_ad) failed: %i\n", status);
++ }
++ #endif
++ close(ethtap->tx_fd);
++ }
++
++ ethtap->rx_fd = open("rpeip",O_RDWR | O_NONBLOCK);
++
++ if ( ethtap->rx_fd < 0 ) {
++ device_error(me, "open(RX-pipe) failed: %s\n", strerror(errno));
++ }
++
++ if ( (ethtap->rx_ad = hwAsyncIoRegister(ethtap->rx_fd, hw_ethtap_cb, me)) < 0 ) {
++ device_error(me, "hwAsyncIoRegister(rx_fd) failed: %i\n", ethtap->rx_ad);
++ }
++
++ ethtap->tx_fd = open("tpeip",O_RDWR | O_NONBLOCK);
++
++ ethtap->rx_len = 0;
++
++ if ( ethtap->tx_fd < 0 ) {
++ device_error(me, "open(TX-pipe) failed: %s\n", strerror(errno));
++ }
++
++ #ifdef TEST_POLLSTUFF
++ if ( (ethtap->tx_ad = hwAsyncIoRegister(ethtap->tx_fd, hw_ethtap_cb, me)) < 0 ) {
++ device_error(me, "hwAsyncIoRegister(tx_fd) failed: %i\n", ethtap->tx_ad);
++ }
++ #endif
++ #else
++
++ if ( device_find_property(me, "tun-device") ) {
++ tun_nam = device_find_string_property(me, "tun-device");
++ }
++
++ ethtap->rx_fd = ethtap->tx_fd = open(tun_nam, O_RDWR | O_NONBLOCK);
++
++ if ( device_find_property(me, "tap-if-name") ) {
++ ethtap->ifnam = device_find_string_property(me, "tap-if-name");
++ } else {
++ ethtap->ifnam = "tap0";
++ }
++
++ if ( ethtap->tx_fd < 0 ) {
++ device_error(me, "open(%s) %s\n", tun_nam, strerror(errno));
++ }
++
++ memset(&ifr, 0, sizeof(ifr));
++ strncpy(ifr.ifr_name, ethtap->ifnam, IFNAMSIZ);
++ ifr.ifr_flags = IFF_TAP | IFF_NO_PI;
++
++ if ( ioctl(ethtap->rx_fd, TUNSETIFF, &ifr) ) {
++ device_error(me, "ioctl(TUNSETIFF) %s\n", strerror(errno));
++ }
++
++ if ( (ethtap->tx_ad = ethtap->rx_ad = hwAsyncIoRegister(ethtap->rx_fd, hw_ethtap_cb, me)) < 0 ) {
++ device_error(me, "hwAsyncIoRegister(rx_fd) failed: %i\n", ethtap->rx_ad);
++ }
++ #endif
++
++ ethtap->tx_idx = 0;
++ ethtap->tx_sta = 0;
++
++ ethtap->rx_sta = 0;
++
++ ethtap->ien = 0;
++ ethtap->ipend = 0;
++
++ ethtap->ilast = ethtap->ien & ethtap->ipend;
++
++ /* enq in linked list of all devices */
++ ethtap->next = thedevs;
++ thedevs = me;
++
++ if ( device_find_property(me, "enable-crc") ) {
++ if ( device_find_boolean_property(me, "enable-crc") ) {
++ ethtap->csr |= TST_CSR_CRCEN;
++ }
++ }
++
++ if ( device_find_property(me, "hw-address") ) {
++ if ( 6 != sscanf(
++ device_find_string_property(me, "hw-address"),
++ "%hhx:%hhx:%hhx:%hhx:%hhx:%hhx",
++ ethtap->enaddr + 0,
++ ethtap->enaddr + 1,
++ ethtap->enaddr + 2,
++ ethtap->enaddr + 3,
++ ethtap->enaddr + 4,
++ ethtap->enaddr + 5) ) {
++ device_error(me, "Invalid hw-address; must be 6 hex octets separated by ':'");
++ }
++ } else {
++ /* mock up a dummy address */
++ memset(ethtap->enaddr, 0, sizeof(ethtap->enaddr));
++ ethtap->enaddr[3] = 0x0a;
++ ethtap->enaddr[4] = 0x22;
++ ethtap->enaddr[5] = 0x3f;
++ }
++
++ /* interrupt line is active-low */
++ device_interrupt_event(me, 0, 1, NULL, 0);
++ }
++
++ static void
++ hw_ethtap_init_address(device *me)
++ {
++ /* attach to my parent */
++ generic_device_init_address(me);
++
++ DTRACE(ethtap, ("fmt %s", "ethtap"));
++ }
++
++ static unsigned
++ hw_ethtap_io_read_buffer_callback(device *me,
++ void *dest,
++ int space,
++ unsigned_word addr,
++ unsigned nr_bytes,
++ cpu *processor,
++ unsigned_word cia)
++ {
++ int i;
++ unsigned_4 v;
++
++ hw_ethtap_device *ethtap = (hw_ethtap_device*)device_data(me);
++
++ if ( nr_bytes % sizeof(unsigned_4) != 0 || addr % sizeof(unsigned_4) != 0 )
++ device_error(me, "missaligned read access (%d:0x%lx:%d) not supported",
++ space, (unsigned long)addr, nr_bytes);
++
++ if ( space != ethtap->space || addr < ethtap->base || addr + nr_bytes > ethtap->bound )
++ device_error(me, "address out of bounds; read access (%d:0x%lx:%d)\n",
++ space, (unsigned long)addr, nr_bytes);
++
++ addr -= ethtap->base;
++
++ for (i=0; i<nr_bytes/sizeof(unsigned_4); i++) {
++ switch ( (addr/sizeof(unsigned_4) + i) & (TST_NUM_REGS-1)) {
++ case TST_VAL_REG: v = ethtap->val; break;
++
++ case TST_TX_BUF_REG: v = ethtap->tx_base; break;
++ case TST_TX_STA_REG: v = ethtap->tx_sta; break;
++
++ case TST_RX_BUF_REG: v = ethtap->rx_base; break;
++ case TST_RX_STA_REG: v = ethtap->rx_sta; break;
++
++ case TST_VER_REG: v = HW_VERSION; break;
++
++ case TST_IEN_REG: v = ethtap->ien; break;
++ case TST_IRQ_REG: v = ethtap->ipend; break;
++
++ case TST_MACA0_REG:
++ memcpy(&v, ethtap->enaddr, 4);
++ v = BE2H_4(v); break;
++
++ case TST_MACA1_REG: memcpy(&v, ethtap->enaddr+4, 4);
++ v = BE2H_4(v); break;
++
++ case TST_CSR_REG: v = ethtap->csr; break;
++
++ default: v = -1; break;
++ }
++ ((unsigned_word*)dest)[i] = H2BE_4(v);
++ }
++
++ DTRACE(ethtap, ("read - %d (0x%lx), val 0x%08x\n",
++ 0, (unsigned long) addr, v));
++
++ return nr_bytes;
++ }
++
++
++ static unsigned
++ hw_ethtap_io_write_buffer_callback(device *me,
++ const void *source,
++ int space,
++ unsigned_word addr,
++ unsigned nr_bytes,
++ cpu *processor,
++ unsigned_word cia)
++ {
++ int i;
++ unsigned cnt;
++ unsigned_4 v;
++
++ hw_ethtap_device *ethtap = (hw_ethtap_device*)device_data(me);
++
++ if ( nr_bytes % sizeof(unsigned_4) != 0 || addr % sizeof(unsigned_4) != 0 )
++ device_error(me, "missaligned write access (%d:0x%lx:%d) not supported",
++ space, (unsigned long)addr, nr_bytes);
++
++ if ( space != ethtap->space || addr < ethtap->base || addr + nr_bytes > ethtap->bound )
++ device_error(me, "address out of bounds; write access (%d:0x%lx:%d)\n",
++ space, (unsigned long)addr, nr_bytes);
++
++ addr -= ethtap->base;
++
++ for (i=0; i<nr_bytes/sizeof(unsigned_4); i++) {
++
++ v = BE2H_4(((unsigned_4*)source)[i]);
++
++ switch ( (addr/sizeof(unsigned_4) + i) & (TST_NUM_REGS - 1) ) {
++
++ case TST_VAL_REG:
++ ethtap->val = v;
++ device_interrupt_event(me, 0, (ethtap->val&1), processor, cia);
++ break;
++
++ case TST_TX_BUF_REG:
++ ethtap->tx_base = v;
++ break;
++
++ case TST_TX_STA_REG:
++ ethtap->tx_sta = (v & (TST_TX_CNT_MSK | TST_TX_STA_LST));
++ cnt = (ethtap->tx_sta & TST_TX_CNT_MSK);
++ if ( ethtap->tx_idx + cnt <= TX_BUFSZ ) {
++ if ( cnt != device_dma_read_buffer(
++ device_parent(me),
++ ethtap->tx_buf + ethtap->tx_idx,
++ space,
++ ethtap->tx_base,
++ cnt) ) {
++ ethtap->tx_sta |= TST_TX_ERR_DMA;
++ }
++ } else {
++ ethtap->tx_sta |= TST_TX_ERR_NOSPC;
++ }
++ ethtap->tx_idx += cnt;
++
++ if ( ethtap->tx_sta & TST_TX_STA_LST ) {
++ if ( ethtap->tx_fd >= 0 ) {
++ if ( ! (ethtap->tx_sta & TST_TX_ERR_MSK) ) {
++ if ( ethtap->tx_idx !=
++ #if defined(TEST_PIPE) && defined(TEST_POLLSTUFF)
++ hwAsyncIoWrite(ethtap->tx_ad, ethtap->tx_buf, ethtap->tx_idx)
++ #else
++ write(ethtap->tx_fd, ethtap->tx_buf, ethtap->tx_idx)
++ #endif
++ ) {
++ ethtap->tx_sta |= TST_TX_ERR_WR;
++ }
++ }
++ } else {
++ ethtap->tx_sta |= TST_TX_ERR_NOFD;
++ }
++
++ ethtap->tx_idx = 0;
++ }
++ ethtap->tx_sta |= TST_TX_STA_DONE;
++ break;
++
++ case TST_RX_BUF_REG:
++ ethtap->rx_base = v;
++ break;
++
++ case TST_RX_STA_REG:
++ ethtap->rx_sta = (v & TST_RX_CNT_MSK);
++ if ( (ethtap->ipend & TST_RX_IRQ) ) {
++ rx_input(me);
++ }
++ break;
++
++ case TST_IEN_REG:
++ ethtap->ien = v;
++ update_irq(me, ethtap);
++ break;
++
++ case TST_CSR_REG:
++ ethtap->csr = v;
++ break;
++
++ default:
++ break;
++ }
++
++ DTRACE(ethtap, ("write - %d (0x%lx), value 0x%08x\n",
++ 0, (unsigned long) addr, v));
++ }
++
++
++ return nr_bytes;
++ }
++
++ static device_callbacks const hw_ethtap_callbacks = {
++ { hw_ethtap_init_address, hw_ethtap_device_init_data },
++ { NULL, }, /* address */
++ { hw_ethtap_io_read_buffer_callback, hw_ethtap_io_write_buffer_callback, },
++ { NULL, }, /* DMA */
++ { NULL, NULL, NULL }, /* interrupt */
++ { NULL, }, /* unit */
++ NULL, /* instance */
++ };
++
++
++ static void *
++ hw_ethtap_create(const char *name,
++ const device_unit *unit_address,
++ const char *args)
++ {
++ /* create the descriptor */
++ hw_ethtap_device *ethtap = ZALLOC(hw_ethtap_device);
++
++ crc32_inittab();
++
++ ethtap->rx_fd = ethtap->tx_fd = -1;
++
++ return ethtap;
++ }
++
++
++ const device_descriptor hw_ethtap_device_descriptor[] = {
++ { "ethtap", hw_ethtap_create, &hw_ethtap_callbacks },
++ { NULL },
++ };
++
++ #endif /* _HW_ETHTAP_C_ */
+diff -crN gdb-6.8.orig/sim/ppc/Makefile.in gdb-6.8/sim/ppc/Makefile.in
+*** gdb-6.8.orig/sim/ppc/Makefile.in 2006-05-31 08:14:45.000000000 -0700
+--- gdb-6.8/sim/ppc/Makefile.in 2009-02-05 16:56:20.000000000 -0800
+***************
+*** 488,494 ****
+ device_table.c \
+ cap.c \
+ mon.c \
+! options.c
+
+ LIB_SRC = \
+ $(PACKAGE_SRC) \
+--- 488,495 ----
+ device_table.c \
+ cap.c \
+ mon.c \
+! options.c \
+! @sim_async_io_src@
+
+ LIB_SRC = \
+ $(PACKAGE_SRC) \
+***************
+*** 536,542 ****
+ psim.o \
+ $(PACKAGE_OBJ) \
+ $(HW_OBJ) \
+! options.o
+
+
+ GDB_OBJ = gdb-sim.o sim_calls.o @sim_callback@
+--- 537,544 ----
+ psim.o \
+ $(PACKAGE_OBJ) \
+ $(HW_OBJ) \
+! options.o \
+! @sim_async_io_obj@
+
+
+ GDB_OBJ = gdb-sim.o sim_calls.o @sim_callback@
+***************
+*** 823,829 ****
+--- 825,833 ----
+ hw_core.o: hw_core.c $(DEVICE_TABLE_H) $(COREFILE_H)
+ hw_disk.o: hw_disk.c $(DEVICE_TABLE_H) $(PK_H)
+ hw_eeprom.o: hw_eeprom.c $(DEVICE_TABLE_H)
++ hw_ethtap.o: hw_ethtap.c $(DEVICE_TABLE_H) async_io.h $(PSIM_H) $(EVENTS_H)
+ hw_glue.o: hw_glue.c $(DEVICE_TABLE_H)
++ hw_test.o: hw_test.c $(DEVICE_TABLE_H)
+ hw_htab.o: hw_htab.c $(DEVICE_TABLE_H) $(BFD_H)
+ hw_ide.o: hw_ide.c $(DEVICE_TABLE_H)
+ hw_init.o: hw_init.c $(DEVICE_TABLE_H) $(BFD_H) $(PSIM_H)
diff --git a/bsps/powerpc/psim/net/if_sim.c b/bsps/powerpc/psim/net/if_sim.c
new file mode 100644
index 0000000..3bb1ec3
--- /dev/null
+++ b/bsps/powerpc/psim/net/if_sim.c
@@ -0,0 +1,504 @@
+/* Trivial driver for PSIM's emulated ethernet device 'hw_ethtap'.
+ *
+ * NOTE: At the time of this writing (2009/1) 'hw_ethtap' requires
+ * a patched version of PSIM -- the vanilla version does not
+ * implement this device.
+ * Also, support for this device is currently only available
+ * on a linux host.
+ *
+ * Author/Copyright: Till Straumann <Till.Straumann@TU-Berlin.de>
+ *
+ * LICENSE
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ */
+
+#include <bsp.h>
+#include <rtems.h>
+#include <bsp/irq.h>
+#include <psim.h>
+#include <libcpu/io.h>
+#include <inttypes.h>
+
+
+#ifndef KERNEL
+#define KERNEL
+#endif
+#ifndef _KERNEL
+#define _KERNEL
+#endif
+
+#include <rtems/rtems_bsdnet.h>
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/ethernet.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <stdio.h>
+
+#define IFSIM_SLOTS 1
+
+#define DRVNAME "if_sim"
+
+#define IFSIM_TX_BUF_REG 1
+#define IFSIM_TX_STA_REG 2
+
+#define IFSIM_RX_BUF_REG 4
+#define IFSIM_RX_STA_REG 5
+
+#define IFSIM_RX_CNT_MSK 0xffff
+#define IFSIM_RX_STA_DONE (1<<31)
+
+#define IFSIM_RX_ERR_NOSPC (1<<20) /* buffer too small */
+#define IFSIM_RX_ERR_DMA (1<<21) /* DMA error */
+#define IFSIM_RX_ERR_RD (1<<23) /* file read error */
+
+#define IFSIM_TX_STA_LST (1<<16)
+#define IFSIM_TX_STA_DONE (1<<31)
+
+#define IFSIM_IEN_REG 6
+#define IFSIM_IRQ_REG 7
+
+#define IFSIM_RX_IRQ (1<<0)
+
+#define IFSIM_MACA0_REG 8
+#define IFSIM_MACA1_REG 9
+
+#define IFSIM_CSR_REG 10
+#define IFSIM_CSR_PROM (1<<0)
+/* Enable CRC generation/checking */
+#define IFSIM_CSR_CRCEN (1<<1)
+
+
+#define RX_BUF_ALIGNMENT 1
+#define ETH_RX_OFFSET 0
+
+/*
+ * Align 'p' up to a multiple of 'a' which must be
+ * a power of two. Result is cast to (uintptr_t)
+ */
+#define ALIGNTO(p,a) ((((uintptr_t)(p)) + (a) - 1) & ~((a)-1))
+
+
+typedef volatile unsigned reg_t;
+
+struct ifsim_private {
+ reg_t *base;
+ void *rbuf;
+ unsigned rx_cserrs;
+ unsigned rx_err_nospc;
+ unsigned rx_err_dma;
+ unsigned rx_err_rd;
+ unsigned rx_nobufs;
+ unsigned rx_irqs;
+};
+
+struct ifsim_softc {
+ struct arpcom arpcom;
+ struct ifsim_private pvt;
+};
+
+struct ifsim_softc theIfSims[IFSIM_SLOTS] = {{{{0}}} };
+
+rtems_id ifsim_tid = 0;
+
+static __inline__ uint32_t
+ifsim_in(struct ifsim_softc *sc, unsigned regno)
+{
+ return in_be32((volatile uint32_t *) (sc->pvt.base + regno));
+}
+
+static __inline__ void
+ifsim_out(struct ifsim_softc *sc, unsigned regno, uint32_t v)
+{
+ out_be32((volatile uint32_t *) (sc->pvt.base + regno), v);
+}
+
+static void *
+alloc_mbuf_rx(int *psz, uintptr_t *paddr)
+{
+struct mbuf *m;
+unsigned long l,o;
+
+ MGETHDR(m, M_DONTWAIT, MT_DATA);
+ if ( !m )
+ return 0;
+ MCLGET(m, M_DONTWAIT);
+ if ( ! (m->m_flags & M_EXT) ) {
+ m_freem(m);
+ return 0;
+ }
+
+ o = mtod(m, unsigned long);
+ l = ALIGNTO(o, RX_BUF_ALIGNMENT) - o;
+
+ /* align start of buffer */
+ m->m_data += l;
+
+ /* reduced length */
+ l = MCLBYTES - l;
+
+ m->m_len = m->m_pkthdr.len = l;
+ *psz = m->m_len;
+ *paddr = mtod(m, unsigned long);
+
+ return (void*) m;
+}
+
+static int
+get_rxbuf(struct ifsim_softc *sc)
+{
+int sz;
+uintptr_t addr;
+void *nbuf;
+
+ nbuf = alloc_mbuf_rx(&sz, &addr);
+
+ if ( nbuf ) {
+ sc->pvt.rbuf = nbuf;
+ ifsim_out(sc, IFSIM_RX_BUF_REG, addr);
+ ifsim_out(sc, IFSIM_RX_STA_REG, sz);
+ return 0;
+ }
+ return -1;
+}
+
+/* set/clear promiscuous mode */
+static void
+ifsim_upd_promisc(struct ifsim_softc *sc)
+{
+uint32_t ncsr, csr;
+
+ ncsr = csr = ifsim_in(sc, IFSIM_CSR_REG);
+
+ if ( sc->arpcom.ac_if.if_flags & IFF_PROMISC )
+ ncsr |= IFSIM_CSR_PROM;
+ else
+ ncsr &= ~IFSIM_CSR_PROM;
+
+ if ( ncsr != csr )
+ ifsim_out(sc, IFSIM_CSR_REG, ncsr);
+}
+
+static void
+ifsim_init(void *arg)
+{
+struct ifsim_softc *sc = arg;
+struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if ( 0 == get_rxbuf(sc) ) {
+ ifsim_upd_promisc(sc);
+ ifp->if_flags |= IFF_RUNNING;
+ }
+}
+
+static void
+ifsim_start(struct ifnet *ifp)
+{
+struct ifsim_softc *sc = ifp->if_softc;
+struct mbuf *m, *mh, *m1;
+
+ while ( ifp->if_snd.ifq_head ) {
+ IF_DEQUEUE( &ifp->if_snd, mh );
+ for ( m=mh, m1 = m->m_next ; m1 ; m1 = m1->m_next ) {
+ ifsim_out(sc, IFSIM_TX_BUF_REG, mtod(m, uint32_t));
+ ifsim_out(sc, IFSIM_TX_STA_REG, m->m_len);
+ /* dummy-busywait; the emulated hardware DMAs our
+ * data away 'immediately' i.e., this loop is
+ * never executed
+ */
+ while ( ! (IFSIM_TX_STA_DONE & ifsim_in(sc, IFSIM_TX_STA_REG)) )
+ /* Loop */;
+ m = m1;
+ }
+ ifsim_out(sc, IFSIM_TX_BUF_REG, mtod(m, uint32_t));
+ ifsim_out(sc, IFSIM_TX_STA_REG, m->m_len | IFSIM_TX_STA_LST);
+
+ /* dummy-busywait; the emulated hardware DMAs our
+ * data away 'immediately' i.e., this loop is
+ * never executed
+ */
+ while ( ! (IFSIM_TX_STA_DONE & ifsim_in(sc, IFSIM_TX_STA_REG)) )
+ /* Loop */;
+
+ m_freem(mh);
+ }
+}
+
+static int
+ifsim_ioctl(struct ifnet *ifp, ioctl_command_t cmd, caddr_t data)
+{
+struct ifsim_softc *sc = ifp->if_softc;
+int rval = 0;
+int f;
+
+ switch (cmd) {
+
+ case SIOCSIFFLAGS:
+ f = ifp->if_flags;
+ if ( f & IFF_UP ) {
+ if ( ! (f & IFF_RUNNING) ) {
+ ifsim_init(sc);
+ } else {
+ ifsim_upd_promisc(sc);
+ }
+ /* FIXME: handle other flags here */
+ } else {
+ if ( f & IFF_RUNNING ) {
+ printk("WARNING: bringing "DRVNAME" down not really implemented\n");
+ ifp->if_flags &= ~(IFF_RUNNING | IFF_OACTIVE);
+ }
+ }
+
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ printf("RX bad chksum : %u\n", sc->pvt.rx_cserrs);
+ printf("RX no space : %u\n", sc->pvt.rx_err_nospc);
+ printf("RX bad DMA : %u\n", sc->pvt.rx_err_dma);
+ printf("RX read errors : %u\n", sc->pvt.rx_err_rd);
+ printf("rx_nobufs : %u\n", sc->pvt.rx_nobufs);
+ printf("rx_irqs : %u\n", sc->pvt.rx_irqs);
+ break;
+
+ default:
+ rval = ether_ioctl(ifp, cmd, data);
+ break;
+ }
+
+ return rval;
+}
+
+static void ifsim_irq_on(const rtems_irq_connect_data *pd)
+{
+struct ifsim_softc *sc = pd->handle;
+ ifsim_out(sc, IFSIM_IEN_REG, IFSIM_RX_IRQ);
+}
+
+static void ifsim_irq_off(const rtems_irq_connect_data *pd)
+{
+struct ifsim_softc *sc = pd->handle;
+ ifsim_out(sc, IFSIM_IEN_REG, 0);
+}
+
+static int ifsim_irq_ison(const rtems_irq_connect_data *pd)
+{
+struct ifsim_softc *sc = pd->handle;
+ return ifsim_in(sc, IFSIM_IEN_REG) & IFSIM_RX_IRQ ? 1 : 0;
+}
+
+static void
+ifsim_isr(void *arg)
+{
+struct ifsim_softc *sc = arg;
+
+ sc->pvt.rx_irqs++;
+#ifdef IRQ_DEBUG
+ printk("ISR happened\n");
+#endif
+
+ ifsim_out(sc, IFSIM_IEN_REG, 0);
+ rtems_bsdnet_event_send(ifsim_tid, (1<<(sc-theIfSims)));
+}
+
+static void
+ifsim_task(void *arg)
+{
+struct ifsim_softc *sc;
+uint32_t sta;
+struct ifnet *ifp;
+unsigned len;
+rtems_event_set evs;
+
+ while (1) {
+
+ rtems_bsdnet_event_receive(
+ ((1<<IFSIM_SLOTS)-1),
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &evs);
+
+ evs &= ((1<<IFSIM_SLOTS)-1);
+
+#ifdef IRQ_DEBUG
+ printk("Task got evs %u\n", evs);
+#endif
+
+ for ( sc = theIfSims; evs; evs>>=1, sc++ ) {
+
+ if ( ! ( evs & 1 ) )
+ continue;
+
+ ifp = &sc->arpcom.ac_if;
+
+ while ( ifsim_in(sc, IFSIM_IRQ_REG) & IFSIM_RX_IRQ ) {
+ struct mbuf *m = sc->pvt.rbuf;
+
+ sta = ifsim_in(sc, IFSIM_RX_STA_REG);
+
+
+ if ( (sta & IFSIM_RX_STA_DONE) ) {
+
+ if ( (ifp->if_flags & IFF_RUNNING) ) {
+ if ( 0 == get_rxbuf(sc) ) {
+ /* enqueue packet */
+ struct ether_header *eh;
+ uint32_t crc_net, crc;
+ int crc_len;
+
+ crc_len = (IFSIM_CSR_CRCEN & ifsim_in(sc, IFSIM_CSR_REG)) ? sizeof(crc_net) : 0;
+
+ len = (sta & IFSIM_RX_CNT_MSK) - crc_len;
+
+ eh = (struct ether_header*)(mtod(m,unsigned long) + ETH_RX_OFFSET);
+
+ m->m_len = m->m_pkthdr.len = len - sizeof(struct ether_header) - ETH_RX_OFFSET;
+ m->m_data += sizeof(struct ether_header) + ETH_RX_OFFSET;
+ m->m_pkthdr.rcvif = ifp;
+
+#ifdef DEBUG_WO_BSDNET
+ {
+ int i;
+ for ( i=0; i<len + crc_len; ) {
+ printk("%02X ",((char*)eh)[i]);
+ if ( 0 == (++i & 0xf) )
+ fputc('\n',stdout);
+ }
+ if ( i & 0xf )
+ fputc('\n', stdout);
+ printk("*****\n");
+ }
+#endif
+
+ if ( crc_len
+ && (memcpy(&crc_net, (char*)eh + len, crc_len),
+ (crc = (ether_crc32_le((uint8_t *)eh, len) ^ 0xffffffff)) != crc_net) ) {
+ printk("CSUM: me 0x%08" PRIx32 ", them 0x%08" PRIx32 "\n", crc, crc_net);
+ sc->pvt.rx_cserrs++;
+ } else {
+
+ ifp->if_ipackets++;
+ ifp->if_ibytes += len;
+
+#ifdef DEBUG_WO_BSDNET
+ m_freem(m);
+#else
+ ether_input(ifp, eh, m);
+#endif
+
+ m = 0;
+ }
+
+ } else {
+ /* throw away and reuse buffer */
+ sc->pvt.rx_nobufs++;
+ }
+ }
+ } else {
+ /* throw away and reuse buffer */
+ if ( (sta & IFSIM_RX_ERR_NOSPC) )
+ sc->pvt.rx_err_nospc++;
+ if ( (sta & IFSIM_RX_ERR_DMA) )
+ sc->pvt.rx_err_dma++;
+ if ( (sta & IFSIM_RX_ERR_RD) )
+ sc->pvt.rx_err_rd++;
+ }
+
+ if ( m ) {
+ /* reuse */
+ ifsim_out(sc, IFSIM_RX_STA_REG, m->m_pkthdr.len);
+ }
+ }
+ /* re-enable interrupt */
+ ifsim_out(sc, IFSIM_IEN_REG, IFSIM_RX_IRQ);
+ }
+ }
+}
+
+int
+rtems_ifsim_attach(struct rtems_bsdnet_ifconfig *ifcfg, int attaching)
+{
+char *unitName;
+int unit;
+struct ifsim_softc *sc;
+struct ifnet *ifp;
+uint32_t v;
+rtems_irq_connect_data ihdl;
+
+ if ( !attaching )
+ return -1;
+
+ unit = rtems_bsdnet_parse_driver_name(ifcfg, &unitName);
+
+ if ( unit <= 0 || unit > IFSIM_SLOTS ) {
+ printk(DRVNAME": Bad unit number %i; must be 1..%i\n", unit, IFSIM_SLOTS);
+ return 1;
+ }
+
+ sc = &theIfSims[unit-1];
+ ifp = &sc->arpcom.ac_if;
+
+ memset(&sc->pvt, 0, sizeof(sc->pvt));
+
+ sc->pvt.base = (reg_t*)ifcfg->port;
+
+ if ( 0 == sc->pvt.base )
+ sc->pvt.base = (reg_t*)PSIM.Ethtap;
+
+
+ sc->pvt.rbuf = 0;
+
+ if ( !ifsim_tid ) {
+ ifsim_tid = rtems_bsdnet_newproc("IFSM", 10000, ifsim_task, 0);
+ }
+
+ ihdl.name = ifcfg->irno;
+ ihdl.hdl = ifsim_isr;
+ ihdl.handle = sc;
+ ihdl.on = ifsim_irq_on;
+ ihdl.off = ifsim_irq_off;
+ ihdl.isOn = ifsim_irq_ison;
+
+ if ( ! BSP_install_rtems_irq_handler(&ihdl) ) {
+ printk(DRVNAME"_attach(): installing ISR failed!\n");
+ return -1;
+ }
+
+ if ( ifcfg->hardware_address ) {
+ memcpy(sc->arpcom.ac_enaddr, ifcfg->hardware_address, ETHER_ADDR_LEN);
+ } else {
+ v = ifsim_in(sc, IFSIM_MACA0_REG);
+ memcpy(sc->arpcom.ac_enaddr, &v, 4);
+ v = ifsim_in(sc, IFSIM_MACA1_REG);
+ memcpy(sc->arpcom.ac_enaddr+4, &v, 2);
+ }
+
+ ifp->if_softc = sc;
+ ifp->if_unit = unit;
+ ifp->if_name = unitName;
+
+ ifp->if_mtu = ifcfg->mtu ? ifcfg->mtu : ETHERMTU;
+
+ ifp->if_init = ifsim_init;
+ ifp->if_ioctl = ifsim_ioctl;
+ ifp->if_start = ifsim_start;
+ ifp->if_output = ether_output;
+
+ ifp->if_watchdog = 0;
+ ifp->if_timer = 0;
+
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ return 0;
+}
diff --git a/bsps/powerpc/qoriq/net/if_intercom.c b/bsps/powerpc/qoriq/net/if_intercom.c
new file mode 100644
index 0000000..3fe7d84
--- /dev/null
+++ b/bsps/powerpc/qoriq/net/if_intercom.c
@@ -0,0 +1,296 @@
+/*
+ * Copyright (c) 2011 embedded brains GmbH. All rights reserved.
+ *
+ * embedded brains GmbH
+ * Obere Lagerstr. 30
+ * 82178 Puchheim
+ * Germany
+ * <info@embedded-brains.de>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <assert.h>
+#include <errno.h>
+#include <inttypes.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+
+#include <rtems.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+
+#include <sys/param.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <sys/mbuf.h>
+
+#include <net/if.h>
+#include <net/if_arp.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <netinet/in_systm.h>
+#include <netinet/ip.h>
+
+#include <libcpu/powerpc-utility.h>
+
+#include <bsp.h>
+#include <bsp/intercom.h>
+
+typedef struct {
+ struct arpcom arpcom;
+ int destination_core;
+ intercom_packet *packet;
+ unsigned transmitted_frames;
+ unsigned received_frames;
+} if_intercom_control;
+
+static if_intercom_control if_intercom;
+
+static struct mbuf *new_mbuf(struct ifnet *ifp, bool wait)
+{
+ struct mbuf *m = NULL;
+ int mw = wait ? M_WAIT : M_DONTWAIT;
+
+ MGETHDR(m, mw, MT_DATA);
+ if (m != NULL) {
+ MCLGET(m, mw);
+ if ((m->m_flags & M_EXT) != 0) {
+ m->m_pkthdr.rcvif = ifp;
+
+ return m;
+ } else {
+ m_free(m);
+ }
+ }
+
+ return NULL;
+}
+
+static void if_intercom_service(intercom_packet *packet, void *arg)
+{
+ rtems_bsdnet_semaphore_obtain();
+
+ if_intercom_control *self = arg;
+ struct ifnet *ifp = &self->arpcom.ac_if;
+ struct mbuf *m = new_mbuf(ifp, true);
+
+ memcpy(mtod(m, void *), packet->data, packet->size);
+
+ /* Ethernet header */
+ struct ether_header *eh = mtod(m, struct ether_header *);
+
+ /* Discard Ethernet header and CRC */
+ int sz = (int) packet->size - ETHER_HDR_LEN;
+
+ /* Update mbuf */
+ m->m_len = sz;
+ m->m_pkthdr.len = sz;
+ m->m_data = mtod(m, char *) + ETHER_HDR_LEN;
+
+ /* Hand over */
+ ether_input(ifp, eh, m);
+
+ ++self->received_frames;
+ qoriq_intercom_free_packet(packet);
+
+ rtems_bsdnet_semaphore_release();
+}
+
+static intercom_packet *allocate_packet(void)
+{
+ intercom_packet *packet = qoriq_intercom_allocate_packet(
+ INTERCOM_TYPE_NETWORK,
+ INTERCOM_SIZE_2K
+ );
+
+ packet->size = 0;
+
+ return packet;
+}
+
+static struct mbuf *get_next_fragment(struct ifnet *ifp, struct mbuf *m)
+{
+ struct mbuf *n = NULL;
+ int size = 0;
+
+ while (true) {
+ if (m == NULL) {
+ /* Dequeue first fragment of the next frame */
+ IF_DEQUEUE(&ifp->if_snd, m);
+
+ /* Empty queue? */
+ if (m == NULL) {
+ return m;
+ }
+ }
+
+ /* Get fragment size */
+ size = m->m_len;
+
+ if (size > 0) {
+ /* Now we have a not empty fragment */
+ break;
+ } else {
+ /* Discard empty fragments */
+ m = m_free(m);
+ }
+ }
+
+ /* Discard empty successive fragments */
+ n = m->m_next;
+ while (n != NULL && n->m_len <= 0) {
+ n = m_free(n);
+ }
+ m->m_next = n;
+
+ return m;
+}
+
+static void if_intercom_start(struct ifnet *ifp)
+{
+ if_intercom_control *self = ifp->if_softc;
+ int destination_core = self->destination_core;
+ intercom_packet *packet = self->packet;
+ size_t size = packet->size;
+ char *data = packet->data + size;
+ struct mbuf *m = NULL;
+
+ while ((m = get_next_fragment(ifp, m)) != NULL) {
+ size_t fragment_size = (size_t) m->m_len;
+ size_t new_size = size + fragment_size;
+
+ assert(new_size <= 2048);
+
+ memcpy(data, mtod(m, void *), fragment_size);
+ data += fragment_size;
+ size = new_size;
+
+ m = m_free(m);
+
+ /* Last fragment of frame ? */
+ if (m == NULL) {
+ packet->size = size;
+ qoriq_intercom_send_packet(destination_core, packet);
+ ++self->transmitted_frames;
+ packet = allocate_packet();
+ data = packet->data;
+ size = 0;
+ }
+ }
+
+ packet->size = size;
+ self->packet = packet;
+ ifp->if_flags &= ~IFF_OACTIVE;
+}
+
+static void if_intercom_init(void *arg)
+{
+ if_intercom_control *self = arg;
+ uint32_t self_core = ppc_processor_id();
+
+ self->destination_core = self_core == 0 ? 1 : 0;
+ self->packet = allocate_packet();
+
+ qoriq_intercom_service_install(
+ INTERCOM_TYPE_NETWORK,
+ if_intercom_service,
+ self
+ );
+}
+
+static void show_stats(if_intercom_control *self)
+{
+ printf("transmitted frames: %u\n", self->transmitted_frames);
+ printf("received frames: %u\n", self->received_frames);
+}
+
+static int if_intercom_ioctl(
+ struct ifnet *ifp,
+ ioctl_command_t command,
+ caddr_t data
+)
+{
+ if_intercom_control *self = ifp->if_softc;
+ int rv = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, command, data);
+ break;
+ case SIOCSIFFLAGS:
+ if (ifp->if_flags & IFF_RUNNING) {
+ /* TODO: off */
+ }
+ if (ifp->if_flags & IFF_UP) {
+ ifp->if_flags |= IFF_RUNNING;
+ /* TODO: init */
+ }
+ break;
+ case SIO_RTEMS_SHOW_STATS:
+ show_stats(self);
+ break;
+ default:
+ rv = EINVAL;
+ break;
+ }
+
+ return rv;
+}
+
+static void if_intercom_watchdog(struct ifnet *ifp)
+{
+ ifp->if_timer = 0;
+}
+
+static int if_intercom_attach(struct rtems_bsdnet_ifconfig *config)
+{
+ if_intercom_control *self = &if_intercom;
+ struct ifnet *ifp = &self->arpcom.ac_if;
+ char *unit_name = NULL;
+ int unit_index = rtems_bsdnet_parse_driver_name(config, &unit_name);
+
+ assert(unit_index == 1);
+ assert(strcmp(unit_name, "intercom") == 0);
+ assert(config->hardware_address != NULL);
+
+ memcpy(self->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+
+ /* Set interface data */
+ ifp->if_softc = self;
+ ifp->if_unit = (short) unit_index;
+ ifp->if_name = unit_name;
+ ifp->if_mtu = (config->mtu > 0) ? (u_long) config->mtu : ETHERMTU;
+ ifp->if_init = if_intercom_init;
+ ifp->if_ioctl = if_intercom_ioctl;
+ ifp->if_start = if_intercom_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = if_intercom_watchdog;
+ ifp->if_flags = config->ignore_broadcast ? 0 : IFF_BROADCAST;
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ ifp->if_timer = 0;
+
+ /* Attach the interface */
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ return 1;
+}
+
+int qoriq_if_intercom_attach_detach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attaching
+)
+{
+ if (attaching) {
+ return if_intercom_attach(config);
+ } else {
+ assert(0);
+ }
+}
diff --git a/bsps/powerpc/qoriq/net/network.c b/bsps/powerpc/qoriq/net/network.c
new file mode 100644
index 0000000..46ab2ba
--- /dev/null
+++ b/bsps/powerpc/qoriq/net/network.c
@@ -0,0 +1,135 @@
+/**
+ * @file
+ *
+ * @ingroup RTEMSBSPsPowerPCQorIQ
+ *
+ * @brief Network configuration.
+ */
+
+/*
+ * Copyright (c) 2010-2015 embedded brains GmbH. All rights reserved.
+ *
+ * embedded brains GmbH
+ * Dornierstr. 4
+ * 82178 Puchheim
+ * Germany
+ * <rtems@embedded-brains.de>
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <assert.h>
+#include <string.h>
+
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_bsdnet_internal.h>
+
+#include <libcpu/powerpc-utility.h>
+
+#include <bsp.h>
+#include <bsp/tsec.h>
+#include <bsp/qoriq.h>
+
+#if QORIQ_CHIP_VARIANT == QORIQ_CHIP_P1020
+
+int BSP_tsec_attach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attaching
+)
+{
+ char *unit_name = NULL;
+ int unit_number = rtems_bsdnet_parse_driver_name(config, &unit_name);
+ tsec_config tsec_cfg;
+ bool has_groups = false;
+
+ memset(&tsec_cfg, 0, sizeof(tsec_cfg));
+ config->drv_ctrl = &tsec_cfg;
+
+ if (unit_number <= 0 || unit_number > TSEC_COUNT) {
+ return 0;
+ }
+
+ switch (ppc_fsl_system_version_sid(ppc_fsl_system_version())) {
+ /* P1010 and P1020 */
+ case 0x0ec:
+ case 0x0e4:
+ case 0x0ed:
+ case 0x0e5:
+ has_groups = true;
+ break;
+ }
+
+ if (config->hardware_address == NULL) {
+ #ifdef HAS_UBOOT
+ switch (unit_number) {
+ case 1:
+ config->hardware_address = bsp_uboot_board_info.bi_enetaddr;
+ break;
+ case 2:
+ config->hardware_address = bsp_uboot_board_info.bi_enet1addr;
+ break;
+ case 3:
+ config->hardware_address = bsp_uboot_board_info.bi_enet2addr;
+ break;
+ default:
+ assert(0);
+ break;
+ }
+ #else
+ assert(0);
+ #endif
+ }
+
+ switch (unit_number) {
+ case 1:
+ if (has_groups) {
+ tsec_cfg.reg_ptr = &qoriq.tsec_1_group_0;
+ } else {
+ tsec_cfg.reg_ptr = &qoriq.tsec_1;
+ }
+ tsec_cfg.mdio_ptr = &qoriq.tsec_1;
+ tsec_cfg.irq_num_tx = QORIQ_IRQ_ETSEC_TX_1;
+ tsec_cfg.irq_num_rx = QORIQ_IRQ_ETSEC_RX_1;
+ tsec_cfg.irq_num_err = QORIQ_IRQ_ETSEC_ER_1;
+ tsec_cfg.phy_default = QORIQ_ETSEC_1_PHY_ADDR;
+ break;
+ case 2:
+ if (has_groups) {
+ tsec_cfg.reg_ptr = &qoriq.tsec_2_group_0;
+ } else {
+ tsec_cfg.reg_ptr = &qoriq.tsec_2;
+ }
+ tsec_cfg.mdio_ptr = &qoriq.tsec_1;
+ tsec_cfg.irq_num_tx = QORIQ_IRQ_ETSEC_TX_2;
+ tsec_cfg.irq_num_rx = QORIQ_IRQ_ETSEC_RX_2;
+ tsec_cfg.irq_num_err = QORIQ_IRQ_ETSEC_ER_2;
+ tsec_cfg.phy_default = QORIQ_ETSEC_2_PHY_ADDR;
+ break;
+ case 3:
+ if (has_groups) {
+ tsec_cfg.reg_ptr = &qoriq.tsec_3_group_0;
+ } else {
+ tsec_cfg.reg_ptr = &qoriq.tsec_3;
+ }
+ tsec_cfg.mdio_ptr = &qoriq.tsec_1;
+ tsec_cfg.irq_num_tx = QORIQ_IRQ_ETSEC_TX_3;
+ tsec_cfg.irq_num_rx = QORIQ_IRQ_ETSEC_RX_3;
+ tsec_cfg.irq_num_err = QORIQ_IRQ_ETSEC_ER_3;
+ tsec_cfg.phy_default = QORIQ_ETSEC_3_PHY_ADDR;
+ break;
+ default:
+ assert(0);
+ break;
+ }
+
+ tsec_cfg.unit_number = unit_number;
+ tsec_cfg.unit_name = unit_name;
+
+ return tsec_driver_attach_detach(config, attaching);
+}
+
+#endif /* QORIQ_CHIP_VARIANT */
diff --git a/bsps/powerpc/tqm8xx/net/network_fec.c b/bsps/powerpc/tqm8xx/net/network_fec.c
new file mode 100644
index 0000000..dec7de4
--- /dev/null
+++ b/bsps/powerpc/tqm8xx/net/network_fec.c
@@ -0,0 +1,1248 @@
+/*===============================================================*\
+| Project: RTEMS TQM8xx BSP |
++-----------------------------------------------------------------+
+| This file has been adapted to MPC8xx by |
+| Thomas Doerfler <Thomas.Doerfler@embedded-brains.de> |
+| Copyright (c) 2008 |
+| Embedded Brains GmbH |
+| Obere Lagerstr. 30 |
+| D-82178 Puchheim |
+| Germany |
+| rtems@embedded-brains.de |
+| |
+| See the other copyright notice below for the original parts. |
++-----------------------------------------------------------------+
+| The license and distribution terms for this file may be |
+| found in the file LICENSE in this distribution or at |
+| |
+| http://www.rtems.org/license/LICENSE. |
+| |
++-----------------------------------------------------------------+
+| this file contains the console driver |
+\*===============================================================*/
+/* derived from: */
+/*
+ * RTEMS/TCPIP driver for MPC8xx Ethernet
+ *
+ * split into separate driver files for SCC and FEC by
+ * Thomas Doerfler <Thomas.Doerfler@embedded-brains.de>
+ *
+ * Modified for MPC860 by Jay Monkman (jmonkman@frasca.com)
+ *
+ * This supports Ethernet on either SCC1 or the FEC of the MPC860T.
+ * Right now, we only do 10 Mbps, even with the FEC. The function
+ * rtems_enet_driver_attach determines which one to use. Currently,
+ * only one may be used at a time.
+ *
+ * Based on the MC68360 network driver by
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ *
+ * This supports ethernet on SCC1. Right now, we only do 10 Mbps.
+ *
+ * Modifications by Darlene Stewart <Darlene.Stewart@iit.nrc.ca>
+ * and Charles-Antoine Gauthier <charles.gauthier@iit.nrc.ca>
+ * Copyright (c) 1999, National Research Council of Canada
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+#include <rtems/rtems_mii_ioctl.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <bsp/irq.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 8
+#define TX_BD_PER_BUF 4
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+#define FEC_WATCHDOG_TIMEOUT 5 /* check media every 5 seconds */
+/*
+ * Per-device data
+ */
+struct m8xx_fec_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ m8xxBufferDescriptor_t *rxBdBase;
+ m8xxBufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * MDIO/Phy info
+ */
+ struct rtems_mdio_info mdio_info;
+ int phy_default;
+ int media_state; /* (last detected) state of media */
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxRunt;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txHeartbeat;
+ unsigned long txLateCollision;
+ unsigned long txRetryLimit;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+};
+static struct m8xx_fec_enet_struct enet_driver[NIFACES];
+
+/* declare ioctl function for internal use */
+static int fec_ioctl (struct ifnet *ifp,
+ ioctl_command_t command, caddr_t data);
+/***************************************************************************\
+| MII Management access functions |
+\***************************************************************************/
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+static void fec_mdio_init
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| initialize the MII interface |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ struct m8xx_fec_enet_struct *sc /* control structure */
+)
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| <none> |
+\*=========================================================================*/
+{
+
+ /* Set FEC registers for MDIO communication */
+ /*
+ * set clock divider
+ */
+ m8xx.fec.mii_speed = BSP_bus_frequency / 25000000 / 2 + 1;
+}
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+int fec_mdio_read
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| read register of a phy |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ int phy, /* PHY number to access or -1 */
+ void *uarg, /* unit argument */
+ unsigned reg, /* register address */
+ uint32_t *pval /* ptr to read buffer */
+ )
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| 0, if ok, else error |
+\*=========================================================================*/
+{
+ struct m8xx_fec_enet_struct *sc = uarg;/* control structure */
+
+ /*
+ * make sure we work with a valid phy
+ */
+ if (phy == -1) {
+ /*
+ * set default phy number: 0
+ */
+ phy = sc->phy_default;
+ }
+ if ( (phy < 0) || (phy > 31)) {
+ /*
+ * invalid phy number
+ */
+ return EINVAL;
+ }
+ /*
+ * clear MII transfer event bit
+ */
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_MII;
+ /*
+ * set access command, data, start transfer
+ */
+ m8xx.fec.mii_data = (M8xx_FEC_MII_DATA_ST |
+ M8xx_FEC_MII_DATA_OP_RD |
+ M8xx_FEC_MII_DATA_PHYAD(phy) |
+ M8xx_FEC_MII_DATA_PHYRA(reg) |
+ M8xx_FEC_MII_DATA_WDATA(0));
+
+ /*
+ * wait for cycle to terminate
+ */
+ do {
+ rtems_task_wake_after(RTEMS_YIELD_PROCESSOR);
+ } while (0 == (m8xx.fec.ievent & M8xx_FEC_IEVENT_MII));
+
+ /*
+ * fetch read data, if available
+ */
+ if (pval != NULL) {
+ *pval = M8xx_FEC_MII_DATA_RDATA(m8xx.fec.mii_data);
+ }
+ return 0;
+}
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+int fec_mdio_write
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| write register of a phy |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ int phy, /* PHY number to access or -1 */
+ void *uarg, /* unit argument */
+ unsigned reg, /* register address */
+ uint32_t val /* write value */
+ )
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| 0, if ok, else error |
+\*=========================================================================*/
+{
+ struct m8xx_fec_enet_struct *sc = uarg;/* control structure */
+
+ /*
+ * make sure we work with a valid phy
+ */
+ if (phy == -1) {
+ /*
+ * set default phy number: 0
+ */
+ phy = sc->phy_default;
+ }
+ if ( (phy < 0) || (phy > 31)) {
+ /*
+ * invalid phy number
+ */
+ return EINVAL;
+ }
+ /*
+ * clear MII transfer event bit
+ */
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_MII;
+ /*
+ * set access command, data, start transfer
+ */
+ m8xx.fec.mii_data = (M8xx_FEC_MII_DATA_ST |
+ M8xx_FEC_MII_DATA_OP_WR |
+ M8xx_FEC_MII_DATA_PHYAD(phy) |
+ M8xx_FEC_MII_DATA_PHYRA(reg) |
+ M8xx_FEC_MII_DATA_WDATA(val));
+
+ /*
+ * wait for cycle to terminate
+ */
+ do {
+ rtems_task_wake_after(RTEMS_YIELD_PROCESSOR);
+ } while (0 == (m8xx.fec.ievent & M8xx_FEC_IEVENT_MII));
+
+ return 0;
+}
+
+/*
+ * FEC interrupt handler
+ */
+static void m8xx_fec_interrupt_handler (void *unused)
+{
+ /*
+ * Frame received?
+ */
+ if (m8xx.fec.ievent & M8xx_FEC_IEVENT_RFINT) {
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_RFINT;
+ enet_driver[0].rxInterrupts++;
+ rtems_bsdnet_event_send (enet_driver[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+
+ /*
+ * Buffer transmitted or transmitter error?
+ */
+ if (m8xx.fec.ievent & M8xx_FEC_IEVENT_TFINT) {
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_TFINT;
+ enet_driver[0].txInterrupts++;
+ rtems_bsdnet_event_send (enet_driver[0].txDaemonTid, INTERRUPT_EVENT);
+ }
+}
+
+/*
+ * Please organize FEC controller code better by moving code from
+ * m860_fec_initialize_hardware to m8xx_fec_ethernet_on
+ */
+static void m8xx_fec_ethernet_on(const rtems_irq_connect_data* ptr){};
+static void m8xx_fec_ethernet_off(const rtems_irq_connect_data* ptr){};
+static int m8xx_fec_ethernet_isOn (const rtems_irq_connect_data* ptr)
+{
+ return 1;
+}
+
+static rtems_irq_connect_data ethernetFECIrqData = {
+ BSP_FAST_ETHERNET_CTRL,
+ m8xx_fec_interrupt_handler,
+ NULL,
+ m8xx_fec_ethernet_on,
+ m8xx_fec_ethernet_off,
+ m8xx_fec_ethernet_isOn
+};
+
+static void
+m8xx_fec_initialize_hardware (struct m8xx_fec_enet_struct *sc)
+{
+ int i;
+ unsigned char *hwaddr;
+
+ /*
+ * Issue reset to FEC
+ */
+ m8xx.fec.ecntrl = M8xx_FEC_ECNTRL_RESET;
+
+ /*
+ * Put ethernet transciever in reset
+ */
+ m8xx.pgcra |= 0x80;
+
+ /*
+ * Configure I/O ports
+ */
+ m8xx.pdpar = 0x1fff;
+ m8xx.pddir = 0x1fff;
+
+ /*
+ * Take ethernet transciever out of reset
+ */
+ m8xx.pgcra &= ~0x80;
+
+ /*
+ * Set SIU interrupt level to LVL2
+ *
+ */
+ m8xx.fec.ivec = ((((unsigned) BSP_FAST_ETHERNET_CTRL)/2) << 29);
+
+ /*
+ * Set the TX and RX fifo sizes. For now, we'll split it evenly
+ */
+ /* If you uncomment these, the FEC will not work right.
+ m8xx.fec.r_fstart = ((m8xx.fec.r_bound & 0x3ff) >> 2) & 0x3ff;
+ m8xx.fec.x_fstart = 0;
+ */
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+
+ m8xx.fec.addr_low = (hwaddr[0] << 24) | (hwaddr[1] << 16) |
+ (hwaddr[2] << 8) | (hwaddr[3] << 0);
+ m8xx.fec.addr_high = (hwaddr[4] << 24) | (hwaddr[5] << 16);
+
+ /*
+ * Clear the hash table
+ */
+ m8xx.fec.hash_table_high = 0;
+ m8xx.fec.hash_table_low = 0;
+
+ /*
+ * Set up receive buffer size
+ */
+ m8xx.fec.r_buf_size = 0x5f0; /* set to 1520 */
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc (sc->rxBdCount * sizeof *sc->rxMbuf,
+ M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc (sc->txBdCount * sizeof *sc->txMbuf,
+ M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = m8xx_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = m8xx_bd_allocate(sc->txBdCount);
+ m8xx.fec.r_des_start = (int)sc->rxBdBase;
+ m8xx.fec.x_des_start = (int)sc->txBdBase;
+
+ /*
+ * Set up Receive Control Register:
+ * Not promiscuous mode
+ * MII mode
+ * Half duplex
+ * No loopback
+ */
+ m8xx.fec.r_cntrl = M8xx_FEC_R_CNTRL_MII_MODE | M8xx_FEC_R_CNTRL_DRT;
+
+ /*
+ * Set up Transmit Control Register:
+ * Full duplex
+ * No heartbeat
+ */
+ m8xx.fec.x_cntrl = M8xx_FEC_X_CNTRL_FDEN;
+
+ /*
+ * Set up DMA function code:
+ * Big-endian
+ * DMA functino code = 0
+ */
+ m8xx.fec.fun_code = 0x78000000;
+
+ /*
+ * Initialize SDMA configuration register
+ * SDMA ignores FRZ
+ * FEC not aggressive
+ * FEC arbitration ID = 0 => U-bus arbitration = 6
+ * RISC arbitration ID = 1 => U-bus arbitration = 5
+ */
+ m8xx.sdcr = M8xx_SDCR_RAID_5;
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++)
+ (sc->rxBdBase + i)->status = 0;
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ (sc->txBdBase + i)->status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Mask all FEC interrupts and clear events
+ */
+ m8xx.fec.imask = M8xx_FEC_IEVENT_TFINT |
+ M8xx_FEC_IEVENT_RFINT;
+ m8xx.fec.ievent = ~0;
+
+ /*
+ * Set up interrupts
+ */
+ if (!BSP_install_rtems_irq_handler (&ethernetFECIrqData))
+ rtems_panic ("Can't attach M860 FEC interrupt handler\n");
+
+}
+static void fec_rxDaemon (void *arg)
+{
+ struct m8xx_fec_enet_struct *sc = (struct m8xx_fec_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ m8xxBufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ rxBd->status = M8xx_BD_EMPTY;
+ m8xx.fec.r_des_active = 0x1000000;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= M8xx_BD_WRAP;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & M8xx_BD_EMPTY) {
+ /*
+ * Clear old events
+ */
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_RFINT;
+
+ /*
+ * Wait for packet
+ * Note that the buffer descriptor is checked
+ * *before* the event wait -- this catches the
+ * possibility that a packet arrived between the
+ * `if' above, and the clearing of the event register.
+ */
+ while ((status = rxBd->status) & M8xx_BD_EMPTY) {
+ rtems_event_set events;
+
+ /*
+ * Unmask RXF (Full frame received) event
+ */
+ m8xx.fec.ievent |= M8xx_FEC_IEVENT_RFINT;
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if (status & M8xx_BD_LAST) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+
+ /*
+ * Invalidate the buffer for this descriptor
+ */
+ rtems_cache_invalidate_multiple_data_lines((const void *)rxBd->buffer, rxBd->length);
+
+ m = sc->rxMbuf[rxBdIndex];
+ m->m_len = m->m_pkthdr.len = rxBd->length -
+ sizeof(uint32_t) -
+ sizeof(struct ether_header);
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ }
+ else {
+ /*
+ * Something went wrong with the reception
+ */
+ if (!(status & M8xx_BD_LAST))
+ sc->rxNotLast++;
+ if (status & M8xx_BD_LONG)
+ sc->rxGiant++;
+ if (status & M8xx_BD_NONALIGNED)
+ sc->rxNonOctet++;
+ if (status & M8xx_BD_SHORT)
+ sc->rxRunt++;
+ if (status & M8xx_BD_CRC_ERROR)
+ sc->rxBadCRC++;
+ if (status & M8xx_BD_OVERRUN)
+ sc->rxOverrun++;
+ if (status & M8xx_BD_COLLISION)
+ sc->rxCollision++;
+ }
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & M8xx_BD_WRAP) |
+ M8xx_BD_EMPTY;
+ m8xx.fec.r_des_active = 0x1000000;
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ * Note that a buffer descriptor can't be retired as soon as it becomes
+ * ready. The MPC860 manual (MPC860UM/AD 07/98 Rev.1) and the MPC821
+ * manual state that, "If an Ethernet frame is made up of multiple
+ * buffers, the user should not reuse the first buffer descriptor until
+ * the last buffer descriptor of the frame has had its ready bit cleared
+ * by the CPM".
+ */
+static void
+m8xx_fec_Enet_retire_tx_bd (struct m8xx_fec_enet_struct *sc)
+{
+ uint16_t status;
+ int i;
+ int nRetired;
+ struct mbuf *m, *n;
+
+ i = sc->txBdTail;
+ nRetired = 0;
+ while ((sc->txBdActiveCount != 0)
+ && (((status = (sc->txBdBase + i)->status) & M8xx_BD_READY) == 0)) {
+ /*
+ * See if anything went wrong
+ */
+ if (status & (M8xx_BD_DEFER |
+ M8xx_BD_HEARTBEAT |
+ M8xx_BD_LATE_COLLISION |
+ M8xx_BD_RETRY_LIMIT |
+ M8xx_BD_UNDERRUN |
+ M8xx_BD_CARRIER_LOST)) {
+ /*
+ * Check for errors which stop the transmitter.
+ */
+ if (status & (M8xx_BD_LATE_COLLISION |
+ M8xx_BD_RETRY_LIMIT |
+ M8xx_BD_UNDERRUN)) {
+ if (status & M8xx_BD_LATE_COLLISION)
+ enet_driver[0].txLateCollision++;
+ if (status & M8xx_BD_RETRY_LIMIT)
+ enet_driver[0].txRetryLimit++;
+ if (status & M8xx_BD_UNDERRUN)
+ enet_driver[0].txUnderrun++;
+
+ }
+ if (status & M8xx_BD_DEFER)
+ enet_driver[0].txDeferred++;
+ if (status & M8xx_BD_HEARTBEAT)
+ enet_driver[0].txHeartbeat++;
+ if (status & M8xx_BD_CARRIER_LOST)
+ enet_driver[0].txLostCarrier++;
+ }
+ nRetired++;
+ if (status & M8xx_BD_LAST) {
+ /*
+ * A full frame has been transmitted.
+ * Free all the associated buffer descriptors.
+ */
+ sc->txBdActiveCount -= nRetired;
+ while (nRetired) {
+ nRetired--;
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE (m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ }
+ }
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+}
+
+static void fec_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct m8xx_fec_enet_struct *sc = ifp->if_softc;
+ volatile m8xxBufferDescriptor_t *firstTxBd, *txBd;
+ /* struct mbuf *l = NULL; */
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ m8xx_fec_Enet_retire_tx_bd (sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ txBd = firstTxBd = sc->txBdBase + sc->txBdHead;
+ for (;;) {
+ /*
+ * Wait for buffer descriptor to become available.
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events
+ */
+ m8xx.fec.ievent = M8xx_FEC_IEVENT_TFINT;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Note that the buffer descriptors are checked
+ * *before* * entering the wait loop -- this catches
+ * the possibility that a buffer descriptor became
+ * available between the `if' above, and the clearing
+ * of the event register.
+ * This is to catch the case where the transmitter
+ * stops in the middle of a frame -- and only the
+ * last buffer descriptor in a frame can generate
+ * an interrupt.
+ */
+ m8xx_fec_Enet_retire_tx_bd (sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+
+ /*
+ * Unmask TXB (buffer transmitted) and
+ * TXE (transmitter error) events.
+ */
+ m8xx.fec.ievent |= M8xx_FEC_IEVENT_TFINT;
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ m8xx_fec_Enet_retire_tx_bd (sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag till the
+ * whole packet has been readied.
+ */
+ status = nAdded ? M8xx_BD_READY : 0;
+
+ /*
+ * FIXME: Why not deal with empty mbufs at at higher level?
+ * The IP fragmentation routine in ip_output
+ * can produce packet fragments with zero length.
+ * I think that ip_output should be changed to get
+ * rid of these zero-length mbufs, but for now,
+ * I'll deal with them here.
+ */
+ if (m->m_len) {
+ /*
+ * Fill in the buffer descriptor
+ */
+ txBd->buffer = mtod (m, void *);
+ txBd->length = m->m_len;
+
+ /*
+ * Flush the buffer for this descriptor
+ */
+ rtems_cache_flush_multiple_data_lines((void *)txBd->buffer, txBd->length);
+
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= M8xx_BD_WRAP;
+ sc->txBdHead = 0;
+ }
+ /* l = m;*/
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE (m, n);
+ m = n;
+ /*
+ if (l != NULL)
+ l->m_next = m;
+ */
+ }
+
+ /*
+ * Set the transmit buffer status.
+ * Break out of the loop if this mbuf is the last in the frame.
+ */
+ if (m == NULL) {
+ if (nAdded) {
+ status |= M8xx_BD_LAST | M8xx_BD_TX_CRC;
+ txBd->status = status;
+ firstTxBd->status |= M8xx_BD_READY;
+ m8xx.fec.x_des_active = 0x1000000;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ txBd = sc->txBdBase + sc->txBdHead;
+ }
+}
+void fec_txDaemon (void *arg)
+{
+ struct m8xx_fec_enet_struct *sc = (struct m8xx_fec_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ fec_sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+static void fec_init (void *arg)
+{
+ struct m8xx_fec_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up FEC hardware
+ */
+ m8xx_fec_initialize_hardware (sc);
+
+ /*
+ * init access to phy
+ */
+ fec_mdio_init(sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("SCtx", 4096, fec_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("SCrx", 4096, fec_rxDaemon, sc);
+
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ m8xx.fec.r_cntrl |= M8xx_FEC_R_CNTRL_PROM;
+ else
+ m8xx.fec.r_cntrl &= ~M8xx_FEC_R_CNTRL_PROM;
+
+ /*
+ * init timer so the "watchdog function gets called periodically
+ */
+ ifp->if_timer = 1;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ m8xx.fec.ecntrl = M8xx_FEC_ECNTRL_ETHER_EN | M8xx_FEC_ECNTRL_FEC_PINMUX;
+}
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+m8xx_fec_enet_start (struct ifnet *ifp)
+{
+ struct m8xx_fec_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+static void fec_stop (struct m8xx_fec_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ m8xx.fec.ecntrl = 0x0;
+}
+
+/*
+ * Show interface statistics
+ */
+static void fec_enet_stats (struct m8xx_fec_enet_struct *sc)
+{
+ int media;
+ int result;
+ /*
+ * fetch/print media info
+ */
+ media = IFM_MAKEWORD(0,0,0,sc->phy_default); /* fetch from default phy */
+
+ result = fec_ioctl(&(sc->arpcom.ac_if),
+ SIOCGIFMEDIA,
+ (caddr_t)&media);
+ if (result == 0) {
+ rtems_ifmedia2str(media,NULL,0);
+ printf ("\n");
+ }
+
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Not First:%-8lu", sc->rxNotFirst);
+ printf (" Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Runt:%-8lu", sc->rxRunt);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" Collision:%-8lu\n", sc->rxCollision);
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" Deferred:%-8lu", sc->txDeferred);
+ printf (" Missed Hearbeat:%-8lu\n", sc->txHeartbeat);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf ("Retransmit Limit:%-8lu", sc->txRetryLimit);
+ printf (" Late Collision:%-8lu\n", sc->txLateCollision);
+ printf (" Underrun:%-8lu", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+static int fec_ioctl (struct ifnet *ifp,
+ ioctl_command_t command, caddr_t data)
+{
+ struct m8xx_fec_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ /*
+ * access PHY via MII
+ */
+ case SIOCGIFMEDIA:
+ case SIOCSIFMEDIA:
+ rtems_mii_ioctl (&(sc->mdio_info),sc,command,(void *)data);
+ break;
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ fec_stop (sc);
+ break;
+
+ case IFF_UP:
+ fec_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ fec_stop (sc);
+ fec_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ fec_enet_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+int fec_mode_adapt
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| init the PHY and adapt FEC settings |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ struct ifnet *ifp
+)
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| 0, if success |
+\*=========================================================================*/
+{
+ int result = 0;
+ struct m8xx_fec_enet_struct *sc = ifp->if_softc;
+ int media = IFM_MAKEWORD( 0, 0, 0, sc->phy_default);
+
+#ifdef DEBUG
+ printf("c");
+#endif
+ /*
+ * fetch media status
+ */
+ result = fec_ioctl(ifp,SIOCGIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+#ifdef DEBUG
+ printf("C");
+#endif
+ /*
+ * status is unchanged? then do nothing
+ */
+ if (media == sc->media_state) {
+ return 0;
+ }
+ /*
+ * otherwise: for the first call, try to negotiate mode
+ */
+ if (sc->media_state == 0) {
+ /*
+ * set media status: set auto negotiation -> start auto-negotiation
+ */
+ media = IFM_MAKEWORD(0,IFM_AUTO,0,sc->phy_default);
+ result = fec_ioctl(ifp,SIOCSIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+ /*
+ * wait for auto-negotiation to terminate
+ */
+ do {
+ media = IFM_MAKEWORD(0,0,0,sc->phy_default);
+ result = fec_ioctl(ifp,SIOCGIFMEDIA,(caddr_t)&media);
+ if (result != 0) {
+ return result;
+ }
+ } while (IFM_NONE == IFM_SUBTYPE(media));
+ }
+
+ /*
+ * now set HW according to media results:
+ */
+ /*
+ * if we are half duplex then switch to half duplex
+ */
+ if (0 == (IFM_FDX & IFM_OPTIONS(media))) {
+ m8xx.fec.x_cntrl &= ~M8xx_FEC_X_CNTRL_FDEN;
+ m8xx.fec.r_cntrl |= M8xx_FEC_R_CNTRL_DRT;
+ }
+ else {
+ m8xx.fec.x_cntrl |= M8xx_FEC_X_CNTRL_FDEN;
+ m8xx.fec.r_cntrl &= ~M8xx_FEC_R_CNTRL_DRT;
+ }
+ /*
+ * store current media state for future compares
+ */
+ sc->media_state = media;
+
+ return 0;
+}
+
+/*=========================================================================*\
+| Function: |
+\*-------------------------------------------------------------------------*/
+static void fec_watchdog
+(
+/*-------------------------------------------------------------------------*\
+| Purpose: |
+| periodically poll the PHY. if mode has changed, |
+| then adjust the FEC settings |
++---------------------------------------------------------------------------+
+| Input Parameters: |
+\*-------------------------------------------------------------------------*/
+ struct ifnet *ifp
+)
+/*-------------------------------------------------------------------------*\
+| Return Value: |
+| 1, if success |
+\*=========================================================================*/
+{
+ fec_mode_adapt(ifp);
+ ifp->if_timer = FEC_WATCHDOG_TIMEOUT;
+}
+
+int rtems_fec_driver_attach (struct rtems_bsdnet_ifconfig *config)
+{
+ struct m8xx_fec_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ static const uint8_t maczero[] ={0,0,0,0,0,0};
+
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES)) {
+ printk ("Bad FEC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printk ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+ if (config->hardware_address) {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+#ifdef BSP_HAS_TQMMON
+ else if(0 != memcmp(maczero,TQM_BD_INFO.eth_addr,ETHER_ADDR_LEN)) {
+ memcpy (sc->arpcom.ac_enaddr, TQM_BD_INFO.eth_addr, ETHER_ADDR_LEN);
+ }
+#endif
+ else {
+ /* FIXME to read the enaddr from NVRAM */
+ }
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * setup info about mdio interface
+ */
+ sc->mdio_info.mdio_r = fec_mdio_read;
+ sc->mdio_info.mdio_w = fec_mdio_write;
+ sc->mdio_info.has_gmii = 0; /* we do not support gigabit IF */
+ /*
+ * assume: IF 1 -> PHY 0
+ */
+ sc->phy_default = unitNumber-1;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = fec_init;
+ ifp->if_ioctl = fec_ioctl;
+ ifp->if_start = m8xx_fec_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_watchdog = fec_watchdog; /* XXX: timer is set in "init" */
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+};
+
+int rtems_fec_enet_driver_attach(struct rtems_bsdnet_ifconfig *config,
+ int attaching)
+{
+ /*
+ * enable FEC functionality at hardware pins*
+ * PD[3-15] are FEC pins
+ */
+ if (attaching) {
+ m8xx.pdpar |= 0x1fff;
+ m8xx.pddir |= 0x1fff;
+ }
+ return rtems_fec_driver_attach(config);
+}
diff --git a/bsps/powerpc/tqm8xx/net/network_scc.c b/bsps/powerpc/tqm8xx/net/network_scc.c
new file mode 100644
index 0000000..e263beb
--- /dev/null
+++ b/bsps/powerpc/tqm8xx/net/network_scc.c
@@ -0,0 +1,1049 @@
+/*===============================================================*\
+| Project: RTEMS TQM8xx BSP |
++-----------------------------------------------------------------+
+| This file has been adapted to MPC8xx by |
+| Thomas Doerfler <Thomas.Doerfler@embedded-brains.de> |
+| Copyright (c) 2008 |
+| Embedded Brains GmbH |
+| Obere Lagerstr. 30 |
+| D-82178 Puchheim |
+| Germany |
+| rtems@embedded-brains.de |
+| |
+| See the other copyright notice below for the original parts. |
++-----------------------------------------------------------------+
+| The license and distribution terms for this file may be |
+| found in the file LICENSE in this distribution or at |
+| |
+| http://www.rtems.org/license/LICENSE. |
+| |
++-----------------------------------------------------------------+
+| this file contains the console driver |
+\*===============================================================*/
+/* derived from: */
+/*
+ * RTEMS/TCPIP driver for MPC8xx SCC1 Ethernet
+ *
+ * Modified for MPC860 by Jay Monkman (jmonkman@frasca.com)
+ *
+ * This supports Ethernet on either SCC1 or the FEC of the MPC860T.
+ * Right now, we only do 10 Mbps, even with the FEC. The function
+ * rtems_enet_driver_attach determines which one to use. Currently,
+ * only one may be used at a time.
+ *
+ * Based on the MC68360 network driver by
+ * W. Eric Norum
+ * Saskatchewan Accelerator Laboratory
+ * University of Saskatchewan
+ * Saskatoon, Saskatchewan, CANADA
+ * eric@skatter.usask.ca
+ *
+ * This supports ethernet on SCC1. Right now, we only do 10 Mbps.
+ *
+ * Modifications by Darlene Stewart <Darlene.Stewart@iit.nrc.ca>
+ * and Charles-Antoine Gauthier <charles.gauthier@iit.nrc.ca>
+ * Copyright (c) 1999, National Research Council of Canada
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <stdio.h>
+#include <errno.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+#include <sys/socket.h>
+#include <sys/sockio.h>
+
+#include <net/if.h>
+
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+#include <bsp/irq.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+
+/*
+ * Number of interfaces supported by this driver
+ */
+#define NIFACES 1
+
+/*
+ * Default number of buffer descriptors set aside for this driver.
+ * The number of transmit buffer descriptors has to be quite large
+ * since a single frame often uses four or more buffer descriptors.
+ */
+#define RX_BUF_COUNT 32
+#define TX_BUF_COUNT 8
+#define TX_BD_PER_BUF 4
+
+#define INET_ADDR_MAX_BUF_SIZE (sizeof "255.255.255.255")
+
+/*
+ * RTEMS event used by interrupt handler to signal daemons.
+ * This must *not* be the same event used by the TCP/IP task synchronization.
+ */
+#define INTERRUPT_EVENT RTEMS_EVENT_1
+
+/*
+ * RTEMS event used to start transmit daemon.
+ * This must not be the same as INTERRUPT_EVENT.
+ */
+#define START_TRANSMIT_EVENT RTEMS_EVENT_2
+
+/*
+ * Receive buffer size -- Allow for a full ethernet packet plus CRC (1518).
+ * Round off to nearest multiple of RBUF_ALIGN.
+ */
+#define MAX_MTU_SIZE 1518
+#define RBUF_ALIGN 4
+#define RBUF_SIZE ((MAX_MTU_SIZE + RBUF_ALIGN) & ~RBUF_ALIGN)
+
+#if (MCLBYTES < RBUF_SIZE)
+# error "Driver must have MCLBYTES > RBUF_SIZE"
+#endif
+
+/*
+ * Per-device data
+ */
+struct m8xx_enet_struct {
+ struct arpcom arpcom;
+ struct mbuf **rxMbuf;
+ struct mbuf **txMbuf;
+ int acceptBroadcast;
+ int rxBdCount;
+ int txBdCount;
+ int txBdHead;
+ int txBdTail;
+ int txBdActiveCount;
+ m8xxBufferDescriptor_t *rxBdBase;
+ m8xxBufferDescriptor_t *txBdBase;
+ rtems_id rxDaemonTid;
+ rtems_id txDaemonTid;
+
+ /*
+ * Statistics
+ */
+ unsigned long rxInterrupts;
+ unsigned long rxNotFirst;
+ unsigned long rxNotLast;
+ unsigned long rxGiant;
+ unsigned long rxNonOctet;
+ unsigned long rxRunt;
+ unsigned long rxBadCRC;
+ unsigned long rxOverrun;
+ unsigned long rxCollision;
+
+ unsigned long txInterrupts;
+ unsigned long txDeferred;
+ unsigned long txHeartbeat;
+ unsigned long txLateCollision;
+ unsigned long txRetryLimit;
+ unsigned long txUnderrun;
+ unsigned long txLostCarrier;
+ unsigned long txRawWait;
+};
+static struct m8xx_enet_struct enet_driver[NIFACES];
+
+static void m8xx_scc1_ethernet_on(const rtems_irq_connect_data* ptr)
+{
+}
+
+static void m8xx_scc1_ethernet_off(const rtems_irq_connect_data* ptr)
+{
+ /*
+ * Please put relevant code there
+ */
+}
+
+static int m8xx_scc1_ethernet_isOn(const rtems_irq_connect_data* ptr)
+{
+ /*
+ * Assume, that we are on
+ */
+ return 1;
+}
+
+/*
+ * SCC1 interrupt handler
+ */
+static void m8xx_scc1_interrupt_handler (void *unused)
+{
+ /* Frame received? */
+ if ((m8xx.scc1.sccm & 0x8) && (m8xx.scc1.scce & 0x8)) {
+ m8xx.scc1.scce = 0x8; /* Clear receive frame int */
+ m8xx.scc1.sccm &= ~0x8; /* Disable receive frame ints */
+ enet_driver[0].rxInterrupts++; /* Rx int has occurred */
+ rtems_bsdnet_event_send (enet_driver[0].rxDaemonTid, INTERRUPT_EVENT);
+ }
+
+ /* Buffer transmitted or transmitter error? */
+ if ((m8xx.scc1.sccm & 0x12) && (m8xx.scc1.scce & 0x12)) {
+ m8xx.scc1.scce = 0x12; /* Clear Tx int */
+ m8xx.scc1.sccm &= ~0x12; /* Disable Tx ints */
+ enet_driver[0].txInterrupts++; /* Tx int has occurred */
+ rtems_bsdnet_event_send (enet_driver[0].txDaemonTid, INTERRUPT_EVENT);
+ }
+}
+
+
+static rtems_irq_connect_data ethernetSCC1IrqData = {
+ BSP_CPM_IRQ_SCC1,
+ (rtems_irq_hdl) m8xx_scc1_interrupt_handler,
+ NULL,
+ m8xx_scc1_ethernet_on,
+ m8xx_scc1_ethernet_off,
+ m8xx_scc1_ethernet_isOn
+};
+
+/*
+ * Initialize the ethernet hardware
+ */
+static void
+m8xx_enet_initialize (struct m8xx_enet_struct *sc)
+{
+ int i;
+ unsigned char *hwaddr;
+
+ /*
+ * Configure port A
+ * PA15 is enet RxD. Set PAPAR(15) to 1, PADIR(15) to 0.
+ * PA14 is enet TxD. Set PAPAR(14) to 1, PADIR(14) to 0, PAODR(14) to 0.
+ * PA7 is input CLK1. Set PAPAR(7) to 1, PADIR(7) to 0.
+ * PA6 is input CLK2. Set PAPAR(6) to 1, PADIR(6) to 0.
+ */
+ m8xx.papar |= 0x303;
+ m8xx.padir &= ~0x303;
+ m8xx.paodr &= ~0x2;
+
+ /*
+ * Configure port C
+ * PC11 is CTS1*. Set PCPAR(11) to 0, PCDIR(11) to 0, and PCSO(11) to 1.
+ * PC10 is CD1*. Set PCPAR(10) to 0, PCDIR(10) to 0, and PCSO(10) to 1.
+ */
+ m8xx.pcpar &= ~0x30;
+ m8xx.pcdir &= ~0x30;
+ m8xx.pcso |= 0x30;
+
+ /*
+ * Connect CLK1 and CLK2 to SCC1 in the SICR.
+ * CLK1 is TxClk, CLK2 is RxClk. No grant mechanism, SCC1 is directly
+ * connected to the NMSI pins.
+ * R1CS = 0b101 (CLK2)
+ * T1CS = 0b100 (CLK1)
+ */
+ m8xx.sicr |= 0x2C;
+
+ /*
+ * Initialize SDMA configuration register
+ */
+ m8xx.sdcr = 1;
+
+ /*
+ * Allocate mbuf pointers
+ */
+ sc->rxMbuf = malloc (sc->rxBdCount * sizeof *sc->rxMbuf,
+ M_MBUF, M_NOWAIT);
+ sc->txMbuf = malloc (sc->txBdCount * sizeof *sc->txMbuf,
+ M_MBUF, M_NOWAIT);
+ if (!sc->rxMbuf || !sc->txMbuf)
+ rtems_panic ("No memory for mbuf pointers");
+
+ /*
+ * Set receiver and transmitter buffer descriptor bases
+ */
+ sc->rxBdBase = m8xx_bd_allocate(sc->rxBdCount);
+ sc->txBdBase = m8xx_bd_allocate(sc->txBdCount);
+ m8xx.scc1p.rbase = (char *)sc->rxBdBase - (char *)&m8xx;
+ m8xx.scc1p.tbase = (char *)sc->txBdBase - (char *)&m8xx;
+
+ /*
+ * Send "Init parameters" command
+ */
+ m8xx_cp_execute_cmd (M8xx_CR_OP_INIT_RX_TX | M8xx_CR_CHAN_SCC1);
+
+ /*
+ * Set receive and transmit function codes
+ */
+ m8xx.scc1p.rfcr = M8xx_RFCR_MOT | M8xx_RFCR_DMA_SPACE(0);
+ m8xx.scc1p.tfcr = M8xx_TFCR_MOT | M8xx_TFCR_DMA_SPACE(0);
+
+ /*
+ * Set maximum receive buffer length
+ */
+ m8xx.scc1p.mrblr = RBUF_SIZE;
+
+ /*
+ * Set CRC parameters
+ */
+ m8xx.scc1p.un.ethernet.c_pres = 0xFFFFFFFF;
+ m8xx.scc1p.un.ethernet.c_mask = 0xDEBB20E3;
+
+ /*
+ * Clear diagnostic counters
+ */
+ m8xx.scc1p.un.ethernet.crcec = 0;
+ m8xx.scc1p.un.ethernet.alec = 0;
+ m8xx.scc1p.un.ethernet.disfc = 0;
+
+ /*
+ * Set pad value
+ */
+ m8xx.scc1p.un.ethernet.pads = 0x8888;
+
+ /*
+ * Set retry limit
+ */
+ m8xx.scc1p.un.ethernet.ret_lim = 15;
+
+ /*
+ * Set maximum and minimum frame length
+ */
+ m8xx.scc1p.un.ethernet.mflr = 1518;
+ m8xx.scc1p.un.ethernet.minflr = 64;
+ m8xx.scc1p.un.ethernet.maxd1 = MAX_MTU_SIZE;
+ m8xx.scc1p.un.ethernet.maxd2 = MAX_MTU_SIZE;
+
+ /*
+ * Clear group address hash table
+ */
+ m8xx.scc1p.un.ethernet.gaddr1 = 0;
+ m8xx.scc1p.un.ethernet.gaddr2 = 0;
+ m8xx.scc1p.un.ethernet.gaddr3 = 0;
+ m8xx.scc1p.un.ethernet.gaddr4 = 0;
+
+ /*
+ * Set our physical address
+ */
+ hwaddr = sc->arpcom.ac_enaddr;
+
+ m8xx.scc1p.un.ethernet.paddr_h = (hwaddr[5] << 8) | hwaddr[4];
+ m8xx.scc1p.un.ethernet.paddr_m = (hwaddr[3] << 8) | hwaddr[2];
+ m8xx.scc1p.un.ethernet.paddr_l = (hwaddr[1] << 8) | hwaddr[0];
+
+ /*
+ * Aggressive retry
+ */
+ m8xx.scc1p.un.ethernet.p_per = 0;
+
+ /*
+ * Clear individual address hash table
+ */
+ m8xx.scc1p.un.ethernet.iaddr1 = 0;
+ m8xx.scc1p.un.ethernet.iaddr2 = 0;
+ m8xx.scc1p.un.ethernet.iaddr3 = 0;
+ m8xx.scc1p.un.ethernet.iaddr4 = 0;
+
+ /*
+ * Clear temp address
+ */
+ m8xx.scc1p.un.ethernet.taddr_l = 0;
+ m8xx.scc1p.un.ethernet.taddr_m = 0;
+ m8xx.scc1p.un.ethernet.taddr_h = 0;
+
+ /*
+ * Set up receive buffer descriptors
+ */
+ for (i = 0 ; i < sc->rxBdCount ; i++) {
+ (sc->rxBdBase + i)->status = 0;
+ }
+
+ /*
+ * Set up transmit buffer descriptors
+ */
+ for (i = 0 ; i < sc->txBdCount ; i++) {
+ (sc->txBdBase + i)->status = 0;
+ sc->txMbuf[i] = NULL;
+ }
+ sc->txBdHead = sc->txBdTail = 0;
+ sc->txBdActiveCount = 0;
+
+ /*
+ * Clear any outstanding events
+ */
+ m8xx.scc1.scce = 0xFFFF;
+
+ /*
+ * Set up interrupts
+ */
+ if (!BSP_install_rtems_irq_handler (&ethernetSCC1IrqData)) {
+ rtems_panic ("Can't attach M8xx SCC1 interrupt handler\n");
+ }
+ m8xx.scc1.sccm = 0; /* No interrupts unmasked till necessary */
+
+ /*
+ * Set up General SCC Mode Register
+ * Ethernet configuration
+ */
+ m8xx.scc1.gsmr_h = 0x0;
+ m8xx.scc1.gsmr_l = 0x1088000c;
+
+ /*
+ * Set up data synchronization register
+ * Ethernet synchronization pattern
+ */
+ m8xx.scc1.dsr = 0xd555;
+
+ /*
+ * Set up protocol-specific mode register
+ * No Heartbeat check
+ * No force collision
+ * Discard short frames
+ * Individual address mode
+ * Ethernet CRC
+ * Not promisuous
+ * Ignore/accept broadcast packets as specified
+ * Normal backoff timer
+ * No loopback
+ * No input sample at end of frame
+ * 64-byte limit for late collision
+ * Wait 22 bits before looking for start of frame delimiter
+ * Disable full-duplex operation
+ */
+ m8xx.scc1.psmr = 0x080A | (sc->acceptBroadcast ? 0 : 0x100);
+
+ /*
+ * Enable the TENA (RTS1*) pin
+ */
+ m8xx.pcpar |= 0x1;
+ m8xx.pcdir &= ~0x1;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ m8xx.scc1.gsmr_l = 0x1088003c;
+}
+
+
+/*
+ * Soak up buffer descriptors that have been sent.
+ * Note that a buffer descriptor can't be retired as soon as it becomes
+ * ready. The MPC860 manual (MPC860UM/AD 07/98 Rev.1) and the MPC821
+ * manual state that, "If an Ethernet frame is made up of multiple
+ * buffers, the user should not reuse the first buffer descriptor until
+ * the last buffer descriptor of the frame has had its ready bit cleared
+ * by the CPM".
+ */
+static void
+m8xx_Enet_retire_tx_bd (struct m8xx_enet_struct *sc)
+{
+ uint16_t status;
+ int i;
+ int nRetired;
+ struct mbuf *m, *n;
+
+ i = sc->txBdTail;
+ nRetired = 0;
+ while ((sc->txBdActiveCount != 0)
+ && (((status = (sc->txBdBase + i)->status) & M8xx_BD_READY) == 0)) {
+ /*
+ * See if anything went wrong
+ */
+ if (status & (M8xx_BD_DEFER |
+ M8xx_BD_HEARTBEAT |
+ M8xx_BD_LATE_COLLISION |
+ M8xx_BD_RETRY_LIMIT |
+ M8xx_BD_UNDERRUN |
+ M8xx_BD_CARRIER_LOST)) {
+ /*
+ * Check for errors which stop the transmitter.
+ */
+ if (status & (M8xx_BD_LATE_COLLISION |
+ M8xx_BD_RETRY_LIMIT |
+ M8xx_BD_UNDERRUN)) {
+ if (status & M8xx_BD_LATE_COLLISION)
+ enet_driver[0].txLateCollision++;
+ if (status & M8xx_BD_RETRY_LIMIT)
+ enet_driver[0].txRetryLimit++;
+ if (status & M8xx_BD_UNDERRUN)
+ enet_driver[0].txUnderrun++;
+
+ /*
+ * Restart the transmitter
+ */
+ m8xx_cp_execute_cmd (M8xx_CR_OP_RESTART_TX | M8xx_CR_CHAN_SCC1);
+ }
+ if (status & M8xx_BD_DEFER)
+ enet_driver[0].txDeferred++;
+ if (status & M8xx_BD_HEARTBEAT)
+ enet_driver[0].txHeartbeat++;
+ if (status & M8xx_BD_CARRIER_LOST)
+ enet_driver[0].txLostCarrier++;
+ }
+ nRetired++;
+ if (status & M8xx_BD_LAST) {
+ /*
+ * A full frame has been transmitted.
+ * Free all the associated buffer descriptors.
+ */
+ sc->txBdActiveCount -= nRetired;
+ while (nRetired) {
+ nRetired--;
+ m = sc->txMbuf[sc->txBdTail];
+ MFREE (m, n);
+ if (++sc->txBdTail == sc->txBdCount)
+ sc->txBdTail = 0;
+ }
+ }
+ if (++i == sc->txBdCount)
+ i = 0;
+ }
+}
+
+/*
+ * reader task
+ */
+static void
+scc_rxDaemon (void *arg)
+{
+ struct m8xx_enet_struct *sc = (struct m8xx_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ uint16_t status;
+ m8xxBufferDescriptor_t *rxBd;
+ int rxBdIndex;
+
+ /*
+ * Allocate space for incoming packets and start reception
+ */
+ for (rxBdIndex = 0 ; ;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ rxBd->status = M8xx_BD_EMPTY | M8xx_BD_INTERRUPT;
+ if (++rxBdIndex == sc->rxBdCount) {
+ rxBd->status |= M8xx_BD_WRAP;
+ break;
+ }
+ }
+
+ /*
+ * Input packet handling loop
+ */
+ rxBdIndex = 0;
+ for (;;) {
+ rxBd = sc->rxBdBase + rxBdIndex;
+
+ /*
+ * Wait for packet if there's not one ready
+ */
+ if ((status = rxBd->status) & M8xx_BD_EMPTY) {
+ /*
+ * Clear old events
+ */
+ m8xx.scc1.scce = 0x8;
+
+ /*
+ * Wait for packet
+ * Note that the buffer descriptor is checked
+ * *before* the event wait -- this catches the
+ * possibility that a packet arrived between the
+ * `if' above, and the clearing of the event register.
+ */
+ while ((status = rxBd->status) & M8xx_BD_EMPTY) {
+ rtems_event_set events;
+
+ /*
+ * Unmask RXF (Full frame received) event
+ */
+ m8xx.scc1.sccm |= 0x8;
+
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ }
+ }
+
+ /*
+ * Check that packet is valid
+ */
+ if ((status & (M8xx_BD_LAST |
+ M8xx_BD_FIRST_IN_FRAME |
+ M8xx_BD_LONG |
+ M8xx_BD_NONALIGNED |
+ M8xx_BD_SHORT |
+ M8xx_BD_CRC_ERROR |
+ M8xx_BD_OVERRUN |
+ M8xx_BD_COLLISION)) ==
+ (M8xx_BD_LAST |
+ M8xx_BD_FIRST_IN_FRAME)) {
+ /*
+ * Pass the packet up the chain.
+ * FIXME: Packet filtering hook could be done here.
+ */
+ struct ether_header *eh;
+
+ /*
+ * Invalidate the buffer for this descriptor
+ */
+ rtems_cache_invalidate_multiple_data_lines((const void *)rxBd->buffer, rxBd->length);
+
+ m = sc->rxMbuf[rxBdIndex];
+ m->m_len = m->m_pkthdr.len = rxBd->length -
+ sizeof(uint32_t) -
+ sizeof(struct ether_header);
+ eh = mtod (m, struct ether_header *);
+ m->m_data += sizeof(struct ether_header);
+ ether_input (ifp, eh, m);
+
+ /*
+ * Allocate a new mbuf
+ */
+ MGETHDR (m, M_WAIT, MT_DATA);
+ MCLGET (m, M_WAIT);
+ m->m_pkthdr.rcvif = ifp;
+ sc->rxMbuf[rxBdIndex] = m;
+ rxBd->buffer = mtod (m, void *);
+ }
+ else {
+ /*
+ * Something went wrong with the reception
+ */
+ if (!(status & M8xx_BD_LAST))
+ sc->rxNotLast++;
+ if (!(status & M8xx_BD_FIRST_IN_FRAME))
+ sc->rxNotFirst++;
+ if (status & M8xx_BD_LONG)
+ sc->rxGiant++;
+ if (status & M8xx_BD_NONALIGNED)
+ sc->rxNonOctet++;
+ if (status & M8xx_BD_SHORT)
+ sc->rxRunt++;
+ if (status & M8xx_BD_CRC_ERROR)
+ sc->rxBadCRC++;
+ if (status & M8xx_BD_OVERRUN)
+ sc->rxOverrun++;
+ if (status & M8xx_BD_COLLISION)
+ sc->rxCollision++;
+ }
+
+ /*
+ * Reenable the buffer descriptor
+ */
+ rxBd->status = (status & (M8xx_BD_WRAP | M8xx_BD_INTERRUPT)) |
+ M8xx_BD_EMPTY;
+
+ /*
+ * Move to next buffer descriptor
+ */
+ if (++rxBdIndex == sc->rxBdCount)
+ rxBdIndex = 0;
+ }
+}
+
+
+static void
+scc_sendpacket (struct ifnet *ifp, struct mbuf *m)
+{
+ struct m8xx_enet_struct *sc = ifp->if_softc;
+ volatile m8xxBufferDescriptor_t *firstTxBd, *txBd;
+ struct mbuf *l = NULL;
+ uint16_t status;
+ int nAdded;
+
+ /*
+ * Free up buffer descriptors
+ */
+ m8xx_Enet_retire_tx_bd (sc);
+
+ /*
+ * Set up the transmit buffer descriptors.
+ * No need to pad out short packets since the
+ * hardware takes care of that automatically.
+ * No need to copy the packet to a contiguous buffer
+ * since the hardware is capable of scatter/gather DMA.
+ */
+ nAdded = 0;
+ txBd = firstTxBd = sc->txBdBase + sc->txBdHead;
+ for (;;) {
+ /*
+ * Wait for buffer descriptor to become available.
+ */
+ if ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ /*
+ * Clear old events
+ */
+ m8xx.scc1.scce = 0x12;
+
+ /*
+ * Wait for buffer descriptor to become available.
+ * Note that the buffer descriptors are checked
+ * *before* * entering the wait loop -- this catches
+ * the possibility that a buffer descriptor became
+ * available between the `if' above, and the clearing
+ * of the event register.
+ * This is to catch the case where the transmitter
+ * stops in the middle of a frame -- and only the
+ * last buffer descriptor in a frame can generate
+ * an interrupt.
+ */
+ m8xx_Enet_retire_tx_bd (sc);
+ while ((sc->txBdActiveCount + nAdded) == sc->txBdCount) {
+ rtems_event_set events;
+
+ /*
+ * Unmask TXB (buffer transmitted) and
+ * TXE (transmitter error) events.
+ */
+ m8xx.scc1.sccm |= 0x12;
+ rtems_bsdnet_event_receive (INTERRUPT_EVENT,
+ RTEMS_WAIT|RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+ m8xx_Enet_retire_tx_bd (sc);
+ }
+ }
+
+ /*
+ * Don't set the READY flag till the
+ * whole packet has been readied.
+ */
+ status = nAdded ? M8xx_BD_READY : 0;
+
+ /*
+ * FIXME: Why not deal with empty mbufs at at higher level?
+ * The IP fragmentation routine in ip_output
+ * can produce packet fragments with zero length.
+ * I think that ip_output should be changed to get
+ * rid of these zero-length mbufs, but for now,
+ * I'll deal with them here.
+ */
+ if (m->m_len) {
+ /*
+ * Fill in the buffer descriptor
+ */
+ txBd->buffer = mtod (m, void *);
+ txBd->length = m->m_len;
+
+ /*
+ * Flush the buffer for this descriptor
+ */
+ rtems_cache_flush_multiple_data_lines((const void *)txBd->buffer, txBd->length);
+
+ sc->txMbuf[sc->txBdHead] = m;
+ nAdded++;
+ if (++sc->txBdHead == sc->txBdCount) {
+ status |= M8xx_BD_WRAP;
+ sc->txBdHead = 0;
+ }
+ l = m;
+ m = m->m_next;
+ }
+ else {
+ /*
+ * Just toss empty mbufs
+ */
+ struct mbuf *n;
+ MFREE (m, n);
+ m = n;
+ if (l != NULL)
+ l->m_next = m;
+ }
+
+ /*
+ * Set the transmit buffer status.
+ * Break out of the loop if this mbuf is the last in the frame.
+ */
+ if (m == NULL) {
+ if (nAdded) {
+ status |= M8xx_BD_PAD | M8xx_BD_LAST | M8xx_BD_TX_CRC | M8xx_BD_INTERRUPT;
+ txBd->status = status;
+ firstTxBd->status |= M8xx_BD_READY;
+ sc->txBdActiveCount += nAdded;
+ }
+ break;
+ }
+ txBd->status = status;
+ txBd = sc->txBdBase + sc->txBdHead;
+ }
+}
+
+
+/*
+ * Driver transmit daemon
+ */
+void
+scc_txDaemon (void *arg)
+{
+ struct m8xx_enet_struct *sc = (struct m8xx_enet_struct *)arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+ struct mbuf *m;
+ rtems_event_set events;
+
+ for (;;) {
+ /*
+ * Wait for packet
+ */
+ rtems_bsdnet_event_receive (START_TRANSMIT_EVENT, RTEMS_EVENT_ANY | RTEMS_WAIT, RTEMS_NO_TIMEOUT, &events);
+
+ /*
+ * Send packets till queue is empty
+ */
+ for (;;) {
+ /*
+ * Get the next mbuf chain to transmit.
+ */
+ IF_DEQUEUE(&ifp->if_snd, m);
+ if (!m)
+ break;
+ scc_sendpacket (ifp, m);
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+ }
+}
+
+
+/*
+ * Send packet (caller provides header).
+ */
+static void
+m8xx_enet_start (struct ifnet *ifp)
+{
+ struct m8xx_enet_struct *sc = ifp->if_softc;
+
+ rtems_bsdnet_event_send (sc->txDaemonTid, START_TRANSMIT_EVENT);
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/*
+ * Initialize and start the device
+ */
+static void
+scc_init (void *arg)
+{
+ struct m8xx_enet_struct *sc = arg;
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ if (sc->txDaemonTid == 0) {
+
+ /*
+ * Set up SCC hardware
+ */
+ m8xx_enet_initialize (sc);
+
+ /*
+ * Start driver tasks
+ */
+ sc->txDaemonTid = rtems_bsdnet_newproc ("SCtx", 4096, scc_txDaemon, sc);
+ sc->rxDaemonTid = rtems_bsdnet_newproc ("SCrx", 4096, scc_rxDaemon, sc);
+
+ }
+
+ /*
+ * Set flags appropriately
+ */
+ if (ifp->if_flags & IFF_PROMISC)
+ m8xx.scc1.psmr |= 0x200;
+ else
+ m8xx.scc1.psmr &= ~0x200;
+
+ /*
+ * Tell the world that we're running.
+ */
+ ifp->if_flags |= IFF_RUNNING;
+
+ /*
+ * Enable receiver and transmitter
+ */
+ m8xx.scc1.gsmr_l |= 0x30;
+}
+
+
+/*
+ * Stop the device
+ */
+static void
+scc_stop (struct m8xx_enet_struct *sc)
+{
+ struct ifnet *ifp = &sc->arpcom.ac_if;
+
+ ifp->if_flags &= ~IFF_RUNNING;
+
+ /*
+ * Shut down receiver and transmitter
+ */
+ m8xx.scc1.gsmr_l &= ~0x30;
+}
+
+
+/*
+ * Show interface statistics
+ */
+static void
+enet_stats (struct m8xx_enet_struct *sc)
+{
+ printf (" Rx Interrupts:%-8lu", sc->rxInterrupts);
+ printf (" Not First:%-8lu", sc->rxNotFirst);
+ printf (" Not Last:%-8lu\n", sc->rxNotLast);
+ printf (" Giant:%-8lu", sc->rxGiant);
+ printf (" Runt:%-8lu", sc->rxRunt);
+ printf (" Non-octet:%-8lu\n", sc->rxNonOctet);
+ printf (" Bad CRC:%-8lu", sc->rxBadCRC);
+ printf (" Overrun:%-8lu", sc->rxOverrun);
+ printf (" Collision:%-8lu\n", sc->rxCollision);
+ printf (" Discarded:%-8lu\n", (unsigned long)m8xx.scc1p.un.ethernet.disfc);
+
+ printf (" Tx Interrupts:%-8lu", sc->txInterrupts);
+ printf (" Deferred:%-8lu", sc->txDeferred);
+ printf (" Missed Hearbeat:%-8lu\n", sc->txHeartbeat);
+ printf (" No Carrier:%-8lu", sc->txLostCarrier);
+ printf ("Retransmit Limit:%-8lu", sc->txRetryLimit);
+ printf (" Late Collision:%-8lu\n", sc->txLateCollision);
+ printf (" Underrun:%-8lu", sc->txUnderrun);
+ printf (" Raw output wait:%-8lu\n", sc->txRawWait);
+}
+
+/*
+ * Driver ioctl handler
+ */
+static int
+scc_ioctl (struct ifnet *ifp, ioctl_command_t command, caddr_t data)
+{
+ struct m8xx_enet_struct *sc = ifp->if_softc;
+ int error = 0;
+
+ switch (command) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl (ifp, command, data);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch (ifp->if_flags & (IFF_UP | IFF_RUNNING)) {
+ case IFF_RUNNING:
+ scc_stop (sc);
+ break;
+
+ case IFF_UP:
+ scc_init (sc);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ scc_stop (sc);
+ scc_init (sc);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIO_RTEMS_SHOW_STATS:
+ enet_stats (sc);
+ break;
+
+ /*
+ * FIXME: All sorts of multicast commands need to be added here!
+ */
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+
+/*
+ * Attach an SCC driver to the system
+ */
+int
+rtems_scc1_driver_attach (struct rtems_bsdnet_ifconfig *config)
+{
+ struct m8xx_enet_struct *sc;
+ struct ifnet *ifp;
+ int mtu;
+ int unitNumber;
+ char *unitName;
+ static const uint8_t maczero[] ={0,0,0,0,0,0};
+ /*
+ * Parse driver name
+ */
+ if ((unitNumber = rtems_bsdnet_parse_driver_name (config, &unitName)) < 0)
+ return 0;
+
+ /*
+ * Is driver free?
+ */
+ if ((unitNumber <= 0) || (unitNumber > NIFACES)) {
+ printf ("Bad SCC unit number.\n");
+ return 0;
+ }
+ sc = &enet_driver[unitNumber - 1];
+ ifp = &sc->arpcom.ac_if;
+ if (ifp->if_softc != NULL) {
+ printf ("Driver already in use.\n");
+ return 0;
+ }
+
+ /*
+ * Process options
+ */
+
+ /*
+ * MAC address: try to fetch it from config, else from TQMMon, else panic
+ */
+ if (config->hardware_address) {
+ memcpy (sc->arpcom.ac_enaddr, config->hardware_address, ETHER_ADDR_LEN);
+ }
+#ifdef BSP_HAS_TQMMON
+ else if(0 != memcmp(maczero,TQM_BD_INFO.eth_addr,ETHER_ADDR_LEN)) {
+ memcpy (sc->arpcom.ac_enaddr, TQM_BD_INFO.eth_addr, ETHER_ADDR_LEN);
+ }
+#endif
+ else {
+ /* There is no ethernet address provided, so it could be read
+ * from the Ethernet protocol block of SCC1 in DPRAM.
+ */
+ rtems_panic("No Ethernet address specified!\n");
+ }
+
+ if (config->mtu)
+ mtu = config->mtu;
+ else
+ mtu = ETHERMTU;
+ if (config->rbuf_count)
+ sc->rxBdCount = config->rbuf_count;
+ else
+ sc->rxBdCount = RX_BUF_COUNT;
+ if (config->xbuf_count)
+ sc->txBdCount = config->xbuf_count;
+ else
+ sc->txBdCount = TX_BUF_COUNT * TX_BD_PER_BUF;
+ sc->acceptBroadcast = !config->ignore_broadcast;
+
+ /*
+ * Set up network interface values
+ */
+ ifp->if_softc = sc;
+ ifp->if_unit = unitNumber;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = scc_init;
+ ifp->if_ioctl = scc_ioctl;
+ ifp->if_start = m8xx_enet_start;
+ ifp->if_output = ether_output;
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX;
+ if (ifp->if_snd.ifq_maxlen == 0)
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+
+ /*
+ * Attach the interface
+ */
+ if_attach (ifp);
+ ether_ifattach (ifp);
+ return 1;
+};
+
+int
+rtems_scc_enet_driver_attach(struct rtems_bsdnet_ifconfig *config, int attaching)
+{
+ return rtems_scc1_driver_attach(config);
+}
diff --git a/bsps/powerpc/virtex/net/xiltemac.c b/bsps/powerpc/virtex/net/xiltemac.c
new file mode 100644
index 0000000..2e8b31b
--- /dev/null
+++ b/bsps/powerpc/virtex/net/xiltemac.c
@@ -0,0 +1,961 @@
+/*
+ * Driver for Xilinx plb temac v3.00a
+ *
+ * Author: Keith Robertson <kjrobert@alumni.uwaterloo.ca>
+ * Copyright (c) 2007 Linn Products Ltd, Scotland.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ *
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+#define PPC_HAS_CLASSIC_EXCEPTIONS FALSE
+
+#include <bsp.h>
+#include <rtems/bspIo.h>
+#include <rtems/rtems_bsdnet.h>
+#include <inttypes.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <stdio.h>
+#include <stdarg.h>
+#include <errno.h>
+#include <string.h>
+#include <assert.h>
+
+#include <xiltemac.h>
+#include <rtems/irq.h>
+
+/* Reading/Writing memory mapped i/o */
+#define IN32(aPtr) ((uint32_t)( *((volatile uint32_t *)(aPtr))) )
+#define OUT32(aPtr, aValue) (*((volatile uint32_t *)(aPtr)) = (uint32_t)aValue)
+#define NUM_XILTEMAC_UNITS 2
+
+/* Why isn't this defined in stdio.h like it's supposed to be? */
+extern int snprintf(char*, size_t, const char*, ...);
+
+extern rtems_isr xilTemacIsr( void *handle );
+extern void xilTemacIsrOn(const rtems_irq_connect_data *);
+extern void xilTemacIsrOff(const rtems_irq_connect_data *);
+extern int xilTemacIsrIsOn(const rtems_irq_connect_data *);
+
+void xilTemacInit( void *voidptr );
+void xilTemacReset(struct ifnet *ifp);
+void xilTemacStop(struct ifnet *ifp);
+void xilTemacSend(struct ifnet *ifp);
+void xilTemacStart(struct ifnet *ifp);
+void xilTemacSetMacAddress(struct ifnet *ifp, unsigned char* aAddr);
+void xilTemacPrintStats(struct ifnet *ifp);
+
+void xilTemacRxThread( void *ignore );
+void xilTemacTxThread( void *ignore );
+
+static struct XilTemac gXilTemac[ NUM_XILTEMAC_UNITS ];
+
+static rtems_id gXilRxThread = 0;
+static rtems_id gXilTxThread = 0;
+
+/*
+** Events, one per unit. The event is sent to the rx task from the isr
+** or from the stack to the tx task whenever a unit needs service. The
+** rx/tx tasks identify the requesting unit(s) by their particular
+** events so only requesting units are serviced.
+*/
+
+static rtems_event_set gUnitSignals[ NUM_XILTEMAC_UNITS ]= { RTEMS_EVENT_1,
+ RTEMS_EVENT_2 };
+
+static uint32_t xilTemacTxFifoVacancyBytes(uint32_t aBaseAddr)
+{
+ uint32_t ipisr = IN32(aBaseAddr + XTE_IPISR_OFFSET);
+ uint32_t bytes = 0;
+ if(ipisr & XTE_IPXR_XMIT_LFIFO_FULL_MASK) {
+ /* If there's no room in the transmit length fifo, then any room in the
+ * data fifo is irrelevant, return 0 */
+ } else {
+ bytes = IN32(aBaseAddr + XTE_PFIFO_TX_VACANCY_OFFSET);
+ bytes &= XTE_PFIFO_COUNT_MASK;
+ bytes *= 8;
+ }
+ return bytes;
+}
+
+static void xilTemacFifoRead64(uint32_t aBaseAddr, uint32_t* aBuf, uint32_t aBytes)
+{
+ uint32_t numqwords = aBytes / 8;
+ uint32_t xtrabytes = aBytes % 8;
+ uint32_t i;
+
+ for(i = 0; i < numqwords; i++)
+ {
+ aBuf[ (i*2) ] = IN32(aBaseAddr + XTE_PFIFO_RX_DATA_OFFSET);
+ aBuf[ (i*2)+1 ] = IN32(aBaseAddr + XTE_PFIFO_RX_DATA_OFFSET + 4);
+ }
+
+ /* If there was a non qword sized read */
+ if( xtrabytes != 0 )
+ {
+ uint32_t lastdwordMS = IN32(aBaseAddr + XTE_PFIFO_RX_DATA_OFFSET);
+ uint32_t lastdwordLS = IN32(aBaseAddr + XTE_PFIFO_RX_DATA_OFFSET + 4);
+ uint8_t* finalbytes = (uint8_t *)&aBuf[ (numqwords*2) ];
+ uint8_t* ptr8;
+ int32_t offset = 0;
+
+ ptr8 = (uint8_t *)&lastdwordMS;
+ if( xtrabytes >= 4 )
+ {
+ finalbytes[ offset++ ] = ptr8[0];
+ finalbytes[ offset++ ] = ptr8[1];
+ finalbytes[ offset++ ] = ptr8[2];
+ finalbytes[ offset++ ] = ptr8[3];
+
+ xtrabytes -= 4;
+ ptr8 = (uint8_t *)&lastdwordLS;
+ }
+
+ if( xtrabytes == 1 )
+ {
+ finalbytes[ offset++ ] = ptr8[0];
+ }
+ else if ( xtrabytes == 2 )
+ {
+ finalbytes[ offset++ ] = ptr8[0];
+ finalbytes[ offset++ ] = ptr8[1];
+ }
+ else if ( xtrabytes == 3 )
+ {
+ finalbytes[ offset++ ] = ptr8[0];
+ finalbytes[ offset++ ] = ptr8[1];
+ finalbytes[ offset++ ] = ptr8[2];
+ }
+ }
+}
+
+static void xilTemacFifoWrite64(uint32_t aBaseAddr, uint32_t* aBuf, uint32_t aBytes)
+{
+ uint32_t numqwords = aBytes / 8;
+ uint32_t xtrabytes = aBytes % 8;
+ uint32_t i;
+
+ for(i = 0; i < numqwords; i++ ) {
+ OUT32(aBaseAddr + XTE_PFIFO_TX_DATA_OFFSET , aBuf[ (i*2) ]);
+ OUT32(aBaseAddr + XTE_PFIFO_TX_DATA_OFFSET + 4, aBuf[ (i*2)+1 ]);
+ }
+
+ /* If there was a non word sized write */
+ if( xtrabytes != 0 ) {
+ uint32_t lastdwordMS = 0;
+ uint32_t lastdwordLS = 0;
+ uint8_t* finalbytes = (uint8_t *)&aBuf[ (numqwords*2) ];
+ uint8_t* ptr8;
+ int32_t offset = 0;
+
+ ptr8 = (uint8_t *)&lastdwordMS;
+
+ if( xtrabytes >= 4 ) {
+ ptr8[0] = finalbytes[ offset++ ];
+ ptr8[1] = finalbytes[ offset++ ];
+ ptr8[2] = finalbytes[ offset++ ];
+ ptr8[3] = finalbytes[ offset++ ];
+
+ xtrabytes -= 4;
+
+ ptr8 = (uint8_t *)&lastdwordLS;
+ }
+
+ if( xtrabytes == 1 ) {
+ ptr8[0] = finalbytes[ offset++ ];
+ }
+ else if ( xtrabytes == 2 ) {
+ ptr8[0] = finalbytes[ offset++ ];
+ ptr8[1] = finalbytes[ offset++ ];
+ }
+ else if ( xtrabytes == 3 ) {
+ ptr8[0] = finalbytes[ offset++ ];
+ ptr8[1] = finalbytes[ offset++ ];
+ ptr8[2] = finalbytes[ offset++ ];
+ }
+
+ OUT32(aBaseAddr + XTE_PFIFO_TX_DATA_OFFSET, lastdwordMS);
+ OUT32(aBaseAddr + XTE_PFIFO_TX_DATA_OFFSET + 4, lastdwordLS);
+ }
+}
+
+void xilTemacStop(struct ifnet *ifp)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+ uint32_t base = xilTemac->iAddr;
+
+ /* Disable ipif interrupts */
+ OUT32(base + XTE_DGIE_OFFSET, 0);
+
+ /* Disable the receiver */
+ uint32_t rxc1 = IN32(base + XTE_ERXC1_OFFSET);
+ rxc1 &= ~XTE_ERXC1_RXEN_MASK;
+ OUT32(base + XTE_ERXC1_OFFSET, rxc1);
+
+ /* If receiver was receiving a packet when we disabled it, it will be
+ * rejected, clear appropriate status bit */
+ uint32_t ipisr = IN32(base + XTE_IPISR_OFFSET);
+ if( ipisr & XTE_IPXR_RECV_REJECT_MASK ) {
+ OUT32(base + XTE_IPISR_OFFSET, XTE_IPXR_RECV_REJECT_MASK);
+ }
+
+#if PPC_HAS_CLASSIC_EXCEPTIONS
+ if( xilTemac->iOldHandler )
+ {
+ opb_intc_set_vector( xilTemac->iOldHandler, xilTemac->iIsrVector, NULL );
+ xilTemac->iOldHandler = 0;
+ }
+#else
+ if( xilTemac->iOldHandler.name != 0)
+ {
+ BSP_install_rtems_irq_handler (&xilTemac->iOldHandler);
+ }
+#endif
+
+ ifp->if_flags &= ~IFF_RUNNING;
+}
+
+void xilTemacStart(struct ifnet *ifp)
+{
+ if( (ifp->if_flags & IFF_RUNNING) == 0 )
+ {
+ struct XilTemac* xilTemac = ifp->if_softc;
+ uint32_t base = xilTemac->iAddr;
+
+ /* Reset plb temac */
+ OUT32(base + XTE_DSR_OFFSET, XTE_DSR_RESET_MASK);
+ /* Don't have usleep on rtems 4.6
+ usleep(1);
+ */
+ /* @ fastest ppc clock of 500 MHz = 2ns clk */
+ uint32_t i = 0;
+ for( i = 0; i < 1 * 500; i++) {
+ }
+
+ /* Reset hard temac */
+ OUT32(base + XTE_CR_OFFSET, XTE_CR_HTRST_MASK);
+ /* Don't have usleep on rtems 4.6
+ usleep(4);
+ */
+ for( i = 0; i < 4 * 500; i++) {
+ }
+
+ /* Disable the receiver -- no need to disable xmit as we control that ;) */
+ uint32_t rxc1 = IN32(base + XTE_ERXC1_OFFSET);
+ rxc1 &= ~XTE_ERXC1_RXEN_MASK;
+ OUT32(base + XTE_ERXC1_OFFSET, rxc1);
+
+ /* If receiver was receiving a packet when we disabled it, it will be
+ * rejected, clear appropriate status bit */
+ uint32_t ipisr = IN32(base + XTE_IPISR_OFFSET);
+ if( ipisr & XTE_IPXR_RECV_REJECT_MASK ) {
+ OUT32(base + XTE_IPISR_OFFSET, XTE_IPXR_RECV_REJECT_MASK);
+ }
+
+ /* Setup IPIF interrupt enables */
+ uint32_t dier = XTE_DXR_CORE_MASK | XTE_DXR_DPTO_MASK | XTE_DXR_TERR_MASK;
+ dier |= XTE_DXR_RECV_FIFO_MASK | XTE_DXR_SEND_FIFO_MASK;
+ OUT32(base + XTE_DIER_OFFSET, dier);
+
+ /* Set the mac address */
+ xilTemacSetMacAddress( ifp, xilTemac->iArpcom.ac_enaddr);
+
+ /* Set the link speed */
+ uint32_t emcfg = IN32(base + XTE_ECFG_OFFSET);
+ printk("xiltemacStart, default linkspeed: %08" PRIx32 "\n", emcfg);
+ emcfg = (emcfg & ~XTE_ECFG_LINKSPD_MASK) | XTE_ECFG_LINKSPD_100;
+ OUT32(base + XTE_ECFG_OFFSET, emcfg);
+
+ /* Set phy divisor and enable mdio. For a plb bus freq of 150MHz (the
+ maximum as of Virtex4 Fx), a divisor of 29 gives a mdio clk freq of
+ 2.5MHz (see Xilinx docs for equation), the maximum in the phy standard.
+ For slower plb frequencies, slower mkdio clks will result. They may not
+ be optimal, but they should work. */
+ uint32_t divisor = 29;
+ OUT32(base + XTE_EMC_OFFSET, divisor | XTE_EMC_MDIO_MASK);
+
+#if PPC_HAS_CLASSIC_EXCEPTIONS /* old connect code */
+ /* Connect isr vector */
+ rtems_status_code sc;
+ extern rtems_isr xilTemacIsr( rtems_vector_number aVector );
+ sc = opb_intc_set_vector( xilTemacIsr, xilTemac->iIsrVector, &xilTemac->iOldHandler );
+ if( sc != RTEMS_SUCCESSFUL )
+ {
+ xilTemac->iOldHandler = 0;
+ printk("%s: Could not set interrupt vector for interface '%s' opb_intc_set_vector ret: %d\n", DRIVER_PREFIX, xilTemac->iUnitName, sc );
+ assert(0);
+ }
+#else
+ {
+ rtems_irq_connect_data IrqConnData;
+
+ /*
+ *get old irq handler
+ */
+ xilTemac->iOldHandler.name = xilTemac->iIsrVector;
+ if (!BSP_get_current_rtems_irq_handler (&xilTemac->iOldHandler)) {
+ xilTemac->iOldHandler.name = 0;
+ printk("%s: Unable to detect previous Irq handler\n",DRIVER_PREFIX);
+ rtems_fatal_error_occurred(1);
+ }
+
+ IrqConnData.on = xilTemacIsrOn;
+ IrqConnData.off = xilTemacIsrOff;
+ IrqConnData.isOn = xilTemacIsrIsOn;
+ IrqConnData.name = xilTemac->iIsrVector;
+ IrqConnData.hdl = xilTemacIsr;
+ IrqConnData.handle = xilTemac;
+
+ if (!BSP_install_rtems_irq_handler (&IrqConnData)) {
+ printk("%s: Unable to connect Irq handler\n",DRIVER_PREFIX);
+ rtems_fatal_error_occurred(1);
+ }
+ }
+#endif
+ /* Enable promiscuous mode -- The temac only supports full duplex, which
+ means we're plugged into a switch. Thus promiscuous mode simply means
+ we get all multicast addresses*/
+ OUT32(base + XTE_EAFM_OFFSET, XTE_EAFM_EPPRM_MASK);
+
+ /* Setup and enable receiver */
+ rxc1 = XTE_ERXC1_RXFCS_MASK | XTE_ERXC1_RXEN_MASK | XTE_ERXC1_RXVLAN_MASK;
+ OUT32(base + XTE_ERXC1_OFFSET, rxc1);
+
+ /* Setup and enable transmitter */
+ uint32_t txc = XTE_ETXC_TXEN_MASK | XTE_ETXC_TXVLAN_MASK;
+ OUT32(base + XTE_ETXC_OFFSET, txc);
+
+ /* Enable interrupts for temac */
+ uint32_t ipier = IN32(base + XTE_IPIER_OFFSET);
+ ipier |= (XTE_IPXR_XMIT_ERROR_MASK);
+ ipier |= (XTE_IPXR_RECV_ERROR_MASK | XTE_IPXR_RECV_DONE_MASK);
+ ipier |= (XTE_IPXR_AUTO_NEG_MASK);
+ OUT32(base + XTE_IPIER_OFFSET, ipier);
+
+ printk("%s: xiltemacStart, ipier: %08" PRIx32 "\n",DRIVER_PREFIX, ipier);
+
+ /* Enable device global interrutps */
+ OUT32(base + XTE_DGIE_OFFSET, XTE_DGIE_ENABLE_MASK);
+ ifp->if_flags |= IFF_RUNNING;
+ }
+}
+
+void xilTemacInit( void *voidptr )
+{
+}
+
+void xilTemacReset(struct ifnet *ifp)
+{
+ xilTemacStop( ifp );
+ xilTemacStart( ifp );
+}
+
+void xilTemacSetMacAddress(struct ifnet *ifp, unsigned char* aAddr)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+ uint32_t base = xilTemac->iAddr;
+
+ /* You can't change the mac address while the card is in operation */
+ if( (ifp->if_flags & IFF_RUNNING) != 0 ) {
+ printk("%s: attempted to change MAC while up, interface '%s'\n", DRIVER_PREFIX, xilTemac->iUnitName );
+ assert(0);
+ }
+ uint32_t mac;
+ mac = aAddr[0] & 0x000000FF;
+ mac |= aAddr[1] << 8;
+ mac |= aAddr[2] << 16;
+ mac |= aAddr[3] << 24;
+ OUT32(base + XTE_EUAW0_OFFSET, mac);
+
+ mac = IN32(base + XTE_EUAW1_OFFSET);
+ mac &= ~XTE_EUAW1_MASK;
+ mac |= aAddr[4] & 0x000000FF;
+ mac |= aAddr[5] << 8;
+ OUT32(base + XTE_EUAW1_OFFSET, mac);
+}
+
+void xilTemacPrintStats( struct ifnet *ifp )
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+
+ printf("\n");
+ printf("%s: Statistics for interface '%s'\n", DRIVER_PREFIX, xilTemac->iUnitName );
+
+ printf("%s: Ipif Interrupts: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iInterrupts);
+ printf("%s: Rx Interrupts: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxInterrupts);
+ printf("%s: Rx Rejected Interrupts: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxRejectedInterrupts);
+ printf("%s: Rx Rej Invalid Frame: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxRejectedInvalidFrame);
+ printf("%s: Rx Rej Data Fifo Full: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxRejectedDataFifoFull);
+ printf("%s:Rx Rej Length Fifo Full: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxRejectedLengthFifoFull);
+ printf("%s: Rx Stray Events: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxStrayEvents);
+ printf("%s: Rx Max Drained: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iRxMaxDrained);
+ printf("%s: Tx Interrupts: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iTxInterrupts);
+ printf("%s: Tx Max Drained: %lu\n", DRIVER_PREFIX, xilTemac->iStats.iTxMaxDrained);
+
+ printf("\n");
+}
+
+static void xilTemacIsrSingle(struct XilTemac* xilTemac)
+{
+ uint32_t base = xilTemac->iAddr;
+ uint32_t disr = IN32( base + XTE_DISR_OFFSET );
+ struct ifnet* ifp = xilTemac->iIfp;
+
+ if( disr && (ifp->if_flags & IFF_RUNNING) == 0 ) {
+ /* some interrupt status bits are asserted but card is down */
+ printk("%s: Fatal error, disr 0 or this emac not running\n", DRIVER_PREFIX);
+ /*assert(0);*/
+ } else {
+ /* Handle all error conditions first */
+ if( disr & (XTE_DXR_DPTO_MASK | XTE_DXR_TERR_MASK |
+ XTE_DXR_RECV_FIFO_MASK | XTE_DXR_SEND_FIFO_MASK) ) {
+ printk("%s: Fatal Bus error, disr: %08" PRIx32 "\n", DRIVER_PREFIX, disr);
+ /*assert(0);*/
+ }
+ if( disr & XTE_DXR_CORE_MASK ) {
+ /* Normal case, temac interrupt */
+ uint32_t ipisr = IN32(base + XTE_IPISR_OFFSET);
+ uint32_t ipier = IN32(base + XTE_IPIER_OFFSET);
+ uint32_t newipier = ipier;
+ uint32_t pending = ipisr & ipier;
+ xilTemac->iStats.iInterrupts++;
+
+ /* Check for all fatal errors, even if that error is not enabled in ipier */
+ if(ipisr & XTE_IPXR_FIFO_FATAL_ERROR_MASK) {
+ printk("%s: Fatal Fifo Error ipisr: %08" PRIx32 "\n", DRIVER_PREFIX, ipisr);
+ /*assert(0);*/
+ }
+
+ if(pending & XTE_IPXR_RECV_DONE_MASK) {
+ /* We've received a packet
+ - inc stats
+ - disable rx interrupt
+ - signal rx thread to empty out fifo
+ (rx thread must renable interrupt)
+ */
+ xilTemac->iStats.iRxInterrupts++;
+
+ newipier &= ~XTE_IPXR_RECV_DONE_MASK;
+
+ rtems_bsdnet_event_send(gXilRxThread, xilTemac->iIoEvent);
+ }
+ if(pending & XTE_IPXR_XMIT_DONE_MASK) {
+ /* We've transmitted a packet. This interrupt is only ever enabled in
+ the ipier if the tx thread didn't have enough space in the data fifo
+ or the tplr fifo. If that's the case, we:
+ - inc stats
+ - disable tx interrupt
+ - signal tx thread that a transmit has completed and thus there is now
+ room to send again.
+ */
+ xilTemac->iStats.iTxInterrupts++;
+
+ newipier &= ~XTE_IPXR_XMIT_DONE_MASK;
+
+ rtems_bsdnet_event_send(gXilTxThread, xilTemac->iIoEvent);
+ }
+ if(pending & XTE_IPXR_RECV_DROPPED_MASK) {
+ /* A packet was dropped (because it was invalid, or receiving it
+ have overflowed one of the rx fifo's).
+ - Increment stats.
+ - Clear interrupt condition.
+ */
+ uint32_t toggle = 0;
+ if(pending & XTE_IPXR_RECV_REJECT_MASK) {
+ xilTemac->iStats.iRxRejectedInvalidFrame++;
+ toggle |= XTE_IPXR_RECV_REJECT_MASK;
+ }
+ if(pending & XTE_IPXR_RECV_PFIFO_ABORT_MASK) {
+ xilTemac->iStats.iRxRejectedDataFifoFull++;
+ toggle |= XTE_IPXR_RECV_PFIFO_ABORT_MASK;
+ }
+ if(pending & XTE_IPXR_RECV_LFIFO_ABORT_MASK) {
+ xilTemac->iStats.iRxRejectedLengthFifoFull++;
+ toggle |= XTE_IPXR_RECV_LFIFO_ABORT_MASK;
+ }
+ xilTemac->iStats.iRxRejectedInterrupts++;
+ OUT32(base + XTE_IPISR_OFFSET, toggle);
+ }
+ if(pending & XTE_IPXR_AUTO_NEG_MASK) {
+ printk("%s: Autonegotiation finished\n", DRIVER_PREFIX);
+ OUT32(base + XTE_IPISR_OFFSET, XTE_IPXR_AUTO_NEG_MASK);
+ }
+ if(newipier != ipier) {
+ OUT32(base + XTE_IPIER_OFFSET, newipier);
+ }
+ }
+ }
+}
+
+#if PPC_HAS_CLASSIC_EXCEPTIONS
+rtems_isr xilTemacIsr( rtems_vector_number aVector )
+{
+ struct XilTemac* xilTemac;
+ int i;
+
+ for( i=0; i< NUM_XILTEMAC_UNITS; i++ ) {
+ xilTemac = &gXilTemac[i];
+
+ if( xilTemac->iIsPresent ) {
+ xilTemacIsrSingle(xilTemac);
+ }
+ }
+}
+#else
+rtems_isr xilTemacIsr(void *handle )
+{
+ struct XilTemac* xilTemac = (struct XilTemac*)handle;
+
+ xilTemacIsrSingle(xilTemac);
+}
+
+void xilTemacIsrOn(const rtems_irq_connect_data *unused)
+{
+}
+
+void xilTemacIsrOff(const rtems_irq_connect_data *unused)
+{
+}
+
+int xilTemacIsrIsOn(const rtems_irq_connect_data *unused)
+{
+ return 1;
+}
+#endif
+
+
+static int32_t xilTemacSetMulticastFilter(struct ifnet *ifp)
+{
+ return 0;
+}
+
+static int xilTemacIoctl(struct ifnet* ifp, ioctl_command_t aCommand, caddr_t aData)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+ int32_t error = 0;
+
+ switch(aCommand) {
+ case SIOCGIFADDR:
+ case SIOCSIFADDR:
+ ether_ioctl(ifp, aCommand, aData);
+ break;
+
+ case SIOCSIFFLAGS:
+ switch(ifp->if_flags & (IFF_UP | IFF_RUNNING))
+ {
+ case IFF_RUNNING:
+ xilTemacStop(ifp);
+ break;
+
+ case IFF_UP:
+ xilTemacStart(ifp);
+ break;
+
+ case IFF_UP | IFF_RUNNING:
+ xilTemacReset(ifp);
+ break;
+
+ default:
+ break;
+ }
+ break;
+
+ case SIOCADDMULTI:
+ case SIOCDELMULTI: {
+ struct ifreq* ifr = (struct ifreq*) aData;
+ error = ((aCommand == SIOCADDMULTI) ?
+ ( ether_addmulti(ifr, &(xilTemac->iArpcom)) ) :
+ ( ether_delmulti(ifr, &(xilTemac->iArpcom)))
+ );
+ /* ENETRESET indicates that driver should update its multicast filters */
+ if(error == ENETRESET)
+ {
+ error = xilTemacSetMulticastFilter( ifp );
+ }
+ break;
+ }
+
+ case SIO_RTEMS_SHOW_STATS:
+ xilTemacPrintStats( ifp );
+ break;
+
+ default:
+ error = EINVAL;
+ break;
+ }
+ return error;
+}
+
+void xilTemacSend(struct ifnet* ifp)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+
+ /* wake up tx thread w/ outbound interface's signal */
+ rtems_bsdnet_event_send( gXilTxThread, xilTemac->iIoEvent );
+
+ ifp->if_flags |= IFF_OACTIVE;
+}
+
+/* align the tx buffer to 32 bytes just for kicks, should make it more
+ * cache friendly */
+static unsigned char gTxBuf[2048] __attribute__ ((aligned (32)));
+
+static void xilTemacSendPacket(struct ifnet *ifp, struct mbuf* aMbuf)
+{
+ struct XilTemac *xilTemac = ifp->if_softc;
+ struct mbuf *n = aMbuf;
+ uint32_t len = 0;
+
+#ifdef DEBUG
+ printk("SendPacket\n");
+ printk("TXD: 0x%08x\n", (int32_t) n->m_data);
+#endif
+
+ /* assemble the packet into the tx buffer */
+ for(;;) {
+#ifdef DEBUG
+ uint32_t i = 0;
+ printk("MBUF: 0x%08x : ", (int32_t) n->m_data);
+ for (i=0;i<n->m_len;i+=2) {
+ printk("%02x%02x ", mtod(n, unsigned char*)[i], mtod(n, unsigned char*)[i+1]);
+ }
+ printk("\n");
+#endif
+
+ if( n->m_len > 0 ) {
+ memcpy( &gTxBuf[ len ], (char *)n->m_data, n->m_len);
+ len += n->m_len;
+ }
+ if( (n = n->m_next) == 0) {
+ break;
+ }
+ }
+
+ xilTemacFifoWrite64( xilTemac->iAddr, (uint32_t*)gTxBuf, len );
+ /* Set the Transmit Packet Length Register which registers the packet
+ * length, enqueues the packet and signals the xmit unit to start
+ * sending. */
+ OUT32(xilTemac->iAddr + XTE_TPLR_OFFSET, len);
+
+#ifdef DEBUG
+ printk("%s: txpkt, len %d\n", DRIVER_PREFIX, len );
+ memset(gTxBuf, 0, len);
+#endif
+}
+
+static void xilTemacTxThreadSingle(struct ifnet* ifp)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+ struct mbuf* m;
+ uint32_t base = xilTemac->iAddr;
+
+#ifdef DEBUG
+ printk("%s: tx send packet, interface '%s'\n", DRIVER_PREFIX, xilTemac->iUnitName );
+#endif
+
+ /* Send packets till mbuf queue empty or tx fifo full */
+ for(;;) {
+ uint32_t i = 0;
+
+ /* 1) clear out any statuses from previously sent tx frames */
+ while( IN32(base + XTE_IPISR_OFFSET) & XTE_IPXR_XMIT_DONE_MASK ) {
+ IN32(base + XTE_TSR_OFFSET);
+ OUT32(base + XTE_IPISR_OFFSET, XTE_IPXR_XMIT_DONE_MASK);
+ i++;
+ }
+ if( i > xilTemac->iStats.iTxMaxDrained ) {
+ xilTemac->iStats.iTxMaxDrained = i;
+ }
+
+ /* 2) Check if enough space in tx data fifo _and_ tx tplr for an entire
+ ethernet frame */
+ if( xilTemacTxFifoVacancyBytes( xilTemac->iAddr ) <= ifp->if_mtu ) {
+ /* 2a) If not, enable transmit done interrupt and break out of loop to
+ wait for space */
+ uint32_t ipier = IN32(base + XTE_IPIER_OFFSET);
+ ipier |= (XTE_IPXR_XMIT_DONE_MASK);
+ OUT32(base + XTE_IPIER_OFFSET, ipier);
+ break;
+ }
+
+ /* 3) Contuine to dequeue mbuf chains till none left */
+ IF_DEQUEUE( &(ifp->if_snd), m);
+ if( !m ) {
+ break;
+ }
+
+ /* 4) Send dequeued mbuf chain */
+ xilTemacSendPacket( ifp, m );
+
+ /* 5) Free mbuf chain */
+ m_freem( m );
+ }
+ ifp->if_flags &= ~IFF_OACTIVE;
+}
+
+void xilTemacTxThread( void *ignore )
+{
+ struct XilTemac *xilTemac;
+ struct ifnet *ifp;
+
+ rtems_event_set events;
+ int i;
+
+ for(;;) {
+ /* Wait for:
+ - notification from stack of packet to send OR
+ - notification from interrupt handler that there is space available to
+ send already queued packets
+ */
+ rtems_bsdnet_event_receive( RTEMS_ALL_EVENTS,
+ RTEMS_EVENT_ANY | RTEMS_WAIT,
+ RTEMS_NO_TIMEOUT,
+ &events );
+
+ for(i=0; i< NUM_XILTEMAC_UNITS; i++) {
+ xilTemac = &gXilTemac[i];
+
+ if( xilTemac->iIsPresent ) {
+ ifp = xilTemac->iIfp;
+
+ if( (ifp->if_flags & IFF_RUNNING) ) {
+
+ if( events & xilTemac->iIoEvent ) {
+ xilTemacTxThreadSingle(ifp);
+ }
+
+ } else {
+ printk("%s: xilTemacTxThread: event received for device: %s, but device not active\n",
+ DRIVER_PREFIX, xilTemac->iUnitName);
+ assert(0);
+ }
+ }
+ }
+ }
+}
+
+static void xilTemacRxThreadSingle(struct ifnet* ifp)
+{
+ struct XilTemac* xilTemac = ifp->if_softc;
+
+ uint32_t npkts = 0;
+#ifdef DEBUG
+ printk("%s: rxthread, packet rx on interface %s\n", DRIVER_PREFIX, xilTemac->iUnitName );
+#endif
+
+ uint32_t base = xilTemac->iAddr;
+
+ /* While RECV_DONE_MASK in ipisr stays set */
+ while( IN32(base + XTE_IPISR_OFFSET) & XTE_IPXR_RECV_DONE_MASK ) {
+
+ /* 1) Read the length of the packet */
+ uint32_t bytes = IN32(base + XTE_RPLR_OFFSET);
+
+ /* 2) Read the Read Status Register (which contains no information). When
+ * all of these in the fifo have been read, then XTE_IPXR_RECV_DONE_MASK
+ * will stay turned off, after it's written to */
+ IN32(base + XTE_RSR_OFFSET);
+ npkts++;
+
+ struct mbuf* m;
+ struct ether_header* eh;
+
+ /* 3) Get some memory from the ip stack to store the packet in */
+ MGETHDR(m, M_WAIT, MT_DATA);
+ MCLGET(m, M_WAIT);
+
+ m->m_pkthdr.rcvif = ifp;
+
+ /* 4) Copy the packet into the ip stack's memory */
+ xilTemacFifoRead64( base, mtod(m, uint32_t*), bytes);
+
+ m->m_len = bytes - sizeof(struct ether_header);
+ m->m_pkthdr.len = bytes - sizeof(struct ether_header);
+
+ eh = mtod(m, struct ether_header*);
+
+ m->m_data += sizeof(struct ether_header);
+
+ /* 5) Tell the ip stack about the received packet */
+ ether_input(ifp, eh, m);
+
+ /* 6) Try and turn off XTE_IPXR_RECV_DONE bit in the ipisr. If there's
+ * still more packets (ie RSR ! empty), then it will stay asserted. If
+ * there's no more packets, this will turn it off.
+ */
+ OUT32(base + XTE_IPISR_OFFSET, XTE_IPXR_RECV_DONE_MASK);
+ }
+
+ /* End) All Rx packets serviced, renable rx interrupt */
+ uint32_t ipier = IN32(base + XTE_IPIER_OFFSET);
+ ipier |= XTE_IPXR_RECV_DONE_MASK;
+ OUT32(base + XTE_IPIER_OFFSET, ipier);
+
+#ifdef DEBUG
+ printk("%s: rxthread, retrieved %d packets\n", DRIVER_PREFIX, npkts );
+#endif
+ if(npkts > xilTemac->iStats.iRxMaxDrained) {
+ xilTemac->iStats.iRxMaxDrained = npkts;
+ }
+ /* ??) Very very occasionally, under extremely high stress, I get a situation
+ * where we process no packets. That is, the rx thread was evented, but
+ * there was no packet available. I'm not sure how this happens. Ideally,
+ * it shouldn't ocurr, and I suspect a minor bug in the driver. However, for
+ * me it's happenning 3 times in several hunderd million interrupts. Nothing
+ * bad happens, as long as we don't read from the rx fifo's if nothing is
+ * there. It is just not as efficient as possible (rx thread being evented
+ * pointlessly) and a bit disconcerting about how it's ocurring.
+ * The best way to reproduce this is to have two clients run:
+ * $ ping <host> -f -s 65507
+ * This flood pings the device from two clients with the maximum size ping
+ * packet. It absolutely hammers the device under test. Eventually, (if
+ * you leave it running overnight for instance), you'll get a couple of these
+ * stray rx events. */
+ if(npkts == 0) {
+ /*printk("%s: RxThreadSingle: fatal error: event received, but no packets available\n", DRIVER_PREFIX);
+ assert(0); */
+ xilTemac->iStats.iRxStrayEvents++;
+ }
+}
+
+void xilTemacRxThread( void *ignore )
+{
+ struct XilTemac* xilTemac;
+ struct ifnet* ifp;
+ int i;
+ rtems_event_set events;
+
+#ifdef DEBUG
+ printk("%s: xilTemacRxThread running\n", DRIVER_PREFIX );
+#endif
+
+ for(;;) {
+ rtems_bsdnet_event_receive( RTEMS_ALL_EVENTS,
+ RTEMS_WAIT | RTEMS_EVENT_ANY,
+ RTEMS_NO_TIMEOUT,
+ &events);
+
+#ifdef DEBUG
+ printk("%s: rxthread, wakeup\n", DRIVER_PREFIX );
+#endif
+
+ for(i=0; i< NUM_XILTEMAC_UNITS; i++) {
+ xilTemac = &gXilTemac[i];
+
+ if( xilTemac->iIsPresent ) {
+ ifp = xilTemac->iIfp;
+
+ if( (ifp->if_flags & IFF_RUNNING) != 0 ) {
+ if( events & xilTemac->iIoEvent ) {
+ xilTemacRxThreadSingle(ifp);
+ }
+ }
+ else {
+ printk("%s: rxthread, interface %s present but not running\n", DRIVER_PREFIX, xilTemac->iUnitName );
+ assert(0);
+ }
+ }
+ }
+ }
+}
+
+int xilTemac_driver_attach(struct rtems_bsdnet_ifconfig* aBsdConfig, int aDummy)
+{
+ struct ifnet* ifp;
+ int32_t mtu;
+ int32_t unit;
+ char* unitName;
+ struct XilTemac* xilTemac;
+
+ unit = rtems_bsdnet_parse_driver_name(aBsdConfig, &unitName);
+ if(unit < 0 )
+ {
+ printk("%s: Interface Unit number < 0\n", DRIVER_PREFIX );
+ return 0;
+ }
+
+ if( aBsdConfig->bpar == 0 )
+ {
+ printk("%s: Did not specify base address for device '%s'", DRIVER_PREFIX, unitName );
+ return 0;
+ }
+
+ if( aBsdConfig->hardware_address == NULL )
+ {
+ printk("%s: No MAC address given for interface '%s'\n", DRIVER_PREFIX, unitName );
+ return 0;
+ }
+
+ xilTemac = &gXilTemac[ unit ];
+ memset(xilTemac, 0, sizeof(struct XilTemac));
+
+ xilTemac->iIsPresent = 1;
+
+ snprintf( xilTemac->iUnitName, MAX_UNIT_BYTES, "%s%" PRId32, unitName, unit );
+
+ xilTemac->iIfp = &(xilTemac->iArpcom.ac_if);
+ ifp = &(xilTemac->iArpcom.ac_if);
+ xilTemac->iAddr = aBsdConfig->bpar;
+ xilTemac->iIoEvent = gUnitSignals[ unit ];
+ xilTemac->iIsrVector = aBsdConfig->irno;
+
+ memcpy( xilTemac->iArpcom.ac_enaddr, aBsdConfig->hardware_address, ETHER_ADDR_LEN);
+
+ if( aBsdConfig->mtu )
+ {
+ mtu = aBsdConfig->mtu;
+ }
+ else
+ {
+ mtu = ETHERMTU;
+ }
+
+ ifp->if_softc = xilTemac;
+ ifp->if_unit = unit;
+ ifp->if_name = unitName;
+ ifp->if_mtu = mtu;
+ ifp->if_init = xilTemacInit;
+ ifp->if_ioctl = xilTemacIoctl;
+ ifp->if_start = xilTemacSend;
+ ifp->if_output = ether_output;
+
+ ifp->if_flags = IFF_BROADCAST | IFF_SIMPLEX | IFF_MULTICAST;
+
+ if(ifp->if_snd.ifq_maxlen == 0)
+ {
+ ifp->if_snd.ifq_maxlen = ifqmaxlen;
+ }
+
+ if_attach(ifp);
+ ether_ifattach(ifp);
+
+ /* create shared rx & tx threads */
+ if( (gXilRxThread == 0) && (gXilTxThread == 0) )
+ {
+ printk("%s: Creating shared RX/TX threads\n", DRIVER_PREFIX );
+ gXilRxThread = rtems_bsdnet_newproc("xerx", 4096, xilTemacRxThread, NULL );
+ gXilTxThread = rtems_bsdnet_newproc("xetx", 4096, xilTemacTxThread, NULL );
+ }
+
+ printk("%s: Initializing driver for '%s'\n", DRIVER_PREFIX, xilTemac->iUnitName );
+
+ printk("%s: base address 0x%08X, intnum 0x%02X, \n",
+ DRIVER_PREFIX,
+ aBsdConfig->bpar,
+ aBsdConfig->irno );
+
+ return 1;
+}
+
diff --git a/bsps/riscv/griscv/net/griscv_greth.c b/bsps/riscv/griscv/net/griscv_greth.c
new file mode 100644
index 0000000..e5c05fd
--- /dev/null
+++ b/bsps/riscv/griscv/net/griscv_greth.c
@@ -0,0 +1,59 @@
+/*
+ * LEON3 Opencores Ethernet MAC Configuration Information
+ *
+ * COPYRIGHT (c) 2004.
+ * Gaisler Research
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+#include <bsp.h>
+#include <amba.h>
+#include <grlib/ambapp.h>
+#include <libchip/greth.h>
+/*#if (GRETH_DEBUG & GRETH_DEBUG_PRINT_REGISTERS)*/
+#include <stdio.h>
+/*#endif*/
+
+/*
+ * Default sizes of transmit and receive descriptor areas
+ */
+#define RDA_COUNT 32
+#define TDA_COUNT 32
+
+greth_configuration_t griscv_greth_configuration;
+
+int rtems_griscv_greth_driver_attach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attach
+)
+{
+ unsigned int base_addr = 0; /* avoid warnings */
+ unsigned int eth_irq = 0; /* avoid warnings */
+ struct ambapp_dev *adev;
+ struct ambapp_apb_info *apb;
+
+ /* Scan for MAC AHB slave interface */
+ adev = (void *)ambapp_for_each(&ambapp_plb, (OPTIONS_ALL|OPTIONS_APB_SLVS),
+ VENDOR_GAISLER, GAISLER_ETHMAC,
+ ambapp_find_by_idx, NULL);
+ if (adev) {
+ apb = DEV_TO_APB(adev);
+ base_addr = apb->start;
+ eth_irq = apb->common.irq;
+
+ /* clear control register and reset NIC */
+ *(volatile int *) base_addr = 0;
+ *(volatile int *) base_addr = GRETH_CTRL_RST;
+ *(volatile int *) base_addr = 0;
+ griscv_greth_configuration.base_address = (void*)base_addr;
+ griscv_greth_configuration.vector = eth_irq; /* on LEON vector is IRQ no. */
+ griscv_greth_configuration.txd_count = TDA_COUNT;
+ griscv_greth_configuration.rxd_count = RDA_COUNT;
+ rtems_greth_driver_attach(config, &griscv_greth_configuration);
+ }
+ return 0;
+}
diff --git a/bsps/sparc/erc32/net/erc32sonic.c b/bsps/sparc/erc32/net/erc32sonic.c
new file mode 100644
index 0000000..af37b42
--- /dev/null
+++ b/bsps/sparc/erc32/net/erc32sonic.c
@@ -0,0 +1,123 @@
+/**
+ * @file
+ *
+ * @ingroup sparc_erc32
+ *
+ * @brief THARSYS VME SPARC RT board SONIC Configuration Information
+ *
+ * References:
+ *
+ * 1) SVME/DMV-171 Single Board Computer Documentation Package, #805905,
+ * DY 4 Systems Inc., Kanata, Ontario, September, 1996.
+ */
+
+/*
+ * COPYRIGHT (c) 2000.
+ * European Space Agency.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/sonic.h>
+#if (SONIC_DEBUG & SONIC_DEBUG_PRINT_REGISTERS)
+#include <stdio.h>
+#endif
+
+static void erc32_sonic_write_register(
+ void *base,
+ uint32_t regno,
+ uint32_t value
+)
+{
+ volatile uint32_t *p = base;
+
+#if (SONIC_DEBUG & SONIC_DEBUG_PRINT_REGISTERS)
+ printf( "%p Write 0x%04x to %s (0x%02x)\n",
+ &p[regno], value, SONIC_Reg_name[regno], regno );
+ fflush( stdout );
+#endif
+ p[regno] = 0x0ffff & value;
+}
+
+static uint32_t erc32_sonic_read_register(
+ void *base,
+ uint32_t regno
+)
+{
+ volatile uint32_t *p = base;
+ uint32_t value;
+
+ value = p[regno];
+#if (SONIC_DEBUG & SONIC_DEBUG_PRINT_REGISTERS)
+ printf( "%p Read 0x%04x from %s (0x%02x)\n",
+ &p[regno], value, SONIC_Reg_name[regno], regno );
+ fflush( stdout );
+#endif
+ return 0x0ffff & value;
+}
+
+/*
+ * Default sizes of transmit and receive descriptor areas
+ */
+#define RDA_COUNT 20 /* 20 */
+#define TDA_COUNT 20 /* 10 */
+
+/*
+ * Default device configuration register values
+ * Conservative, generic values.
+ * DCR:
+ * No extended bus mode
+ * Unlatched bus retry
+ * Programmable outputs unused
+ * Asynchronous bus mode
+ * User definable pins unused
+ * No wait states (access time controlled by DTACK*)
+ * 32-bit DMA
+ * Empty/Fill DMA mode
+ * Maximum Transmit/Receive FIFO
+ * DC2:
+ * Extended programmable outputs unused
+ * Normal HOLD request
+ * Packet compress output unused
+ * No reject on CAM match
+ */
+#define SONIC_DCR ( DCR_DW32 | DCR_RFT24 | DCR_TFT28)
+#define SONIC_DC2 (0)
+
+/*
+ * Default location of device registers
+ */
+#define SONIC_BASE_ADDRESS 0x10000100
+
+/*
+ * Default interrupt vector
+ */
+#define SONIC_VECTOR 0x1E
+
+sonic_configuration_t erc32_sonic_configuration = {
+ (void *)SONIC_BASE_ADDRESS, /* base address */
+ SONIC_VECTOR, /* vector number */
+ SONIC_DCR, /* DCR register value */
+ SONIC_DC2, /* DC2 register value */
+ TDA_COUNT, /* number of transmit descriptors */
+ RDA_COUNT, /* number of receive descriptors */
+ erc32_sonic_write_register,
+ erc32_sonic_read_register
+};
+
+int rtems_erc32_sonic_driver_attach(struct rtems_bsdnet_ifconfig *config)
+{
+
+ ERC32_MEC.IO_Configuration |=
+ (0x15 << (((SONIC_BASE_ADDRESS >> 24) & 0x3) * 8));
+ ERC32_MEC.Control &= ~0x60001; /* Disable DMA time-out, parity & power-down */
+ ERC32_MEC.Control |= 0x10000; /* Enable DMA */
+ ERC32_MEC.Interrupt_Mask &= ~(1 << (SONIC_VECTOR - 0x10));
+ return(rtems_sonic_driver_attach( config, &erc32_sonic_configuration ));
+
+}
diff --git a/bsps/sparc/leon2/net/leon_open_eth.c b/bsps/sparc/leon2/net/leon_open_eth.c
new file mode 100644
index 0000000..7191e37
--- /dev/null
+++ b/bsps/sparc/leon2/net/leon_open_eth.c
@@ -0,0 +1,64 @@
+/**
+ * @file
+ * @ingroup RTEMSBSPsSPARCLEON2
+ * @brief LEON2 Opencores Ethernet MAC Configuration Information
+ */
+
+/*
+ * Copyright (c) 2004.
+ * Aeroflex Gaisler AB.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/open_eth.h>
+#if (OPEN_ETH_DEBUG & OPEN_ETH_DEBUG_PRINT_REGISTERS)
+#include <stdio.h>
+#endif
+
+/*
+ * Default sizes of transmit and receive descriptor areas
+ */
+#define RDA_COUNT 16
+#define TDA_COUNT 16
+
+/*
+ * Default location of device registers
+ */
+#define OPEN_ETH_BASE_ADDRESS ((void *)0xb0000000)
+
+/*
+ * Default interrupt vector
+ */
+#define OPEN_ETH_VECTOR 0x1C
+
+open_eth_configuration_t leon_open_eth_configuration = {
+ OPEN_ETH_BASE_ADDRESS, /* base address */
+ OPEN_ETH_VECTOR, /* vector number */
+ TDA_COUNT, /* number of transmit descriptors */
+ RDA_COUNT, /* number of receive descriptors */
+ 0 /* 100 MHz operation */
+};
+
+int rtems_leon_open_eth_driver_attach(struct rtems_bsdnet_ifconfig *config)
+{
+
+ /* clear control register and reset NIC */
+ *(volatile int *) OPEN_ETH_BASE_ADDRESS = 0;
+ *(volatile int *) OPEN_ETH_BASE_ADDRESS = 0x800;
+ *(volatile int *) OPEN_ETH_BASE_ADDRESS = 0;
+
+ /* enable 100 MHz operation only if cpu frequency >= 50 MHz */
+ if (LEON_REG.Scaler_Reload >= 49) leon_open_eth_configuration.en100MHz = 1;
+
+ if (rtems_open_eth_driver_attach( config, &leon_open_eth_configuration )) {
+ LEON_REG.Interrupt_Clear = (1 << (OPEN_ETH_VECTOR - 0x10));
+ LEON_REG.Interrupt_Mask |= (1 << (OPEN_ETH_VECTOR - 0x10));
+ }
+ return 0;
+}
diff --git a/bsps/sparc/leon2/net/leon_smc91111.c b/bsps/sparc/leon2/net/leon_smc91111.c
new file mode 100644
index 0000000..cf0f81f
--- /dev/null
+++ b/bsps/sparc/leon2/net/leon_smc91111.c
@@ -0,0 +1,69 @@
+/**
+ * @file
+ * @ingroup RTEMSBSPsSPARCLEON2
+ * @brief SMC91111 Driver
+ */
+
+/*
+ * Copyright (c) 2006.
+ * Aeroflex Gaisler AB.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <rtems.h>
+
+#include <bsp.h>
+#include <rtems/bspIo.h>
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdarg.h>
+#include <rtems/error.h>
+#include <rtems/rtems_bsdnet.h>
+
+#include <sys/param.h>
+#include <sys/mbuf.h>
+
+#include <sys/socket.h>
+#include <sys/sockio.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <netinet/if_ether.h>
+
+#include <libchip/smc91111exp.h>
+
+
+#define SMC91111_BASE_ADDR (void*)0x20000300
+#define SMC91111_BASE_IRQ 4
+#define SMC91111_BASE_PIO 4
+
+scmv91111_configuration_t leon_scmv91111_configuration = {
+ SMC91111_BASE_ADDR, /* base address */
+ SMC91111_BASE_IRQ, /* IRQ number (on LEON vector is irq) */
+ SMC91111_BASE_PIO, /* PIO */
+ 100, /* 100b */
+ 1, /* fulldx */
+ 1 /* autoneg */
+};
+
+/*
+ * Attach an SMC91111 driver to the system
+ */
+int rtems_smc91111_driver_attach_leon2(struct rtems_bsdnet_ifconfig *config)
+{
+
+ /* activate io area */
+ printk("Activating Leon2 io port\n");
+ /*configure pio */
+ *((volatile unsigned int *)0x80000000) |= 0x10f80000;
+ *((volatile unsigned int *)0x800000A8) |=
+ (0xe0 | leon_scmv91111_configuration.pio)
+ << (8 * (leon_scmv91111_configuration.vector - 4)); /* vector = irq-no */
+
+ return _rtems_smc91111_driver_attach(config,&leon_scmv91111_configuration);
+}
diff --git a/bsps/sparc/leon3/net/leon_greth.c b/bsps/sparc/leon3/net/leon_greth.c
new file mode 100644
index 0000000..5b0c99d
--- /dev/null
+++ b/bsps/sparc/leon3/net/leon_greth.c
@@ -0,0 +1,58 @@
+/*
+ * LEON3 Opencores Ethernet MAC Configuration Information
+ *
+ * COPYRIGHT (c) 2004.
+ * Gaisler Research
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/greth.h>
+/*#if (GRETH_DEBUG & GRETH_DEBUG_PRINT_REGISTERS)*/
+#include <stdio.h>
+/*#endif*/
+
+/*
+ * Default sizes of transmit and receive descriptor areas
+ */
+#define RDA_COUNT 32
+#define TDA_COUNT 32
+
+greth_configuration_t leon_greth_configuration;
+
+int rtems_leon_greth_driver_attach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attach
+)
+{
+ unsigned int base_addr = 0; /* avoid warnings */
+ unsigned int eth_irq = 0; /* avoid warnings */
+ struct ambapp_dev *adev;
+ struct ambapp_apb_info *apb;
+
+ /* Scan for MAC AHB slave interface */
+ adev = (void *)ambapp_for_each(&ambapp_plb, (OPTIONS_ALL|OPTIONS_APB_SLVS),
+ VENDOR_GAISLER, GAISLER_ETHMAC,
+ ambapp_find_by_idx, NULL);
+ if (adev) {
+ apb = DEV_TO_APB(adev);
+ base_addr = apb->start;
+ eth_irq = apb->common.irq;
+
+ /* clear control register and reset NIC */
+ *(volatile int *) base_addr = 0;
+ *(volatile int *) base_addr = GRETH_CTRL_RST;
+ *(volatile int *) base_addr = 0;
+ leon_greth_configuration.base_address = (void*)base_addr;
+ leon_greth_configuration.vector = eth_irq; /* on LEON vector is IRQ no. */
+ leon_greth_configuration.txd_count = TDA_COUNT;
+ leon_greth_configuration.rxd_count = RDA_COUNT;
+ rtems_greth_driver_attach(config, &leon_greth_configuration);
+ }
+ return 0;
+}
diff --git a/bsps/sparc/leon3/net/leon_open_eth.c b/bsps/sparc/leon3/net/leon_open_eth.c
new file mode 100644
index 0000000..2b386f8
--- /dev/null
+++ b/bsps/sparc/leon3/net/leon_open_eth.c
@@ -0,0 +1,75 @@
+/**
+ * @file
+ * @ingroup sparc_leon3
+ * @brief LEON3 Opencores Ethernet MAC Configuration Information
+ */
+
+/*
+ * Copyright (c) 2004.
+ * Aeroflex Gaisler AB.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/open_eth.h>
+#if (OPEN_ETH_DEBUG & OPEN_ETH_DEBUG_PRINT_REGISTERS)
+#include <stdio.h>
+#endif
+
+/*
+ * Default sizes of transmit and receive descriptor areas
+ */
+#define RDA_COUNT 16
+#define TDA_COUNT 16
+
+open_eth_configuration_t leon_open_eth_configuration;
+
+int rtems_leon_open_eth_driver_attach(
+ struct rtems_bsdnet_ifconfig *config,
+ int attach
+)
+{
+ unsigned int base_addr = 0; /* avoid warnings */
+ unsigned int eth_irq = 0; /* avoid warnings */
+ struct ambapp_dev *adev;
+ struct ambapp_ahb_info *ahb;
+
+ /* Scan for MAC AHB slave interface */
+ adev = (void *)ambapp_for_each(&ambapp_plb, (OPTIONS_ALL|OPTIONS_AHB_SLVS),
+ VENDOR_OPENCORES, OPENCORES_ETHMAC,
+ ambapp_find_by_idx, NULL);
+ if (!adev) {
+ adev = (void *)ambapp_for_each(&ambapp_plb, (OPTIONS_ALL|OPTIONS_AHB_SLVS),
+ VENDOR_GAISLER, GAISLER_ETHAHB,
+ ambapp_find_by_idx, NULL);
+ }
+
+ if (adev)
+ {
+ ahb = DEV_TO_AHB(adev);
+ base_addr = ahb->start[0];
+ eth_irq = ahb->common.irq;
+
+ /* clear control register and reset NIC */
+ *(volatile int *) base_addr = 0;
+ *(volatile int *) base_addr = 0x800;
+ *(volatile int *) base_addr = 0;
+ leon_open_eth_configuration.base_address = (void *) base_addr;
+ leon_open_eth_configuration.vector = eth_irq + 0x10;
+ leon_open_eth_configuration.txd_count = TDA_COUNT;
+ leon_open_eth_configuration.rxd_count = RDA_COUNT;
+ /* enable 100 MHz operation only if cpu frequency >= 50 MHz */
+ if (LEON3_Timer_Regs->scaler_reload >= 49)
+ leon_open_eth_configuration.en100MHz = 1;
+ if (rtems_open_eth_driver_attach( config, &leon_open_eth_configuration )) {
+ LEON_Clear_interrupt(eth_irq);
+ LEON_Unmask_interrupt(eth_irq);
+ }
+ }
+ return 0;
+}
diff --git a/bsps/sparc/leon3/net/leon_smc91111.c b/bsps/sparc/leon3/net/leon_smc91111.c
new file mode 100644
index 0000000..70b2dcc
--- /dev/null
+++ b/bsps/sparc/leon3/net/leon_smc91111.c
@@ -0,0 +1,89 @@
+/**
+ * @file
+ * @ingroup sparc_leon3
+ * @brief LEON3 BSP SMC91111 registration and low-level initialization
+ */
+
+/*
+ * Copyright (c) 2006.
+ * Aeroflex Gaisler AB.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.org/license/LICENSE.
+ */
+
+#include <machine/rtems-bsd-kernel-space.h>
+
+#include <bsp.h>
+#include <libchip/smc91111exp.h>
+#include <rtems/bspIo.h>
+#include <grlib/ambapp.h>
+
+#define SMC91111_BASE_ADDR (void*)0x20000300
+#define SMC91111_BASE_IRQ 4
+#define SMC91111_BASE_PIO 4
+
+scmv91111_configuration_t leon_scmv91111_configuration = {
+ SMC91111_BASE_ADDR, /* base address */
+ SMC91111_BASE_IRQ, /* IRQ number (on LEON vector is irq) */
+ SMC91111_BASE_PIO, /* PIO */
+ 100, /* 100b */
+ 1, /* fulldx */
+ 1 /* autoneg */
+};
+
+/*
+ * Attach an SMC91111 driver to the system
+ */
+int
+rtems_smc91111_driver_attach_leon3 (struct rtems_bsdnet_ifconfig *config,
+ int attach)
+{
+ unsigned long addr_mctrl = 0;
+ struct grgpio_regs *io;
+ struct ambapp_apb_info apbpio;
+ struct ambapp_apb_info apbmctrl;
+
+ if (ambapp_find_apbslv(&ambapp_plb, VENDOR_GAISLER, GAISLER_GPIO, &apbpio)
+ != 1) {
+ printk("SMC9111_leon3: didn't find PIO\n");
+ return 0;
+ }
+
+ /* In order to access the SMC controller the memory controller must have
+ * I/O bus enabled. Find first memory controller.
+ */
+ if (ambapp_find_apbslv(&ambapp_plb, VENDOR_ESA, ESA_MCTRL, &apbmctrl) != 1) {
+ if (ambapp_find_apbslv(&ambapp_plb, VENDOR_GAISLER, GAISLER_FTMCTRL,
+ &apbmctrl) != 1) {
+ if (ambapp_find_apbslv(&ambapp_plb, VENDOR_GAISLER, GAISLER_FTSRCTRL,
+ &apbmctrl) != 1) {
+ if (ambapp_find_apbslv(&ambapp_plb, VENDOR_GAISLER, GAISLER_FTSRCTRL8,
+ &apbmctrl) != 1) {
+ printk("SMC9111_leon3: didn't find any memory controller\n");
+ return 0;
+ }
+ }
+ }
+ }
+
+ /* Get controller address */
+ addr_mctrl = (unsigned long) apbmctrl.start;
+ io = (struct grgpio_regs *) apbpio.start;
+
+ printk("Activating Leon3 io port for smsc_lan91cxx (pio:%x mctrl:%x)\n",
+ (unsigned int)io, (unsigned int)addr_mctrl);
+
+ /* Setup PIO IRQ */
+ io->imask |= (1 << leon_scmv91111_configuration.pio);
+ io->ipol |= (1 << leon_scmv91111_configuration.pio);
+ io->iedge |= (1 << leon_scmv91111_configuration.pio);
+ io->dir &= ~(1 << leon_scmv91111_configuration.pio);
+
+ /* Setup memory controller I/O waitstates */
+ *((volatile unsigned int *) addr_mctrl) |=
+ 0x10f80000; /* enable I/O area access */
+
+ return _rtems_smc91111_driver_attach(config, &leon_scmv91111_configuration);
+};
diff --git a/lnetworking.py b/lnetworking.py
index 5e14e52..6965a7e 100644
--- a/lnetworking.py
+++ b/lnetworking.py
@@ -26,12 +26,13 @@
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
from rtems_waf import rtems
+import bsp_drivers
import os
source_files = []
include_files = {}
test_source = []
-exclude_dirs = ['pppd', 'nfsclient', 'testsuites', 'librpc/include']
+exclude_dirs = ['pppd', 'nfsclient', 'testsuites', 'librpc/include', 'bsps']
exclude_headers = ['rtems-bsd-user-space.h', 'rtems-bsd-kernel-space.h']
for root, dirs, files in os.walk("."):
@@ -49,20 +50,50 @@ for root, dirs, files in os.walk('./testsuites'):
test_source.append(os.path.join(root, name))
def build(bld):
- include_path = ['./', os.path.relpath(bld.env.PREFIX), './testsuites/include']
+ include_path = []
+ ip = ''
+ BSP = bld.env.RTEMS_ARCH_BSP.split('-')[-1]
+
+ bsp_dirs, bsp_sources, bsp_archs = bsp_drivers.bsp_files(bld)
+
+ include_path.extend(['.',
+ os.path.relpath(bld.env.PREFIX),
+ './testsuites/include',
+ os.path.relpath(os.path.join(bld.env.PREFIX, 'include')),
+ './bsps/include'])
arch_lib_path = rtems.arch_bsp_lib_path(bld.env.RTEMS_VERSION,
bld.env.RTEMS_ARCH_BSP)
+ include_path.append(os.path.relpath(os.path.join(bld.env.PREFIX,
+ arch_lib_path)))
+ include_path.append(os.path.relpath(os.path.join(bld.env.PREFIX,
+ arch_lib_path,
+ 'include')))
+ if BSP in bsp_dirs:
+ include_path.extend(bsp_dirs[BSP])
+
+ for i in include_path:
+ ip = ip + i + ' '
+
+ if (BSP in bsp_sources):
+ bld(target = 'bsp_objs',
+ features = 'c',
+ cflags = ['-O2', '-g'],
+ includes = ip,
+ source = bsp_sources[BSP])
+
+ bld(target = 'network_objects',
+ features = 'c',
+ includes = ip,
+ source = source_files)
- bld.stlib(target = 'networking',
- features = 'c',
- cflags = ['-O2', '-g'],
- includes = include_path,
- source = source_files)
+ bld(target = 'networking',
+ features = 'c cstlib',
+ use = ['bsp_objs', 'network_objects'])
bld.program(target = 'networking01.exe',
features = 'c cprogram',
cflags = ['-O2', '-g'],
- includes = include_path,
+ includes = ip,
use = 'networking',
source = test_source)
diff --git a/wscript b/wscript
index 33ba1f2..adc253e 100644
--- a/wscript
+++ b/wscript
@@ -30,6 +30,7 @@ from rtems_waf import rtems
import lnetworking
import sys
+top = '.'
rtems_version = "6"
subdirs = ['pppd', 'nfsclient']
@@ -49,11 +50,12 @@ def options(opt):
def configure(conf):
rtems.configure(conf)
+
def recurse(ctx):
for sd in subdirs:
ctx.recurse(sd)
def build(bld):
- rtems.build(bld)
lnetworking.build(bld)
+ rtems.build(bld)
recurse(bld)