class BaseTsunami(Tsunami):
ethernet = NSGigE(configdata=NSGigEPciData(),
pci_bus=0, pci_dev=1, pci_func=0)
- etherint = NSGigEInt(device=Parent.ethernet)
ide = IdeController(disks=[Parent.disk0, Parent.disk2],
pci_func=0, pci_dev=0, pci_bus=0)
self = Root()
self.testsys = testSystem
self.drivesys = driveSystem
- self.etherlink = EtherLink(int1 = Parent.testsys.tsunami.etherint[0],
- int2 = Parent.drivesys.tsunami.etherint[0])
+ self.etherlink = EtherLink()
+ self.etherlink.int0 = Parent.testsys.tsunami.ethernet.interface
+ self.etherlink.int1 = Parent.drivesys.tsunami.ethernet.interface
+
if dumpfile:
self.etherdump = EtherDump(file=dumpfile)
self.etherlink.dump = Parent.etherdump
from m5.proxy import *
from Pci import PciDevice, PciConfigData
-class EtherInt(SimObject):
- type = 'EtherInt'
+class EtherObject(SimObject):
+ type = 'EtherObject'
abstract = True
- peer = Param.EtherInt(NULL, "peer interface")
-class EtherLink(SimObject):
+class EtherLink(EtherObject):
type = 'EtherLink'
- int1 = Param.EtherInt("interface 1")
- int2 = Param.EtherInt("interface 2")
+ int0 = Port("interface 0")
+ int1 = Port("interface 1")
delay = Param.Latency('0us', "packet transmit delay")
delay_var = Param.Latency('0ns', "packet transmit delay variability")
speed = Param.NetworkBandwidth('1Gbps', "link speed")
dump = Param.EtherDump(NULL, "dump object")
-class EtherBus(SimObject):
+class EtherBus(EtherObject):
type = 'EtherBus'
loopback = Param.Bool(True, "send packet back to the sending interface")
dump = Param.EtherDump(NULL, "dump object")
speed = Param.NetworkBandwidth('100Mbps', "bus speed in bits per second")
-class EtherTap(EtherInt):
+class EtherTap(EtherObject):
type = 'EtherTap'
bufsz = Param.Int(10000, "tap buffer size")
dump = Param.EtherDump(NULL, "dump object")
file = Param.String("dump file")
maxlen = Param.Int(96, "max portion of packet data to dump")
-class IGbE(PciDevice):
+class EtherDevice(PciDevice):
+ type = 'EtherDevice'
+ abstract = True
+ interface = Port("Ethernet Interrface")
+
+class IGbE(EtherDevice):
type = 'IGbE'
hardware_address = Param.EthernetAddr(NextEthernetAddr,
"Ethernet Hardware Address")
InterruptPin = 0x01
BAR0Size = '128kB'
-class IGbEInt(EtherInt):
- type = 'IGbEInt'
- device = Param.IGbE("Ethernet device of this interface")
-
-class EtherDevBase(PciDevice):
+class EtherDevBase(EtherDevice):
type = 'EtherDevBase'
abstract = True
hardware_address = Param.EthernetAddr(NextEthernetAddr,
configdata = NSGigEPciData()
-class NSGigEInt(EtherInt):
- type = 'NSGigEInt'
- device = Param.NSGigE("Ethernet device of this interface")
-
class SinicPciData(PciConfigData):
VendorID = 0x1291
DeviceID = 0x1293
configdata = SinicPciData()
-class SinicInt(EtherInt):
- type = 'SinicInt'
- cxx_namespace = 'Sinic'
- cxx_class = 'Interface'
-
- device = Param.Sinic("Ethernet device of this interface")
using namespace std;
-EtherBus::EtherBus(const string &name, double speed, bool loop,
- EtherDump *packet_dump)
- : SimObject(name), ticksPerByte(speed), loopback(loop),
- event(&mainEventQueue, this), sender(0), dump(packet_dump)
+EtherBus::EtherBus(const Params *p)
+ : EtherObject(p), ticksPerByte(p->speed), loopback(p->loopback),
+ event(&mainEventQueue, this), sender(0), dump(p->dump)
{
}
packet = 0;
}
-void
-EtherBus::reg(EtherInt *dev)
-{ devlist.push_back(dev); }
+EtherInt*
+EtherBus::getEthPort(const std::string &if_name, int idx)
+{
+ panic("Etherbus doesn't work\n");
+}
bool
EtherBus::send(EtherInt *sndr, EthPacketPtr &pkt)
EtherBus *
EtherBusParams::create()
{
- return new EtherBus(name, speed, loopback, dump);
+ return new EtherBus(this);
}
#include "sim/eventq.hh"
#include "dev/etherpkt.hh"
+#include "dev/etherobject.hh"
+#include "params/EtherBus.hh"
#include "sim/sim_object.hh"
class EtherDump;
class EtherInt;
-class EtherBus : public SimObject
+class EtherBus : public EtherObject
{
protected:
typedef std::list<EtherInt *> devlist_t;
EtherDump *dump;
public:
- EtherBus(const std::string &name, double speed, bool loopback,
- EtherDump *dump);
+ typedef EtherBusParams Params;
+ EtherBus(const Params *p);
virtual ~EtherBus() {}
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
void txDone();
void reg(EtherInt *dev);
bool busy() const { return (bool)packet; }
bool send(EtherInt *sender, EthPacketPtr &packet);
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
};
#endif // __ETHERBUS_H__
--- /dev/null
+/*
+ * Copyright (c) 2007 The Regents of The University of Michigan
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met: redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer;
+ * 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;
+ * neither the name of the copyright holders nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * Authors: Ali Saidi
+ */
+
+/**
+ * @file
+ * Base Ethernet Device declaration.
+ */
+
+#ifndef __DEV_ETHERDEVICE_HH__
+#define __DEV_ETHERDEVICE_HH__
+
+#include "dev/pcidev.hh"
+#include "params/EtherDevice.hh"
+#include "sim/sim_object.hh"
+
+class EtherInt;
+
+/**
+ * The base EtherObject class, allows for an accesor function to a
+ * simobj that returns the Port.
+ */
+class EtherDevice : public PciDev
+{
+ public:
+ typedef EtherDeviceParams Params;
+ EtherDevice(const Params *params)
+ : PciDev(params)
+ {}
+
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
+ public:
+ /** Additional function to return the Port of a memory object. */
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx = -1) = 0;
+
+};
+
+#endif //__DEV_ETHERDEVICE_HH__
#include <string>
#include "dev/etherpkt.hh"
-#include "sim/sim_object.hh"
/*
* Class representing the actual interface between two ethernet
* components. These components are intended to attach to another
* ethernet interface on one side and whatever device on the other.
*/
-class EtherInt : public SimObject
+class EtherInt
{
protected:
+ mutable std::string portName;
EtherInt *peer;
public:
- EtherInt(const std::string &name) : SimObject(name), peer(NULL) {}
+ EtherInt(const std::string &name)
+ : portName(name), peer(NULL) {}
virtual ~EtherInt() {}
+ /** Return port name (for DPRINTF). */
+ const std::string &name() const { return portName; }
+
void setPeer(EtherInt *p);
+ EtherInt* getPeer() { return peer; }
void recvDone() { peer->sendDone(); }
virtual void sendDone() = 0;
using namespace std;
-EtherLink::EtherLink(const string &name, EtherInt *peer0, EtherInt *peer1,
- double rate, Tick delay, Tick delayVar, EtherDump *dump)
- : SimObject(name)
+EtherLink::EtherLink(const Params *p)
+ : EtherObject(p)
{
- link[0] = new Link(name + ".link0", this, 0, rate, delay, delayVar, dump);
- link[1] = new Link(name + ".link1", this, 1, rate, delay, delayVar, dump);
+ link[0] = new Link(name() + ".link0", this, 0, params()->speed,
+ params()->delay, params()->delay_var, params()->dump);
+ link[1] = new Link(name() + ".link1", this, 1, params()->speed,
+ params()->delay, params()->delay_var, params()->dump);
- interface[0] = new Interface(name + ".int0", link[0], link[1]);
- interface[1] = new Interface(name + ".int1", link[1], link[0]);
-
- interface[0]->setPeer(peer0);
- peer0->setPeer(interface[0]);
- interface[1]->setPeer(peer1);
- peer1->setPeer(interface[1]);
+ interface[0] = new Interface(name() + ".int0", link[0], link[1]);
+ interface[1] = new Interface(name() + ".int1", link[1], link[0]);
}
+
EtherLink::~EtherLink()
{
delete link[0];
delete interface[1];
}
+EtherInt*
+EtherLink::getEthPort(const std::string &if_name, int idx)
+{
+ Interface *i;
+ if (if_name == "int0")
+ i = interface[0];
+ else if (if_name == "int1")
+ i = interface[1];
+ else
+ return NULL;
+ if (i->getPeer())
+ panic("interface already connected to\n");
+
+ return i;
+}
+
+
EtherLink::Interface::Interface(const string &name, Link *tx, Link *rx)
: EtherInt(name), txlink(tx)
{
EtherLink *
EtherLinkParams::create()
{
- return new EtherLink(name, int1, int2, speed, delay, delay_var, dump);
+ return new EtherLink(this);
}
#ifndef __DEV_ETHERLINK_HH__
#define __DEV_ETHERLINK_HH__
+#include "dev/etherobject.hh"
#include "dev/etherint.hh"
#include "dev/etherpkt.hh"
+#include "params/EtherLink.hh"
#include "sim/eventq.hh"
#include "sim/host.hh"
#include "sim/sim_object.hh"
/*
* Model for a fixed bandwidth full duplex ethernet link
*/
-class EtherLink : public SimObject
+class EtherLink : public EtherObject
{
protected:
class Interface;
};
Link *link[2];
- EtherInt *interface[2];
+ Interface *interface[2];
public:
- EtherLink(const std::string &name, EtherInt *peer0, EtherInt *peer1,
- double rate, Tick delay, Tick delayVar, EtherDump *dump);
+ typedef EtherLinkParams Params;
+ EtherLink(const Params *p);
virtual ~EtherLink();
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
+
virtual void serialize(std::ostream &os);
virtual void unserialize(Checkpoint *cp, const std::string §ion);
--- /dev/null
+/*
+ * Copyright (c) 2007 The Regents of The University of Michigan
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met: redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer;
+ * 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;
+ * neither the name of the copyright holders nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * Authors: Ali Saidi
+ */
+
+/**
+ * @file
+ * Base Ethernet Object declaration.
+ */
+
+#ifndef __DEV_ETHEROBJECT_HH__
+#define __DEV_ETHEROBJECT_HH__
+
+#include "params/EtherObject.hh"
+#include "sim/sim_object.hh"
+
+class EtherInt;
+
+/**
+ * The base EtherObject class, allows for an accesor function to a
+ * simobj that returns the Port.
+ */
+class EtherObject : public SimObject
+{
+ public:
+ typedef EtherObjectParams Params;
+ EtherObject(const Params *params)
+ : SimObject(params) {}
+
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
+ public:
+ /** Additional function to return the Port of a memory object. */
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx = -1) = 0;
+
+};
+
+#endif //__MEM_MEM_OBJECT_HH__
int slack;
public:
- EthPacketData() : data(NULL), length(0), slack(0) { }
+ EthPacketData() : data(NULL), length(0), slack(0)
+ { }
+
explicit EthPacketData(size_t size)
- : data(new uint8_t[size]), length(0), slack(0) { }
+ : data(new uint8_t[size]), length(0), slack(0)
+ { }
+
EthPacketData(std::auto_ptr<uint8_t> d, int l, int s = 0)
- : data(d.release()), length(l), slack(s) { }
+ : data(d.release()), length(l), slack(s)
+ { }
+
~EthPacketData() { if (data) delete [] data; }
public:
#include "dev/etherint.hh"
#include "dev/etherpkt.hh"
#include "dev/ethertap.hh"
-#include "params/EtherTap.hh"
using namespace std;
virtual void process(int revent) { tap->process(revent); }
};
-EtherTap::EtherTap(const string &name, EtherDump *d, int port, int bufsz)
- : EtherInt(name), event(NULL), socket(-1), buflen(bufsz), dump(d),
- txEvent(this)
+EtherTap::EtherTap(const Params *p)
+ : EtherObject(p), event(NULL), socket(-1), buflen(p->bufsz), dump(p->dump),
+ interface(NULL), txEvent(this)
{
buffer = new char[buflen];
- listener = new TapListener(this, port);
+ listener = new TapListener(this, p->port);
listener->listen();
+ interface = new EtherTapInt(name() + ".interface", this);
}
EtherTap::~EtherTap()
write(socket, &len, sizeof(len));
write(socket, packet->data, packet->length);
- recvDone();
+ interface->recvDone();
return true;
}
DPRINTF(Ethernet, "EtherTap input len=%d\n", packet->length);
DDUMP(EthernetData, packet->data, packet->length);
- if (!sendPacket(packet)) {
+ if (!interface->sendPacket(packet)) {
DPRINTF(Ethernet, "bus busy...buffer for retransmission\n");
packetBuffer.push(packet);
if (!txEvent.scheduled())
return;
EthPacketPtr packet = packetBuffer.front();
- if (sendPacket(packet)) {
+ if (interface->sendPacket(packet)) {
if (dump)
dump->dump(packet);
DPRINTF(Ethernet, "EtherTap retransmit\n");
txEvent.schedule(curTick + retryTime);
}
+EtherInt*
+EtherTap::getEthPort(const std::string &if_name, int idx)
+{
+ if (if_name == "tap") {
+ if (interface->getPeer())
+ panic("Interface already connected to\n");
+ return interface;
+ }
+ return NULL;
+}
+
+
//=====================================================================
void
EtherTap *
EtherTapParams::create()
{
- EtherTap *tap = new EtherTap(name, dump, port, bufsz);
-
- if (peer) {
- tap->setPeer(peer);
- peer->setPeer(tap);
- }
-
- return tap;
+ return new EtherTap(this);
}
#include <queue>
#include <string>
+#include "base/pollevent.hh"
+#include "dev/etherobject.hh"
#include "dev/etherint.hh"
#include "dev/etherpkt.hh"
+#include "params/EtherTap.hh"
#include "sim/eventq.hh"
-#include "base/pollevent.hh"
#include "sim/sim_object.hh"
class TapEvent;
class TapListener;
+class EtherTapInt;
/*
* Interface to connect a simulated ethernet device to the real world
*/
-class EtherTap : public EtherInt
+class EtherTap : public EtherObject
{
protected:
friend class TapEvent;
protected:
std::string device;
std::queue<EthPacketPtr> packetBuffer;
+ EtherTapInt *interface;
void process(int revent);
void enqueue(EthPacketData *packet);
TxEvent txEvent;
public:
- EtherTap(const std::string &name, EtherDump *dump, int port, int bufsz);
+ typedef EtherTapParams Params;
+ EtherTap(const Params *p);
virtual ~EtherTap();
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
+
virtual bool recvPacket(EthPacketPtr packet);
virtual void sendDone();
virtual void unserialize(Checkpoint *cp, const std::string §ion);
};
+class EtherTapInt : public EtherInt
+{
+ private:
+ EtherTap *tap;
+ public:
+ EtherTapInt(const std::string &name, EtherTap *t)
+ : EtherInt(name), tap(t)
+ { }
+
+ virtual bool recvPacket(EthPacketPtr pkt) { return tap->recvPacket(pkt); }
+ virtual void sendDone() { tap->sendDone(); }
+};
+
+
#endif // __ETHERTAP_HH__
#include "mem/packet.hh"
#include "mem/packet_access.hh"
#include "params/IGbE.hh"
-#include "params/IGbEInt.hh"
#include "sim/stats.hh"
#include "sim/system.hh"
using namespace iGbReg;
using namespace Net;
-IGbE::IGbE(Params *p)
- : PciDev(p), etherInt(NULL), drainEvent(NULL), useFlowControl(p->use_flow_control),
+IGbE::IGbE(const Params *p)
+ : EtherDevice(p), etherInt(NULL), drainEvent(NULL), useFlowControl(p->use_flow_control),
rxFifo(p->rx_fifo_size), txFifo(p->tx_fifo_size), rxTick(false),
txTick(false), txFifoTick(false), rdtrEvent(this), radvEvent(this),
tadvEvent(this), tidvEvent(this), tickEvent(this), interEvent(this),
rxDescCache(this, name()+".RxDesc", p->rx_desc_cache_size),
txDescCache(this, name()+".TxDesc", p->tx_desc_cache_size), clock(p->clock)
{
+ etherInt = new IGbEInt(name() + ".int", this);
+
// Initialized internal registers per Intel documentation
// All registers intialized to 0 by per register constructor
regs.ctrl.fd(1);
txFifo.clear();
}
+EtherInt*
+IGbE::getEthPort(const std::string &if_name, int idx)
+{
+
+ if (if_name == "interface" && !etherInt) {
+ if (etherInt->getPeer())
+ panic("Port already connected to\n");
+ return etherInt;
+ }
+ return NULL;
+}
Tick
IGbE::writeConfig(PacketPtr pkt)
rxDescCache.unserialize(cp, csprintf("%s.RxDescCache", section));
}
-IGbEInt *
-IGbEIntParams::create()
-{
- IGbEInt *dev_int = new IGbEInt(name, device);
-
- EtherInt *p = (EtherInt *)peer;
- if (p) {
- dev_int->setPeer(p);
- p->setPeer(dev_int);
- }
-
- return dev_int;
-}
-
IGbE *
IGbEParams::create()
{
#include "base/inet.hh"
#include "base/statistics.hh"
+#include "dev/etherdevice.hh"
#include "dev/etherint.hh"
#include "dev/etherpkt.hh"
#include "dev/i8254xGBe_defs.hh"
class IGbEInt;
-class IGbE : public PciDev
+class IGbE : public EtherDevice
{
private:
IGbEInt *etherInt;
{
return dynamic_cast<const Params *>(_params);
}
- IGbE(Params *params);
+ IGbE(const Params *params);
~IGbE() {}
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
+
Tick clock;
inline Tick cycles(int numCycles) const { return numCycles * clock; }
bool ethRxPkt(EthPacketPtr packet);
void ethTxDone();
- void setEthInt(IGbEInt *i) { assert(!etherInt); etherInt = i; }
-
virtual void serialize(std::ostream &os);
virtual void unserialize(Checkpoint *cp, const std::string §ion);
virtual unsigned int drain(Event *de);
public:
IGbEInt(const std::string &name, IGbE *d)
: EtherInt(name), dev(d)
- { dev->setEthInt(this); }
+ { }
virtual bool recvPacket(EthPacketPtr pkt) { return dev->ethRxPkt(pkt); }
virtual void sendDone() { dev->ethTxDone(); }
#include "mem/packet.hh"
#include "mem/packet_access.hh"
#include "params/NSGigE.hh"
-#include "params/NSGigEInt.hh"
#include "sim/debug.hh"
#include "sim/host.hh"
#include "sim/stats.hh"
// NSGigE PCI Device
//
NSGigE::NSGigE(Params *p)
- : PciDev(p), ioEnable(false),
+ : EtherDevice(p), ioEnable(false),
txFifo(p->tx_fifo_size), rxFifo(p->rx_fifo_size),
txPacket(0), rxPacket(0), txPacketBufPtr(NULL), rxPacketBufPtr(NULL),
txXferLen(0), rxXferLen(0), rxDmaFree(false), txDmaFree(false),
{
+ interface = new NSGigEInt(name() + ".int0", this);
+
regsReset();
memcpy(&rom.perfectMatch, p->hardware_address.bytes(), ETH_ADDR_LEN);
return configDelay;
}
+EtherInt*
+NSGigE::getEthPort(const std::string &if_name, int idx)
+{
+ if (if_name == "interface") {
+ if (interface->getPeer())
+ panic("interface already connected to\n");
+ return interface;
+ }
+ return NULL;
+}
+
/**
* This reads the device registers, which are detailed in the NS83820
* spec sheet
}
}
-NSGigEInt *
-NSGigEIntParams::create()
-{
- NSGigEInt *dev_int = new NSGigEInt(name, device);
-
- EtherInt *p = (EtherInt *)peer;
- if (p) {
- dev_int->setPeer(p);
- p->setPeer(dev_int);
- }
-
- return dev_int;
-}
-
NSGigE *
NSGigEParams::create()
{
#include "base/inet.hh"
#include "base/statistics.hh"
+#include "dev/etherdevice.hh"
#include "dev/etherint.hh"
#include "dev/etherpkt.hh"
#include "dev/io_device.hh"
#include "dev/ns_gige_reg.h"
-#include "dev/pcidev.hh"
#include "dev/pktfifo.hh"
#include "params/NSGigE.hh"
#include "sim/eventq.hh"
/**
* NS DP83820 Ethernet device model
*/
-class NSGigE : public PciDev
+class NSGigE : public EtherDevice
{
public:
/** Transmit State Machine states */
NSGigE(Params *params);
~NSGigE();
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
+
virtual Tick writeConfig(PacketPtr pkt);
virtual Tick read(PacketPtr pkt);
bool recvPacket(EthPacketPtr packet);
void transferDone();
- void setInterface(NSGigEInt *i) { assert(!interface); interface = i; }
-
virtual void serialize(std::ostream &os);
virtual void unserialize(Checkpoint *cp, const std::string §ion);
public:
NSGigEInt(const std::string &name, NSGigE *d)
- : EtherInt(name), dev(d) { dev->setInterface(this); }
+ : EtherInt(name), dev(d)
+ { }
virtual bool recvPacket(EthPacketPtr pkt) { return dev->recvPacket(pkt); }
virtual void sendDone() { dev->transferDone(); }
}
-PciDev::PciDev(Params *p)
+PciDev::PciDev(const Params *p)
: DmaDevice(p), plat(p->platform), configData(p->configdata),
pioDelay(p->pio_latency), configDelay(p->config_latency),
configPort(NULL)
* config file object PCIConfigData and registers the device with
* a PciConfigAll object.
*/
- PciDev(Params *params);
+ PciDev(const Params *params);
virtual void init();
//
// Sinic PCI Device
//
-Base::Base(Params *p)
+Base::Base(const Params *p)
: PciDev(p), rxEnable(false), txEnable(false), clock(p->clock),
intrDelay(p->intr_delay), intrTick(0), cpuIntrEnable(false),
cpuPendingIntr(false), intrEvent(0), interface(NULL)
{
}
-Device::Device(Params *p)
+Device::Device(const Params *p)
: Base(p), rxUnique(0), txUnique(0),
virtualRegs(p->virtual_count < 1 ? 1 : p->virtual_count),
rxFifo(p->rx_fifo_size), txFifo(p->tx_fifo_size),
dmaReadDelay(p->dma_read_delay), dmaReadFactor(p->dma_read_factor),
dmaWriteDelay(p->dma_write_delay), dmaWriteFactor(p->dma_write_factor)
{
+ interface = new Interface(name() + ".int0", this);
reset();
}
rxPacketRate = rxPackets / simSeconds;
}
+EtherInt*
+Device::getEthPort(const std::string &if_name, int idx)
+{
+ if (if_name == "interface") {
+ if (interface->getPeer())
+ panic("interface already connected to\n");
+
+ return interface;
+ }
+ return NULL;
+}
+
+
void
Device::prepareIO(int cpu, int index)
{
/* namespace Sinic */ }
-Sinic::Interface *
-SinicIntParams::create()
-{
- using namespace Sinic;
-
- Interface *dev_int = new Interface(name, device);
-
- if (peer) {
- dev_int->setPeer(peer);
- peer->setPeer(dev_int);
- }
-
- return dev_int;
-}
-
Sinic::Device *
SinicParams::create()
{
#include "dev/pktfifo.hh"
#include "dev/sinicreg.hh"
#include "params/Sinic.hh"
-#include "params/SinicInt.hh"
#include "sim/eventq.hh"
namespace Sinic {
public:
typedef SinicParams Params;
const Params *params() const { return (const Params *)_params; }
- Base(Params *p);
+ Base(const Params *p);
};
class Device : public Base
public:
bool recvPacket(EthPacketPtr packet);
void transferDone();
- void setInterface(Interface *i) { assert(!interface); interface = i; }
+ virtual EtherInt *getEthPort(const std::string &if_name, int idx);
/**
* DMA parameters
virtual void unserialize(Checkpoint *cp, const std::string §ion);
public:
- Device(Params *p);
+ Device(const Params *p);
~Device();
};
public:
Interface(const std::string &name, Device *d)
- : EtherInt(name), dev(d) { dev->setInterface(this); }
+ : EtherInt(name), dev(d)
+ { }
virtual bool recvPacket(EthPacketPtr pkt) { return dev->recvPacket(pkt); }
virtual void sendDone() { dev->transferDone(); }
#include "base/inifile.hh"
#include "base/output.hh"
+#include "dev/etherdevice.hh"
+#include "dev/etherobject.hh"
+#include "dev/etherint.hh"
#include "mem/mem_object.hh"
#include "mem/port.hh"
#include "sim/sim_object.hh"
return p;
}
+EtherInt *
+lookupEthPort(SimObject *so, const std::string &name, int i)
+{
+ EtherObject *eo = dynamic_cast<EtherObject *>(so);
+ EtherDevice *ed = dynamic_cast<EtherDevice *>(so);
+ if (eo == NULL && ed == NULL) {
+ warn("error casting SimObject %s", so->name());
+ return NULL;
+ }
+
+ EtherInt *p = NULL;
+ if (eo)
+ p = eo->getEthPort(name, i);
+ else
+ p = ed->getEthPort(name, i);
+ return p;
+}
/**
* Connect the described MemObject ports. Called from Python via SWIG.
connectPorts(SimObject *o1, const std::string &name1, int i1,
SimObject *o2, const std::string &name2, int i2)
{
+ EtherObject *eo1, *eo2;
+ EtherDevice *ed1, *ed2;
+ MemObject *mo1, *mo2;
+
+ eo1 = dynamic_cast<EtherObject*>(o1);
+ ed1 = dynamic_cast<EtherDevice*>(o1);
+ mo1 = dynamic_cast<MemObject*>(o1);
+
+ eo2 = dynamic_cast<EtherObject*>(o2);
+ ed2 = dynamic_cast<EtherDevice*>(o2);
+ mo2 = dynamic_cast<MemObject*>(o2);
+
+ if ((eo1 || ed1) && (eo2 || ed2)) {
+ EtherInt *p1 = lookupEthPort(o1, name1, i1);
+ EtherInt *p2 = lookupEthPort(o2, name2, i2);
+
+ if (p1 != NULL && p2 != NULL) {
+
+ p1->setPeer(p2);
+ p2->setPeer(p1);
+
+ return 1;
+ }
+ }
+
Port *p1 = lookupPort(o1, name1, i1);
Port *p2 = lookupPort(o2, name2, i2);