summaryrefslogtreecommitdiff
path: root/src/mem/ruby
diff options
context:
space:
mode:
Diffstat (limited to 'src/mem/ruby')
-rw-r--r--src/mem/ruby/SConscript1
-rw-r--r--src/mem/ruby/network/MessageBuffer.cc6
-rw-r--r--src/mem/ruby/slicc_interface/AbstractController.cc164
-rw-r--r--src/mem/ruby/slicc_interface/AbstractController.hh65
-rw-r--r--src/mem/ruby/slicc_interface/Controller.py8
-rw-r--r--src/mem/ruby/structures/Cache.py1
-rw-r--r--src/mem/ruby/structures/DirectoryMemory.py2
-rw-r--r--src/mem/ruby/structures/MemoryControl.cc49
-rw-r--r--src/mem/ruby/structures/MemoryControl.hh114
-rw-r--r--src/mem/ruby/structures/MemoryControl.py39
-rw-r--r--src/mem/ruby/structures/MemoryNode.cc2
-rw-r--r--src/mem/ruby/structures/MemoryNode.hh12
-rw-r--r--src/mem/ruby/structures/MemoryVector.hh237
-rw-r--r--src/mem/ruby/structures/RubyMemoryControl.cc184
-rw-r--r--src/mem/ruby/structures/RubyMemoryControl.hh62
-rw-r--r--src/mem/ruby/structures/RubyMemoryControl.py10
-rw-r--r--src/mem/ruby/structures/SConscript2
-rw-r--r--src/mem/ruby/system/RubySystem.py4
-rw-r--r--src/mem/ruby/system/Sequencer.py2
-rw-r--r--src/mem/ruby/system/System.cc58
-rw-r--r--src/mem/ruby/system/System.hh14
21 files changed, 376 insertions, 660 deletions
diff --git a/src/mem/ruby/SConscript b/src/mem/ruby/SConscript
index 4200ddaeb..8133820b9 100644
--- a/src/mem/ruby/SConscript
+++ b/src/mem/ruby/SConscript
@@ -126,7 +126,6 @@ MakeInclude('structures/Prefetcher.hh')
MakeInclude('structures/CacheMemory.hh')
MakeInclude('system/DMASequencer.hh')
MakeInclude('structures/DirectoryMemory.hh')
-MakeInclude('structures/MemoryControl.hh')
MakeInclude('structures/WireBuffer.hh')
MakeInclude('structures/PerfectCacheMemory.hh')
MakeInclude('structures/PersistentTable.hh')
diff --git a/src/mem/ruby/network/MessageBuffer.cc b/src/mem/ruby/network/MessageBuffer.cc
index 1bc55c2c9..57a8d5519 100644
--- a/src/mem/ruby/network/MessageBuffer.cc
+++ b/src/mem/ruby/network/MessageBuffer.cc
@@ -144,16 +144,16 @@ random_time()
void
MessageBuffer::enqueue(MsgPtr message, Cycles delta)
{
- m_msg_counter++;
+ assert(m_ordering_set);
// record current time incase we have a pop that also adjusts my size
if (m_time_last_time_enqueue < m_sender->curCycle()) {
m_msgs_this_cycle = 0; // first msg this cycle
m_time_last_time_enqueue = m_sender->curCycle();
}
- m_msgs_this_cycle++;
- assert(m_ordering_set);
+ m_msg_counter++;
+ m_msgs_this_cycle++;
// Calculate the arrival time of the message, that is, the first
// cycle the message can be dequeued.
diff --git a/src/mem/ruby/slicc_interface/AbstractController.cc b/src/mem/ruby/slicc_interface/AbstractController.cc
index 366ea04ce..6bcbfbcbf 100644
--- a/src/mem/ruby/slicc_interface/AbstractController.cc
+++ b/src/mem/ruby/slicc_interface/AbstractController.cc
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2011 Mark D. Hill and David A. Wood
+ * Copyright (c) 2011-2014 Mark D. Hill and David A. Wood
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -26,21 +26,28 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
+#include "mem/protocol/MemoryMsg.hh"
#include "mem/ruby/slicc_interface/AbstractController.hh"
#include "mem/ruby/system/Sequencer.hh"
#include "mem/ruby/system/System.hh"
+#include "sim/system.hh"
AbstractController::AbstractController(const Params *p)
- : ClockedObject(p), Consumer(this)
+ : MemObject(p), Consumer(this), m_version(p->version),
+ m_clusterID(p->cluster_id),
+ m_masterId(p->system->getMasterId(name())), m_is_blocking(false),
+ m_number_of_TBEs(p->number_of_TBEs),
+ m_transitions_per_cycle(p->transitions_per_cycle),
+ m_buffer_size(p->buffer_size), m_recycle_latency(p->recycle_latency),
+ memoryPort(csprintf("%s.memory", name()), this, ""),
+ m_responseFromMemory_ptr(new MessageBuffer())
{
- m_version = p->version;
- m_clusterID = p->cluster_id;
-
- m_transitions_per_cycle = p->transitions_per_cycle;
- m_buffer_size = p->buffer_size;
- m_recycle_latency = p->recycle_latency;
- m_number_of_TBEs = p->number_of_TBEs;
- m_is_blocking = false;
+ // Set the sender pointer of the response message buffer from the
+ // memory controller.
+ // This pointer is used for querying for the current time.
+ m_responseFromMemory_ptr->setSender(this);
+ m_responseFromMemory_ptr->setReceiver(this);
+ m_responseFromMemory_ptr->setOrdering(false);
if (m_version == 0) {
// Combine the statistics from all controllers
@@ -187,3 +194,140 @@ AbstractController::unblock(Address addr)
m_is_blocking = false;
}
}
+
+BaseMasterPort &
+AbstractController::getMasterPort(const std::string &if_name,
+ PortID idx)
+{
+ return memoryPort;
+}
+
+void
+AbstractController::queueMemoryRead(const MachineID &id, Address addr,
+ Cycles latency)
+{
+ RequestPtr req = new Request(addr.getAddress(),
+ RubySystem::getBlockSizeBytes(), 0,
+ m_masterId);
+
+ PacketPtr pkt = Packet::createRead(req);
+ uint8_t *newData = new uint8_t[RubySystem::getBlockSizeBytes()];
+ pkt->dataDynamic(newData);
+
+ SenderState *s = new SenderState(id);
+ pkt->pushSenderState(s);
+
+ memoryPort.schedTimingReq(pkt, clockEdge(latency));
+}
+
+void
+AbstractController::queueMemoryWrite(const MachineID &id, Address addr,
+ Cycles latency, const DataBlock &block)
+{
+ RequestPtr req = new Request(addr.getAddress(),
+ RubySystem::getBlockSizeBytes(), 0,
+ m_masterId);
+
+ PacketPtr pkt = Packet::createWrite(req);
+ uint8_t *newData = new uint8_t[RubySystem::getBlockSizeBytes()];
+ pkt->dataDynamic(newData);
+ memcpy(newData, block.getData(0, RubySystem::getBlockSizeBytes()),
+ RubySystem::getBlockSizeBytes());
+
+ SenderState *s = new SenderState(id);
+ pkt->pushSenderState(s);
+
+ // Create a block and copy data from the block.
+ memoryPort.schedTimingReq(pkt, clockEdge(latency));
+}
+
+void
+AbstractController::queueMemoryWritePartial(const MachineID &id, Address addr,
+ Cycles latency,
+ const DataBlock &block, int size)
+{
+ RequestPtr req = new Request(addr.getAddress(),
+ RubySystem::getBlockSizeBytes(), 0,
+ m_masterId);
+
+ PacketPtr pkt = Packet::createWrite(req);
+ uint8_t *newData = new uint8_t[size];
+ pkt->dataDynamic(newData);
+ memcpy(newData, block.getData(addr.getOffset(), size), size);
+
+ SenderState *s = new SenderState(id);
+ pkt->pushSenderState(s);
+
+ // Create a block and copy data from the block.
+ memoryPort.schedTimingReq(pkt, clockEdge(latency));
+}
+
+void
+AbstractController::functionalMemoryRead(PacketPtr pkt)
+{
+ memoryPort.sendFunctional(pkt);
+}
+
+int
+AbstractController::functionalMemoryWrite(PacketPtr pkt)
+{
+ int num_functional_writes = 0;
+
+ // Check the message buffer that runs from the memory to the controller.
+ num_functional_writes += m_responseFromMemory_ptr->functionalWrite(pkt);
+
+ // Check the buffer from the controller to the memory.
+ if (memoryPort.checkFunctional(pkt)) {
+ num_functional_writes++;
+ }
+
+ // Update memory itself.
+ memoryPort.sendFunctional(pkt);
+ return num_functional_writes + 1;
+}
+
+void
+AbstractController::recvTimingResp(PacketPtr pkt)
+{
+ assert(pkt->isResponse());
+
+ std::shared_ptr<MemoryMsg> msg = std::make_shared<MemoryMsg>(clockEdge());
+ (*msg).m_Addr.setAddress(pkt->getAddr());
+ (*msg).m_Sender = m_machineID;
+
+ SenderState *s = dynamic_cast<SenderState *>(pkt->senderState);
+ (*msg).m_OriginalRequestorMachId = s->id;
+ delete s;
+
+ if (pkt->isRead()) {
+ (*msg).m_Type = MemoryRequestType_MEMORY_READ;
+ (*msg).m_MessageSize = MessageSizeType_Response_Data;
+
+ // Copy data from the packet
+ (*msg).m_DataBlk.setData(pkt->getPtr<uint8_t>(), 0,
+ RubySystem::getBlockSizeBytes());
+ } else if (pkt->isWrite()) {
+ (*msg).m_Type = MemoryRequestType_MEMORY_WB;
+ (*msg).m_MessageSize = MessageSizeType_Writeback_Control;
+ } else {
+ panic("Incorrect packet type received from memory controller!");
+ }
+
+ m_responseFromMemory_ptr->enqueue(msg);
+ delete pkt;
+}
+
+bool
+AbstractController::MemoryPort::recvTimingResp(PacketPtr pkt)
+{
+ controller->recvTimingResp(pkt);
+ return true;
+}
+
+AbstractController::MemoryPort::MemoryPort(const std::string &_name,
+ AbstractController *_controller,
+ const std::string &_label)
+ : QueuedMasterPort(_name, _controller, _queue),
+ _queue(*_controller, *this, _label), controller(_controller)
+{
+}
diff --git a/src/mem/ruby/slicc_interface/AbstractController.hh b/src/mem/ruby/slicc_interface/AbstractController.hh
index 98fce574f..45d355b3e 100644
--- a/src/mem/ruby/slicc_interface/AbstractController.hh
+++ b/src/mem/ruby/slicc_interface/AbstractController.hh
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2009 Mark D. Hill and David A. Wood
+ * Copyright (c) 2009-2014 Mark D. Hill and David A. Wood
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -43,12 +43,13 @@
#include "mem/ruby/network/Network.hh"
#include "mem/ruby/system/CacheRecorder.hh"
#include "mem/packet.hh"
+#include "mem/qport.hh"
#include "params/RubyController.hh"
-#include "sim/clocked_object.hh"
+#include "mem/mem_object.hh"
class Network;
-class AbstractController : public ClockedObject, public Consumer
+class AbstractController : public MemObject, public Consumer
{
public:
typedef RubyControllerParams Params;
@@ -79,10 +80,12 @@ class AbstractController : public ClockedObject, public Consumer
//! These functions are used by ruby system to read/write the data blocks
//! that exist with in the controller.
virtual void functionalRead(const Address &addr, PacketPtr) = 0;
+ void functionalMemoryRead(PacketPtr);
//! The return value indicates the number of messages written with the
//! data from the packet.
- virtual uint32_t functionalWriteBuffers(PacketPtr&) = 0;
+ virtual int functionalWriteBuffers(PacketPtr&) = 0;
virtual int functionalWrite(const Address &addr, PacketPtr) = 0;
+ int functionalMemoryWrite(PacketPtr);
//! Function for enqueuing a prefetch request
virtual void enqueuePrefetch(const Address&, const RubyRequestType&)
@@ -97,6 +100,17 @@ class AbstractController : public ClockedObject, public Consumer
//! Set the message buffer with given name.
virtual void setNetQueue(const std::string& name, MessageBuffer *b) = 0;
+ /** A function used to return the port associated with this bus object. */
+ BaseMasterPort& getMasterPort(const std::string& if_name,
+ PortID idx = InvalidPortID);
+
+ void queueMemoryRead(const MachineID &id, Address addr, Cycles latency);
+ void queueMemoryWrite(const MachineID &id, Address addr, Cycles latency,
+ const DataBlock &block);
+ void queueMemoryWritePartial(const MachineID &id, Address addr, Cycles latency,
+ const DataBlock &block, int size);
+ void recvTimingResp(PacketPtr pkt);
+
public:
MachineID getMachineID() const { return m_machineID; }
@@ -120,6 +134,9 @@ class AbstractController : public ClockedObject, public Consumer
MachineID m_machineID;
NodeID m_clusterID;
+ // MasterID used by some components of gem5.
+ MasterID m_masterId;
+
Network* m_net_ptr;
bool m_is_blocking;
std::map<Address, MessageBuffer*> m_block_map;
@@ -156,6 +173,46 @@ class AbstractController : public ClockedObject, public Consumer
StatsCallback(AbstractController *_ctr) : ctr(_ctr) {}
void process() {ctr->collateStats();}
};
+
+ /**
+ * Port that forwards requests and receives responses from the
+ * memory controller. It has a queue of packets not yet sent.
+ */
+ class MemoryPort : public QueuedMasterPort
+ {
+ private:
+ // Packet queue used to store outgoing requests and responses.
+ MasterPacketQueue _queue;
+
+ // Controller that operates this port.
+ AbstractController *controller;
+
+ public:
+ MemoryPort(const std::string &_name, AbstractController *_controller,
+ const std::string &_label);
+
+ // Function for receiving a timing response from the peer port.
+ // Currently the pkt is handed to the coherence controller
+ // associated with this port.
+ bool recvTimingResp(PacketPtr pkt);
+ };
+
+ /* Master port to the memory controller. */
+ MemoryPort memoryPort;
+
+ // Message Buffer for storing the response received from the
+ // memory controller.
+ MessageBuffer *m_responseFromMemory_ptr;
+
+ // State that is stored in packets sent to the memory controller.
+ struct SenderState : public Packet::SenderState
+ {
+ // Id of the machine from which the request originated.
+ MachineID id;
+
+ SenderState(MachineID _id) : id(_id)
+ {}
+ };
};
#endif // __MEM_RUBY_SLICC_INTERFACE_ABSTRACTCONTROLLER_HH__
diff --git a/src/mem/ruby/slicc_interface/Controller.py b/src/mem/ruby/slicc_interface/Controller.py
index f82e0a70d..ba7d17c7c 100644
--- a/src/mem/ruby/slicc_interface/Controller.py
+++ b/src/mem/ruby/slicc_interface/Controller.py
@@ -28,9 +28,10 @@
# Brad Beckmann
from m5.params import *
-from ClockedObject import ClockedObject
+from m5.proxy import *
+from MemObject import MemObject
-class RubyController(ClockedObject):
+class RubyController(MemObject):
type = 'RubyController'
cxx_class = 'AbstractController'
cxx_header = "mem/ruby/slicc_interface/AbstractController.hh"
@@ -46,4 +47,5 @@ class RubyController(ClockedObject):
number_of_TBEs = Param.Int(256, "")
ruby_system = Param.RubySystem("")
- peer = Param.RubyController(NULL, "")
+ memory = MasterPort("Port for attaching a memory controller")
+ system = Param.System(Parent.any, "system object parameter")
diff --git a/src/mem/ruby/structures/Cache.py b/src/mem/ruby/structures/Cache.py
index 14a359233..c6e165e3a 100644
--- a/src/mem/ruby/structures/Cache.py
+++ b/src/mem/ruby/structures/Cache.py
@@ -29,7 +29,6 @@
from m5.params import *
from m5.SimObject import SimObject
-from Controller import RubyController
class RubyCache(SimObject):
type = 'RubyCache'
diff --git a/src/mem/ruby/structures/DirectoryMemory.py b/src/mem/ruby/structures/DirectoryMemory.py
index c64439ce5..bb9765bdb 100644
--- a/src/mem/ruby/structures/DirectoryMemory.py
+++ b/src/mem/ruby/structures/DirectoryMemory.py
@@ -37,8 +37,6 @@ class RubyDirectoryMemory(SimObject):
cxx_header = "mem/ruby/structures/DirectoryMemory.hh"
version = Param.Int(0, "")
size = Param.MemorySize("1GB", "capacity in bytes")
- use_map = Param.Bool(False, "enable sparse memory")
- map_levels = Param.Int(4, "sparse memory map levels")
# the default value of the numa high bit is specified in the command line
# option and must be passed into the directory memory sim object
numa_high_bit = Param.Int("numa high bit")
diff --git a/src/mem/ruby/structures/MemoryControl.cc b/src/mem/ruby/structures/MemoryControl.cc
deleted file mode 100644
index 6c933b4d4..000000000
--- a/src/mem/ruby/structures/MemoryControl.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-/*
- * Copyright (c) 1999-2008 Mark D. Hill and David A. Wood
- * Copyright (c) 2012 Advanced Micro Devices, 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: 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.
- */
-
-#include "debug/RubyStats.hh"
-#include "mem/ruby/common/Global.hh"
-#include "mem/ruby/slicc_interface/RubySlicc_ComponentMapping.hh"
-#include "mem/ruby/structures/MemoryControl.hh"
-#include "mem/ruby/system/System.hh"
-
-using namespace std;
-MemoryControl::MemoryControl(const Params *p)
- : ClockedObject(p), Consumer(this), m_event(this)
-{
- g_system_ptr->registerMemController(this);
-}
-
-MemoryControl::~MemoryControl() {};
-
-void
-MemoryControl::recordRequestType(MemoryControlRequestType request) {
- DPRINTF(RubyStats, "Recorded request: %s\n",
- MemoryControlRequestType_to_string(request));
-}
diff --git a/src/mem/ruby/structures/MemoryControl.hh b/src/mem/ruby/structures/MemoryControl.hh
deleted file mode 100644
index b1cbe982f..000000000
--- a/src/mem/ruby/structures/MemoryControl.hh
+++ /dev/null
@@ -1,114 +0,0 @@
-/*
- * Copyright (c) 1999-2008 Mark D. Hill and David A. Wood
- * Copyright (c) 2012 Advanced Micro Devices, 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: 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.
- */
-
-#ifndef __MEM_RUBY_STRUCTURES_ABSTRACT_MEMORY_CONTROL_HH__
-#define __MEM_RUBY_STRUCTURES_ABSTRACT_MEMORY_CONTROL_HH__
-
-#include <iostream>
-#include <list>
-#include <string>
-
-#include "mem/protocol/MemoryControlRequestType.hh"
-#include "mem/ruby/common/Consumer.hh"
-#include "mem/ruby/slicc_interface/Message.hh"
-#include "mem/ruby/structures/MemoryNode.hh"
-#include "params/MemoryControl.hh"
-#include "sim/clocked_object.hh"
-
-//////////////////////////////////////////////////////////////////////////////
-
-class MemoryControl : public ClockedObject, public Consumer
-{
- public:
- typedef MemoryControlParams Params;
- const Params *params() const
- { return dynamic_cast<const Params *>(_params); }
-
- MemoryControl(const Params *p);
- virtual void init() = 0;
- virtual void reset() = 0;
-
- ~MemoryControl();
-
- virtual void wakeup() = 0;
-
- virtual void setConsumer(Consumer* consumer_ptr) = 0;
- virtual Consumer* getConsumer() = 0;
- virtual void setClockObj(ClockedObject* consumer_ptr) {}
-
- virtual void setDescription(const std::string& name) = 0;
- virtual std::string getDescription() = 0;
-
- // Called from the directory:
- virtual void enqueue(const MsgPtr& message, Cycles latency) = 0;
- virtual void enqueueMemRef(MemoryNode *memRef) = 0;
- virtual void dequeue() = 0;
- virtual const Message* peek() = 0;
- virtual MemoryNode *peekNode() = 0;
- virtual bool isReady() = 0;
- virtual bool areNSlotsAvailable(int n) = 0; // infinite queue length
-
- virtual void print(std::ostream& out) const = 0;
- virtual void regStats() {};
-
- virtual const int getChannel(const physical_address_t addr) const = 0;
- virtual const int getBank(const physical_address_t addr) const = 0;
- virtual const int getRank(const physical_address_t addr) const = 0;
- virtual const int getRow(const physical_address_t addr) const = 0;
-
- //added by SS
- virtual int getBanksPerRank() = 0;
- virtual int getRanksPerDimm() = 0;
- virtual int getDimmsPerChannel() = 0;
-
- virtual void recordRequestType(MemoryControlRequestType requestType);
-
- virtual bool functionalRead(Packet *pkt)
- { fatal("Functional read access not implemented!");}
- virtual uint32_t functionalWrite(Packet *pkt)
- { fatal("Functional read access not implemented!");}
-
-protected:
- class MemCntrlEvent : public Event
- {
- public:
- MemCntrlEvent(MemoryControl* _mem_cntrl)
- {
- mem_cntrl = _mem_cntrl;
- }
- private:
- void process() { mem_cntrl->wakeup(); }
-
- MemoryControl* mem_cntrl;
- };
-
- MemCntrlEvent m_event;
-};
-
-#endif // __MEM_RUBY_STRUCTURES_ABSTRACT_MEMORY_CONTROL_HH__
diff --git a/src/mem/ruby/structures/MemoryControl.py b/src/mem/ruby/structures/MemoryControl.py
deleted file mode 100644
index 8a6879cb9..000000000
--- a/src/mem/ruby/structures/MemoryControl.py
+++ /dev/null
@@ -1,39 +0,0 @@
-# Copyright (c) 2009 Advanced Micro Devices, 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: 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: Steve Reinhardt
-# Brad Beckmann
-
-from m5.params import *
-from ClockedObject import ClockedObject
-
-class MemoryControl(ClockedObject):
- abstract = True
- type = 'MemoryControl'
- cxx_class = 'MemoryControl'
- cxx_header = "mem/ruby/structures/MemoryControl.hh"
- version = Param.Int("");
- ruby_system = Param.RubySystem("")
diff --git a/src/mem/ruby/structures/MemoryNode.cc b/src/mem/ruby/structures/MemoryNode.cc
index 2a5cbb189..1e68cc459 100644
--- a/src/mem/ruby/structures/MemoryNode.cc
+++ b/src/mem/ruby/structures/MemoryNode.cc
@@ -36,6 +36,6 @@ MemoryNode::print(ostream& out) const
out << "[";
out << m_time << ", ";
out << m_msg_counter << ", ";
- out << m_msgptr << "; ";
+ out << pkt << "; ";
out << "]";
}
diff --git a/src/mem/ruby/structures/MemoryNode.hh b/src/mem/ruby/structures/MemoryNode.hh
index 3f40e3648..b48f64704 100644
--- a/src/mem/ruby/structures/MemoryNode.hh
+++ b/src/mem/ruby/structures/MemoryNode.hh
@@ -47,25 +47,23 @@ class MemoryNode
{
public:
// old constructor
- MemoryNode(const Cycles& time, int counter, const MsgPtr& msgptr,
+ MemoryNode(const Cycles& time, int counter, const PacketPtr p,
const physical_address_t addr, const bool is_mem_read)
- : m_time(time)
+ : m_time(time), pkt(p)
{
m_msg_counter = counter;
- m_msgptr = msgptr;
m_addr = addr;
m_is_mem_read = is_mem_read;
m_is_dirty_wb = !is_mem_read;
}
// new constructor
- MemoryNode(const Cycles& time, const MsgPtr& msgptr,
+ MemoryNode(const Cycles& time, const PacketPtr p,
const physical_address_t addr, const bool is_mem_read,
const bool is_dirty_wb)
- : m_time(time)
+ : m_time(time), pkt(p)
{
m_msg_counter = 0;
- m_msgptr = msgptr;
m_addr = addr;
m_is_mem_read = is_mem_read;
m_is_dirty_wb = is_dirty_wb;
@@ -75,7 +73,7 @@ class MemoryNode
Cycles m_time;
int m_msg_counter;
- MsgPtr m_msgptr;
+ PacketPtr pkt;
physical_address_t m_addr;
bool m_is_mem_read;
bool m_is_dirty_wb;
diff --git a/src/mem/ruby/structures/MemoryVector.hh b/src/mem/ruby/structures/MemoryVector.hh
deleted file mode 100644
index 384c68ad6..000000000
--- a/src/mem/ruby/structures/MemoryVector.hh
+++ /dev/null
@@ -1,237 +0,0 @@
-/*
- * Copyright (c) 2009 Mark D. Hill and David A. Wood
- * 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.
- */
-
-#ifndef __MEM_RUBY_STRUCTURES_MEMORYVECTOR_HH__
-#define __MEM_RUBY_STRUCTURES_MEMORYVECTOR_HH__
-
-#include "base/trace.hh"
-#include "debug/RubyCacheTrace.hh"
-#include "mem/ruby/common/Address.hh"
-
-class DirectoryMemory;
-
-/**
- * MemoryVector holds memory data (DRAM only)
- */
-class MemoryVector
-{
- public:
- MemoryVector();
- MemoryVector(uint64 size);
- ~MemoryVector();
- friend class DirectoryMemory;
-
- void resize(uint64 size); // destructive
-
- void write(const Address & paddr, uint8_t *data, int len);
- uint8_t *read(const Address & paddr, uint8_t *data, int len);
- uint32_t collatePages(uint8_t *&raw_data);
- void populatePages(uint8_t *raw_data);
-
- private:
- uint8_t *getBlockPtr(const PhysAddress & addr);
-
- uint64 m_size;
- uint8_t **m_pages;
- uint32_t m_num_pages;
- const uint32_t m_page_offset_mask;
- static const uint32_t PAGE_SIZE = 4096;
-};
-
-inline
-MemoryVector::MemoryVector()
- : m_page_offset_mask(4095)
-{
- m_size = 0;
- m_num_pages = 0;
- m_pages = NULL;
-}
-
-inline
-MemoryVector::MemoryVector(uint64 size)
- : m_page_offset_mask(4095)
-{
- resize(size);
-}
-
-inline
-MemoryVector::~MemoryVector()
-{
- for (int i = 0; i < m_num_pages; i++) {
- if (m_pages[i] != 0) {
- delete [] m_pages[i];
- }
- }
- delete [] m_pages;
-}
-
-inline void
-MemoryVector::resize(uint64 size)
-{
- if (m_pages != NULL){
- for (int i = 0; i < m_num_pages; i++) {
- if (m_pages[i] != 0) {
- delete [] m_pages[i];
- }
- }
- delete [] m_pages;
- }
- m_size = size;
- assert(size%PAGE_SIZE == 0);
- m_num_pages = size >> 12;
- m_pages = new uint8_t*[m_num_pages];
- memset(m_pages, 0, m_num_pages * sizeof(uint8_t*));
-}
-
-inline void
-MemoryVector::write(const Address & paddr, uint8_t *data, int len)
-{
- assert(paddr.getAddress() + len <= m_size);
- uint32_t page_num = paddr.getAddress() >> 12;
- if (m_pages[page_num] == 0) {
- bool all_zeros = true;
- for (int i = 0; i < len;i++) {
- if (data[i] != 0) {
- all_zeros = false;
- break;
- }
- }
- if (all_zeros)
- return;
- m_pages[page_num] = new uint8_t[PAGE_SIZE];
- memset(m_pages[page_num], 0, PAGE_SIZE);
- uint32_t offset = paddr.getAddress() & m_page_offset_mask;
- memcpy(&m_pages[page_num][offset], data, len);
- } else {
- memcpy(&m_pages[page_num][paddr.getAddress()&m_page_offset_mask],
- data, len);
- }
-}
-
-inline uint8_t*
-MemoryVector::read(const Address & paddr, uint8_t *data, int len)
-{
- assert(paddr.getAddress() + len <= m_size);
- uint32_t page_num = paddr.getAddress() >> 12;
- if (m_pages[page_num] == 0) {
- memset(data, 0, len);
- } else {
- memcpy(data, &m_pages[page_num][paddr.getAddress()&m_page_offset_mask],
- len);
- }
- return data;
-}
-
-inline uint8_t*
-MemoryVector::getBlockPtr(const PhysAddress & paddr)
-{
- uint32_t page_num = paddr.getAddress() >> 12;
- if (m_pages[page_num] == 0) {
- m_pages[page_num] = new uint8_t[PAGE_SIZE];
- memset(m_pages[page_num], 0, PAGE_SIZE);
- }
- return &m_pages[page_num][paddr.getAddress()&m_page_offset_mask];
-}
-
-/*!
- * Function for collating all the pages of the physical memory together.
- * In case a pointer for a page is NULL, this page needs only a single byte
- * to represent that the pointer is NULL. Otherwise, it needs 1 + PAGE_SIZE
- * bytes. The first represents that the page pointer is not NULL, and rest of
- * the bytes represent the data on the page.
- */
-
-inline uint32_t
-MemoryVector::collatePages(uint8_t *&raw_data)
-{
- uint32_t num_zero_pages = 0;
- uint32_t data_size = 0;
-
- for (uint32_t i = 0;i < m_num_pages; ++i)
- {
- if (m_pages[i] == 0) num_zero_pages++;
- }
-
- raw_data = new uint8_t[sizeof(uint32_t) /* number of pages*/ +
- m_num_pages /* whether the page is all zeros */ +
- PAGE_SIZE * (m_num_pages - num_zero_pages)];
-
- /* Write the number of pages to be stored. */
- memcpy(raw_data, &m_num_pages, sizeof(uint32_t));
- data_size = sizeof(uint32_t);
-
- DPRINTF(RubyCacheTrace, "collating %d pages\n", m_num_pages);
-
- for (uint32_t i = 0;i < m_num_pages; ++i)
- {
- if (m_pages[i] == 0) {
- raw_data[data_size] = 0;
- } else {
- raw_data[data_size] = 1;
- memcpy(raw_data + data_size + 1, m_pages[i], PAGE_SIZE);
- data_size += PAGE_SIZE;
- }
- data_size += 1;
- }
-
- return data_size;
-}
-
-/*!
- * Function for populating the pages of the memory using the available raw
- * data. Each page has a byte associate with it, which represents whether the
- * page was NULL or not, when all the pages were collated. The function assumes
- * that the number of pages in the memory are same as those that were recorded
- * in the checkpoint.
- */
-inline void
-MemoryVector::populatePages(uint8_t *raw_data)
-{
- uint32_t data_size = 0;
- uint32_t num_pages = 0;
-
- /* Read the number of pages that were stored. */
- memcpy(&num_pages, raw_data, sizeof(uint32_t));
- data_size = sizeof(uint32_t);
- assert(num_pages == m_num_pages);
-
- DPRINTF(RubyCacheTrace, "Populating %d pages\n", num_pages);
-
- for (uint32_t i = 0;i < m_num_pages; ++i)
- {
- assert(m_pages[i] == 0);
- if (raw_data[data_size] != 0) {
- m_pages[i] = new uint8_t[PAGE_SIZE];
- memcpy(m_pages[i], raw_data + data_size + 1, PAGE_SIZE);
- data_size += PAGE_SIZE;
- }
- data_size += 1;
- }
-}
-
-#endif // __MEM_RUBY_STRUCTURES_MEMORYVECTOR_HH__
diff --git a/src/mem/ruby/structures/RubyMemoryControl.cc b/src/mem/ruby/structures/RubyMemoryControl.cc
index 2e71c0c2f..a7a815adb 100644
--- a/src/mem/ruby/structures/RubyMemoryControl.cc
+++ b/src/mem/ruby/structures/RubyMemoryControl.cc
@@ -145,7 +145,8 @@ operator<<(ostream& out, const RubyMemoryControl& obj)
// CONSTRUCTOR
RubyMemoryControl::RubyMemoryControl(const Params *p)
- : MemoryControl(p)
+ : AbstractMemory(p), Consumer(this), port(name() + ".port", *this),
+ m_event(this)
{
m_banks_per_rank = p->banks_per_rank;
m_ranks_per_dimm = p->ranks_per_dimm;
@@ -173,9 +174,7 @@ RubyMemoryControl::RubyMemoryControl(const Params *p)
void
RubyMemoryControl::init()
{
- m_ram = g_system_ptr->getMemoryVector();
m_msg_counter = 0;
-
assert(m_tFaw <= 62); // must fit in a uint64 shift register
m_total_banks = m_banks_per_rank * m_ranks_per_dimm * m_dimms_per_channel;
@@ -221,6 +220,16 @@ RubyMemoryControl::init()
}
}
+BaseSlavePort&
+RubyMemoryControl::getSlavePort(const string &if_name, PortID idx)
+{
+ if (if_name != "port") {
+ return MemObject::getSlavePort(if_name, idx);
+ } else {
+ return port;
+ }
+}
+
void
RubyMemoryControl::reset()
{
@@ -275,30 +284,18 @@ RubyMemoryControl::~RubyMemoryControl()
}
// enqueue new request from directory
-void
-RubyMemoryControl::enqueue(const MsgPtr& message, Cycles latency)
+bool
+RubyMemoryControl::recvTimingReq(PacketPtr pkt)
{
- Cycles arrival_time = curCycle() + latency;
- const MemoryMsg* memMess = safe_cast<const MemoryMsg*>(message.get());
- physical_address_t addr = memMess->getAddr().getAddress();
- MemoryRequestType type = memMess->getType();
- bool is_mem_read = (type == MemoryRequestType_MEMORY_READ);
-
- if (is_mem_read) {
- m_ram->read(memMess->getAddr(), const_cast<uint8_t *>(
- memMess->getDataBlk().getData(0,
- RubySystem::getBlockSizeBytes())),
- RubySystem::getBlockSizeBytes());
- } else {
- m_ram->write(memMess->getAddr(), const_cast<uint8_t *>(
- memMess->getDataBlk().getData(0,
- RubySystem::getBlockSizeBytes())),
- RubySystem::getBlockSizeBytes());
- }
-
- MemoryNode *thisReq = new MemoryNode(arrival_time, message, addr,
+ Cycles arrival_time = curCycle();
+ physical_address_t addr = pkt->getAddr();
+ bool is_mem_read = pkt->isRead();
+
+ access(pkt);
+ MemoryNode *thisReq = new MemoryNode(arrival_time, pkt, addr,
is_mem_read, !is_mem_read);
enqueueMemRef(thisReq);
+ return true;
}
// Alternate entry point used when we already have a MemoryNode
@@ -325,51 +322,6 @@ RubyMemoryControl::enqueueMemRef(MemoryNode *memRef)
}
}
-// dequeue, peek, and isReady are used to transfer completed requests
-// back to the directory
-void
-RubyMemoryControl::dequeue()
-{
- assert(isReady());
- MemoryNode *req = m_response_queue.front();
- m_response_queue.pop_front();
- delete req;
-}
-
-const Message*
-RubyMemoryControl::peek()
-{
- MemoryNode *node = peekNode();
- Message* msg_ptr = node->m_msgptr.get();
- assert(msg_ptr != NULL);
- return msg_ptr;
-}
-
-MemoryNode *
-RubyMemoryControl::peekNode()
-{
- assert(isReady());
- MemoryNode *req = m_response_queue.front();
- DPRINTF(RubyMemory, "Peek: memory request%7d: %#08x %c sched %c\n",
- req->m_msg_counter, req->m_addr, req->m_is_mem_read ? 'R':'W',
- m_event.scheduled() ? 'Y':'N');
-
- return req;
-}
-
-bool
-RubyMemoryControl::isReady()
-{
- return ((!m_response_queue.empty()) &&
- (m_response_queue.front()->m_time <= g_system_ptr->curCycle()));
-}
-
-void
-RubyMemoryControl::setConsumer(Consumer* consumer_ptr)
-{
- m_consumer_ptr = consumer_ptr;
-}
-
void
RubyMemoryControl::print(ostream& out) const
{
@@ -380,15 +332,17 @@ void
RubyMemoryControl::enqueueToDirectory(MemoryNode *req, Cycles latency)
{
Tick arrival_time = clockEdge(latency);
- Cycles ruby_arrival_time = g_system_ptr->ticksToCycles(arrival_time);
- req->m_time = ruby_arrival_time;
- m_response_queue.push_back(req);
+ PacketPtr pkt = req->pkt;
+
+ // access already turned the packet into a response
+ assert(pkt->isResponse());
+
+ // queue the packet in the response queue to be sent out after
+ // the static latency has passed
+ port.schedTimingResp(pkt, arrival_time);
DPRINTF(RubyMemory, "Enqueueing msg %#08x %c back to directory at %15d\n",
req->m_addr, req->m_is_mem_read ? 'R':'W', arrival_time);
-
- // schedule the wake up
- m_consumer_ptr->scheduleEventAbsolute(arrival_time);
}
// getBank returns an integer that is unique for each
@@ -560,9 +514,8 @@ RubyMemoryControl::issueRequest(int bank)
req->m_is_mem_read? 'R':'W',
bank, m_event.scheduled() ? 'Y':'N');
- if (req->m_msgptr) { // don't enqueue L3 writebacks
- enqueueToDirectory(req, Cycles(m_mem_ctl_latency + m_mem_fixed_delay));
- }
+ enqueueToDirectory(req, Cycles(m_mem_ctl_latency + m_mem_fixed_delay));
+
m_oldRequest[bank] = 0;
markTfaw(rank);
m_bankBusyCounter[bank] = m_bank_busy_time;
@@ -724,16 +677,16 @@ RubyMemoryControl::functionalRead(Packet *pkt)
{
for (std::list<MemoryNode *>::iterator it = m_input_queue.begin();
it != m_input_queue.end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalRead(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
return true;
}
}
for (std::list<MemoryNode *>::iterator it = m_response_queue.begin();
it != m_response_queue.end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalRead(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
return true;
}
}
@@ -741,16 +694,14 @@ RubyMemoryControl::functionalRead(Packet *pkt)
for (uint32_t bank = 0; bank < m_total_banks; ++bank) {
for (std::list<MemoryNode *>::iterator it = m_bankQueues[bank].begin();
it != m_bankQueues[bank].end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalRead(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
return true;
}
}
}
- m_ram->read(Address(pkt->getAddr()), pkt->getPtr<uint8_t>(true),
- pkt->getSize());
-
+ functionalAccess(pkt);
return true;
}
@@ -769,16 +720,16 @@ RubyMemoryControl::functionalWrite(Packet *pkt)
for (std::list<MemoryNode *>::iterator it = m_input_queue.begin();
it != m_input_queue.end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalWrite(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
num_functional_writes++;
}
}
for (std::list<MemoryNode *>::iterator it = m_response_queue.begin();
it != m_response_queue.end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalWrite(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
num_functional_writes++;
}
}
@@ -786,17 +737,15 @@ RubyMemoryControl::functionalWrite(Packet *pkt)
for (uint32_t bank = 0; bank < m_total_banks; ++bank) {
for (std::list<MemoryNode *>::iterator it = m_bankQueues[bank].begin();
it != m_bankQueues[bank].end(); ++it) {
- Message* msg_ptr = (*it)->m_msgptr.get();
- if (msg_ptr->functionalWrite(pkt)) {
+ PacketPtr msg = (*it)->pkt;
+ if (pkt->checkFunctional(msg)) {
num_functional_writes++;
}
}
}
- m_ram->write(Address(pkt->getAddr()), pkt->getPtr<uint8_t>(true),
- pkt->getSize());
+ functionalAccess(pkt);
num_functional_writes++;
-
return num_functional_writes;
}
@@ -804,6 +753,7 @@ void
RubyMemoryControl::regStats()
{
m_profiler_ptr->regStats();
+ AbstractMemory::regStats();
}
RubyMemoryControl *
@@ -811,3 +761,45 @@ RubyMemoryControlParams::create()
{
return new RubyMemoryControl(this);
}
+
+RubyMemoryControl::MemoryPort::MemoryPort(const std::string& name,
+ RubyMemoryControl& _memory)
+ : QueuedSlavePort(name, &_memory, queue), queue(_memory, *this),
+ memory(_memory)
+{ }
+
+AddrRangeList
+RubyMemoryControl::MemoryPort::getAddrRanges() const
+{
+ AddrRangeList ranges;
+ ranges.push_back(memory.getAddrRange());
+ return ranges;
+}
+
+void
+RubyMemoryControl::MemoryPort::recvFunctional(PacketPtr pkt)
+{
+ pkt->pushLabel(memory.name());
+
+ if (!queue.checkFunctional(pkt)) {
+ // Default implementation of SimpleTimingPort::recvFunctional()
+ // calls recvAtomic() and throws away the latency; we can save a
+ // little here by just not calculating the latency.
+ memory.functionalWrite(pkt);
+ }
+
+ pkt->popLabel();
+}
+
+Tick
+RubyMemoryControl::MemoryPort::recvAtomic(PacketPtr pkt)
+{
+ panic("This controller does not support recv atomic!\n");
+}
+
+bool
+RubyMemoryControl::MemoryPort::recvTimingReq(PacketPtr pkt)
+{
+ // pass it to the memory controller
+ return memory.recvTimingReq(pkt);
+}
diff --git a/src/mem/ruby/structures/RubyMemoryControl.hh b/src/mem/ruby/structures/RubyMemoryControl.hh
index dde6143c4..6b1ec1702 100644
--- a/src/mem/ruby/structures/RubyMemoryControl.hh
+++ b/src/mem/ruby/structures/RubyMemoryControl.hh
@@ -34,12 +34,12 @@
#include <list>
#include <string>
+#include "mem/abstract_mem.hh"
#include "mem/protocol/MemoryMsg.hh"
#include "mem/ruby/common/Address.hh"
#include "mem/ruby/common/Global.hh"
#include "mem/ruby/profiler/MemCntrlProfiler.hh"
-#include "mem/ruby/structures/MemoryControl.hh"
-#include "mem/ruby/structures/MemoryVector.hh"
+#include "mem/ruby/structures/MemoryNode.hh"
#include "mem/ruby/system/System.hh"
#include "params/RubyMemoryControl.hh"
@@ -49,7 +49,7 @@
//////////////////////////////////////////////////////////////////////////////
-class RubyMemoryControl : public MemoryControl
+class RubyMemoryControl : public AbstractMemory, public Consumer
{
public:
typedef RubyMemoryControlParams Params;
@@ -59,22 +59,18 @@ class RubyMemoryControl : public MemoryControl
~RubyMemoryControl();
+ virtual BaseSlavePort& getSlavePort(const std::string& if_name,
+ PortID idx = InvalidPortID);
unsigned int drain(DrainManager *dm);
-
void wakeup();
- void setConsumer(Consumer* consumer_ptr);
- Consumer* getConsumer() { return m_consumer_ptr; };
void setDescription(const std::string& name) { m_description = name; };
std::string getDescription() { return m_description; };
// Called from the directory:
- void enqueue(const MsgPtr& message, Cycles latency);
+ bool recvTimingReq(PacketPtr pkt);
+ void recvFunctional(PacketPtr pkt);
void enqueueMemRef(MemoryNode *memRef);
- void dequeue();
- const Message* peek();
- MemoryNode *peekNode();
- bool isReady();
bool areNSlotsAvailable(int n) { return true; }; // infinite queue length
void print(std::ostream& out) const;
@@ -108,8 +104,34 @@ class RubyMemoryControl : public MemoryControl
RubyMemoryControl (const RubyMemoryControl& obj);
RubyMemoryControl& operator=(const RubyMemoryControl& obj);
+ private:
+ // For now, make use of a queued slave port to avoid dealing with
+ // flow control for the responses being sent back
+ class MemoryPort : public QueuedSlavePort
+ {
+ SlavePacketQueue queue;
+ RubyMemoryControl& memory;
+
+ public:
+ MemoryPort(const std::string& name, RubyMemoryControl& _memory);
+
+ protected:
+ Tick recvAtomic(PacketPtr pkt);
+
+ void recvFunctional(PacketPtr pkt);
+
+ bool recvTimingReq(PacketPtr);
+
+ virtual AddrRangeList getAddrRanges() const;
+ };
+
+ /**
+ * Our incoming port, for a multi-ported controller add a crossbar
+ * in front of it
+ */
+ MemoryPort port;
+
// data members
- Consumer* m_consumer_ptr; // Consumer to signal a wakeup()
std::string m_description;
int m_msg_counter;
@@ -163,8 +185,20 @@ class RubyMemoryControl : public MemoryControl
MemCntrlProfiler* m_profiler_ptr;
- // Actual physical memory.
- MemoryVector* m_ram;
+ class MemCntrlEvent : public Event
+ {
+ public:
+ MemCntrlEvent(RubyMemoryControl* _mem_cntrl)
+ {
+ mem_cntrl = _mem_cntrl;
+ }
+ private:
+ void process() { mem_cntrl->wakeup(); }
+
+ RubyMemoryControl* mem_cntrl;
+ };
+
+ MemCntrlEvent m_event;
};
std::ostream& operator<<(std::ostream& out, const RubyMemoryControl& obj);
diff --git a/src/mem/ruby/structures/RubyMemoryControl.py b/src/mem/ruby/structures/RubyMemoryControl.py
index f0828fb19..78f2d8dcb 100644
--- a/src/mem/ruby/structures/RubyMemoryControl.py
+++ b/src/mem/ruby/structures/RubyMemoryControl.py
@@ -28,14 +28,12 @@
# Brad Beckmann
from m5.params import *
-from m5.SimObject import SimObject
-from MemoryControl import MemoryControl
+from AbstractMemory import AbstractMemory
-class RubyMemoryControl(MemoryControl):
+class RubyMemoryControl(AbstractMemory):
type = 'RubyMemoryControl'
cxx_class = 'RubyMemoryControl'
cxx_header = "mem/ruby/structures/RubyMemoryControl.hh"
- version = Param.Int("");
banks_per_rank = Param.Int(8, "");
ranks_per_dimm = Param.Int(2, "");
@@ -53,3 +51,7 @@ class RubyMemoryControl(MemoryControl):
tFaw = Param.Int(0, "");
mem_random_arbitrate = Param.Int(0, "");
mem_fixed_delay = Param.Cycles(0, "");
+
+ # single-ported on the system interface side, instantiate with a
+ # crossbar in front of the controller for multiple ports
+ port = SlavePort("Slave port")
diff --git a/src/mem/ruby/structures/SConscript b/src/mem/ruby/structures/SConscript
index dee5769d3..ed00d7382 100644
--- a/src/mem/ruby/structures/SConscript
+++ b/src/mem/ruby/structures/SConscript
@@ -35,14 +35,12 @@ if env['PROTOCOL'] == 'None':
SimObject('Cache.py')
SimObject('DirectoryMemory.py')
-SimObject('MemoryControl.py')
SimObject('RubyMemoryControl.py')
SimObject('RubyPrefetcher.py')
SimObject('WireBuffer.py')
Source('DirectoryMemory.cc')
Source('CacheMemory.cc')
-Source('MemoryControl.cc')
Source('WireBuffer.cc')
Source('RubyMemoryControl.cc')
Source('MemoryNode.cc')
diff --git a/src/mem/ruby/system/RubySystem.py b/src/mem/ruby/system/RubySystem.py
index 0943fb3f6..77bd9448d 100644
--- a/src/mem/ruby/system/RubySystem.py
+++ b/src/mem/ruby/system/RubySystem.py
@@ -38,8 +38,8 @@ class RubySystem(ClockedObject):
"insert random delays on message enqueue times");
block_size_bytes = Param.UInt32(64,
"default cache block size; must be a power of two");
- mem_size = Param.MemorySize("total memory size of the system");
- no_mem_vec = Param.Bool(False, "do not allocate Ruby's mem vector");
+ memory_size_bits = Param.UInt32(64,
+ "number of bits that a memory address requires");
# Profiler related configuration variables
hot_lines = Param.Bool(False, "")
diff --git a/src/mem/ruby/system/Sequencer.py b/src/mem/ruby/system/Sequencer.py
index 6f64207dc..b54924ba7 100644
--- a/src/mem/ruby/system/Sequencer.py
+++ b/src/mem/ruby/system/Sequencer.py
@@ -55,7 +55,7 @@ class RubyPort(MemObject):
class RubyPortProxy(RubyPort):
type = 'RubyPortProxy'
cxx_header = "mem/ruby/system/RubyPortProxy.hh"
- access_phys_mem = True
+ access_phys_mem = False
class RubySequencer(RubyPort):
type = 'RubySequencer'
diff --git a/src/mem/ruby/system/System.cc b/src/mem/ruby/system/System.cc
index 8bcc87474..066cfae87 100644
--- a/src/mem/ruby/system/System.cc
+++ b/src/mem/ruby/system/System.cc
@@ -47,7 +47,6 @@ int RubySystem::m_random_seed;
bool RubySystem::m_randomization;
uint32_t RubySystem::m_block_size_bytes;
uint32_t RubySystem::m_block_size_bits;
-uint64_t RubySystem::m_memory_size_bytes;
uint32_t RubySystem::m_memory_size_bits;
RubySystem::RubySystem(const Params *p)
@@ -63,20 +62,7 @@ RubySystem::RubySystem(const Params *p)
m_block_size_bytes = p->block_size_bytes;
assert(isPowerOf2(m_block_size_bytes));
m_block_size_bits = floorLog2(m_block_size_bytes);
-
- m_memory_size_bytes = p->mem_size;
- if (m_memory_size_bytes == 0) {
- m_memory_size_bits = 0;
- } else {
- m_memory_size_bits = ceilLog2(m_memory_size_bytes);
- }
-
- if (p->no_mem_vec) {
- m_mem_vec = NULL;
- } else {
- m_mem_vec = new MemoryVector;
- m_mem_vec->resize(m_memory_size_bytes);
- }
+ m_memory_size_bits = p->memory_size_bits;
m_warmup_enabled = false;
m_cooldown_enabled = false;
@@ -108,17 +94,10 @@ RubySystem::registerAbstractController(AbstractController* cntrl)
g_abs_controls[id.getType()][id.getNum()] = cntrl;
}
-void
-RubySystem::registerMemController(MemoryControl *mc) {
- m_memory_controller_vec.push_back(mc);
-}
-
RubySystem::~RubySystem()
{
delete m_network;
delete m_profiler;
- if (m_mem_vec)
- delete m_mem_vec;
}
void
@@ -206,19 +185,8 @@ RubySystem::serialize(std::ostream &os)
// Restore curTick
setCurTick(curtick_original);
- uint8_t *raw_data = NULL;
- uint64 memory_trace_size = m_mem_vec->collatePages(raw_data);
-
- string memory_trace_file = name() + ".memory.gz";
- writeCompressedTrace(raw_data, memory_trace_file,
- memory_trace_size);
-
- SERIALIZE_SCALAR(memory_trace_file);
- SERIALIZE_SCALAR(memory_trace_size);
-
-
// Aggergate the trace entries together into a single array
- raw_data = new uint8_t[4096];
+ uint8_t *raw_data = new uint8_t[4096];
uint64 cache_trace_size = m_cache_recorder->aggregateRecords(&raw_data,
4096);
string cache_trace_file = name() + ".cache.gz";
@@ -272,22 +240,6 @@ RubySystem::unserialize(Checkpoint *cp, const string &section)
uint64 block_size_bytes = getBlockSizeBytes();
UNSERIALIZE_OPT_SCALAR(block_size_bytes);
- if (m_mem_vec != NULL) {
- string memory_trace_file;
- uint64 memory_trace_size = 0;
-
- UNSERIALIZE_SCALAR(memory_trace_file);
- UNSERIALIZE_SCALAR(memory_trace_size);
- memory_trace_file = cp->cptDir + "/" + memory_trace_file;
-
- readCompressedTrace(memory_trace_file, uncompressed_trace,
- memory_trace_size);
- m_mem_vec->populatePages(uncompressed_trace);
-
- delete [] uncompressed_trace;
- uncompressed_trace = NULL;
- }
-
string cache_trace_file;
uint64 cache_trace_size = 0;
@@ -355,12 +307,6 @@ RubySystem::startup()
m_cache_recorder = NULL;
m_warmup_enabled = false;
- // reset DRAM so that it's not waiting for events on the old event
- // queue
- for (int i = 0; i < m_memory_controller_vec.size(); ++i) {
- m_memory_controller_vec[i]->reset();
- }
-
// Restore eventq head
eventq_head = eventq->replaceHead(eventq_head);
// Restore curTick and Ruby System's clock
diff --git a/src/mem/ruby/system/System.hh b/src/mem/ruby/system/System.hh
index 8193764dc..81c6029c6 100644
--- a/src/mem/ruby/system/System.hh
+++ b/src/mem/ruby/system/System.hh
@@ -39,8 +39,6 @@
#include "base/output.hh"
#include "mem/ruby/profiler/Profiler.hh"
#include "mem/ruby/slicc_interface/AbstractController.hh"
-#include "mem/ruby/structures/MemoryControl.hh"
-#include "mem/ruby/structures/MemoryVector.hh"
#include "mem/ruby/system/CacheRecorder.hh"
#include "mem/packet.hh"
#include "params/RubySystem.hh"
@@ -75,7 +73,6 @@ class RubySystem : public ClockedObject
static int getRandomization() { return m_randomization; }
static uint32_t getBlockSizeBytes() { return m_block_size_bytes; }
static uint32_t getBlockSizeBits() { return m_block_size_bits; }
- static uint64_t getMemorySizeBytes() { return m_memory_size_bytes; }
static uint32_t getMemorySizeBits() { return m_memory_size_bits; }
// Public Methods
@@ -86,13 +83,6 @@ class RubySystem : public ClockedObject
return m_profiler;
}
- MemoryVector*
- getMemoryVector()
- {
- assert(m_mem_vec != NULL);
- return m_mem_vec;
- }
-
void regStats() { m_profiler->regStats(name()); }
void collateStats() { m_profiler->collateStats(); }
void resetStats();
@@ -106,7 +96,6 @@ class RubySystem : public ClockedObject
void registerNetwork(Network*);
void registerAbstractController(AbstractController*);
- void registerMemController(MemoryControl *mc);
bool eventQueueEmpty() { return eventq->empty(); }
void enqueueRubyEvent(Tick tick)
@@ -132,16 +121,13 @@ class RubySystem : public ClockedObject
static bool m_randomization;
static uint32_t m_block_size_bytes;
static uint32_t m_block_size_bits;
- static uint64_t m_memory_size_bytes;
static uint32_t m_memory_size_bits;
Network* m_network;
- std::vector<MemoryControl *> m_memory_controller_vec;
std::vector<AbstractController *> m_abs_cntrl_vec;
public:
Profiler* m_profiler;
- MemoryVector* m_mem_vec;
bool m_warmup_enabled;
bool m_cooldown_enabled;
CacheRecorder* m_cache_recorder;