summaryrefslogtreecommitdiffstats
path: root/bsps/powerpc/mvme5500
diff options
context:
space:
mode:
Diffstat (limited to 'bsps/powerpc/mvme5500')
-rw-r--r--bsps/powerpc/mvme5500/headers.am21
-rw-r--r--bsps/powerpc/mvme5500/include/bsp.h206
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/GT64260TWSI.h20
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/GT64260eth.h140
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/GT64260ethreg.h879
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/VMEConfig.h67
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/VPD.h9
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/bspException.h99
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/bspMvme5500.h15
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/gtpcireg.h99
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/gtreg.h810
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/if_wmreg.h740
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/irq.h137
-rw-r--r--bsps/powerpc/mvme5500/include/bsp/pcireg.h386
-rw-r--r--bsps/powerpc/mvme5500/include/tm27.h66
15 files changed, 3694 insertions, 0 deletions
diff --git a/bsps/powerpc/mvme5500/headers.am b/bsps/powerpc/mvme5500/headers.am
new file mode 100644
index 0000000000..94c03a6982
--- /dev/null
+++ b/bsps/powerpc/mvme5500/headers.am
@@ -0,0 +1,21 @@
+## This file was generated by "./boostrap -H".
+
+include_HEADERS =
+include_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp.h
+include_HEADERS += include/bspopts.h
+include_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/tm27.h
+
+include_bspdir = $(includedir)/bsp
+include_bsp_HEADERS =
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/GT64260TWSI.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/GT64260eth.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/GT64260ethreg.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/VMEConfig.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/VPD.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/bspException.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/bspMvme5500.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/gtpcireg.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/gtreg.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/if_wmreg.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/irq.h
+include_bsp_HEADERS += ../../../../../../bsps/powerpc/mvme5500/include/bsp/pcireg.h
diff --git a/bsps/powerpc/mvme5500/include/bsp.h b/bsps/powerpc/mvme5500/include/bsp.h
new file mode 100644
index 0000000000..c1b17cee10
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp.h
@@ -0,0 +1,206 @@
+/*
+ * Copyright (C) 1999 Eric Valette. valette@crf.canon.fr
+ *
+ * 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.
+ *
+ * (C) S. Kate Feng 2003-2007 : Modified it to support the mvme5500 BSP.
+ */
+
+#ifndef LIBBSP_POWERPC_MVME5500_BSP_H
+#define LIBBSP_POWERPC_MVME5500_BSP_H
+
+#ifndef ASM
+
+#include <bspopts.h>
+#include <bsp/default-initial-extension.h>
+
+#include <rtems.h>
+#include <libcpu/io.h>
+#include <bsp/vectors.h>
+
+/* Board type */
+typedef enum {
+ undefined = 0,
+ MVME5500,
+ MVME6100
+} BSP_BoardTypes;
+
+BSP_BoardTypes BSP_getBoardType(void);
+
+/* Board type */
+typedef enum {
+ Undefined,
+ UNIVERSE2,
+ TSI148,
+} BSP_VMEchipTypes;
+
+BSP_VMEchipTypes BSP_getVMEchipType(void);
+
+/* The version of Discovery system controller */
+
+typedef enum {
+ notdefined,
+ GT64260A,
+ GT64260B,
+ MV64360,
+} DiscoveryChipVersion;
+
+DiscoveryChipVersion BSP_getDiscoveryChipVersion(void);
+
+#define _256M 0x10000000
+#define _512M 0x20000000
+
+#define GT64x60_REG_BASE 0xf1000000 /* Base of GT64260 Reg Space */
+#define GT64x60_REG_SPACE_SIZE 0x10000 /* 64Kb Internal Reg Space */
+
+#define GT64x60_DEV1_BASE 0xf1100000 /* Device bank1(chip select 1) base
+ */
+#define GT64260_DEV1_SIZE 0x00100000 /* Device bank size */
+
+/* fundamental addresses for this BSP (PREPxxx are from libcpu/io.h) */
+#define _IO_BASE GT64x60_REG_BASE
+
+#define BSP_NVRAM_BASE_ADDR 0xf1110000
+
+#define BSP_RTC_INTA_REG 0x7ff0
+#define BSP_RTC_SECOND 0x7ff2
+#define BSP_RTC_MINUTE 0x7ff3
+#define BSP_RTC_HOUR 0x7ff4
+#define BSP_RTC_DATE 0x7ff5
+#define BSP_RTC_INTERRUPTS 0x7ff6
+#define BSP_RTC_WATCHDOG 0x7ff7
+
+/* PCI0 Domain I/O space */
+#define PCI0_IO_BASE 0xf0000000
+#define PCI1_IO_BASE 0xf0800000
+
+/* PCI 0 memory space as seen from the CPU */
+#define PCI0_MEM_BASE 0x80000000
+#define PCI_MEM_BASE 0 /* glue for vmeUniverse */
+#define PCI_MEM_BASE_ADJUSTMENT 0
+
+/* address of our ram on the PCI bus */
+#define PCI_DRAM_OFFSET 0
+
+/* PCI 1 memory space as seen from the CPU */
+#define PCI1_MEM_BASE 0xe0000000
+#define PCI1_MEM_SIZE 0x10000000
+
+/* Needed for hot adding via PMCspan on the PCI0 local bus.
+ * This is board dependent, only because mvme5500
+ * supports hot adding and has more than one local PCI
+ * bus.
+ */
+#define BSP_MAX_PCI_BUS_ON_PCI0 8
+#define BSP_MAX_PCI_BUS_ON_PCI1 2
+#define BSP_MAX_PCI_BUS (BSP_MAX_PCI_BUS_ON_PCI0+BSP_MAX_PCI_BUS_ON_PCI1)
+
+
+/* The glues to Till's vmeUniverse, although the name does not
+ * actually reflect the relevant architect of the MVME5500.
+ */
+#define BSP_PCI_IRQ0 BSP_GPP_IRQ_LOWEST_OFFSET
+
+/*
+ * confdefs.h overrides for this BSP:
+ * - Interrupt stack space is not minimum if defined.
+ */
+#define BSP_INTERRUPT_STACK_SIZE (16 * 1024) /* <skf> 2/09 wants it to be adjustable by BSP */
+
+/* uart.c uses out_8 instead of outb */
+#define BSP_UART_IOBASE_COM1 GT64x60_DEV1_BASE + 0x20000
+#define BSP_UART_IOBASE_COM2 GT64x60_DEV1_BASE + 0x21000
+
+#define BSP_CONSOLE_PORT BSP_UART_COM1 /* console */
+#define BSP_UART_BAUD_BASE 115200
+
+/*
+ * Total memory using RESIDUAL DATA
+ */
+extern unsigned int BSP_mem_size;
+/*
+ * PCI Bus Frequency
+ */
+extern unsigned int BSP_bus_frequency;
+/*
+ * processor clock frequency
+ */
+extern unsigned int BSP_processor_frequency;
+/*
+ * Time base divisior (how many tick for 1 second).
+ */
+extern unsigned int BSP_time_base_divisor;
+
+#define BSP_Convert_decrementer( _value ) \
+ ((unsigned long long) ((((unsigned long long)BSP_time_base_divisor) * 1000000ULL) /((unsigned long long) BSP_bus_frequency)) * ((unsigned long long) (_value)))
+
+extern void bsp_reset(void);
+/* extern int printk(const char *, ...) __attribute__((format(printf, 1, 2))); */
+extern int BSP_disconnect_clock_handler(void);
+extern int BSP_connect_clock_handler(void);
+
+unsigned long _BSP_clear_hostbridge_errors(int enableMCP, int quiet);
+
+/*
+ * Prototypes for methods called only from .S for dependency tracking
+ */
+char *save_boot_params(
+ void *r3,
+ void *r4,
+ void *r5,
+ char *cmdline_start,
+ char *cmdline_end
+);
+void zero_bss(void);
+
+/*
+ * Prototypes for methods in the BSP that cross file boundaries
+ */
+uint32_t probeMemoryEnd(void);
+void pci_interface(void);
+void BSP_printPicIsrTbl(void);
+int I2Cread_eeprom(
+ unsigned char I2cBusAddr,
+ uint32_t devA2A1A0,
+ uint32_t AddrBytes,
+ unsigned char *pBuff,
+ uint32_t numBytes
+);
+
+#if 0
+#define RTEMS_BSP_NETWORK_DRIVER_NAME "gt1"
+#define RTEMS_BSP_NETWORK_DRIVER_ATTACH rtems_GT64260eth_driver_attach
+#else
+#define RTEMS_BSP_NETWORK_DRIVER_NAME "wmG1"
+#define RTEMS_BSP_NETWORK_DRIVER_ATTACH rtems_i82544EI_driver_attach
+#endif
+
+extern int RTEMS_BSP_NETWORK_DRIVER_ATTACH();
+
+#define gccMemBar() RTEMS_COMPILER_MEMORY_BARRIER()
+
+static inline void lwmemBar(void)
+{
+ __asm__ volatile("lwsync":::"memory");
+}
+
+static inline void io_flush(void)
+{
+ __asm__ volatile("isync":::"memory");
+}
+
+static inline void memBar(void)
+{
+ __asm__ volatile("sync":::"memory");
+}
+
+static inline void ioBar(void)
+{
+ __asm__ volatile("eieio":::"memory");
+}
+
+#endif
+
+#endif /* !ASM */
diff --git a/bsps/powerpc/mvme5500/include/bsp/GT64260TWSI.h b/bsps/powerpc/mvme5500/include/bsp/GT64260TWSI.h
new file mode 100644
index 0000000000..1377e6f607
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/GT64260TWSI.h
@@ -0,0 +1,20 @@
+#ifndef __GT64260TWSI_h
+#define __GT64260TWSI_h
+
+/* GT64260TWSI.h - header for the GT64260 Two-Wire Serial Interface */
+
+/* TWSI Control Register Bits */
+#define TWSI_ACK 4
+#define TWSI_INTFLG 8
+#define TWSI_STOP 0x10
+#define TWSI_START 0x20
+#define TWSI_TWSIEN 0x40
+#define TWSI_INTEN 0x80
+
+void GT64260TWSIinit(void);
+int GT64260TWSIstart(void);
+int GT64260TWSIwrite(unsigned char Data);
+int GT64260TWSIread(unsigned char *, int lastByte);
+int GT64260TWSIstop(void);
+
+#endif
diff --git a/bsps/powerpc/mvme5500/include/bsp/GT64260eth.h b/bsps/powerpc/mvme5500/include/bsp/GT64260eth.h
new file mode 100644
index 0000000000..2703bb423e
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/GT64260eth.h
@@ -0,0 +1,140 @@
+/* GT64260eth.h
+ *
+ * Copyright (c) 2002 Allegro Networks, Inc., Wasabi Systems, Inc.
+ * All rights reserved.
+ *
+ * RTEMS/Mvme5500 port 2004 by S. Kate Feng, <feng1@bnl.gov>,
+ * 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.
+ */
+
+/* Keep the ring sizes a power of two for efficiency.
+ Making the Tx ring too long decreases the effectiveness of channel
+ bonding and packet priority.
+ There are no ill effects from too-large receive rings. */
+#define TX_RING_SIZE 32
+#define GT_NEXTTX(x) ((x + 1) % TX_RING_SIZE )
+#define TX_QUARTER_FULL TX_RING_SIZE/2
+#define TX_HALF_FULL TX_RING_SIZE/2
+#define RX_RING_SIZE 16
+#define HASH_TABLE_SIZE 16
+#define HASH_DRAM_SIZE HASH_TABLE_SIZE*1024 /* size of DRAM for hash table */
+#define INTR_ERR_SIZE 16
+
+enum GTeth_txprio {
+ GE_TXPRIO_HI=1,
+ GE_TXPRIO_LO=0,
+ GE_TXPRIO_NONE=2
+};
+enum GTeth_rxprio {
+ GE_RXPRIO_HI=3,
+ GE_RXPRIO_MEDHI=2,
+ GE_RXPRIO_MEDLO=1,
+ GE_RXPRIO_LO=0
+};
+
+struct GTeth_softc {
+ struct GTeth_desc txq_desc[TX_RING_SIZE]; /* transmit descriptor memory */
+ struct GTeth_desc rxq_desc[RX_RING_SIZE]; /* receive descriptor memory */
+ struct mbuf* txq_mbuf[TX_RING_SIZE]; /* transmit buffer memory */
+ struct mbuf* rxq_mbuf[RX_RING_SIZE]; /* receive buffer memory */
+ struct GTeth_softc *next_module;
+ volatile unsigned int intr_errsts[INTR_ERR_SIZE]; /* capture the right intr_status */
+ unsigned int intr_err_ptr1; /* ptr used in GTeth_error() */
+ unsigned int intr_err_ptr2; /* ptr used in ISR */
+ struct ifqueue txq_pendq; /* these are ready to go to the GT */
+ unsigned int txq_pending;
+ unsigned int txq_lo; /* next to be given to GT DMA */
+ unsigned int txq_fi; /* next to be free */
+ unsigned int txq_to_cpu; /* next to be returned to CPU */
+ unsigned int txq_ei_gapcount; /* counter until next EI */
+ unsigned int txq_nactive; /* number of active descriptors */
+ unsigned int txq_nintr; /* number of txq desc. send TX_EVENT */
+ unsigned int txq_outptr; /* where to put next transmit packet */
+ unsigned int txq_inptr; /* start of 1st queued tx packet */
+ unsigned int txq_free; /* free Tx queue slots. */
+ unsigned txq_intrbits; /* bits to write to EIMR */
+ unsigned txq_esdcmrbits; /* bits to write to ESDCMR */
+ unsigned txq_epsrbits; /* bits to test with EPSR */
+
+ caddr_t txq_ectdp; /* offset to cur. tx desc ptr reg */
+ unsigned long txq_desc_busaddr; /* bus addr of tx descriptors */
+ caddr_t txq_buf_busaddr; /* bus addr of tx buffers */
+
+ struct mbuf *rxq_curpkt; /* mbuf for current packet */
+ struct GTeth_desc *rxq_head_desc; /* rxq head descriptor */
+ unsigned int rxq_fi; /* next to be returned to CPU */
+ unsigned int rxq_active; /* # of descriptors given to GT */
+ unsigned rxq_intrbits; /* bits to write to EIMR */
+ unsigned long rxq_desc_busaddr; /* bus addr of rx descriptors */
+
+ struct arpcom arpcom; /* rtems if structure, contains ifnet */
+ 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
+ unsigned sc_pcr; /* current EPCR value */
+ unsigned sc_pcxr; /* current EPCXR value */
+ unsigned sc_intrmask; /* current EIMR value */
+ unsigned sc_idlemask; /* suspended EIMR bits */
+ unsigned sc_max_frame_length; /* maximum frame length */
+ unsigned rx_buf_sz;
+
+ /* Hash table related members */
+ unsigned long long *sc_hashtable;
+ unsigned int sc_hashmask; /* 0x1ff or 0x1fff */
+
+ rtems_id daemonTid;
+ rtems_id daemonSync; /* synchronization with the daemon */
+ /* statistics */
+ struct {
+ volatile unsigned long rxInterrupts;
+
+ volatile unsigned long txInterrupts;
+ unsigned long txMultiBuffPacket;
+ unsigned long txMultiMaxLen;
+ unsigned long txSinglMaxLen;
+ unsigned long txMultiMaxLoop;
+ unsigned long txBuffMaxLen;
+ unsigned long length_errors;
+ unsigned long frame_errors;
+ unsigned long crc_errors;
+ unsigned long or_errors; /* overrun error */
+ } stats;
+};
diff --git a/bsps/powerpc/mvme5500/include/bsp/GT64260ethreg.h b/bsps/powerpc/mvme5500/include/bsp/GT64260ethreg.h
new file mode 100644
index 0000000000..d9081ccb53
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/GT64260ethreg.h
@@ -0,0 +1,879 @@
+/* $NetBSD: GT64260ethreg.h,v 1.2 2003/03/17 16:41:16 matt 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) (1ULL << (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) ((unsigned long long)(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 GTeth_desc {
+#if defined(BYTE_ORDER) && BYTE_ORDER == BIG_ENDIAN /* for mvme5500 */
+ unsigned ed_lencnt; /* Buffer size is hi 16 bits; Byte count (rx) is lo 16 */
+ unsigned ed_cmdsts; /* command (hi16)/status (lo16) bits */
+ unsigned ed_nxtptr; /* next descriptor (must be 4LW aligned) */
+ unsigned ed_bufptr; /* pointer to packet buffer */
+#endif
+#if defined(BYTE_ORDER) && BYTE_ORDER == LITTLE_ENDIAN
+ unsigned ed_cmdsts; /* command (hi16)/status (lo16) bits */
+ unsigned ed_lencnt; /* length is hi 16 bits; count (rx) is lo 16 */
+ unsigned ed_bufptr; /* pointer to packet buffer */
+ unsigned ed_nxtptr; /* next descriptor (must be 4LW aligned) */
+#endif
+};
+
+/* Ethernet 0 address control (Low), Offset: 0xf200 */
+#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 */
+
+/* Ethernet 0 address control (High), Offset: 0xf204 */
+#define HashSnoopEn ETH__BIT(6) /* Hash Table snoop enable */
+
+/* <skf> */
+#define GT_CUU_Eth0_AddrCtrlLow 0xf200
+#define GT_CUU_Eth0_AddrCtrlHigh 0xf204
+
+/* 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 608: 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 */
+
+/* SKF : we are only concerned with the Ethernet0 for the mvme5500 board */
+#define ETH0_EBASE 0x2400 /* Base of Registers */
+#define ETH0_EPCR 0x2400 /* Port Config. Register */
+#define ETH0_EPCXR 0x2408 /* Port Config. Extend Reg */
+#define ETH0_EPCMR 0x2410 /* Port Command Register */
+#define ETH0_EPSR 0x2418 /* Port Status Register */
+#define ETH0_ESPR 0x2420 /* Port Serial Parameters Reg */
+#define ETH0_EHTPR 0x2428 /* Port Hash Table Pointer Reg*/
+#define ETH0_EFCSAL 0x2430 /* Flow Control Src Addr Low */
+#define ETH0_EFCSAH 0x2438 /* Flow Control Src Addr High */
+#define ETH0_ESDCR 0x2440 /* SDMA Configuration Reg */
+#define ETH0_ESDCMR 0x2448 /* SDMA Command Register */
+#define ETH0_EICR 0x2450 /* Interrupt Cause Register */
+#define ETH0_EIMR 0x2458 /* Interrupt Mask Register */
+#define ETH0_EFRDP0 0x2480 /* First Rx Desc Pointer 0 */
+#define ETH0_EFRDP1 0x2484 /* First Rx Desc Pointer 1 */
+#define ETH0_EFRDP2 0x2488 /* First Rx Desc Pointer 2 */
+#define ETH0_EFRDP3 0x248c /* First Rx Desc Pointer 3 */
+#define ETH0_ECRDP0 0x24a0 /* Current Rx Desc Pointer 0 */
+#define ETH0_ECRDP1 0x24a4 /* Current Rx Desc Pointer 1 */
+#define ETH0_ECRDP2 0x24a8 /* Current Rx Desc Pointer 2 */
+#define ETH0_ECRDP3 0x24ac /* Current Rx Desc Pointer 3 */
+#define ETH0_ECTDP0 0x24e0 /* Current Tx Desc Pointer 0 */
+#define ETH0_ECTDP1 0x24e4 /* Current Tx Desc Pointer 1 */
+#define ETH0_EDSCP2P0L 0x2460 /* IP Differentiated Services
+ CodePoint to Priority0 low */
+#define ETH0_EDSCP2P0H 0x2464 /* IP Differentiated Services
+ CodePoint to Priority0 high*/
+#define ETH0_EDSCP2P1L 0x2468 /* IP Differentiated Services
+ CodePoint to Priority1 low */
+#define ETH0_EDSCP2P1H 0x246c /* IP Differentiated Services
+ CodePoint to Priority1 high*/
+#define ETH0_EVPT2P 0x2468 /* VLAN Prio. Tag to Priority */
+#define ETH0_EMIBCTRS 0x2500 /* 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_2048 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 (1<<31)
+#define ETH_IR_Summary (1<<31)
+#define ETH_IR_ErrorSum 0x803d00
+#define INTR_RX_ERROR 0x801100
+#define INTR_TX_ERROR 0x002c00
+
+/*
+ * 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
+ */
+#endif /* _DEV_GTETHREG_H_ */
diff --git a/bsps/powerpc/mvme5500/include/bsp/VMEConfig.h b/bsps/powerpc/mvme5500/include/bsp/VMEConfig.h
new file mode 100644
index 0000000000..ecc5789899
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/VMEConfig.h
@@ -0,0 +1,67 @@
+#ifndef RTEMS_BSP_VME_CONFIG_H
+#define RTEMS_BSP_VME_CONFIG_H
+/* VMEConfig.h, S. Kate Feng modified it for MVME5500 3/04
+ *
+ * May 2011 : Use the VME shared IRQ handlers.
+ *
+ * It seems that the implementation of VMEUNIVERSE_IRQ_MGR_FLAG_PW_WORKAROUND
+ * is not fully developed. The UNIV_REGOFF_VCSR_BS is defined for VME64
+ * specification, which does not apply to a VME32 crate. In order to avoid
+ * spurious VME interrupts, a better and more universal solution is
+ * to flush the vmeUniverse FIFO by reading a register back within the
+ * users' Interrupt Service Routine (ISR) before returning.
+ *
+ * Some devices might require the ISR to issue an interrupt status READ
+ * after its IRQ is cleared, but before its corresponding interrupt
+ * is enabled again.
+ *
+ */
+
+/*
+ * Prototypes
+ */
+int BSP_VMEInit(void);
+int BSP_VMEIrqMgrInstall(void);
+
+/* BSP specific address space configuration parameters */
+
+/*
+ * The BSP maps VME address ranges into
+ * one BAT.
+ * NOTE: the BSP (startup/bspstart.c) uses
+ * hardcoded window lengths that match this
+ * layout:
+ */
+#define _VME_A32_WIN0_ON_PCI 0x90000000
+/* If _VME_CSR_ON_PCI is defined then the A32 window is reduced to accommodate
+ * CSR for space.
+ */
+#define _VME_CSR_ON_PCI 0x9e000000
+#define _VME_A24_ON_PCI 0x9f000000
+#define _VME_A16_ON_PCI 0x9fff0000
+
+/* Reuse BAT 0 for VME */
+#define BSP_VME_BAT_IDX 0
+
+/* start of the A32 window on the VME bus
+ * TODO: this should perhaps be a configuration option
+ */
+#define _VME_A32_WIN0_ON_VME 0x20000000
+
+/* if _VME_DRAM_OFFSET is defined, the BSP
+ * will map our RAM onto the VME bus, starting
+ * at _VME_DRAM_OFFSET
+ */
+#define _VME_DRAM_OFFSET 0x90000000
+
+#define BSP_VME_UNIVERSE_INSTALL_IRQ_MGR(err) \
+ do { \
+ err = vmeUniverseInstallIrqMgrAlt(VMEUNIVERSE_IRQ_MGR_FLAG_SHARED,\
+ 0, BSP_GPP_VME_VLINT0, \
+ 1, BSP_GPP_VME_VLINT1, \
+ 2, BSP_GPP_VME_VLINT2, \
+ 3, BSP_GPP_VME_VLINT3, \
+ -1 /* terminate list */); \
+ } while (0)
+
+#endif
diff --git a/bsps/powerpc/mvme5500/include/bsp/VPD.h b/bsps/powerpc/mvme5500/include/bsp/VPD.h
new file mode 100644
index 0000000000..33aec8b74c
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/VPD.h
@@ -0,0 +1,9 @@
+/* The mapping of the Configuration VPD
+ *
+ * (C) 2004, NSLS, Brookhaven National Laboratory,
+ * S. Kate Feng, <feng1@bnl.gov>
+ *
+ */
+
+#define VPD_ENET0_OFFSET 0x3c
+#define VPD_ENET1_OFFSET 0x45
diff --git a/bsps/powerpc/mvme5500/include/bsp/bspException.h b/bsps/powerpc/mvme5500/include/bsp/bspException.h
new file mode 100644
index 0000000000..7cd816e818
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/bspException.h
@@ -0,0 +1,99 @@
+#ifndef BSP_EXCEPTION_HANDLER_H
+#define BSP_EXCEPTION_HANDLER_H
+
+/* A slightly improved exception 'default' exception handler for RTEMS / SVGM */
+
+/*
+ * Authorship
+ * ----------
+ * This software was created by
+ * Till Straumann <strauman@slac.stanford.edu>, 5/2002,
+ * Stanford Linear Accelerator Center, Stanford University.
+ *
+ * Acknowledgement of sponsorship
+ * ------------------------------
+ * This 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
+ */
+
+#include <bsp/vectors.h>
+
+/* Two types of exception intercepting / catching is supported:
+ *
+ * - lowlevel handling (runs at IRQ level, before restoring any
+ * task context).
+ * - highlevel handling.
+ *
+ * A lowlevel user hook is invoked twice, before and after processing
+ * (printing) the exception.
+ * If the user hook returns a nonzero value, normal processing
+ * is skipped (including the second call to the hook)
+ *
+ * If the hook returns nonzero to the second call, no default
+ * 'panic' occurs.
+ *
+ * Default 'panic':
+ * - if a task context is available:
+ * - if a highlevel handler is installed, pass control
+ * to the highlevel handler when returning from the
+ * exception (the highlevel handler should probably
+ * do a longjmp()). Otherwise:
+ * - try to suspend interrupted task.
+ * - hang if no task context is available.
+ *
+ */
+
+typedef struct BSP_ExceptionExtensionRec_ *BSP_ExceptionExtension;
+
+typedef int (*BSP_ExceptionHookProc)(BSP_Exception_frame *frame, BSP_ExceptionExtension ext, int after);
+
+typedef struct BSP_ExceptionExtensionRec_ {
+ BSP_ExceptionHookProc lowlevelHook;
+ int quiet; /* silence the exception handler */
+ void (*highlevelHook)(BSP_ExceptionExtension);
+ /* user fields may be added after this */
+} BSP_ExceptionExtensionRec;
+
+#define SRR1_TEA_EXC (1<<(31-13))
+#define SRR1_MCP_EXC (1<<(31-12))
+
+void
+BSP_exceptionHandler(BSP_Exception_frame* excPtr);
+
+/* install an exception handler to the current task context */
+BSP_ExceptionExtension
+BSP_exceptionHandlerInstall(BSP_ExceptionExtension e);
+
+#endif
diff --git a/bsps/powerpc/mvme5500/include/bsp/bspMvme5500.h b/bsps/powerpc/mvme5500/include/bsp/bspMvme5500.h
new file mode 100644
index 0000000000..9fb53869ff
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/bspMvme5500.h
@@ -0,0 +1,15 @@
+/* GT64260 register base mapping on the MVME5500
+ *
+ * (C) Shuchen K. Feng <feng1@bnl.gov>,NSLS,
+ * Brookhaven National Laboratory, 2003
+ *
+ */
+#define _256M 0x10000000
+#define _512M 0x20000000
+
+#define GT64260_REG_BASE 0xf1000000 /* Base of GT64260 Reg Space */
+#define GT64260_REG_SPACE_SIZE 0x10000 /* 64Kb Internal Reg Space */
+
+#define GT64260_DEV1_BASE 0xf1100000 /* Device bank1(chip select 1) base
+ */
+#define GT64260_DEV1_SIZE 0x00100000 /* Device bank size */
diff --git a/bsps/powerpc/mvme5500/include/bsp/gtpcireg.h b/bsps/powerpc/mvme5500/include/bsp/gtpcireg.h
new file mode 100644
index 0000000000..74751f6088
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/gtpcireg.h
@@ -0,0 +1,99 @@
+/* $NetBSD: gtpcireg.h,v 1.2 2003/03/24 17:03:18 matt 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.
+ */
+#define PCI_ARBCTL_EN (1<<31)
+
+#define PCI_COMMAND_SB_DIS 0x2000 /* PCI configuration read will stop
+ * acting as sync barrier transactin
+ */
+
+#define PCI_MEM_BASE_ADDR PCI_BASE_ADDRESS_4
+
+#define PCI_IO_BASE_ADDR PCI_BASE_ADDRESS_5
+
+#define PCI_STATUS_CLRERR_MASK 0xf9000000 /* <SKF> */
+
+#define PCI_BARE_IntMemEn 0x200
+
+#define PCI_ACCCTLBASEL_PrefetchEn 0x0001000
+#define PCI_ACCCTLBASEL_RdPrefetch 0x0010000
+#define PCI_ACCCTLBASEL_RdLinePrefetch 0x0020000
+#define PCI_ACCCTLBASEL_RdMulPrefetch 0x0040000
+#define PCI_ACCCTLBASEL_WBurst_8_QW 0x0100000
+#define PCI_ACCCTLBASEL_PCISwap_NoSwap 0x1000000
+
+#define PCI0_P2P_CONFIG 0x1d14
+#define PCI_SNOOP_BASE0_LOW 0x1f00
+#define PCI_SNOOP_BASE0_HIGH 0x1f04
+#define PCI_SNOOP_TOP0 0x1f08
+
+#define PCI0_SCS0_BAR_SIZE 0x0c08
+#define PCI0_SCS1_BAR_SIZE 0x0d08
+#define PCI0_SCS2_BAR_SIZE 0x0c0c
+#define PCI0_SCS3_BAR_SIZE 0x0d0c
+
+#define PCI0_BASE_ADDR_REG_ENABLE 0x0c3c
+#define PCI0_ARBITER_CNTL 0x1d00
+#define PCI0_ACCESS_CNTL_BASE0_LOW 0x1e00
+#define PCI0_ACCESS_CNTL_BASE0_HIGH 0x1e04
+#define PCI0_ACCESS_CNTL_BASE0_TOP 0x1e08
+
+#define PCI0_ACCESS_CNTL_BASE1_LOW 0x1e10
+#define PCI0_ACCESS_CNTL_BASE1_HIGH 0x1e14
+#define PCI0_ACCESS_CNTL_BASE1_TOP 0x1e18
+
+#define PCI1_BASE_ADDR_REG_ENABLE 0x0cbc
+#define PCI1_ARBITER_CNTL 0x1d80
+#define PCI1_ACCESS_CNTL_BASE0_LOW 0x1e80
+#define PCI1_ACCESS_CNTL_BASE0_HIGH 0x1e84
+#define PCI1_ACCESS_CNTL_BASE0_TOP 0x1e88
+
+#define PCI1_ACCESS_CNTL_BASE1_LOW 0x1e90
+#define PCI1_ACCESS_CNTL_BASE1_HIGH 0x1e94
+#define PCI1_ACCESS_CNTL_BASE1_TOP 0x1e98
+
+#define PCI_SNOOP_BASE1_LOW 0x1f10
+#define PCI_SNOOP_BASE1_HIGH 0x1f14
+#define PCI_SNOOP_TOP1 0x1f18
+
+#define PCI0_CMD_CNTL 0xc00
+
+#define PCI1_P2P_CONFIG 0x1d94
+#define PCI1_CMD_CNTL 0xc80
+#define PCI1_CONFIG_ADDR 0xc78
+#define PCI1_CONFIG_DATA 0xc7c
diff --git a/bsps/powerpc/mvme5500/include/bsp/gtreg.h b/bsps/powerpc/mvme5500/include/bsp/gtreg.h
new file mode 100644
index 0000000000..e9aaeff844
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/gtreg.h
@@ -0,0 +1,810 @@
+/* $NetBSD: gtreg.h,v 1.1 2003/03/05 22:08:22 matt 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 _DISCOVERY_DEV_GTREG_H_
+#define _DISCOVERY_DEV_GTREG_H_
+
+#define GT__BIT(bit) (1U << (bit))
+#define GT__MASK(bit) (GT__BIT(bit) - 1)
+#define GT__EXT(data, bit, len) (((data) >> (bit)) & GT__MASK(len))
+#define GT__CLR(data, bit, len) ((data) &= ~(GT__MASK(len) << (bit)))
+#define GT__INS(new, bit) ((new) << (bit))
+
+
+/*
+ * Table 30: CPU Address Decode Register Map
+ */
+#define GT_SCS0_Low_Decode 0x0008
+#define GT_SCS0_High_Decode 0x0010
+#define GT_SCS1_Low_Decode 0x0208
+#define GT_SCS1_High_Decode 0x0210
+#define GT_SCS2_Low_Decode 0x0018
+#define GT_SCS2_High_Decode 0x0020
+#define GT_SCS3_Low_Decode 0x0218
+#define GT_SCS3_High_Decode 0x0220
+#define GT_CS0_Low_Decode 0x0028
+#define GT_CS0_High_Decode 0x0030
+#define GT_CS1_Low_Decode 0x0228
+#define GT_CS1_High_Decode 0x0230
+#define GT_CS2_Low_Decode 0x0248
+#define GT_CS2_High_Decode 0x0250
+#define GT_CS3_Low_Decode 0x0038
+#define GT_CS3_High_Decode 0x0040
+#define GT_BootCS_Low_Decode 0x0238
+#define GT_BootCS_High_Decode 0x0240
+#define GT_PCI0_IO_Low_Decode 0x0048
+#define GT_PCI0_IO_High_Decode 0x0050
+#define GT_PCI0_Mem0_Low_Decode 0x0058
+#define GT_PCI0_Mem0_High_Decode 0x0060
+#define GT_PCI0_Mem1_Low_Decode 0x0080
+#define GT_PCI0_Mem1_High_Decode 0x0088
+#define GT_PCI0_Mem2_Low_Decode 0x0258
+#define GT_PCI0_Mem2_High_Decode 0x0260
+#define GT_PCI0_Mem3_Low_Decode 0x0280
+#define GT_PCI0_Mem3_High_Decode 0x0288
+#define GT_PCI1_IO_Low_Decode 0x0090
+#define GT_PCI1_IO_High_Decode 0x0098
+#define GT_PCI1_Mem0_Low_Decode 0x00a0
+#define GT_PCI1_Mem0_High_Decode 0x00a8
+#define GT_PCI1_Mem1_Low_Decode 0x00b0
+#define GT_PCI1_Mem1_High_Decode 0x00b8
+#define GT_PCI1_Mem2_Low_Decode 0x02a0
+#define GT_PCI1_Mem2_High_Decode 0x02a8
+#define GT_PCI1_Mem3_Low_Decode 0x02b0
+#define GT_PCI1_Mem3_High_Decode 0x02b8
+#define GT_Internal_Decode 0x0068
+#define GT_CPU0_Low_Decode 0x0290
+#define GT_CPU0_High_Decode 0x0298
+#define GT_CPU1_Low_Decode 0x02c0
+#define GT_CPU1_High_Decode 0x02c8
+#define GT_PCI0_IO_Remap 0x00f0
+#define GT_PCI0_Mem0_Remap_Low 0x00f8
+#define GT_PCI0_Mem0_Remap_High 0x0320
+#define GT_PCI0_Mem1_Remap_Low 0x0100
+#define GT_PCI0_Mem1_Remap_High 0x0328
+#define GT_PCI0_Mem2_Remap_Low 0x02f8
+#define GT_PCI0_Mem2_Remap_High 0x0330
+#define GT_PCI0_Mem3_Remap_Low 0x0300
+#define GT_PCI0_Mem3_Remap_High 0x0338
+#define GT_PCI1_IO_Remap 0x0108
+#define GT_PCI1_Mem0_Remap_Low 0x0110
+#define GT_PCI1_Mem0_Remap_High 0x0340
+#define GT_PCI1_Mem1_Remap_Low 0x0118
+#define GT_PCI1_Mem1_Remap_High 0x0348
+#define GT_PCI1_Mem2_Remap_Low 0x0310
+#define GT_PCI1_Mem2_Remap_High 0x0350
+#define GT_PCI1_Mem3_Remap_Low 0x0318
+#define GT_PCI1_Mem3_Remap_High 0x0358
+
+
+/*
+ * Table 31: CPU Control Register Map
+ */
+#define GT_CPU_Cfg 0x0000
+#define GT_CPU_Mode 0x0120
+#define GT_CPU_Master_Ctl 0x0160
+#define GT_CPU_If_Xbar_Ctl_Low 0x0150
+#define GT_CPU_If_Xbar_Ctl_High 0x0158
+#define GT_CPU_If_Xbar_Timeout 0x0168
+#define GT_CPU_Rd_Rsp_Xbar_Ctl_Low 0x0170
+#define GT_CPU_Rd_Rsp_Xbar_Ctl_High 0x0178
+
+/*
+ * Table 32: CPU Sync Barrier Register Map
+ */
+#define GT_PCI_Sync_Barrier(bus) (0x00c0 | ((bus) << 3))
+#define GT_PCI0_Sync_Barrier 0x00c0
+#define GT_PCI1_Sync_Barrier 0x00c8
+
+/*
+ * Table 33: CPU Access Protection Register Map
+ */
+#define GT_Protect_Low_0 0x0180
+#define GT_Protect_High_0 0x0188
+#define GT_Protect_Low_1 0x0190
+#define GT_Protect_High_1 0x0198
+#define GT_Protect_Low_2 0x01a0
+#define GT_Protect_High_2 0x01a8
+#define GT_Protect_Low_3 0x01b0
+#define GT_Protect_High_3 0x01b8
+#define GT_Protect_Low_4 0x01c0
+#define GT_Protect_High_4 0x01c8
+#define GT_Protect_Low_5 0x01d0
+#define GT_Protect_High_5 0x01d8
+#define GT_Protect_Low_6 0x01e0
+#define GT_Protect_High_6 0x01e8
+#define GT_Protect_Low_7 0x01f0
+#define GT_Protect_High_7 0x01f8
+
+/*
+ * Table 34: Snoop Control Register Map
+ */
+#define GT_Snoop_Base_0 0x0380
+#define GT_Snoop_Top_0 0x0388
+#define GT_Snoop_Base_1 0x0390
+#define GT_Snoop_Top_1 0x0398
+#define GT_Snoop_Base_2 0x03a0
+#define GT_Snoop_Top_2 0x03a8
+#define GT_Snoop_Base_3 0x03b0
+#define GT_Snoop_Top_3 0x03b8
+
+/*
+ * Table 35: CPU Error Report Register Map
+ */
+#define GT_CPU_Error_Address_Low 0x0070
+#define GT_CPU_Error_Address_High 0x0078
+#define GT_CPU_Error_Data_Low 0x0128
+#define GT_CPU_Error_Data_High 0x0130
+#define GT_CPU_Error_Parity 0x0138
+#define GT_CPU_Error_Cause 0x0140
+#define GT_CPU_Error_Mask 0x0148
+
+#define GT_DecodeAddr_SET(g, r, v) \
+ do { \
+ gt_read((g), GT_Internal_Decode); \
+ gt_write((g), (r), ((v) & 0xfff00000) >> 20); \
+ while ((gt_read((g), (r)) & 0xfff) != ((v) >> 20)); \
+ } while (0)
+
+#define GT_LowAddr_GET(v) (GT__EXT((v), 0, 12) << 20)
+#define GT_HighAddr_GET(v) ((GT__EXT((v), 0, 12) << 20) | 0xfffff)
+
+#define GT_MPP_Control0 0xf000
+#define GT_MPP_Control1 0xf004
+#define GT_MPP_Control2 0xf008
+#define GT_MPP_Control3 0xf00c
+
+/* <skf> added for GT64260 */
+#define GT_MPP_SerialPortMultiplex 0xf010
+
+#define GT_GPP_IO_Control 0xf100
+#define GT_GPP_Level_Control 0xf110
+#define GT_GPP_Value 0xf104
+#define GT_GPP_Interrupt_Cause 0xf108
+#define GT_GPP_Interrupt_Mask 0xf10c
+/*
+ * Table 36: SCS[0]* Low Decode Address, Offset: 0x008
+ * Table 38: SCS[1]* Low Decode Address, Offset: 0x208
+ * Table 40: SCS[2]* Low Decode Address, Offset: 0x018
+ * Table 42: SCS[3]* Low Decode Address, Offset: 0x218
+ * Table 44: CS[0]* Low Decode Address, Offset: 0x028
+ * Table 46: CS[1]* Low Decode Address, Offset: 0x228
+ * Table 48: CS[2]* Low Decode Address, Offset: 0x248
+ * Table 50: CS[3]* Low Decode Address, Offset: 0x038
+ * Table 52: BootCS* Low Decode Address, Offset: 0x238
+ * Table 75: CPU 0 Low Decode Address, Offset: 0x290
+ * Table 77: CPU 1 Low Decode Address, Offset: 0x2c0
+ *
+ * 11:00 LowAddr SCS[0] Base Address
+ * 31:12 Reserved Must be 0.
+ */
+
+/*
+ * Table 37: SCS[0]* High Decode Address, Offset: 0x010
+ * Table 39: SCS[1]* High Decode Address, Offset: 0x210
+ * Table 41: SCS[2]* High Decode Address, Offset: 0x020
+ * Table 43: SCS[3]* High Decode Address, Offset: 0x220
+ * Table 45: CS[0]* High Decode Address, Offset: 0x030
+ * Table 47: CS[1]* High Decode Address, Offset: 0x230
+ * Table 49: CS[2]* High Decode Address, Offset: 0x250
+ * Table 51: CS[3]* High Decode Address, Offset: 0x040
+ * Table 53: BootCS* High Decode Address, Offset: 0x240
+ * Table 76: CPU 0 High Decode Address, Offset: 0x298
+ * Table 78: CPU 1 High Decode Address, Offset: 0x2c8
+ *
+ * 11:00 HighAddr SCS[0] Top Address
+ * 31:12 Reserved
+ */
+
+/*
+ * Table 54: PCI_0 I/O Low Decode Address, Offset: 0x048
+ * Table 56: PCI_0 Memory 0 Low Decode Address, Offset: 0x058
+ * Table 58: PCI_0 Memory 1 Low Decode Address, Offset: 0x080
+ * Table 60: PCI_0 Memory 2 Low Decode Address, Offset: 0x258
+ * Table 62: PCI_0 Memory 3 Low Decode Address, Offset: 0x280
+ * Table 64: PCI_1 I/O Low Decode Address, Offset: 0x090
+ * Table 66: PCI_1 Memory 0 Low Decode Address, Offset: 0x0a0
+ * Table 68: PCI_1 Memory 1 Low Decode Address, Offset: 0x0b0
+ * Table 70: PCI_1 Memory 2 Low Decode Address, Offset: 0x2a0
+ * Table 72: PCI_1 Memory 3 Low Decode Address, Offset: 0x2b0
+ *
+ * 11:00 LowAddr PCI IO/Memory Space Base Address
+ * 23:12 Reserved
+ * 26:24 PCISwap PCI Master Data Swap Control (0: Byte Swap;
+ * 1: No swapping; 2: Both byte and word swap;
+ * 3: Word swap; 4..7: Reserved)
+ * 27:27 PCIReq64 PCI master REQ64* policy (Relevant only when
+ * configured to 64-bit PCI bus and not I/O)
+ * 0: Assert s REQ64* only when transaction
+ * is longer than 64-bits.
+ * 1: Always assert REQ64*.
+ * 31:28 Reserved
+ */
+#define GT_PCISwap_GET(v) GT__EXT((v), 24, 3)
+#define GT_PCISwap_ByteSwap 0
+#define GT_PCISwap_NoSwap 1
+#define GT_PCISwap_ByteWordSwap 2
+#define GT_PCISwap_WordSwap 3
+#define GT_PCI_LowDecode_PCIReq64 GT__BIT(27)
+
+/*
+ * Table 55: PCI_0 I/O High Decode Address, Offset: 0x050
+ * Table 57: PCI_0 Memory 0 High Decode Address, Offset: 0x060
+ * Table 59: PCI_0 Memory 1 High Decode Address, Offset: 0x088
+ * Table 61: PCI_0 Memory 2 High Decode Address, Offset: 0x260
+ * Table 63: PCI_0 Memory 3 High Decode Address, Offset: 0x288
+ * Table 65: PCI_1 I/O High Decode Address, Offset: 0x098
+ * Table 67: PCI_1 Memory 0 High Decode Address, Offset: 0x0a8
+ * Table 69: PCI_1 Memory 1 High Decode Address, Offset: 0x0b8
+ * Table 71: PCI_1 Memory 2 High Decode Address, Offset: 0x2a8
+ * Table 73: PCI_1 Memory 3 High Decode Address, Offset: 0x2b8
+ *
+ * 11:00 HighAddr PCI_0 I/O Space Top Address
+ * 31:12 Reserved
+ */
+
+/*
+ * Table 74: Internal Space Decode, Offset: 0x068
+ * 15:00 IntDecode GT64260 Internal Space Base Address
+ * 23:16 Reserved
+ * 26:24 PCISwap Same as PCI_0 Memory 0 Low Decode Address.
+ * NOTE: Reserved for Galileo Technology usage.
+ * Relevant only for PCI master configuration
+ * transactions on the PCI bus.
+ * 31:27 Reserved
+ */
+
+/*
+ * Table 79: PCI_0 I/O Address Remap, Offset: 0x0f0
+ * Table 80: PCI_0 Memory 0 Address Remap Low, Offset: 0x0f8
+ * Table 82: PCI_0 Memory 1 Address Remap Low, Offset: 0x100
+ * Table 84: PCI_0 Memory 2 Address Remap Low, Offset: 0x2f8
+ * Table 86: PCI_0 Memory 3 Address Remap Low, Offset: 0x300
+ * Table 88: PCI_1 I/O Address Remap, Offset: 0x108
+ * Table 89: PCI_1 Memory 0 Address Remap Low, Offset: 0x110
+ * Table 91: PCI_1 Memory 1 Address Remap Low, Offset: 0x118
+ * Table 93: PCI_1 Memory 2 Address Remap Low, Offset: 0x310
+ * Table 95: PCI_1 Memory 3 Address Remap Low, Offset: 0x318
+ *
+ * 11:00 Remap PCI IO/Memory Space Address Remap (31:20)
+ * 31:12 Reserved
+ */
+
+/*
+ * Table 81: PCI_0 Memory 0 Address Remap High, Offset: 0x320
+ * Table 83: PCI_0 Memory 1 Address Remap High, Offset: 0x328
+ * Table 85: PCI_0 Memory 2 Address Remap High, Offset: 0x330
+ * Table 87: PCI_0 Memory 3 Address Remap High, Offset: 0x338
+ * Table 90: PCI_1 Memory 0 Address Remap High, Offset: 0x340
+ * Table 92: PCI_1 Memory 1 Address Remap High, Offset: 0x348
+ * Table 94: PCI_1 Memory 2 Address Remap High, Offset: 0x350
+ * Table 96: PCI_1 Memory 3 Address Remap High, Offset: 0x358
+ *
+ * 31:00 Remap PCI Memory Address Remap (high 32 bits)
+ */
+
+/*
+ * Table 97: CPU Configuration, Offset: 0x000
+ * 07:00 NoMatchCnt CPU Address Miss Counter
+ * 08:08 NoMatchCntEn CPU Address Miss Counter Enable
+ * NOTE: Relevant only if multi-GT is enabled.
+ * (0: Disabled; 1: Enabled)
+ * 09:09 NoMatchCntExt CPU address miss counter MSB
+ * 10:10 Reserved
+ * 11:11 AACKDelay Address Acknowledge Delay
+ * 0: AACK* is asserted one cycle after TS*.
+ * 1: AACK* is asserted two cycles after TS*.
+ * 12:12 Endianess Must be 0
+ * NOTE: The GT64260 does not support the PowerPC
+ * Little Endian convention
+ * 13:13 Pipeline Pipeline Enable
+ * 0: Disabled. The GT64260 will not respond with
+ * AACK* to a new CPU transaction, before the
+ * previous transaction data phase completes.
+ * 1: Enabled.
+ * 14:14 Reserved
+ * 15:15 TADelay Transfer Acknowledge Delay
+ * 0: TA* is asserted one cycle after AACK*
+ * 1: TA* is asserted two cycles after AACK*
+ * 16:16 RdOOO Read Out of Order Completion
+ * 0: Not Supported, Data is always returned in
+ * order (DTI[0-2] is always driven
+ * 1: Supported
+ * 17:17 StopRetry Relevant only if PCI Retry is enabled
+ * 0: Keep Retry all PCI transactions targeted
+ * to the GT64260.
+ * 1: Stop Retry of PCI transactions.
+ * 18:18 MultiGTDec Multi-GT Address Decode
+ * 0: Normal address decoding
+ * 1: Multi-GT address decoding
+ * 19:19 DPValid CPU DP[0-7] Connection. CPU write parity ...
+ * 0: is not checked. (Not connected)
+ * 1: is checked (Connected)
+ * 21:20 Reserved
+ * 22:22 PErrProp Parity Error Propagation
+ * 0: GT64260 always drives good parity on
+ * DP[0-7] during CPU reads.
+ * 1: GT64260 drives bad parity on DP[0-7] in case
+ * the read response from the target interface
+ * comes with erroneous data indication
+ * (e.g. ECC error from SDRAM interface).
+ * 25:23 Reserved
+ * 26:26 APValid CPU AP[0-3] Connection. CPU address parity ...
+ * 0: is not checked. (Not connected)
+ * 1: is checked (Connected)
+ * 27:27 RemapWrDis Address Remap Registers Write Control
+ * 0: Write to Low Address decode register.
+ * Results in writing of the corresponding
+ * Remap register.
+ * 1: Write to Low Address decode register. No
+ * affect on the corresponding Remap register.
+ * 28:28 ConfSBDis Configuration Read Sync Barrier Disable
+ * 0: enabled; 1: disabled
+ * 29:29 IOSBDis I/O Read Sync Barrier Disable
+ * 0: enabled; 1: disabled
+ * 30:30 ClkSync Clocks Synchronization
+ * 0: The CPU interface is running with SysClk,
+ * which is asynchronous to TClk.
+ * 1: The CPU interface is running with TClk.
+ * 31:31 Reserved
+ */
+#define GT_CPUCfg_NoMatchCnt_GET(v) GT__EXT((v), 0, 8)
+#define GT_CPUCfg_NoMatchCntEn GT__BIT( 9)
+#define GT_CPUCfg_NoMatchCntExt GT__BIT(10)
+#define GT_CPUCfg_AACKDelay GT__BIT(11)
+#define GT_CPUCfg_Endianess GT__BIT(12)
+#define GT_CPUCfg_Pipeline GT__BIT(13)
+#define GT_CPUCfg_TADelay GT__BIT(15)
+#define GT_CPUCfg_RdOOO GT__BIT(16)
+#define GT_CPUCfg_StopRetry GT__BIT(17)
+#define GT_CPUCfg_MultiGTDec GT__BIT(18)
+#define GT_CPUCfg_DPValid GT__BIT(19)
+#define GT_CPUCfg_PErrProp GT__BIT(22)
+#define GT_CPUCfg_APValid GT__BIT(26)
+#define GT_CPUCfg_RemapWrDis GT__BIT(27)
+#define GT_CPUCfg_ConfSBDis GT__BIT(28)
+#define GT_CPUCfg_IOSBDis GT__BIT(29)
+#define GT_CPUCfg_ClkSync GT__BIT(30)
+
+/*
+ * Table 98: CPU Mode, Offset: 0x120, Read only
+ * 01:00 MultiGTID Multi-GT ID
+ * Represents the ID to which the GT64260 responds
+ * to during a multi-GT address decoding period.
+ * 02:02 MultiGT (0: Single; 1: Multiple) GT configuration
+ * 03:03 RetryEn (0: Don't; 1: Do) Retry PCI transactions
+ * 07:04 CPUType
+ * 0x0-0x3: Reserved
+ * 0x4: 64-bit PowerPC CPU, 60x bus
+ * 0x5: 64-bit PowerPC CPU, MPX bus
+ * 0x6-0xf: Reserved
+ * 31:08 Reserved
+ */
+#define GT_CPUMode_MultiGTID_GET(v) GT__EXT(v, 0, 2)
+#define GT_CPUMode_MultiGT GT__BIT(2)
+#define GT_CPUMode_RetryEn GT__BIT(3)
+#define GT_CPUMode_CPUType_GET(v) GT__EXT(v, 4, 4)
+
+/*
+ * Table 99: CPU Master Control, Offset: 0x160
+ * 07:00 Reserved
+ * 08:08 IntArb CPU Bus Internal Arbiter Enable
+ * NOTE: Only relevant to 60x bus mode. When
+ * running MPX bus, the GT64260 internal
+ * arbiter must be used.
+ * 0: Disabled. External arbiter is required.
+ * 1: Enabled. Use the GT64260 CPU bus arbiter.
+ * 09:09 IntBusCtl CPU Interface Unit Internal Bus Control
+ * NOTE: This bit must be set to 1. It is reserved
+ * for Galileo Technology usage.
+ * 0: Enable internal bus sharing between master
+ * and slave interfaces.
+ * 1: Disable internal bus sharing between master
+ * and slave interfaces.
+ * 10:10 MWrTrig Master Write Transaction Trigger
+ * 0: With first valid write data
+ * 1: With last valid write data
+ * 11:11 MRdTrig Master Read Response Trigger
+ * 0: With first valid read data
+ * 1: With last valid read data
+ * 12:12 CleanBlock Clean Block Snoop Transaction Support
+ * 0: CPU does not support clean block (603e,750)
+ * 1: CPU supports clean block (604e,G4)
+ * 13:13 FlushBlock Flush Block Snoop Transaction Support
+ * 0: CPU does not support flush block (603e,750)
+ * 1: CPU supports flush block (604e,G4)
+ * 31:14 Reserved
+ */
+#define GT_CPUMstrCtl_IntArb GT__BIT(8)
+#define GT_CPUMstrCtl_IntBusCtl GT__BIT(9)
+#define GT_CPUMstrCtl_MWrTrig GT__BIT(10)
+#define GT_CPUMstrCtl_MRdTrig GT__BIT(11)
+#define GT_CPUMstrCtl_CleanBlock GT__BIT(12)
+#define GT_CPUMstrCtl_FlushBlock GT__BIT(13)
+
+#define GT_ArbSlice_SDRAM 0x0 /* SDRAM interface snoop request */
+#define GT_ArbSlice_DEVICE 0x1 /* Device request */
+#define GT_ArbSlice_NULL 0x2 /* NULL request */
+#define GT_ArbSlice_PCI0 0x3 /* PCI_0 access */
+#define GT_ArbSlice_PCI1 0x4 /* PCI_1 access */
+#define GT_ArbSlice_COMM 0x5 /* Comm unit access */
+#define GT_ArbSlice_IDMA0123 0x6 /* IDMA channels 0/1/2/3 access */
+#define GT_ArbSlice_IDMA4567 0x7 /* IDMA channels 4/5/6/7 access */
+ /* 0x8-0xf: Reserved */
+
+/* Pass in the slice number (from 0..16) as 'n'
+ */
+#define GT_XbarCtl_GET_ArbSlice(v, n) GT__EXT((v), (((n) & 7)*4, 4)
+
+/*
+ * Table 100: CPU Interface Crossbar Control Low, Offset: 0x150
+ * 03:00 Arb0 Slice 0 of CPU Master pizza Arbiter
+ * 07:04 Arb1 Slice 1 of CPU Master pizza Arbiter
+ * 11:08 Arb2 Slice 2 of CPU Master pizza Arbiter
+ * 15:12 Arb3 Slice 3 of CPU Master pizza Arbiter
+ * 19:16 Arb4 Slice 4 of CPU Master pizza Arbiter
+ * 23:20 Arb5 Slice 5 of CPU Master pizza Arbiter
+ * 27:24 Arb6 Slice 6 of CPU Master pizza Arbiter
+ * 31:28 Arb7 Slice 7 of CPU Master pizza Arbiter
+ */
+
+/*
+ * Table 101: CPU Interface Crossbar Control High, Offset: 0x158
+ * 03:00 Arb8 Slice 8 of CPU Master pizza Arbiter
+ * 07:04 Arb9 Slice 9 of CPU Master pizza Arbiter
+ * 11:08 Arb10 Slice 10 of CPU Master pizza Arbiter
+ * 15:12 Arb11 Slice 11 of CPU Master pizza Arbiter
+ * 19:16 Arb12 Slice 12 of CPU Master pizza Arbiter
+ * 23:20 Arb13 Slice 13 of CPU Master pizza Arbiter
+ * 27:24 Arb14 Slice 14 of CPU Master pizza Arbiter
+ * 31:28 Arb15 Slice 15 of CPU Master pizza Arbiter
+ */
+
+/*
+ * Table 102: CPU Interface Crossbar Timeout, Offset: 0x168
+ * NOTE: Reserved for Galileo Technology usage.
+ * 07:00 Timeout Crossbar Arbiter Timeout Preset Value
+ * 15:08 Reserved
+ * 16:16 TimeoutEn Crossbar Arbiter Timer Enable
+ * (0: Enable; 1: Disable)
+ * 31:17 Reserved
+ */
+
+/*
+ * Table 103: CPU Read Response Crossbar Control Low, Offset: 0x170
+ * 03:00 Arb0 Slice 0 of CPU Slave pizza Arbiter
+ * 07:04 Arb1 Slice 1 of CPU Slave pizza Arbiter
+ * 11:08 Arb2 Slice 2 of CPU Slave pizza Arbiter
+ * 15:12 Arb3 Slice 3 of CPU Slave pizza Arbiter
+ * 19:16 Arb4 Slice 4 of CPU Slave pizza Arbiter
+ * 23:20 Arb5 Slice 5 of CPU Slave pizza Arbiter
+ * 27:24 Arb6 Slice 6 of CPU Slave pizza Arbiter
+ * 31:28 Arb7 Slice 7 of CPU Slave pizza Arbiter
+ */
+/*
+ * Table 104: CPU Read Response Crossbar Control High, Offset: 0x178
+ * 03:00 Arb8 Slice 8 of CPU Slave pizza Arbiter
+ * 07:04 Arb9 Slice 9 of CPU Slave pizza Arbiter
+ * 11:08 Arb10 Slice 10 of CPU Slave pizza Arbiter
+ * 15:12 Arb11 Slice 11 of CPU Slave pizza Arbiter
+ * 19:16 Arb12 Slice 12 of CPU Slave pizza Arbiter
+ * 23:20 Arb13 Slice 13 of CPU Slave pizza Arbiter
+ * 27:24 Arb14 Slice 14 of CPU Slave pizza Arbiter
+ * 31:28 Arb15 Slice 15 of CPU Slave pizza Arbiter
+ */
+
+/*
+ * Table 105: PCI_0 Sync Barrier Virtual Register, Offset: 0x0c0
+ * Table 106: PCI_1 Sync Barrier Virtual Register, Offset: 0x0c8
+ * NOTE: The read data is random and should be ignored.
+ * 31:00 SyncBarrier A CPU read from this register creates a
+ * synchronization barrier cycle.
+ */
+
+/*
+ * Table 107: CPU Protect Address 0 Low, Offset: 0x180
+ * Table 109: CPU Protect Address 1 Low, Offset: 0x190
+ * Table 111: CPU Protect Address 2 Low, Offset: 0x1a0
+ * Table 113: CPU Protect Address 3 Low, Offset: 0x1b0
+ * Table 115: CPU Protect Address 4 Low, Offset: 0x1c0
+ * Table 117: CPU Protect Address 5 Low, Offset: 0x1d0
+ * Table 119: CPU Protect Address 6 Low, Offset: 0x1e0
+ * Table 121: CPU Protect Address 7 Low, Offset: 0x1f0
+ *
+ * 11:00 LowAddr CPU Protect Region Base Address
+ * Corresponds to address bits[31:20].
+ * 15:12 Reserved. Must be 0
+ * 16:16 AccProtect CPU Access Protect
+ * Access is (0: allowed; 1: forbidden)
+ * 17:17 WrProtect CPU Write Protect
+ * Writes are (0: allowed; 1: forbidden)
+ * 18:18 CacheProtect CPU caching protect. Caching (block read)
+ * is (0: allowed; 1: forbidden)
+ * 31:19 Reserved
+ */
+#define GT_CPU_AccProtect GT__BIT(16)
+#define GT_CPU_WrProtect GT__BIT(17)
+#define GT_CPU_CacheProtect GT__BIT(18)
+
+/*
+ * Table 108: CPU Protect Address 0 High, Offset: 0x188
+ * Table 110: CPU Protect Address 1 High, Offset: 0x198
+ * Table 112: CPU Protect Address 2 High, Offset: 0x1a8
+ * Table 114: CPU Protect Address 3 High, Offset: 0x1b8
+ * Table 116: CPU Protect Address 4 High, Offset: 0x1c8
+ * Table 118: CPU Protect Address 5 High, Offset: 0x1d8
+ * Table 120: CPU Protect Address 6 High, Offset: 0x1e8
+ * Table 122: CPU Protect Address 7 High, Offset: 0x1f8
+ *
+ * 11:00 HighAddr CPU Protect Region Top Address
+ * Corresponds to address bits[31:20]
+ * 31:12 Reserved
+ */
+
+/*
+ * Table 123: Snoop Base Address 0, Offset: 0x380
+ * Table 125: Snoop Base Address 1, Offset: 0x390
+ * Table 127: Snoop Base Address 2, Offset: 0x3a0
+ * Table 129: Snoop Base Address 3, Offset: 0x3b0
+ *
+ * 11:00 LowAddr Snoop Region Base Address [31:20]
+ * 15:12 Reserved Must be 0.
+ * 17:16 Snoop Snoop Type
+ * 0x0: No Snoop
+ * 0x1: Snoop to WT region
+ * 0x2: Snoop to WB region
+ * 0x3: Reserved
+ * 31:18 Reserved
+ */
+#define GT_Snoop_GET(v) GT__EXT((v), 16, 2)
+#define GT_Snoop_INS(v) GT__INS((v), 16)
+#define GT_Snoop_None 0
+#define GT_Snoop_WT 1
+#define GT_Snoop_WB 2
+
+
+/*
+ * Table 124: Snoop Top Address 0, Offset: 0x388
+ * Table 126: Snoop Top Address 1, Offset: 0x398
+ * Table 128: Snoop Top Address 2, Offset: 0x3a8
+ * Table 130: Snoop Top Address 3, Offset: 0x3b8
+ * 11:00 HighAddr Snoop Region Top Address [31:20]
+ * 31:12 Reserved
+ */
+
+
+/*
+ * Table 131: CPU Error Address Low, Offset: 0x070, Read Only.
+ * In case of multiple errors, only the first one is latched. New error
+ * report latching is enabled only after the CPU Error Address Low register
+ * is being read.
+ * 31:00 ErrAddr Latched address bits [31:0] of a CPU
+ * transaction in case of:
+ * o illegal address (failed address decoding)
+ * o access protection violation
+ * o bad data parity
+ * o bad address parity
+ * Upon address latch, no new address are
+ * registered (due to additional error condition),
+ * until the register is being read.
+ */
+
+/*
+ * Table 132: CPU Error Address High, Offset: 0x078, Read Only.
+ * Once data is latched, no new data can be registered (due to additional
+ * error condition), until CPU Error Low Address is being read (which
+ * implies, it should be the last being read by the interrupt handler).
+ * 03:00 Reserved
+ * 07:04 ErrPar Latched address parity bits in case
+ * of bad CPU address parity detection.
+ * 31:08 Reserved
+ */
+#define GT_CPUErrorAddrHigh_ErrPar_GET(v) GT__EXT((v), 4, 4)
+
+/*
+ * Table 133: CPU Error Data Low, Offset: 0x128, Read only.
+ * 31:00 PErrData Latched data bits [31:0] in case of bad data
+ * parity sampled on write transactions or on
+ * master read transactions.
+ */
+
+/*
+ * Table 134: CPU Error Data High, Offset: 0x130, Read only.
+ * 31:00 PErrData Latched data bits [63:32] in case of bad data
+ * parity sampled on write transactions or on
+ * master read transactions.
+ */
+
+/*
+ * Table 135: CPU Error Parity, Offset: 0x138, Read only.
+ * 07:00 PErrPar Latched data parity bus in case of bad data
+ * parity sampled on write transactions or on
+ * master read transactions.
+ * 31:10 Reserved
+ */
+#define GT_CPUErrorParity_PErrPar_GET(v) GT__EXT((v), 0, 8)
+
+/*
+ * Table 136: CPU Error Cause, Offset: 0x140
+ * Bits[7:0] are clear only. A cause bit is set upon an error condition
+ * occurrence. Write a 0 value to clear the bit. Writing a 1 value has
+ * no affect.
+ * 00:00 AddrOut CPU Address Out of Range
+ * 01:01 AddrPErr Bad Address Parity Detected
+ * 02:02 TTErr Transfer Type Violation.
+ * The CPU attempts to burst (read or write) to an
+ * internal register.
+ * 03:03 AccErr Access to a Protected Region
+ * 04:04 WrErr Write to a Write Protected Region
+ * 05:05 CacheErr Read from a Caching protected region
+ * 06:06 WrDataPErr Bad Write Data Parity Detected
+ * 07:07 RdDataPErr Bad Read Data Parity Detected
+ * 26:08 Reserved
+ * 31:27 Sel Specifies the error event currently being
+ * reported in Error Address, Error Data, and
+ * Error Parity registers.
+ * 0x0: AddrOut
+ * 0x1: AddrPErr
+ * 0x2: TTErr
+ * 0x3: AccErr
+ * 0x4: WrErr
+ * 0x5: CacheErr
+ * 0x6: WrDataPErr
+ * 0x7: RdDataPErr
+ * 0x8-0x1f: Reserved
+ */
+#define GT_CPUError_AddrOut GT__BIT(GT_CPUError_Sel_AddrOut)
+#define GT_CPUError_AddrPErr GT__BIT(GT_CPUError_Sel_AddrPErr)
+#define GT_CPUError_TTErr GT__BIT(GT_CPUError_Sel_TTErr)
+#define GT_CPUError_AccErr GT__BIT(GT_CPUError_Sel_AccErr)
+#define GT_CPUError_WrErr GT__BIT(GT_CPUError_Sel_WrPErr)
+#define GT_CPUError_CacheErr GT__BIT(GT_CPUError_Sel_CachePErr)
+#define GT_CPUError_WrDataPErr GT__BIT(GT_CPUError_Sel_WrDataPErr)
+#define GT_CPUError_RdDataPErr GT__BIT(GT_CPUError_Sel_RdDataPErr)
+
+#define GT_CPUError_Sel_AddrOut 0
+#define GT_CPUError_Sel_AddrPErr 1
+#define GT_CPUError_Sel_TTErr 2
+#define GT_CPUError_Sel_AccErr 3
+#define GT_CPUError_Sel_WrErr 4
+#define GT_CPUError_Sel_CacheErr 5
+#define GT_CPUError_Sel_WrDataPErr 6
+#define GT_CPUError_Sel_RdDataPErr 7
+
+#define GT_CPUError_Sel_GET(v) GT__EXT((v), 27, 5)
+
+/*
+ * Table 137: CPU Error Mask, Offset: 0x148
+ * 00:00 AddrOut If set to 1, enables AddrOut interrupt.
+ * 01:01 AddrPErr If set to 1, enables AddrPErr interrupt.
+ * 02:02 TTErr If set to 1, enables TTErr interrupt.
+ * 03:03 AccErr If set to 1, enables AccErr interrupt.
+ * 04:04 WrErr If set to 1, enables WrErr interrupt.
+ * 05:05 CacheErr If set to 1, enables CacheErr interrupt.
+ * 06:06 WrDataPErr If set to 1, enables WrDataPErr interrupt.
+ * 07:07 RdDataPErr If set to 1, enables RdDataPErr interrupt.
+ * 31:08 Reserved
+ */
+
+/* Comm Unit Arbiter Control */
+#define GT_CommUnitArb_Ctrl 0xf300 /*<skf>*/
+/*
+ * Comm Unit Interrupt registers
+ */
+#define GT_CommUnitIntr_Cause 0xf310
+#define GT_CommUnitIntr_Mask 0xf314
+#define GT_CommUnitIntr_ErrAddr 0xf318
+
+#define GT_CommUnitIntr_E0 0x00000007
+#define GT_CommUnitIntr_E1 0x00000070
+#define GT_CommUnitIntr_E2 0x00000700
+#define GT_CommUnitIntr_S0 0x00070000
+#define GT_CommUnitIntr_S1 0x00700000
+#define GT_CommUnitIntr_Sel 0x70000000
+
+/*
+ * SDRAM Error Report (ECC) Registers
+ */
+#define GT_ECC_Data_Lo 0x484 /* latched Error Data (low) */
+#define GT_ECC_Data_Hi 0x480 /* latched Error Data (high) */
+#define GT_ECC_Addr 0x490 /* latched Error Address */
+#define GT_ECC_Rec 0x488 /* latched ECC code from SDRAM */
+#define GT_ECC_Calc 0x48c /* latched ECC code from SDRAM */
+#define GT_ECC_Ctl 0x494 /* ECC Control */
+#define GT_ECC_Count 0x498 /* ECC 1-bit error count */
+
+/*
+ * Watchdog Registers
+ */
+#define GT_WDOG_Config 0xb410
+#define GT_WDOG_Value 0xb414
+#define GT_WDOG_Value_NMI GT__MASK(24)
+#define GT_WDOG_Config_Preset GT__MASK(24)
+#define GT_WDOG_Config_Ctl1a GT__BIT(24)
+#define GT_WDOG_Config_Ctl1b GT__BIT(25)
+#define GT_WDOG_Config_Ctl2a GT__BIT(26)
+#define GT_WDOG_Config_Ctl2b GT__BIT(27)
+#define GT_WDOG_Config_Enb GT__BIT(31)
+
+#define GT_WDOG_NMI_DFLT (GT__MASK(24) & GT_WDOG_Value_NMI)
+#define GT_WDOG_Preset_DFLT (GT__MASK(22) & GT_WDOG_Config_Preset)
+
+/*
+ * Device Bus Interrupts
+ */
+#define GT_DEVBUS_ICAUSE 0x4d0 /* Device Interrupt Cause */
+#define GT_DEVBUS_IMASK 0x4d4 /* Device Interrupt Mask */
+#define GT_DEVBUS_ERR_ADDR 0x4d8 /* Device Error Address */
+
+/*
+ * bit defines for GT_DEVBUS_ICAUSE, GT_DEVBUS_IMASK
+ */
+#define GT_DEVBUS_DBurstErr GT__BIT(0)
+#define GT_DEVBUS_DRdyErr GT__BIT(1)
+#define GT_DEVBUS_Sel GT__BIT(27)
+#define GT_DEVBUS_RES ~(GT_DEVBUS_DBurstErr|GT_DEVBUS_DRdyErr|GT_DEVBUS_Sel)
+
+/* TWSI Interface - TWSI Interface Registers <skf> */
+#define TWSI_SLV_ADDR 0xc000
+#define TWSI_EXT_SLV_ADDR 0xc010
+#define TWSI_DATA 0xc004
+#define TWSI_CTRL 0xc008
+#define TWSI_STATUS 0xc00c
+#define TWSI_BAUDE_RATE 0xc00c
+#define TWSI_SFT_RST 0xc01c
+
+/* Section 25.2 : Table 734 <skf> */
+
+#define GT64260_MAIN_INT_CAUSE_LO 0xc18 /* read Only */
+#define GT64260_MAIN_INT_CAUSE_HI 0xc68 /* read Only */
+#define GT64260_CPU_INT_MASK_LO 0xc1c
+#define GT64260_CPU_INT_MASK_HI 0xc6c
+#define GT64260_CPU_SEL_CAUSE 0xc70 /* read Only */
+#define GT_PCI0_INT_MASK_LO 0xc24
+#define GT_PCI0_INT_MASK_HI 0xc64
+#define GT_PCI0_SEL_CAUSE 0xc74 /* read Only */
+#define GT_PCI1_INT_MASK_LO 0xca4
+#define GT_PCI1_INT_MASK_HI 0xce4
+#define GT_PCI1_SEL_CAUSE 0xcf4 /* read Only */
+#define GT_CPU_INT0_MASK 0xe60
+#define GT_CPU_INT1_MASK 0xe64
+#define GT_CPU_INT2_MASK 0xe68
+#define GT_CPU_INT3_MASK 0xe6c
+
+#endif /* !_DISCOVERY_DEV_GTREG_H */
diff --git a/bsps/powerpc/mvme5500/include/bsp/if_wmreg.h b/bsps/powerpc/mvme5500/include/bsp/if_wmreg.h
new file mode 100644
index 0000000000..3e21c62581
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/if_wmreg.h
@@ -0,0 +1,740 @@
+/* $NetBSD: if_wmreg.h,v 1.22 2007/04/29 20:35:21 bouyer Exp $ */
+
+/*
+ * Copyright (c) 2001 Wasabi Systems, Inc.
+ * All rights reserved.
+ *
+ * Written by Jason R. Thorpe for Wasabi Systems, Inc.
+ * Some are added by Shuchen Kate Feng <feng1@bnl.gov>,
+ * NSLS, Brookhaven National Laboratory. All rights reserved.
+ * under the Deaprtment of Energy contract DE-AC02-98CH10886
+ *
+ * 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
+ * Wasabi Systems, Inc.
+ * 4. 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 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 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.
+ */
+
+/*
+ * Register description for the Intel i82542 (``Wiseman''),
+ * i82543 (``Livengood''), and i82544 (``Cordova'') Gigabit
+ * Ethernet chips.
+ */
+
+/*
+ * The wiseman supports 64-bit PCI addressing. This structure
+ * describes the address in descriptors.
+ */
+typedef struct wiseman_addr {
+ uint32_t wa_low; /* low-order 32 bits */
+ uint32_t wa_high; /* high-order 32 bits */
+} __attribute__((__packed__)) wiseman_addr_t;
+
+/*
+ * The Wiseman receive descriptor.
+ *
+ * The receive descriptor ring must be aligned to a 4K boundary,
+ * and there must be an even multiple of 8 descriptors in the ring.
+ */
+typedef volatile struct wiseman_rxdesc {
+ wiseman_addr_t wrx_addr; /* buffer address */
+
+ uint16_t wrx_len; /* buffer length */
+ uint16_t wrx_cksum; /* checksum (starting at PCSS) */
+
+ uint8_t wrx_status; /* Rx status */
+ uint8_t wrx_errors; /* Rx errors */
+ uint16_t wrx_special; /* special field (VLAN, etc.) */
+} __attribute__((__packed__)) wiseman_rxdesc_t;
+
+/* wrx_status bits */
+#define WRX_ST_DD (1U << 0) /* descriptor done */
+#define WRX_ST_EOP (1U << 1) /* end of packet */
+#define WRX_ST_IXSM (1U << 2) /* ignore checksum indication */
+#define WRX_ST_VP (1U << 3) /* VLAN packet */
+#define WRX_ST_BPDU (1U << 4) /* ??? */
+#define WRX_ST_TCPCS (1U << 5) /* TCP checksum performed */
+#define WRX_ST_IPCS (1U << 6) /* IP checksum performed */
+#define WRX_ST_PIF (1U << 7) /* passed in-exact filter */
+
+/* wrx_error bits */
+#define WRX_ER_CE (1U << 0) /* CRC error */
+#define WRX_ER_SE (1U << 1) /* symbol error */
+#define WRX_ER_SEQ (1U << 2) /* sequence error */
+#define WRX_ER_ICE (1U << 3) /* ??? */
+#define WRX_ER_CXE (1U << 4) /* carrier extension error */
+#define WRX_ER_TCPE (1U << 5) /* TCP checksum error */
+#define WRX_ER_IPE (1U << 6) /* IP checksum error */
+#define WRX_ER_RXE (1U << 7) /* Rx data error */
+
+/* wrx_special field for VLAN packets */
+#define WRX_VLAN_ID(x) ((x) & 0x0fff) /* VLAN identifier */
+#define WRX_VLAN_CFI (1U << 12) /* Canonical Form Indicator */
+#define WRX_VLAN_PRI(x) (((x) >> 13) & 7)/* VLAN priority field */
+
+/*
+ * The Wiseman transmit descriptor.
+ *
+ * The transmit descriptor ring must be aligned to a 4K boundary,
+ * and there must be an even multiple of 8 descriptors in the ring.
+ */
+typedef struct wiseman_tx_fields {
+ uint8_t wtxu_status; /* Tx status */
+ uint8_t wtxu_options; /* options */
+ uint16_t wtxu_vlan; /* VLAN info */
+} __attribute__((__packed__)) wiseman_txfields_t;
+typedef volatile struct wiseman_txdesc {
+ wiseman_addr_t wtx_addr; /* buffer address */
+ uint32_t wtx_cmdlen; /* command and length */
+ wiseman_txfields_t wtx_fields; /* fields; see below */
+} __attribute__((__packed__)) wiseman_txdesc_t;
+
+/* Commands for wtx_cmdlen */
+#define WTX_CMD_EOP (1U << 24) /* end of packet */
+#define WTX_CMD_IFCS (1U << 25) /* insert FCS */
+#define WTX_CMD_RS (1U << 27) /* report status */
+#define WTX_CMD_RPS (1U << 28) /* report packet sent */
+#define WTX_CMD_DEXT (1U << 29) /* descriptor extension */
+#define WTX_CMD_VLE (1U << 30) /* VLAN enable */
+#define WTX_CMD_IDE (1U << 31) /* interrupt delay enable */
+
+/* Descriptor types (if DEXT is set) */
+#define WTX_DTYP_C (0U << 20) /* context */
+#define WTX_DTYP_D (1U << 20) /* data */
+
+/* wtx_fields status bits */
+#define WTX_ST_DD (1U << 0) /* descriptor done */
+#define WTX_ST_EC (1U << 1) /* excessive collisions */
+#define WTX_ST_LC (1U << 2) /* late collision */
+#define WTX_ST_TU (1U << 3) /* transmit underrun */
+
+/* wtx_fields option bits for IP/TCP/UDP checksum offload */
+#define WTX_IXSM (1U << 0) /* IP checksum offload */
+#define WTX_TXSM (1U << 1) /* TCP/UDP checksum offload */
+
+/* Maximum payload per Tx descriptor */
+#define WTX_MAX_LEN 4096
+
+/*
+ * The Livengood TCP/IP context descriptor.
+ */
+struct livengood_tcpip_ctxdesc {
+ uint32_t tcpip_ipcs; /* IP checksum context */
+ uint32_t tcpip_tucs; /* TCP/UDP checksum context */
+ uint32_t tcpip_cmdlen;
+ uint32_t tcpip_seg; /* TCP segmentation context */
+};
+
+/* commands for context descriptors */
+#define WTX_TCPIP_CMD_TCP (1U << 24) /* 1 = TCP, 0 = UDP */
+#define WTX_TCPIP_CMD_IP (1U << 25) /* 1 = IPv4, 0 = IPv6 */
+#define WTX_TCPIP_CMD_TSE (1U << 26) /* segmentation context valid */
+
+#define WTX_TCPIP_IPCSS(x) ((x) << 0) /* checksum start */
+#define WTX_TCPIP_IPCSO(x) ((x) << 8) /* checksum value offset */
+#define WTX_TCPIP_IPCSE(x) ((x) << 16) /* checksum end */
+
+#define WTX_TCPIP_TUCSS(x) ((x) << 0) /* checksum start */
+#define WTX_TCPIP_TUCSO(x) ((x) << 8) /* checksum value offset */
+#define WTX_TCPIP_TUCSE(x) ((x) << 16) /* checksum end */
+
+#define WTX_TCPIP_SEG_STATUS(x) ((x) << 0)
+#define WTX_TCPIP_SEG_HDRLEN(x) ((x) << 8)
+#define WTX_TCPIP_SEG_MSS(x) ((x) << 16)
+
+/*
+ * PCI config registers used by the Wiseman.
+ */
+#define WM_PCI_MMBA PCI_MAPREG_START
+/* registers for FLASH access on ICH8 */
+#define WM_ICH8_FLASH 0x0014
+
+/*
+ * Wiseman Control/Status Registers.
+ */
+#define WMREG_CTRL 0x0000 /* Device Control Register */
+#define CTRL_FD (1U << 0) /* full duplex */
+#define CTRL_BEM (1U << 1) /* big-endian mode */
+#define CTRL_PRIOR (1U << 2) /* 0 = receive, 1 = fair */
+#define CTRL_LRST (1U << 3) /* link reset */
+#define CTRL_ASDE (1U << 5) /* auto speed detect enable */
+#define CTRL_SLU (1U << 6) /* set link up */
+#define CTRL_ILOS (1U << 7) /* invert loss of signal */
+#define CTRL_SPEED(x) ((x) << 8) /* speed (Livengood) */
+#define CTRL_SPEED_10 CTRL_SPEED(0)
+#define CTRL_SPEED_100 CTRL_SPEED(1)
+#define CTRL_SPEED_1000 CTRL_SPEED(2)
+#define CTRL_SPEED_MASK CTRL_SPEED(3)
+#define CTRL_FRCSPD (1U << 11) /* force speed (Livengood) */
+#define CTRL_FRCFDX (1U << 12) /* force full-duplex (Livengood) */
+#define CTRL_D_UD_EN (1U << 13) /* Dock/Undock enable */
+#define CTRL_D_UD_POL (1U << 14) /* Defined polarity of Dock/Undock indication in SDP[0] */
+#define CTRL_F_PHY_R (1U << 15) /* Reset both PHY ports, through PHYRST_N pin */
+#define CTRL_EXT_LINK_EN (1U << 16) /* enable link status from external LINK_0 and LINK_1 pins */
+#define CTRL_SWDPINS_SHIFT 18
+#define CTRL_SWDPINS_MASK 0x0f
+#define CTRL_SWDPIN(x) (1U << (CTRL_SWDPINS_SHIFT + (x)))
+#define CTRL_SWDPIO_SHIFT 22
+#define CTRL_SWDPIO_MASK 0x0f
+#define CTRL_SWDPIO(x) (1U << (CTRL_SWDPIO_SHIFT + (x)))
+#define CTRL_RST (1U << 26) /* device reset */
+#define CTRL_RFCE (1U << 27) /* Rx flow control enable */
+#define CTRL_TFCE (1U << 28) /* Tx flow control enable */
+#define CTRL_VME (1U << 30) /* VLAN Mode Enable */
+#define CTRL_PHY_RESET (1U << 31) /* PHY reset (Cordova) */
+
+#define WMREG_CTRL_SHADOW 0x0004 /* Device Control Register (shadow) */
+
+#define WMREG_STATUS 0x0008 /* Device Status Register */
+#define STATUS_FD (1U << 0) /* full duplex */
+#define STATUS_LU (1U << 1) /* link up */
+#define STATUS_TCKOK (1U << 2) /* Tx clock running */
+#define STATUS_RBCOK (1U << 3) /* Rx clock running */
+#define STATUS_FUNCID_SHIFT 2 /* 82546 function ID */
+#define STATUS_FUNCID_MASK 3 /* ... */
+#define STATUS_TXOFF (1U << 4) /* Tx paused */
+#define STATUS_TBIMODE (1U << 5) /* fiber mode (Livengood) */
+#define STATUS_SPEED(x) ((x) << 6) /* speed indication */
+#define STATUS_SPEED_10 STATUS_SPEED(0)
+#define STATUS_SPEED_100 STATUS_SPEED(1)
+#define STATUS_SPEED_1000 STATUS_SPEED(2)
+#define STATUS_ASDV(x) ((x) << 8) /* auto speed det. val. (Livengood) */
+#define STATUS_MTXCKOK (1U << 10) /* MTXD clock running */
+#define STATUS_PCI66 (1U << 11) /* 66MHz bus (Livengood) */
+#define STATUS_BUS64 (1U << 12) /* 64-bit bus (Livengood) */
+#define STATUS_PCIX_MODE (1U << 13) /* PCIX mode (Cordova) */
+#define STATUS_PCIXSPD(x) ((x) << 14) /* PCIX speed indication (Cordova) */
+#define STATUS_PCIXSPD_50_66 STATUS_PCIXSPD(0)
+#define STATUS_PCIXSPD_66_100 STATUS_PCIXSPD(1)
+#define STATUS_PCIXSPD_100_133 STATUS_PCIXSPD(2)
+#define STATUS_PCIXSPD_MASK STATUS_PCIXSPD(3)
+
+#define WMREG_EECD 0x0010 /* EEPROM Control Register */
+#define EECD_SK (1U << 0) /* clock */
+#define EECD_CS (1U << 1) /* chip select */
+#define EECD_DI (1U << 2) /* data in */
+#define EECD_DO (1U << 3) /* data out */
+#define EECD_FWE(x) ((x) << 4) /* flash write enable control */
+#define EECD_FWE_DISABLED EECD_FWE(1)
+#define EECD_FWE_ENABLED EECD_FWE(2)
+#define EECD_EE_REQ (1U << 6) /* (shared) EEPROM request */
+#define EECD_EE_GNT (1U << 7) /* (shared) EEPROM grant */
+#define EECD_EE_PRES (1U << 8) /* EEPROM present */
+#define EECD_EE_SIZE (1U << 9) /* EEPROM size
+ (0 = 64 word, 1 = 256 word) */
+#define EECD_EE_AUTORD (1U << 9) /* auto read done */
+#define EECD_EE_ABITS (1U << 10) /* EEPROM address bits
+ (based on type) */
+#define EECD_EE_TYPE (1U << 13) /* EEPROM type
+ (0 = Microwire, 1 = SPI) */
+#define EECD_SEC1VAL (1U << 22) /* Sector One Valid */
+
+#define UWIRE_OPC_ERASE 0x04 /* MicroWire "erase" opcode */
+#define UWIRE_OPC_WRITE 0x05 /* MicroWire "write" opcode */
+#define UWIRE_OPC_READ 0x06 /* MicroWire "read" opcode */
+
+#define SPI_OPC_WRITE 0x02 /* SPI "write" opcode */
+#define SPI_OPC_READ 0x03 /* SPI "read" opcode */
+#define SPI_OPC_A8 0x08 /* opcode bit 3 == address bit 8 */
+#define SPI_OPC_WREN 0x06 /* SPI "set write enable" opcode */
+#define SPI_OPC_WRDI 0x04 /* SPI "clear write enable" opcode */
+#define SPI_OPC_RDSR 0x05 /* SPI "read status" opcode */
+#define SPI_OPC_WRSR 0x01 /* SPI "write status" opcode */
+#define SPI_MAX_RETRIES 5000 /* max wait of 5ms for RDY signal */
+
+#define SPI_SR_RDY 0x01
+#define SPI_SR_WEN 0x02
+#define SPI_SR_BP0 0x04
+#define SPI_SR_BP1 0x08
+#define SPI_SR_WPEN 0x80
+
+#define EEPROM_OFF_MACADDR 0x00 /* MAC address offset */
+#define EEPROM_OFF_CFG1 0x0a /* config word 1 */
+#define EEPROM_OFF_CFG2 0x0f /* config word 2 */
+#define EEPROM_OFF_SWDPIN 0x20 /* SWD Pins (Cordova) */
+
+#define EEPROM_CFG1_LVDID (1U << 0)
+#define EEPROM_CFG1_LSSID (1U << 1)
+#define EEPROM_CFG1_PME_CLOCK (1U << 2)
+#define EEPROM_CFG1_PM (1U << 3)
+#define EEPROM_CFG1_ILOS (1U << 4)
+#define EEPROM_CFG1_SWDPIO_SHIFT 5
+#define EEPROM_CFG1_SWDPIO_MASK (0xf << EEPROM_CFG1_SWDPIO_SHIFT)
+#define EEPROM_CFG1_IPS1 (1U << 8)
+#define EEPROM_CFG1_LRST (1U << 9)
+#define EEPROM_CFG1_FD (1U << 10)
+#define EEPROM_CFG1_FRCSPD (1U << 11)
+#define EEPROM_CFG1_IPS0 (1U << 12)
+#define EEPROM_CFG1_64_32_BAR (1U << 13)
+
+#define EEPROM_CFG2_CSR_RD_SPLIT (1U << 1)
+#define EEPROM_CFG2_APM_EN (1U << 2)
+#define EEPROM_CFG2_64_BIT (1U << 3)
+#define EEPROM_CFG2_MAX_READ (1U << 4)
+#define EEPROM_CFG2_DMCR_MAP (1U << 5)
+#define EEPROM_CFG2_133_CAP (1U << 6)
+#define EEPROM_CFG2_MSI_DIS (1U << 7)
+#define EEPROM_CFG2_FLASH_DIS (1U << 8)
+#define EEPROM_CFG2_FLASH_SIZE(x) (((x) & 3) >> 9)
+#define EEPROM_CFG2_ANE (1U << 11)
+#define EEPROM_CFG2_PAUSE(x) (((x) & 3) >> 12)
+#define EEPROM_CFG2_ASDE (1U << 14)
+#define EEPROM_CFG2_APM_PME (1U << 15)
+#define EEPROM_CFG2_SWDPIO_SHIFT 4
+#define EEPROM_CFG2_SWDPIO_MASK (0xf << EEPROM_CFG2_SWDPIO_SHIFT)
+
+#define EEPROM_SWDPIN_MASK 0xdf
+#define EEPROM_SWDPIN_SWDPIN_SHIFT 0
+#define EEPROM_SWDPIN_SWDPIO_SHIFT 8
+
+#define WMREG_EERD 0x0014 /* EEPROM read */
+#define EERD_DONE 0x02 /* done bit */
+#define EERD_START 0x01 /* First bit for telling part to start operation */
+#define EERD_ADDR_SHIFT 2 /* Shift to the address bits */
+#define EERD_DATA_SHIFT 16 /* Offset to data in EEPROM read/write registers */
+
+#define WMREG_CTRL_EXT 0x0018 /* Extended Device Control Register */
+#define CTRL_EXT_GPI_EN(x) (1U << (x)) /* gpin interrupt enable */
+#define CTRL_EXT_SWDPINS_SHIFT 4
+#define CTRL_EXT_SWDPINS_MASK 0x0d
+#define CTRL_EXT_SWDPIN(x) (1U << (CTRL_EXT_SWDPINS_SHIFT + (x) - 4))
+#define CTRL_EXT_SWDPIO_SHIFT 8
+#define CTRL_EXT_SWDPIO_MASK 0x0d
+#define CTRL_EXT_SWDPIO(x) (1U << (CTRL_EXT_SWDPIO_SHIFT + (x) - 4))
+#define CTRL_EXT_ASDCHK (1U << 12) /* ASD check */
+#define CTRL_EXT_EE_RST (1U << 13) /* EEPROM reset */
+#define CTRL_EXT_IPS (1U << 14) /* invert power state bit 0 */
+#define CTRL_EXT_SPD_BYPS (1U << 15) /* speed select bypass */
+#define CTRL_EXT_IPS1 (1U << 16) /* invert power state bit 1 */
+#define CTRL_EXT_RO_DIS (1U << 17) /* relaxed ordering disabled */
+#define CTRL_EXT_LINK_MODE_MASK 0x00C00000
+#define CTRL_EXT_LINK_MODE_GMII 0x00000000
+#define CTRL_EXT_LINK_MODE_TBI 0x00C00000
+#define CTRL_EXT_LINK_MODE_KMRN 0x00000000
+#define CTRL_EXT_LINK_MODE_SERDES 0x00C00000
+
+
+#define WMREG_MDIC 0x0020 /* MDI Control Register */
+#define MDIC_DATA(x) ((x) & 0xffff)
+#define MDIC_REGADD(x) ((x) << 16)
+#define MDIC_PHYADD(x) ((x) << 21)
+#define MDIC_OP_WRITE (1U << 26)
+#define MDIC_OP_READ (2U << 26)
+#define MDIC_READY (1U << 28)
+#define MDIC_I (1U << 29) /* interrupt on MDI complete */
+#define MDIC_E (1U << 30) /* MDI error */
+
+#define WMREG_FCAL 0x0028 /* Flow Control Address Low */
+#define FCAL_CONST 0x00c28001 /* Flow Control MAC addr low */
+
+#define WMREG_FCAH 0x002c /* Flow Control Address High */
+#define FCAH_CONST 0x00000100 /* Flow Control MAC addr high */
+
+#define WMREG_FCT 0x0030 /* Flow Control Type */
+
+#define WMREG_VET 0x0038 /* VLAN Ethertype */
+
+#define WMREG_RAL_BASE 0x0040 /* Receive Address List */
+#define WMREG_CORDOVA_RAL_BASE 0x5400
+#define WMREG_RAL_LO(b, x) ((b) + ((x) << 3))
+#define WMREG_RAL_HI(b, x) (WMREG_RAL_LO(b, x) + 4)
+ /*
+ * Receive Address List: The LO part is the low-order 32-bits
+ * of the MAC address. The HI part is the high-order 16-bits
+ * along with a few control bits.
+ */
+#define RAL_AS(x) ((x) << 16) /* address select */
+#define RAL_AS_DEST RAL_AS(0) /* (cordova?) */
+#define RAL_AS_SOURCE RAL_AS(1) /* (cordova?) */
+#define RAL_RDR1 (1U << 30) /* put packet in alt. rx ring */
+#define RAL_AV (1U << 31) /* entry is valid */
+
+#define WM_RAL_TABSIZE 16
+#define WM_ICH8_RAL_TABSIZE 7
+
+#define WMREG_ICR 0x00c0 /* Interrupt Cause Register */
+#define ICR_TXDW (1U << 0) /* Tx desc written back */
+#define ICR_TXQE (1U << 1) /* Tx queue empty */
+#define ICR_LSC (1U << 2) /* link status change */
+#define ICR_RXSEQ (1U << 3) /* receive sequence error */
+#define ICR_RXDMT0 (1U << 4) /* Rx ring 0 nearly empty */
+#define ICR_RXO (1U << 6) /* Rx overrun */
+#define ICR_RXT0 (1U << 7) /* Rx ring 0 timer */
+#define ICR_MDAC (1U << 9) /* MDIO access complete */
+#define ICR_RXCFG (1U << 10) /* Receiving /C/ */
+#define ICR_GPI(x) (1U << (x)) /* general purpose interrupts */
+#define ICR_INT (1U << 31) /* device generated an interrupt */
+
+#define WMREG_ITR 0x00c4 /* Interrupt Throttling Register */
+#define ITR_IVAL_MASK 0xffff /* Interval mask */
+#define ITR_IVAL_SHIFT 0 /* Interval shift */
+
+#define WMREG_ICS 0x00c8 /* Interrupt Cause Set Register */
+ /* See ICR bits. */
+
+#define WMREG_IMS 0x00d0 /* Interrupt Mask Set Register */
+ /* See ICR bits. */
+
+#define WMREG_IMC 0x00d8 /* Interrupt Mask Clear Register */
+ /* See ICR bits. */
+
+#define WMREG_RCTL 0x0100 /* Receive Control */
+#define RCTL_EN (1U << 1) /* receiver enable */
+#define RCTL_SBP (1U << 2) /* store bad packets */
+#define RCTL_UPE (1U << 3) /* unicast promisc. enable */
+#define RCTL_MPE (1U << 4) /* multicast promisc. enable */
+#define RCTL_LPE (1U << 5) /* large packet enable */
+#define RCTL_LBM(x) ((x) << 6) /* loopback mode */
+#define RCTL_LBM_NONE RCTL_LBM(0)
+#define RCTL_LBM_PHY RCTL_LBM(3)
+#define RCTL_RDMTS(x) ((x) << 8) /* receive desc. min thresh size */
+#define RCTL_RDMTS_1_2 RCTL_RDMTS(0)
+#define RCTL_RDMTS_1_4 RCTL_RDMTS(1)
+#define RCTL_RDMTS_1_8 RCTL_RDMTS(2)
+#define RCTL_RDMTS_MASK RCTL_RDMTS(3)
+#define RCTL_MO(x) ((x) << 12) /* multicast offset */
+#define RCTL_BAM (1U << 15) /* broadcast accept mode */
+#define RCTL_2k (0 << 16) /* 2k Rx buffers */
+#define RCTL_1k (1 << 16) /* 1k Rx buffers */
+#define RCTL_512 (2 << 16) /* 512 byte Rx buffers */
+#define RCTL_256 (3 << 16) /* 256 byte Rx buffers */
+#define RCTL_BSEX_16k (1 << 16) /* 16k Rx buffers (BSEX) */
+#define RCTL_BSEX_8k (2 << 16) /* 8k Rx buffers (BSEX) */
+#define RCTL_BSEX_4k (3 << 16) /* 4k Rx buffers (BSEX) */
+#define RCTL_DPF (1U << 22) /* discard pause frames */
+#define RCTL_PMCF (1U << 23) /* pass MAC control frames */
+#define RCTL_BSEX (1U << 25) /* buffer size extension (Livengood) */
+#define RCTL_SECRC (1U << 26) /* strip Ethernet CRC */
+
+#define WMREG_OLD_RDTR0 0x0108 /* Receive Delay Timer (ring 0) */
+#define WMREG_RDTR 0x2820
+#define RDTR_FPD (1U << 31) /* flush partial descriptor */
+
+#define WMREG_RADV 0x282c /* Receive Interrupt Absolute Delay Timer */
+
+#define WMREG_OLD_RDBAL0 0x0110 /* Receive Descriptor Base Low (ring 0) */
+#define WMREG_RDBAL 0x2800
+
+#define WMREG_OLD_RDBAH0 0x0114 /* Receive Descriptor Base High (ring 0) */
+#define WMREG_RDBAH 0x2804
+
+#define WMREG_OLD_RDLEN0 0x0118 /* Receive Descriptor Length (ring 0) */
+#define WMREG_RDLEN 0x2808
+
+#define WMREG_OLD_RDH0 0x0120 /* Receive Descriptor Head (ring 0) */
+#define WMREG_RDH 0x2810
+
+#define WMREG_OLD_RDT0 0x0128 /* Receive Descriptor Tail (ring 0) */
+#define WMREG_RDT 0x2818
+
+#define WMREG_RXDCTL 0x2828 /* Receive Descriptor Control */
+#define RXDCTL_PTHRESH(x) ((x) << 0) /* prefetch threshold */
+#define RXDCTL_HTHRESH(x) ((x) << 8) /* host threshold */
+#define RXDCTL_WTHRESH(x) ((x) << 16) /* write back threshold */
+#define RXDCTL_GRAN (1U << 24) /* 0 = cacheline, 1 = descriptor */
+
+#define WMREG_OLD_RDTR1 0x0130 /* Receive Delay Timer (ring 1) */
+
+#define WMREG_OLD_RDBA1_LO 0x0138 /* Receive Descriptor Base Low (ring 1) */
+
+#define WMREG_OLD_RDBA1_HI 0x013c /* Receive Descriptor Base High (ring 1) */
+
+#define WMREG_OLD_RDLEN1 0x0140 /* Receive Drscriptor Length (ring 1) */
+
+#define WMREG_OLD_RDH1 0x0148
+
+#define WMREG_OLD_RDT1 0x0150
+
+#define WMREG_OLD_FCRTH 0x0160 /* Flow Control Rx Threshold Hi (OLD) */
+#define WMREG_FCRTL 0x2160 /* Flow Control Rx Threshold Lo */
+#define FCRTH_DFLT 0x00008000
+
+#define WMREG_OLD_FCRTL 0x0168 /* Flow Control Rx Threshold Lo (OLD) */
+#define WMREG_FCRTH 0x2168 /* Flow Control Rx Threhsold Hi */
+#define FCRTL_DFLT 0x00004000
+#define FCRTL_XONE 0x80000000 /* Enable XON frame transmission */
+
+#define WMREG_FCTTV 0x0170 /* Flow Control Transmit Timer Value */
+#define FCTTV_DFLT 0x00000600
+
+#define WMREG_TXCW 0x0178 /* Transmit Configuration Word (TBI mode) */
+ /* See MII ANAR_X bits. */
+#define TXCW_TxConfig (1U << 30) /* Tx Config */
+#define TXCW_ANE (1U << 31) /* Autonegotiate */
+
+#define WMREG_RXCW 0x0180 /* Receive Configuration Word (TBI mode) */
+ /* See MII ANLPAR_X bits. */
+#define RXCW_NC (1U << 26) /* no carrier */
+#define RXCW_IV (1U << 27) /* config invalid */
+#define RXCW_CC (1U << 28) /* config change */
+#define RXCW_C (1U << 29) /* /C/ reception */
+#define RXCW_SYNCH (1U << 30) /* synchronized */
+#define RXCW_ANC (1U << 31) /* autonegotiation complete */
+
+#define WMREG_MTA 0x0200 /* Multicast Table Array */
+#define WMREG_CORDOVA_MTA 0x5200
+
+#define WMREG_TCTL 0x0400 /* Transmit Control Register */
+#define TCTL_EN (1U << 1) /* transmitter enable */
+#define TCTL_PSP (1U << 3) /* pad short packets */
+#define TCTL_CT(x) (((x) & 0xff) << 4) /* 4:11 - collision threshold */
+#define TCTL_COLD(x) (((x) & 0x3ff) << 12) /* 12:21 - collision distance */
+#define TCTL_SWXOFF (1U << 22) /* software XOFF */
+#define TCTL_RTLC (1U << 24) /* retransmit on late collision */
+#define TCTL_NRTU (1U << 25) /* no retransmit on underrun */
+#define TCTL_MULR (1U << 28) /* multiple request */
+
+#define TX_COLLISION_THRESHOLD 15
+#define TX_COLLISION_DISTANCE_HDX 512
+#define TX_COLLISION_DISTANCE_FDX 64
+
+#define WMREG_TCTL_EXT 0x0404 /* Transmit Control Register */
+#define TCTL_EXT_BST_MASK 0x000003FF /* Backoff Slot Time */
+#define TCTL_EXT_GCEX_MASK 0x000FFC00 /* Gigabit Carry Extend Padding */
+
+#define DEFAULT_80003ES2LAN_TCTL_EXT_GCEX 0x00010000
+
+#define WMREG_TQSA_LO 0x0408
+
+#define WMREG_TQSA_HI 0x040c
+
+#define WMREG_TIPG 0x0410 /* Transmit IPG Register */
+#define TIPG_IPGT(x) (x) /* IPG transmit time */
+#define TIPG_IPGR1(x) ((x) << 10) /* IPG receive time 1 */
+#define TIPG_IPGR2(x) ((x) << 20) /* IPG receive time 2 */
+
+#define TIPG_WM_DFLT (TIPG_IPGT(0x0a) | TIPG_IPGR1(0x02) | TIPG_IPGR2(0x0a))
+#define TIPG_LG_DFLT (TIPG_IPGT(0x06) | TIPG_IPGR1(0x08) | TIPG_IPGR2(0x06))
+#define TIPG_1000T_DFLT (TIPG_IPGT(0x08) | TIPG_IPGR1(0x08) | TIPG_IPGR2(0x06))
+#define TIPG_1000T_80003_DFLT \
+ (TIPG_IPGT(0x08) | TIPG_IPGR1(0x02) | TIPG_IPGR2(0x07))
+#define TIPG_10_100_80003_DFLT \
+ (TIPG_IPGT(0x09) | TIPG_IPGR1(0x02) | TIPG_IPGR2(0x07))
+
+#define WMREG_TQC 0x0418
+
+#define WMREG_EEWR 0x102c /* EEPROM write */
+
+#define WMREG_RDFH 0x2410 /* Receive Data FIFO Head */
+
+#define WMREG_RDFT 0x2418 /* Receive Data FIFO Tail */
+
+#define WMREG_RDFHS 0x2420 /* Receive Data FIFO Head Saved */
+
+#define WMREG_RDFTS 0x2428 /* Receive Data FIFO Tail Saved */
+
+#define WMREG_TDFH 0x3410 /* Transmit Data FIFO Head */
+
+#define WMREG_TDFT 0x3418 /* Transmit Data FIFO Tail */
+
+#define WMREG_TDFHS 0x3420 /* Transmit Data FIFO Head Saved */
+
+#define WMREG_TDFTS 0x3428 /* Transmit Data FIFO Tail Saved */
+
+#define WMREG_TDFPC 0x3430 /* Transmit Data FIFO Packet Count */
+
+#define WMREG_OLD_TBDAL 0x0420 /* Transmit Descriptor Base Lo */
+#define WMREG_TBDAL 0x3800
+
+#define WMREG_OLD_TBDAH 0x0424 /* Transmit Descriptor Base Hi */
+#define WMREG_TBDAH 0x3804
+
+#define WMREG_OLD_TDLEN 0x0428 /* Transmit Descriptor Length */
+#define WMREG_TDLEN 0x3808
+
+#define WMREG_OLD_TDH 0x0430 /* Transmit Descriptor Head */
+#define WMREG_TDH 0x3810
+
+#define WMREG_OLD_TDT 0x0438 /* Transmit Descriptor Tail */
+#define WMREG_TDT 0x3818
+
+#define WMREG_OLD_TIDV 0x0440 /* Transmit Delay Interrupt Value */
+#define WMREG_TIDV 0x3820
+
+#define WMREG_TXDCTL 0x3828 /* Trandmit Descriptor Control */
+#define TXDCTL_PTHRESH(x) ((x) << 0) /* prefetch threshold */
+#define TXDCTL_HTHRESH(x) ((x) << 8) /* host threshold */
+#define TXDCTL_WTHRESH(x) ((x) << 16) /* write back threshold */
+
+#define WMREG_TADV 0x382c /* Transmit Absolute Interrupt Delay Timer */
+
+#define WMREG_AIT 0x0458 /* Adaptive IFS Throttle */
+
+#define WMREG_VFTA 0x0600
+
+#define WM_MC_TABSIZE 128
+#define WM_ICH8_MC_TABSIZE 32
+#define WM_VLAN_TABSIZE 128
+
+#define WMREG_PBA 0x1000 /* Packet Buffer Allocation */
+#define PBA_BYTE_SHIFT 10 /* KB -> bytes */
+#define PBA_ADDR_SHIFT 7 /* KB -> quadwords */
+#define PBA_8K 0x0008
+#define PBA_12K 0x000c
+#define PBA_16K 0x0010 /* 16K, default Tx allocation */
+#define PBA_22K 0x0016
+#define PBA_24K 0x0018
+#define PBA_30K 0x001e
+#define PBA_32K 0x0020
+#define PBA_40K 0x0028
+#define PBA_48K 0x0030 /* 48K, default Rx allocation */
+
+#define WMREG_PBS 0x1000 /* Packet Buffer Size (ICH8 only ?) */
+
+#define WMREG_TXDMAC 0x3000 /* Transfer DMA Control */
+#define TXDMAC_DPP (1U << 0) /* disable packet prefetch */
+
+#define WMREG_TSPMT 0x3830 /* TCP Segmentation Pad and Minimum
+ Threshold (Cordova) */
+#define TSPMT_TSMT(x) (x) /* TCP seg min transfer */
+#define TSPMT_TSPBP(x) ((x) << 16) /* TCP seg pkt buf padding */
+
+#define WMREG_RXCSUM 0x5000 /* Receive Checksum register */
+#define RXCSUM_PCSS 0x000000ff /* Packet Checksum Start */
+#define RXCSUM_IPOFL (1U << 8) /* IP checksum offload */
+#define RXCSUM_TUOFL (1U << 9) /* TCP/UDP checksum offload */
+#define RXCSUM_IPV6OFL (1U << 10) /* IPv6 checksum offload */
+
+#define WMREG_RXERRC 0x400C /* receive error Count - R/clr */
+#define WMREG_COLC 0x4028 /* collision Count - R/clr */
+#define WMREG_XONRXC 0x4048 /* XON Rx Count - R/clr */
+#define WMREG_XONTXC 0x404c /* XON Tx Count - R/clr */
+#define WMREG_XOFFRXC 0x4050 /* XOFF Rx Count - R/clr */
+#define WMREG_XOFFTXC 0x4054 /* XOFF Tx Count - R/clr */
+#define WMREG_FCRUC 0x4058 /* Flow Control Rx Unsupported Count - R/clr */
+
+#define WMREG_KUMCTRLSTA 0x0034 /* MAC-PHY interface - RW */
+#define KUMCTRLSTA_MASK 0x0000FFFF
+#define KUMCTRLSTA_OFFSET 0x001F0000
+#define KUMCTRLSTA_OFFSET_SHIFT 16
+#define KUMCTRLSTA_REN 0x00200000
+
+#define KUMCTRLSTA_OFFSET_FIFO_CTRL 0x00000000
+#define KUMCTRLSTA_OFFSET_CTRL 0x00000001
+#define KUMCTRLSTA_OFFSET_INB_CTRL 0x00000002
+#define KUMCTRLSTA_OFFSET_DIAG 0x00000003
+#define KUMCTRLSTA_OFFSET_TIMEOUTS 0x00000004
+#define KUMCTRLSTA_OFFSET_INB_PARAM 0x00000009
+#define KUMCTRLSTA_OFFSET_HD_CTRL 0x00000010
+#define KUMCTRLSTA_OFFSET_M2P_SERDES 0x0000001E
+#define KUMCTRLSTA_OFFSET_M2P_MODES 0x0000001F
+
+/* FIFO Control */
+#define KUMCTRLSTA_FIFO_CTRL_RX_BYPASS 0x00000008
+#define KUMCTRLSTA_FIFO_CTRL_TX_BYPASS 0x00000800
+
+/* In-Band Control */
+#define KUMCTRLSTA_INB_CTRL_LINK_TMOUT_DFLT 0x00000500
+#define KUMCTRLSTA_INB_CTRL_DIS_PADDING 0x00000010
+
+/* Half-Duplex Control */
+#define KUMCTRLSTA_HD_CTRL_10_100_DEFAULT 0x00000004
+#define KUMCTRLSTA_HD_CTRL_1000_DEFAULT 0x00000000
+
+#define WMREG_MDPHYA 0x003C /* PHY address - RW */
+
+#define WMREG_MANC2H 0x5860 /* Managment Control To Host - RW */
+
+#define WMREG_SWSM 0x5b50 /* SW Semaphore */
+#define SWSM_SMBI 0x00000001 /* Driver Semaphore bit */
+#define SWSM_SWESMBI 0x00000002 /* FW Semaphore bit */
+#define SWSM_WMNG 0x00000004 /* Wake MNG Clock */
+#define SWSM_DRV_LOAD 0x00000008 /* Driver Loaded Bit */
+
+#define WMREG_SW_FW_SYNC 0x5b5c /* software-firmware semaphore */
+#define SWFW_EEP_SM 0x0001 /* eeprom access */
+#define SWFW_PHY0_SM 0x0002 /* first ctrl phy access */
+#define SWFW_PHY1_SM 0x0004 /* second ctrl phy access */
+#define SWFW_MAC_CSR_SM 0x0008
+#define SWFW_SOFT_SHIFT 0 /* software semaphores */
+#define SWFW_FIRM_SHIFT 16 /* firmware semaphores */
+
+#define WMREG_EXTCNFCTR 0x0f00 /* Extended Configuration Control */
+#define EXTCNFCTR_PCIE_WRITE_ENABLE 0x00000001
+#define EXTCNFCTR_PHY_WRITE_ENABLE 0x00000002
+#define EXTCNFCTR_D_UD_ENABLE 0x00000004
+#define EXTCNFCTR_D_UD_LATENCY 0x00000008
+#define EXTCNFCTR_D_UD_OWNER 0x00000010
+#define EXTCNFCTR_MDIO_SW_OWNERSHIP 0x00000020
+#define EXTCNFCTR_MDIO_HW_OWNERSHIP 0x00000040
+#define EXTCNFCTR_EXT_CNF_POINTER 0x0FFF0000
+#define E1000_EXTCNF_CTRL_SWFLAG EXTCNFCTR_MDIO_SW_OWNERSHIP
+
+/* ich8 flash control */
+#define ICH_FLASH_COMMAND_TIMEOUT 5000 /* 5000 uSecs - adjusted */
+#define ICH_FLASH_ERASE_TIMEOUT 3000000 /* Up to 3 seconds - worst case */
+#define ICH_FLASH_CYCLE_REPEAT_COUNT 10 /* 10 cycles */
+#define ICH_FLASH_SEG_SIZE_256 256
+#define ICH_FLASH_SEG_SIZE_4K 4096
+#define ICH_FLASH_SEG_SIZE_64K 65536
+
+#define ICH_CYCLE_READ 0x0
+#define ICH_CYCLE_RESERVED 0x1
+#define ICH_CYCLE_WRITE 0x2
+#define ICH_CYCLE_ERASE 0x3
+
+#define ICH_FLASH_GFPREG 0x0000
+#define ICH_FLASH_HSFSTS 0x0004 /* Flash Status Register */
+#define HSFSTS_DONE 0x0001 /* Flash Cycle Done */
+#define HSFSTS_ERR 0x0002 /* Flash Cycle Error */
+#define HSFSTS_DAEL 0x0004 /* Direct Access error Log */
+#define HSFSTS_ERSZ_MASK 0x0018 /* Block/Sector Erase Size */
+#define HSFSTS_ERSZ_SHIFT 3
+#define HSFSTS_FLINPRO 0x0020 /* flash SPI cycle in Progress */
+#define HSFSTS_FLDVAL 0x4000 /* Flash Descriptor Valid */
+#define HSFSTS_FLLK 0x8000 /* Flash Configuration Lock-Down */
+#define ICH_FLASH_HSFCTL 0x0006 /* Flash control Register */
+#define HSFCTL_GO 0x0001 /* Flash Cycle Go */
+#define HSFCTL_CYCLE_MASK 0x0006 /* Flash Cycle */
+#define HSFCTL_CYCLE_SHIFT 1
+#define HSFCTL_BCOUNT_MASK 0x0300 /* Data Byte Count */
+#define HSFCTL_BCOUNT_SHIFT 8
+#define ICH_FLASH_FADDR 0x0008
+#define ICH_FLASH_FDATA0 0x0010
+#define ICH_FLASH_FRACC 0x0050
+#define ICH_FLASH_FREG0 0x0054
+#define ICH_FLASH_FREG1 0x0058
+#define ICH_FLASH_FREG2 0x005C
+#define ICH_FLASH_FREG3 0x0060
+#define ICH_FLASH_FPR0 0x0074
+#define ICH_FLASH_FPR1 0x0078
+#define ICH_FLASH_SSFSTS 0x0090
+#define ICH_FLASH_SSFCTL 0x0092
+#define ICH_FLASH_PREOP 0x0094
+#define ICH_FLASH_OPTYPE 0x0096
+#define ICH_FLASH_OPMENU 0x0098
+
+#define ICH_FLASH_REG_MAPSIZE 0x00A0
+#define ICH_FLASH_SECTOR_SIZE 4096
+#define ICH_GFPREG_BASE_MASK 0x1FFF
+#define ICH_FLASH_LINEAR_ADDR_MASK 0x00FFFFFF
+
+/* start of Kate Feng added */
+#define WMREG_GPTC 0x4080 /* Good packets transmitted count */
+#define WMREG_GPRC 0x4074 /* Good packets received count */
+#define WMREG_CRCERRS 0x4000 /* CRC Error Count */
+#define WMREG_RLEC 0x4040 /* Receive Length Error Count */
+/* end of Kate Feng added */
diff --git a/bsps/powerpc/mvme5500/include/bsp/irq.h b/bsps/powerpc/mvme5500/include/bsp/irq.h
new file mode 100644
index 0000000000..6704c2f626
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/irq.h
@@ -0,0 +1,137 @@
+/* irq.h
+ *
+ * This include file describe the data structure and the functions implemented
+ * by rtems to write interrupt handlers.
+ *
+ * CopyRight (C) 1999 valette@crf.canon.fr
+ *
+ * This code is heavilly inspired by the public specification of STREAM V2
+ * that can be found at :
+ *
+ * <http://www.chorus.com/Documentation/index.html> by following
+ * the STREAM API Specification Document link.
+ *
+ * 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 2004, 2005 Brookhaven National Laboratory and
+ * Shuchen Kate Feng <feng1@bnl.gov>
+ *
+ * - modified shared/irq/irq.h for Mvme5500 (no ISA devices/PIC)
+ * - Discovery GT64260 interrupt controller instead of 8259.
+ * - Added support for software IRQ priority levels.
+ * - modified to optimize the IRQ latency and handling
+ */
+
+#ifndef LIBBSP_POWERPC_MVME5500_IRQ_IRQ_H
+#define LIBBSP_POWERPC_MVME5500_IRQ_IRQ_H
+
+#define BSP_SHARED_HANDLER_SUPPORT 1
+#include <rtems/irq.h>
+
+#ifndef ASM
+
+#define OneTierIrqPrioTbl 1
+
+/*
+ * Symbolic IRQ names and related definitions.
+ */
+
+/* leave the ISA symbols in there, so we can reuse shared/irq.c
+ * Also, we start numbering PCI irqs at 16 because the OPENPIC
+ * driver relies on this when mapping irq number <-> vectors
+ * (OPENPIC_VEC_SOURCE in openpic.h)
+ */
+
+ /* See section 25.2 , Table 734 of GT64260 controller
+ * Main Interrupt Cause Low register
+ */
+#define BSP_MICL_IRQ_NUMBER (32)
+#define BSP_MICL_IRQ_LOWEST_OFFSET (0)
+#define BSP_MICL_IRQ_MAX_OFFSET (BSP_MICL_IRQ_LOWEST_OFFSET + BSP_MICL_IRQ_NUMBER -1)
+ /*
+ * Main Interrupt Cause High register
+ */
+#define BSP_MICH_IRQ_NUMBER (32)
+#define BSP_MICH_IRQ_LOWEST_OFFSET (BSP_MICL_IRQ_MAX_OFFSET+1)
+#define BSP_MICH_IRQ_MAX_OFFSET (BSP_MICH_IRQ_LOWEST_OFFSET + BSP_MICH_IRQ_NUMBER -1)
+ /* External GPP Interrupt assignements
+ */
+#define BSP_GPP_IRQ_NUMBER (32)
+#define BSP_GPP_IRQ_LOWEST_OFFSET (BSP_MICH_IRQ_MAX_OFFSET+1)
+#define BSP_GPP_IRQ_MAX_OFFSET (BSP_GPP_IRQ_LOWEST_OFFSET + BSP_GPP_IRQ_NUMBER - 1)
+
+ /*
+ * PowerPc exceptions handled as interrupt where a rtems managed interrupt
+ * handler might be connected
+ */
+#define BSP_PROCESSOR_IRQ_NUMBER (1)
+#define BSP_PROCESSOR_IRQ_LOWEST_OFFSET (BSP_GPP_IRQ_MAX_OFFSET + 1)
+#define BSP_PROCESSOR_IRQ_MAX_OFFSET (BSP_PROCESSOR_IRQ_LOWEST_OFFSET + BSP_PROCESSOR_IRQ_NUMBER - 1)
+
+ /* allow a couple of vectors for VME and counter/timer irq sources etc.
+ * This is probably not needed any more.
+ */
+#define BSP_MISC_IRQ_NUMBER (30)
+#define BSP_MISC_IRQ_LOWEST_OFFSET (BSP_PROCESSOR_IRQ_MAX_OFFSET + 1)
+#define BSP_MISC_IRQ_MAX_OFFSET (BSP_MISC_IRQ_LOWEST_OFFSET + BSP_MISC_IRQ_NUMBER - 1)
+
+ /*
+ * Summary
+ */
+#define BSP_IRQ_NUMBER (BSP_MISC_IRQ_MAX_OFFSET + 1)
+#define BSP_MAIN_IRQ_NUMBER (64)
+#define BSP_PIC_IRQ_NUMBER (96)
+#define BSP_LOWEST_OFFSET (BSP_MICL_IRQ_LOWEST_OFFSET)
+#define BSP_MAX_OFFSET (BSP_MISC_IRQ_MAX_OFFSET)
+
+ /* Main CPU interrupt cause (Low) */
+#define BSP_MAIN_TIMER0_1_IRQ (BSP_MICL_IRQ_LOWEST_OFFSET+8)
+#define BSP_MAIN_PCI0_7_0 (BSP_MICL_IRQ_LOWEST_OFFSET+12)
+#define BSP_MAIN_PCI0_15_8 (BSP_MICL_IRQ_LOWEST_OFFSET+13)
+#define BSP_MAIN_PCI0_23_16 (BSP_MICL_IRQ_LOWEST_OFFSET+14)
+#define BSP_MAIN_PCI0_31_24 (BSP_MICL_IRQ_LOWEST_OFFSET+15)
+#define BSP_MAIN_PCI1_7_0 (BSP_MICL_IRQ_LOWEST_OFFSET+16)
+#define BSP_MAIN_PCI1_15_8 (BSP_MICL_IRQ_LOWEST_OFFSET+18)
+#define BSP_MAIN_PCI1_23_16 (BSP_MICL_IRQ_LOWEST_OFFSET+19)
+#define BSP_MAIN_PCI1_31_24 (BSP_MICL_IRQ_LOWEST_OFFSET+20)
+
+
+ /* Main CPU interrupt cause (High) */
+#define BSP_MAIN_ETH0_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET)
+#define BSP_MAIN_ETH1_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+1)
+#define BSP_MAIN_ETH2_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+2)
+#define BSP_MAIN_GPP7_0_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+24)
+#define BSP_MAIN_GPP15_8_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+25)
+#define BSP_MAIN_GPP23_16_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+26)
+#define BSP_MAIN_GPP31_24_IRQ (BSP_MICH_IRQ_LOWEST_OFFSET+27)
+
+ /* on the MVME5500, these are the GT64260B external GPP0 interrupt */
+#define BSP_PCI_IRQ_LOWEST_OFFSET (BSP_GPP_IRQ_LOWEST_OFFSET)
+#define BSP_UART_COM2_IRQ (BSP_GPP_IRQ_LOWEST_OFFSET)
+#define BSP_UART_COM1_IRQ (BSP_GPP_IRQ_LOWEST_OFFSET)
+#define BSP_GPP8_IRQ_OFFSET (BSP_GPP_IRQ_LOWEST_OFFSET+8)
+#define BSP_GPP_PMC1_INTA (BSP_GPP8_IRQ_OFFSET)
+#define BSP_GPP16_IRQ_OFFSET (BSP_GPP_IRQ_LOWEST_OFFSET+16)
+#define BSP_GPP24_IRQ_OFFSET (BSP_GPP_IRQ_LOWEST_OFFSET+24)
+#define BSP_GPP_VME_VLINT0 (BSP_GPP_IRQ_LOWEST_OFFSET+12)
+#define BSP_GPP_VME_VLINT1 (BSP_GPP_IRQ_LOWEST_OFFSET+13)
+#define BSP_GPP_VME_VLINT2 (BSP_GPP_IRQ_LOWEST_OFFSET+14)
+#define BSP_GPP_VME_VLINT3 (BSP_GPP_IRQ_LOWEST_OFFSET+15)
+#define BSP_GPP_PMC2_INTA (BSP_GPP_IRQ_LOWEST_OFFSET+16)
+#define BSP_GPP_82544_IRQ (BSP_GPP_IRQ_LOWEST_OFFSET+20)
+#define BSP_GPP_WDT_NMI_IRQ (BSP_GPP_IRQ_LOWEST_OFFSET+24)
+#define BSP_GPP_WDT_EXP_IRQ (BSP_GPP_IRQ_LOWEST_OFFSET+25)
+
+ /*
+ * Some Processor execption handled as rtems IRQ symbolic name definition
+ */
+#define BSP_DECREMENTER (BSP_PROCESSOR_IRQ_LOWEST_OFFSET)
+
+extern void BSP_rtems_irq_mng_init(unsigned cpuId);
+
+#include <bsp/irq_supp.h>
+
+#endif
+#endif
diff --git a/bsps/powerpc/mvme5500/include/bsp/pcireg.h b/bsps/powerpc/mvme5500/include/bsp/pcireg.h
new file mode 100644
index 0000000000..2b8b10d853
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/bsp/pcireg.h
@@ -0,0 +1,386 @@
+/* $NetBSD: pcireg.h,v 1.44 2003/12/02 16:31:06 briggs Exp $ */
+
+/*
+ * Copyright (c) 1995, 1996, 1999, 2000
+ * Christopher G. Demetriou. All rights reserved.
+ * Copyright (c) 1994, 1996 Charles M. Hannum. All rights reserved.
+ * Copyright (C) 2007 Brookhaven National Laboratory, Shuchen Kate Feng
+ *
+ * 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 M. 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.
+ */
+#include <bsp.h>
+
+/*
+ * PCI Class and Revision Register; defines type and revision of device.
+ */
+#define PCI_CLASS_REG 0x08
+
+#define PCI_CLASS_SHIFT 24
+#define PCI_CLASS_MASK 0xff
+#define PCI_CLASS(cr) \
+ (((cr) >> PCI_CLASS_SHIFT) & PCI_CLASS_MASK)
+
+#define PCI_SUBCLASS_SHIFT 16
+#define PCI_SUBCLASS_MASK 0xff
+#define PCI_SUBCLASS(cr) \
+ (((cr) >> PCI_SUBCLASS_SHIFT) & PCI_SUBCLASS_MASK)
+
+#define PCI_INTERFACE_SHIFT 8
+#define PCI_INTERFACE_MASK 0xff
+#define PCI_INTERFACE(cr) \
+ (((cr) >> PCI_INTERFACE_SHIFT) & PCI_INTERFACE_MASK)
+
+#define PCI_REVISION_SHIFT 0
+#define PCI_REVISION_MASK 0xff
+#define PCI_REVISION(cr) \
+ (((cr) >> PCI_REVISION_SHIFT) & PCI_REVISION_MASK)
+
+#define PCI_CLASS_CODE(mainclass, subclass, interface) \
+ ((((mainclass) & PCI_CLASS_MASK) << PCI_CLASS_SHIFT) | \
+ (((subclass) & PCI_SUBCLASS_MASK) << PCI_SUBCLASS_SHIFT) | \
+ (((interface) & PCI_INTERFACE_MASK) << PCI_INTERFACE_SHIFT))
+
+/* base classes */
+#define PCI_CLASS_PREHISTORIC 0x00
+#define PCI_CLASS_MASS_STORAGE 0x01
+#define PCI_CLASS_NETWORK 0x02
+#define PCI_CLASS_DISPLAY 0x03
+#define PCI_CLASS_MULTIMEDIA 0x04
+#define PCI_CLASS_MEMORY 0x05
+#define PCI_CLASS_BRIDGE 0x06
+#define PCI_CLASS_COMMUNICATIONS 0x07
+#define PCI_CLASS_SYSTEM 0x08
+#define PCI_CLASS_INPUT 0x09
+#define PCI_CLASS_DOCK 0x0a
+#define PCI_CLASS_PROCESSOR 0x0b
+#define PCI_CLASS_SERIALBUS 0x0c
+#define PCI_CLASS_WIRELESS 0x0d
+#define PCI_CLASS_I2O 0x0e
+#define PCI_CLASS_SATCOM 0x0f
+#define PCI_CLASS_CRYPTO 0x10
+#define PCI_CLASS_DASP 0x11
+#define PCI_CLASS_UNDEFINED 0xff
+
+/* 0x00 prehistoric subclasses */
+#define PCI_SUBCLASS_PREHISTORIC_MISC 0x00
+#define PCI_SUBCLASS_PREHISTORIC_VGA 0x01
+
+/* 0x01 mass storage subclasses */
+#define PCI_SUBCLASS_MASS_STORAGE_SCSI 0x00
+#define PCI_SUBCLASS_MASS_STORAGE_IDE 0x01
+#define PCI_SUBCLASS_MASS_STORAGE_FLOPPY 0x02
+#define PCI_SUBCLASS_MASS_STORAGE_IPI 0x03
+#define PCI_SUBCLASS_MASS_STORAGE_RAID 0x04
+#define PCI_SUBCLASS_MASS_STORAGE_ATA 0x05
+#define PCI_SUBCLASS_MASS_STORAGE_SATA 0x06
+#define PCI_SUBCLASS_MASS_STORAGE_MISC 0x80
+
+/* 0x02 network subclasses */
+#define PCI_SUBCLASS_NETWORK_ETHERNET 0x00
+#define PCI_SUBCLASS_NETWORK_TOKENRING 0x01
+#define PCI_SUBCLASS_NETWORK_FDDI 0x02
+#define PCI_SUBCLASS_NETWORK_ATM 0x03
+#define PCI_SUBCLASS_NETWORK_ISDN 0x04
+#define PCI_SUBCLASS_NETWORK_WORLDFIP 0x05
+#define PCI_SUBCLASS_NETWORK_PCIMGMULTICOMP 0x06
+#define PCI_SUBCLASS_NETWORK_MISC 0x80
+
+/* 0x03 display subclasses */
+#define PCI_SUBCLASS_DISPLAY_VGA 0x00
+#define PCI_SUBCLASS_DISPLAY_XGA 0x01
+#define PCI_SUBCLASS_DISPLAY_3D 0x02
+#define PCI_SUBCLASS_DISPLAY_MISC 0x80
+
+/* 0x04 multimedia subclasses */
+#define PCI_SUBCLASS_MULTIMEDIA_VIDEO 0x00
+#define PCI_SUBCLASS_MULTIMEDIA_AUDIO 0x01
+#define PCI_SUBCLASS_MULTIMEDIA_TELEPHONY 0x02
+#define PCI_SUBCLASS_MULTIMEDIA_MISC 0x80
+
+/* 0x05 memory subclasses */
+#define PCI_SUBCLASS_MEMORY_RAM 0x00
+#define PCI_SUBCLASS_MEMORY_FLASH 0x01
+#define PCI_SUBCLASS_MEMORY_MISC 0x80
+
+/* 0x06 bridge subclasses */
+#define PCI_SUBCLASS_BRIDGE_HOST 0x00
+#define PCI_SUBCLASS_BRIDGE_ISA 0x01
+#define PCI_SUBCLASS_BRIDGE_EISA 0x02
+#define PCI_SUBCLASS_BRIDGE_MC 0x03 /* XXX _MCA? */
+#define PCI_SUBCLASS_BRIDGE_PCI 0x04
+#define PCI_SUBCLASS_BRIDGE_PCMCIA 0x05
+#define PCI_SUBCLASS_BRIDGE_NUBUS 0x06
+#define PCI_SUBCLASS_BRIDGE_CARDBUS 0x07
+#define PCI_SUBCLASS_BRIDGE_RACEWAY 0x08
+#define PCI_SUBCLASS_BRIDGE_STPCI 0x09
+#define PCI_SUBCLASS_BRIDGE_INFINIBAND 0x0a
+#define PCI_SUBCLASS_BRIDGE_MISC 0x80
+
+/* 0x07 communications subclasses */
+#define PCI_SUBCLASS_COMMUNICATIONS_SERIAL 0x00
+#define PCI_SUBCLASS_COMMUNICATIONS_PARALLEL 0x01
+#define PCI_SUBCLASS_COMMUNICATIONS_MPSERIAL 0x02
+#define PCI_SUBCLASS_COMMUNICATIONS_MODEM 0x03
+#define PCI_SUBCLASS_COMMUNICATIONS_GPIB 0x04
+#define PCI_SUBCLASS_COMMUNICATIONS_SMARTCARD 0x05
+#define PCI_SUBCLASS_COMMUNICATIONS_MISC 0x80
+
+/* 0x08 system subclasses */
+#define PCI_SUBCLASS_SYSTEM_PIC 0x00
+#define PCI_SUBCLASS_SYSTEM_DMA 0x01
+#define PCI_SUBCLASS_SYSTEM_TIMER 0x02
+#define PCI_SUBCLASS_SYSTEM_RTC 0x03
+#define PCI_SUBCLASS_SYSTEM_PCIHOTPLUG 0x04
+#define PCI_SUBCLASS_SYSTEM_MISC 0x80
+
+/* 0x09 input subclasses */
+#define PCI_SUBCLASS_INPUT_KEYBOARD 0x00
+#define PCI_SUBCLASS_INPUT_DIGITIZER 0x01
+#define PCI_SUBCLASS_INPUT_MOUSE 0x02
+#define PCI_SUBCLASS_INPUT_SCANNER 0x03
+#define PCI_SUBCLASS_INPUT_GAMEPORT 0x04
+#define PCI_SUBCLASS_INPUT_MISC 0x80
+
+/* 0x0a dock subclasses */
+#define PCI_SUBCLASS_DOCK_GENERIC 0x00
+#define PCI_SUBCLASS_DOCK_MISC 0x80
+
+/* 0x0b processor subclasses */
+#define PCI_SUBCLASS_PROCESSOR_386 0x00
+#define PCI_SUBCLASS_PROCESSOR_486 0x01
+#define PCI_SUBCLASS_PROCESSOR_PENTIUM 0x02
+#define PCI_SUBCLASS_PROCESSOR_ALPHA 0x10
+#define PCI_SUBCLASS_PROCESSOR_POWERPC 0x20
+#define PCI_SUBCLASS_PROCESSOR_MIPS 0x30
+#define PCI_SUBCLASS_PROCESSOR_COPROC 0x40
+
+/* 0x0c serial bus subclasses */
+#define PCI_SUBCLASS_SERIALBUS_FIREWIRE 0x00
+#define PCI_SUBCLASS_SERIALBUS_ACCESS 0x01
+#define PCI_SUBCLASS_SERIALBUS_SSA 0x02
+#define PCI_SUBCLASS_SERIALBUS_USB 0x03
+#define PCI_SUBCLASS_SERIALBUS_FIBER 0x04 /* XXX _FIBRECHANNEL */
+#define PCI_SUBCLASS_SERIALBUS_SMBUS 0x05
+#define PCI_SUBCLASS_SERIALBUS_INFINIBAND 0x06
+#define PCI_SUBCLASS_SERIALBUS_IPMI 0x07
+#define PCI_SUBCLASS_SERIALBUS_SERCOS 0x08
+#define PCI_SUBCLASS_SERIALBUS_CANBUS 0x09
+
+/* 0x0d wireless subclasses */
+#define PCI_SUBCLASS_WIRELESS_IRDA 0x00
+#define PCI_SUBCLASS_WIRELESS_CONSUMERIR 0x01
+#define PCI_SUBCLASS_WIRELESS_RF 0x10
+#define PCI_SUBCLASS_WIRELESS_BLUETOOTH 0x11
+#define PCI_SUBCLASS_WIRELESS_BROADBAND 0x12
+#define PCI_SUBCLASS_WIRELESS_802_11A 0x20
+#define PCI_SUBCLASS_WIRELESS_802_11B 0x21
+#define PCI_SUBCLASS_WIRELESS_MISC 0x80
+
+/* 0x0e I2O (Intelligent I/O) subclasses */
+#define PCI_SUBCLASS_I2O_STANDARD 0x00
+
+/* 0x0f satellite communication subclasses */
+/* PCI_SUBCLASS_SATCOM_??? 0x00 / * XXX ??? */
+#define PCI_SUBCLASS_SATCOM_TV 0x01
+#define PCI_SUBCLASS_SATCOM_AUDIO 0x02
+#define PCI_SUBCLASS_SATCOM_VOICE 0x03
+#define PCI_SUBCLASS_SATCOM_DATA 0x04
+
+/* 0x10 encryption/decryption subclasses */
+#define PCI_SUBCLASS_CRYPTO_NETCOMP 0x00
+#define PCI_SUBCLASS_CRYPTO_ENTERTAINMENT 0x10
+#define PCI_SUBCLASS_CRYPTO_MISC 0x80
+
+/* 0x11 data acquisition and signal processing subclasses */
+#define PCI_SUBCLASS_DASP_DPIO 0x00
+#define PCI_SUBCLASS_DASP_TIMEFREQ 0x01
+#define PCI_SUBCLASS_DASP_SYNC 0x10
+#define PCI_SUBCLASS_DASP_MGMT 0x20
+#define PCI_SUBCLASS_DASP_MISC 0x80
+
+/*
+ * PCI BIST/Header Type/Latency Timer/Cache Line Size Register.
+ */
+#define PCI_BHLC_REG 0x0c
+
+#define PCI_BIST_SHIFT 24
+#define PCI_BIST_MASK 0xff
+#define PCI_BIST(bhlcr) \
+ (((bhlcr) >> PCI_BIST_SHIFT) & PCI_BIST_MASK)
+
+#define PCI_HDRTYPE_SHIFT 16
+#define PCI_HDRTYPE_MASK 0xff
+#define PCI_HDRTYPE(bhlcr) \
+ (((bhlcr) >> PCI_HDRTYPE_SHIFT) & PCI_HDRTYPE_MASK)
+
+#define PCI_HDRTYPE_TYPE(bhlcr) \
+ (PCI_HDRTYPE(bhlcr) & 0x7f)
+#define PCI_HDRTYPE_MULTIFN(bhlcr) \
+ ((PCI_HDRTYPE(bhlcr) & 0x80) != 0)
+
+#define PCI_LATTIMER_SHIFT 8
+#define PCI_LATTIMER_MASK 0xff
+#define PCI_LATTIMER(bhlcr) \
+ (((bhlcr) >> PCI_LATTIMER_SHIFT) & PCI_LATTIMER_MASK)
+
+#define PCI_CACHELINE_SHIFT 0
+#define PCI_CACHELINE_MASK 0xff
+#define PCI_CACHELINE(bhlcr) \
+ (((bhlcr) >> PCI_CACHELINE_SHIFT) & PCI_CACHELINE_MASK)
+
+#define PCI_BHLC_CODE(bist,type,multi,latency,cacheline) \
+ ((((bist) & PCI_BIST_MASK) << PCI_BIST_SHIFT) | \
+ (((type) & PCI_HDRTYPE_MASK) << PCI_HDRTYPE_SHIFT) | \
+ (((multi)?0x80:0) << PCI_HDRTYPE_SHIFT) | \
+ (((latency) & PCI_LATTIMER_MASK) << PCI_LATTIMER_SHIFT) | \
+ (((cacheline) & PCI_CACHELINE_MASK) << PCI_CACHELINE_SHIFT))
+
+/*
+ * PCI header type
+ */
+#define PCI_HDRTYPE_DEVICE 0
+#define PCI_HDRTYPE_PPB 1
+#define PCI_HDRTYPE_PCB 2
+
+/*
+ * Mapping registers
+ */
+#define PCI_MAPREG_START 0x10
+#define PCI_MAPREG_END 0x28
+#define PCI_MAPREG_ROM 0x30
+#define PCI_MAPREG_PPB_END 0x18
+#define PCI_MAPREG_PCB_END 0x14
+
+#define PCI_MAPREG_TYPE(mr) \
+ ((mr) & PCI_MAPREG_TYPE_MASK)
+#define PCI_MAPREG_TYPE_MASK 0x00000001
+
+#define PCI_MAPREG_TYPE_MEM 0x00000000
+#define PCI_MAPREG_TYPE_IO 0x00000001
+#define PCI_MAPREG_ROM_ENABLE 0x00000001
+
+#define PCI_MAPREG_MEM_TYPE(mr) \
+ ((mr) & PCI_MAPREG_MEM_TYPE_MASK)
+#define PCI_MAPREG_MEM_TYPE_MASK 0x00000006
+
+#define PCI_MAPREG_MEM_TYPE_32BIT 0x00000000
+#define PCI_MAPREG_MEM_TYPE_32BIT_1M 0x00000002
+#define PCI_MAPREG_MEM_TYPE_64BIT 0x00000004
+
+#define PCI_MAPREG_MEM_PREFETCHABLE(mr) \
+ (((mr) & PCI_MAPREG_MEM_PREFETCHABLE_MASK) != 0)
+#define PCI_MAPREG_MEM_PREFETCHABLE_MASK 0x00000008
+
+#define PCI_MAPREG_MEM_ADDR(mr) \
+ ((mr) & PCI_MAPREG_MEM_ADDR_MASK)
+#define PCI_MAPREG_MEM_SIZE(mr) \
+ (PCI_MAPREG_MEM_ADDR(mr) & -PCI_MAPREG_MEM_ADDR(mr))
+#define PCI_MAPREG_MEM_ADDR_MASK 0xfffffff0
+
+#define PCI_MAPREG_MEM64_ADDR(mr) \
+ ((mr) & PCI_MAPREG_MEM64_ADDR_MASK)
+#define PCI_MAPREG_MEM64_SIZE(mr) \
+ (PCI_MAPREG_MEM64_ADDR(mr) & -PCI_MAPREG_MEM64_ADDR(mr))
+#define PCI_MAPREG_MEM64_ADDR_MASK 0xfffffffffffffff0ULL
+
+#define PCI_MAPREG_IO_ADDR(mr) \
+ ((mr+PCI0_IO_BASE) & PCI_MAPREG_IO_ADDR_MASK)
+#define PCI_MAPREG_IO_SIZE(mr) \
+ (PCI_MAPREG_IO_ADDR(mr) & -PCI_MAPREG_IO_ADDR(mr))
+#define PCI_MAPREG_IO_ADDR_MASK 0xfffffffc
+
+#define PCI_MAPREG_SIZE_TO_MASK(size) \
+ (-(size))
+
+#define PCI_MAPREG_NUM(offset) \
+ (((unsigned)(offset)-PCI_MAPREG_START)/4)
+
+
+/*
+ * Cardbus CIS pointer (PCI rev. 2.1)
+ */
+#define PCI_CARDBUS_CIS_REG 0x28
+
+/*
+ * Subsystem identification register; contains a vendor ID and a device ID.
+ * Types/macros for PCI_ID_REG apply.
+ * (PCI rev. 2.1)
+ */
+#define PCI_SUBSYS_ID_REG 0x2c
+
+/*
+ * capabilities link list (PCI rev. 2.2)
+ */
+#define PCI_CAPLISTPTR_REG 0x34 /* header type 0 */
+#define PCI_CARDBUS_CAPLISTPTR_REG 0x14 /* header type 2 */
+#define PCI_CAPLIST_PTR(cpr) ((cpr) & 0xff)
+#define PCI_CAPLIST_NEXT(cr) (((cr) >> 8) & 0xff)
+#define PCI_CAPLIST_CAP(cr) ((cr) & 0xff)
+
+#define PCI_CAP_RESERVED0 0x00
+#define PCI_CAP_PWRMGMT 0x01
+#define PCI_CAP_AGP 0x02
+#define PCI_CAP_VPD 0x03
+#define PCI_CAP_SLOTID 0x04
+#define PCI_CAP_MSI 0x05
+#define PCI_CAP_CPCI_HOTSWAP 0x06
+#define PCI_CAP_PCIX 0x07
+#define PCI_CAP_LDT 0x08
+#define PCI_CAP_VENDSPEC 0x09
+#define PCI_CAP_DEBUGPORT 0x0a
+#define PCI_CAP_CPCI_RSRCCTL 0x0b
+#define PCI_CAP_HOTPLUG 0x0c
+#define PCI_CAP_AGP8 0x0e
+#define PCI_CAP_SECURE 0x0f
+#define PCI_CAP_PCIEXPRESS 0x10
+#define PCI_CAP_MSIX 0x11
+
+/*
+ * Vital Product Data; access via capability pointer (PCI rev 2.2).
+ */
+#define PCI_VPD_ADDRESS_MASK 0x7fff
+#define PCI_VPD_ADDRESS_SHIFT 16
+#define PCI_VPD_ADDRESS(ofs) \
+ (((ofs) & PCI_VPD_ADDRESS_MASK) << PCI_VPD_ADDRESS_SHIFT)
+#define PCI_VPD_DATAREG(ofs) ((ofs) + 4)
+#define PCI_VPD_OPFLAG 0x80000000
+
+/*
+ * Power Management Capability; access via capability pointer.
+ */
+
+/* Power Management Capability Register */
+#define PCI_PMCR 0x02
+#define PCI_PMCR_D1SUPP 0x0200
+#define PCI_PMCR_D2SUPP 0x0400
+/* Power Management Control Status Register */
+#define PCI_PMCSR 0x04
+#define PCI_PMCSR_STATE_MASK 0x03
+#define PCI_PMCSR_STATE_D0 0x00
+#define PCI_PMCSR_STATE_D1 0x01
+#define PCI_PMCSR_STATE_D2 0x02
+#define PCI_PMCSR_STATE_D3 0x03
+
diff --git a/bsps/powerpc/mvme5500/include/tm27.h b/bsps/powerpc/mvme5500/include/tm27.h
new file mode 100644
index 0000000000..2a80618cfb
--- /dev/null
+++ b/bsps/powerpc/mvme5500/include/tm27.h
@@ -0,0 +1,66 @@
+/*
+ * @file
+ * @ingroup powerpc_mvme5500
+ * @brief Implementations for interrupt mechanisms for Time Test 27
+ */
+
+/*
+ * 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 _RTEMS_TMTEST27
+#error "This is an RTEMS internal file you must not include directly."
+#endif
+
+#ifndef __tm27_h
+#define __tm27_h
+
+#include <bsp/irq.h>
+
+/*
+ * Stuff for Time Test 27
+ */
+
+#define MUST_WAIT_FOR_INTERRUPT 1
+
+void nullFunc() {}
+static rtems_irq_connect_data clockIrqData = {BSP_DECREMENTER,
+ 0,
+ (rtems_irq_enable)nullFunc,
+ (rtems_irq_disable)nullFunc,
+ (rtems_irq_is_enabled) nullFunc};
+
+void Install_tm27_vector(void (*_handler)())
+{
+ clockIrqData.hdl = _handler;
+ if (!BSP_install_rtems_irq_handler (&clockIrqData)) {
+ printk("Error installing clock interrupt handler!\n");
+ rtems_fatal_error_occurred(1);
+ }
+}
+
+#define Cause_tm27_intr() \
+ do { \
+ uint32_t _clicks = 1; \
+ __asm__ volatile( "mtdec %0" : "=r" ((_clicks)) : "r" ((_clicks)) ); \
+ } while (0)
+
+
+#define Clear_tm27_intr() \
+ do { \
+ uint32_t _clicks = 0xffffffff; \
+ __asm__ volatile( "mtdec %0" : "=r" ((_clicks)) : "r" ((_clicks)) ); \
+ } while (0)
+
+#define Lower_tm27_intr() \
+ do { \
+ uint32_t _msr = 0; \
+ _ISR_Set_level( 0 ); \
+ __asm__ volatile( "mfmsr %0 ;" : "=r" (_msr) : "r" (_msr) ); \
+ _msr |= 0x8002; \
+ __asm__ volatile( "mtmsr %0 ;" : "=r" (_msr) : "r" (_msr) ); \
+ } while (0)
+
+#endif