summaryrefslogtreecommitdiff
path: root/src/cpu/o3
diff options
context:
space:
mode:
Diffstat (limited to 'src/cpu/o3')
-rw-r--r--src/cpu/o3/alpha_cpu.hh141
-rw-r--r--src/cpu/o3/alpha_cpu_builder.cc3
-rw-r--r--src/cpu/o3/alpha_cpu_impl.hh39
-rw-r--r--src/cpu/o3/alpha_dyn_inst.hh8
-rw-r--r--src/cpu/o3/alpha_params.hh3
-rw-r--r--src/cpu/o3/commit_impl.hh2
-rw-r--r--src/cpu/o3/cpu.cc1
-rw-r--r--src/cpu/o3/cpu.hh7
-rw-r--r--src/cpu/o3/dep_graph.hh29
-rw-r--r--src/cpu/o3/fetch.hh34
-rw-r--r--src/cpu/o3/fetch_impl.hh89
-rw-r--r--src/cpu/o3/fu_pool.cc4
-rw-r--r--src/cpu/o3/fu_pool.hh4
-rw-r--r--src/cpu/o3/iew.hh3
-rw-r--r--src/cpu/o3/iew_impl.hh18
-rw-r--r--src/cpu/o3/inst_queue_impl.hh4
-rw-r--r--src/cpu/o3/lsq.cc2
-rw-r--r--src/cpu/o3/lsq.hh9
-rw-r--r--src/cpu/o3/lsq_impl.hh13
-rw-r--r--src/cpu/o3/lsq_unit.cc5
-rw-r--r--src/cpu/o3/lsq_unit.hh54
-rw-r--r--src/cpu/o3/lsq_unit_impl.hh158
-rw-r--r--src/cpu/o3/regfile.hh40
-rw-r--r--src/cpu/o3/rename_impl.hh13
-rw-r--r--src/cpu/o3/scoreboard.cc5
-rw-r--r--src/cpu/o3/scoreboard.hh5
-rw-r--r--src/cpu/o3/thread_state.hh4
27 files changed, 361 insertions, 336 deletions
diff --git a/src/cpu/o3/alpha_cpu.hh b/src/cpu/o3/alpha_cpu.hh
index 3449454bd..f81837f3c 100644
--- a/src/cpu/o3/alpha_cpu.hh
+++ b/src/cpu/o3/alpha_cpu.hh
@@ -77,6 +77,11 @@ class AlphaFullCPU : public FullO3CPU<Impl>
* external objects try to update state through this interface,
* the CPU will create an event to squash all in-flight
* instructions in order to ensure state is maintained correctly.
+ * It must be defined specifically for the AlphaFullCPU because
+ * not all architectural state is located within the O3ThreadState
+ * (such as the commit PC, and registers), and specific actions
+ * must be taken when using this interface (such as squashing all
+ * in-flight instructions when doing a write to this interface).
*/
class AlphaTC : public ThreadContext
{
@@ -96,8 +101,6 @@ class AlphaFullCPU : public FullO3CPU<Impl>
/** Reads this CPU's ID. */
virtual int readCpuId() { return cpu->cpu_id; }
- virtual TranslatingPort *getMemPort() { return thread->getMemPort(); }
-
#if FULL_SYSTEM
/** Returns a pointer to the system. */
virtual System *getSystemPtr() { return cpu->system; }
@@ -114,7 +117,15 @@ class AlphaFullCPU : public FullO3CPU<Impl>
/** Returns a pointer to this thread's kernel statistics. */
virtual Kernel::Statistics *getKernelStats()
{ return thread->kernelStats; }
+
+ virtual FunctionalPort *getPhysPort() { return thread->getPhysPort(); }
+
+ virtual VirtualPort *getVirtPort(ThreadContext *src_tc = NULL);
+
+ void delVirtPort(VirtualPort *vp);
#else
+ virtual TranslatingPort *getMemPort() { return thread->getMemPort(); }
+
/** Returns a pointer to this thread's process. */
virtual Process *getProcessPtr() { return thread->getProcessPtr(); }
#endif
@@ -301,43 +312,40 @@ class AlphaFullCPU : public FullO3CPU<Impl>
#if FULL_SYSTEM
/** Translates instruction requestion. */
- Fault translateInstReq(RequestPtr &req)
+ Fault translateInstReq(RequestPtr &req, Thread *thread)
{
- return itb->translate(req);
+ return itb->translate(req, thread->getTC());
}
/** Translates data read request. */
- Fault translateDataReadReq(RequestPtr &req)
+ Fault translateDataReadReq(RequestPtr &req, Thread *thread)
{
- return dtb->translate(req, false);
+ return dtb->translate(req, thread->getTC(), false);
}
/** Translates data write request. */
- Fault translateDataWriteReq(RequestPtr &req)
+ Fault translateDataWriteReq(RequestPtr &req, Thread *thread)
{
- return dtb->translate(req, true);
+ return dtb->translate(req, thread->getTC(), true);
}
#else
/** Translates instruction requestion in syscall emulation mode. */
- Fault translateInstReq(RequestPtr &req)
+ Fault translateInstReq(RequestPtr &req, Thread *thread)
{
- int tid = req->getThreadNum();
- return this->thread[tid]->getProcessPtr()->pTable->translate(req);
+ return thread->getProcessPtr()->pTable->translate(req);
}
/** Translates data read request in syscall emulation mode. */
- Fault translateDataReadReq(RequestPtr &req)
+ Fault translateDataReadReq(RequestPtr &req, Thread *thread)
{
- int tid = req->getThreadNum();
- return this->thread[tid]->getProcessPtr()->pTable->translate(req);
+ return thread->getProcessPtr()->pTable->translate(req);
}
/** Translates data write request in syscall emulation mode. */
- Fault translateDataWriteReq(RequestPtr &req)
+ Fault translateDataWriteReq(RequestPtr &req, Thread *thread)
{
- int tid = req->getThreadNum();
- return this->thread[tid]->getProcessPtr()->pTable->translate(req);
+ return thread->getProcessPtr()->pTable->translate(req);
}
#endif
@@ -403,33 +411,6 @@ class AlphaFullCPU : public FullO3CPU<Impl>
void setSyscallReturn(SyscallReturn return_value, int tid);
#endif
- /** Read from memory function. */
- template <class T>
- Fault read(RequestPtr &req, T &data)
- {
-#if 0
-#if FULL_SYSTEM && THE_ISA == ALPHA_ISA
- if (req->flags & LOCKED) {
- req->xc->setMiscReg(TheISA::Lock_Addr_DepTag, req->paddr);
- req->xc->setMiscReg(TheISA::Lock_Flag_DepTag, true);
- }
-#endif
-#endif
- Fault error;
-
-#if FULL_SYSTEM
- // @todo: Fix this LL/SC hack.
- if (req->flags & LOCKED) {
- lockAddr = req->paddr;
- lockFlag = true;
- }
-#endif
-
- error = this->mem->read(req, data);
- data = gtoh(data);
- return error;
- }
-
/** CPU read function, forwards read to LSQ. */
template <class T>
Fault read(RequestPtr &req, T &data, int load_idx)
@@ -437,78 +418,6 @@ class AlphaFullCPU : public FullO3CPU<Impl>
return this->iew.ldstQueue.read(req, data, load_idx);
}
- /** Write to memory function. */
- template <class T>
- Fault write(RequestPtr &req, T &data)
- {
-#if 0
-#if FULL_SYSTEM && THE_ISA == ALPHA_ISA
- ExecContext *xc;
-
- // If this is a store conditional, act appropriately
- if (req->flags & LOCKED) {
- xc = req->xc;
-
- if (req->flags & UNCACHEABLE) {
- // Don't update result register (see stq_c in isa_desc)
- req->result = 2;
- xc->setStCondFailures(0);//Needed? [RGD]
- } else {
- bool lock_flag = xc->readMiscReg(TheISA::Lock_Flag_DepTag);
- Addr lock_addr = xc->readMiscReg(TheISA::Lock_Addr_DepTag);
- req->result = lock_flag;
- if (!lock_flag ||
- ((lock_addr & ~0xf) != (req->paddr & ~0xf))) {
- xc->setMiscReg(TheISA::Lock_Flag_DepTag, false);
- xc->setStCondFailures(xc->readStCondFailures() + 1);
- if (((xc->readStCondFailures()) % 100000) == 0) {
- std::cerr << "Warning: "
- << xc->readStCondFailures()
- << " consecutive store conditional failures "
- << "on cpu " << req->xc->readCpuId()
- << std::endl;
- }
- return NoFault;
- }
- else xc->setStCondFailures(0);
- }
- }
-
- // Need to clear any locked flags on other proccessors for
- // this address. Only do this for succsful Store Conditionals
- // and all other stores (WH64?). Unsuccessful Store
- // Conditionals would have returned above, and wouldn't fall
- // through.
- for (int i = 0; i < this->system->execContexts.size(); i++){
- xc = this->system->execContexts[i];
- if ((xc->readMiscReg(TheISA::Lock_Addr_DepTag) & ~0xf) ==
- (req->paddr & ~0xf)) {
- xc->setMiscReg(TheISA::Lock_Flag_DepTag, false);
- }
- }
-
-#endif
-#endif
-
-#if FULL_SYSTEM
- // @todo: Fix this LL/SC hack.
- if (req->getFlags() & LOCKED) {
- if (req->getFlags() & UNCACHEABLE) {
- req->setScResult(2);
- } else {
- if (this->lockFlag) {
- req->setScResult(1);
- } else {
- req->setScResult(0);
- return NoFault;
- }
- }
- }
-#endif
-
- return this->mem->write(req, (T)htog(data));
- }
-
/** CPU write function, forwards write to LSQ. */
template <class T>
Fault write(RequestPtr &req, T &data, int store_idx)
diff --git a/src/cpu/o3/alpha_cpu_builder.cc b/src/cpu/o3/alpha_cpu_builder.cc
index 1592261de..828977ccb 100644
--- a/src/cpu/o3/alpha_cpu_builder.cc
+++ b/src/cpu/o3/alpha_cpu_builder.cc
@@ -58,7 +58,6 @@ SimObjectParam<AlphaITB *> itb;
SimObjectParam<AlphaDTB *> dtb;
#else
SimObjectVectorParam<Process *> workload;
-//SimObjectParam<PageTable *> page_table;
#endif // FULL_SYSTEM
SimObjectParam<MemObject *> mem;
@@ -165,7 +164,6 @@ BEGIN_INIT_SIM_OBJECT_PARAMS(DerivAlphaFullCPU)
INIT_PARAM(dtb, "Data translation buffer"),
#else
INIT_PARAM(workload, "Processes to run"),
-// INIT_PARAM(page_table, "Page table"),
#endif // FULL_SYSTEM
INIT_PARAM(mem, "Memory"),
@@ -309,7 +307,6 @@ CREATE_SIM_OBJECT(DerivAlphaFullCPU)
params->dtb = dtb;
#else
params->workload = workload;
-// params->pTable = page_table;
#endif // FULL_SYSTEM
params->mem = mem;
diff --git a/src/cpu/o3/alpha_cpu_impl.hh b/src/cpu/o3/alpha_cpu_impl.hh
index 2debe074b..fb2fea8e6 100644
--- a/src/cpu/o3/alpha_cpu_impl.hh
+++ b/src/cpu/o3/alpha_cpu_impl.hh
@@ -46,6 +46,7 @@
#include "arch/isa_traits.hh"
#include "cpu/quiesce_event.hh"
#include "kern/kernel_stats.hh"
+#include "sim/system.hh"
#endif
using namespace TheISA;
@@ -67,7 +68,7 @@ AlphaFullCPU<Impl>::AlphaFullCPU(Params *params)
#if FULL_SYSTEM
// SMT is not supported in FS mode yet.
assert(this->numThreads == 1);
- this->thread[i] = new Thread(this, 0, params->mem);
+ this->thread[i] = new Thread(this, 0);
this->thread[i]->setStatus(ThreadContext::Suspended);
#else
if (i < params->workload.size()) {
@@ -128,14 +129,14 @@ AlphaFullCPU<Impl>::AlphaFullCPU(Params *params)
FunctionalPort *phys_port;
VirtualPort *virt_port;
phys_port = new FunctionalPort(csprintf("%s-%d-funcport",
- cpu->name(), tid));
- mem_port = system->physmem->getPort("functional");
+ name(), i));
+ mem_port = this->system->physmem->getPort("functional");
mem_port->setPeer(phys_port);
phys_port->setPeer(mem_port);
virt_port = new VirtualPort(csprintf("%s-%d-vport",
- cpu->name(), tid));
- mem_port = system->physmem->getPort("functional");
+ name(), i));
+ mem_port = this->system->physmem->getPort("functional");
mem_port->setPeer(virt_port);
virt_port->setPeer(mem_port);
@@ -183,6 +184,23 @@ AlphaFullCPU<Impl>::regStats()
#if FULL_SYSTEM
template <class Impl>
+VirtualPort *
+AlphaFullCPU<Impl>::AlphaTC::getVirtPort(ThreadContext *src_tc)
+{
+ if (!src_tc)
+ return thread->getVirtPort();
+
+ VirtualPort *vp;
+ Port *mem_port;
+
+ vp = new VirtualPort("tc-vport", src_tc);
+ mem_port = cpu->system->physmem->getPort("functional");
+ mem_port->setPeer(vp);
+ vp->setPeer(mem_port);
+ return vp;
+}
+
+template <class Impl>
void
AlphaFullCPU<Impl>::AlphaTC::dumpFuncProfile()
{
@@ -195,7 +213,6 @@ void
AlphaFullCPU<Impl>::AlphaTC::takeOverFrom(ThreadContext *old_context)
{
// some things should already be set up
- assert(getMemPort() == old_context->getMemPort());
#if FULL_SYSTEM
assert(getSystemPtr() == old_context->getSystemPtr());
#else
@@ -232,6 +249,16 @@ AlphaFullCPU<Impl>::AlphaTC::takeOverFrom(ThreadContext *old_context)
thread->trapPending = false;
}
+#if FULL_SYSTEM
+template <class Impl>
+void
+AlphaFullCPU<Impl>::AlphaTC::delVirtPort(VirtualPort *vp)
+{
+ delete vp->getPeer();
+ delete vp;
+}
+#endif
+
template <class Impl>
void
AlphaFullCPU<Impl>::AlphaTC::activate(int delay)
diff --git a/src/cpu/o3/alpha_dyn_inst.hh b/src/cpu/o3/alpha_dyn_inst.hh
index 143ffe7e4..36a08c4a7 100644
--- a/src/cpu/o3/alpha_dyn_inst.hh
+++ b/src/cpu/o3/alpha_dyn_inst.hh
@@ -207,26 +207,26 @@ class AlphaDynInst : public BaseDynInst<Impl>
void setFloatReg(const StaticInst *si, int idx, FloatReg val, int width)
{
this->cpu->setFloatReg(_destRegIdx[idx], val, width);
- BaseDynInst<Impl>::setFloatRegSingle(si, idx, val);
+ BaseDynInst<Impl>::setFloatReg(si, idx, val, width);
}
void setFloatReg(const StaticInst *si, int idx, FloatReg val)
{
this->cpu->setFloatReg(_destRegIdx[idx], val);
- BaseDynInst<Impl>::setFloatRegDouble(si, idx, val);
+ BaseDynInst<Impl>::setFloatReg(si, idx, val);
}
void setFloatRegBits(const StaticInst *si, int idx,
FloatRegBits val, int width)
{
this->cpu->setFloatRegBits(_destRegIdx[idx], val, width);
- this->instResult.integer = val;
+ BaseDynInst<Impl>::setFloatRegBits(si, idx, val);
}
void setFloatRegBits(const StaticInst *si, int idx, FloatRegBits val)
{
this->cpu->setFloatRegBits(_destRegIdx[idx], val);
- BaseDynInst<Impl>::setFloatRegInt(si, idx, val);
+ BaseDynInst<Impl>::setFloatRegBits(si, idx, val);
}
/** Returns the physical register index of the i'th destination
diff --git a/src/cpu/o3/alpha_params.hh b/src/cpu/o3/alpha_params.hh
index e48abd9ed..f3cf36887 100644
--- a/src/cpu/o3/alpha_params.hh
+++ b/src/cpu/o3/alpha_params.hh
@@ -58,9 +58,6 @@ class AlphaSimpleParams : public BaseFullCPU::Params
Process *process;
#endif // FULL_SYSTEM
- //Page Table
-// PageTable *pTable;
-
MemObject *mem;
BaseCPU *checker;
diff --git a/src/cpu/o3/commit_impl.hh b/src/cpu/o3/commit_impl.hh
index 8ee47e907..ceb2918e0 100644
--- a/src/cpu/o3/commit_impl.hh
+++ b/src/cpu/o3/commit_impl.hh
@@ -907,7 +907,7 @@ DefaultCommit<Impl>::commitInsts()
!thread[tid]->trapPending);
oldpc = PC[tid];
cpu->system->pcEventQueue.service(
- thread[tid]->getXCProxy());
+ thread[tid]->getTC());
count++;
} while (oldpc != PC[tid]);
if (count > 1) {
diff --git a/src/cpu/o3/cpu.cc b/src/cpu/o3/cpu.cc
index c5f78d63d..788c6b164 100644
--- a/src/cpu/o3/cpu.cc
+++ b/src/cpu/o3/cpu.cc
@@ -122,7 +122,6 @@ FullO3CPU<Impl>::FullO3CPU(Params *params)
#if FULL_SYSTEM
system(params->system),
- memCtrl(system->memctrl),
physmem(system->physmem),
#endif // FULL_SYSTEM
mem(params->mem),
diff --git a/src/cpu/o3/cpu.hh b/src/cpu/o3/cpu.hh
index 8e482f1e5..ff41a3306 100644
--- a/src/cpu/o3/cpu.hh
+++ b/src/cpu/o3/cpu.hh
@@ -474,8 +474,6 @@ class FullO3CPU : public BaseFullCPU
/** Pointer to the system. */
System *system;
- /** Pointer to the memory controller. */
- MemoryController *memCtrl;
/** Pointer to physical memory. */
PhysicalMemory *physmem;
#endif
@@ -492,11 +490,6 @@ class FullO3CPU : public BaseFullCPU
/** Pointers to all of the threads in the CPU. */
std::vector<Thread *> thread;
-#if 0
- /** Page table pointer. */
- PageTable *pTable;
-#endif
-
/** Pointer to the icache interface. */
MemInterface *icacheInterface;
/** Pointer to the dcache interface. */
diff --git a/src/cpu/o3/dep_graph.hh b/src/cpu/o3/dep_graph.hh
index b6c5f1ab1..3659b1a37 100644
--- a/src/cpu/o3/dep_graph.hh
+++ b/src/cpu/o3/dep_graph.hh
@@ -1,3 +1,32 @@
+/*
+ * Copyright (c) 2006 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: Kevin Lim
+ */
#ifndef __CPU_O3_DEP_GRAPH_HH__
#define __CPU_O3_DEP_GRAPH_HH__
diff --git a/src/cpu/o3/fetch.hh b/src/cpu/o3/fetch.hh
index 9e8aeb8fb..76b32de68 100644
--- a/src/cpu/o3/fetch.hh
+++ b/src/cpu/o3/fetch.hh
@@ -69,29 +69,41 @@ class DefaultFetch
typedef TheISA::MachInst MachInst;
typedef TheISA::ExtMachInst ExtMachInst;
+ /** IcachePort class for DefaultFetch. Handles doing the
+ * communication with the cache/memory.
+ */
class IcachePort : public Port
{
protected:
+ /** Pointer to fetch. */
DefaultFetch<Impl> *fetch;
public:
+ /** Default constructor. */
IcachePort(DefaultFetch<Impl> *_fetch)
: Port(_fetch->name() + "-iport"), fetch(_fetch)
{ }
protected:
+ /** Atomic version of receive. Panics. */
virtual Tick recvAtomic(PacketPtr pkt);
+ /** Functional version of receive. Panics. */
virtual void recvFunctional(PacketPtr pkt);
+ /** Receives status change. Other than range changing, panics. */
virtual void recvStatusChange(Status status);
+ /** Returns the address ranges of this device. */
virtual void getDeviceAddressRanges(AddrRangeList &resp,
AddrRangeList &snoop)
{ resp.clear(); snoop.clear(); }
+ /** Timing version of receive. Handles setting fetch to the
+ * proper status to start fetching. */
virtual bool recvTiming(PacketPtr pkt);
+ /** Handles doing a retry of a failed fetch. */
virtual void recvRetry();
};
@@ -115,7 +127,7 @@ class DefaultFetch
QuiescePending,
SwitchOut,
IcacheWaitResponse,
- IcacheRetry,
+ IcacheWaitRetry,
IcacheAccessComplete
};
@@ -163,9 +175,6 @@ class DefaultFetch
/** Sets pointer to time buffer used to communicate to the next stage. */
void setFetchQueue(TimeBuffer<FetchStruct> *fq_ptr);
- /** Sets pointer to page table. */
-// void setPageTable(PageTable *pt_ptr);
-
/** Initialize stage. */
void initStage();
@@ -268,6 +277,9 @@ class DefaultFetch
}
private:
+ /** Handles retrying the fetch access. */
+ void recvRetry();
+
/** Returns the appropriate thread to fetch, given the fetch policy. */
int getFetchingThread(FetchPriority &fetch_priority);
@@ -360,6 +372,15 @@ class DefaultFetch
/** The width of fetch in instructions. */
unsigned fetchWidth;
+ /** Is the cache blocked? If so no threads can access it. */
+ bool cacheBlocked;
+
+ /** The packet that is waiting to be retried. */
+ PacketPtr retryPkt;
+
+ /** The thread that is waiting on the cache to tell fetch to retry. */
+ int retryTid;
+
/** Cache block size. */
int cacheBlkSize;
@@ -395,11 +416,6 @@ class DefaultFetch
/** Records if fetch is switched out. */
bool switchedOut;
-#if !FULL_SYSTEM
- /** Page table pointer. */
-// PageTable *pTable;
-#endif
-
// @todo: Consider making these vectors and tracking on a per thread basis.
/** Stat for total number of cycles stalled due to an icache miss. */
Stats::Scalar<> icacheStallCycles;
diff --git a/src/cpu/o3/fetch_impl.hh b/src/cpu/o3/fetch_impl.hh
index f3793db6d..c0a2a5d09 100644
--- a/src/cpu/o3/fetch_impl.hh
+++ b/src/cpu/o3/fetch_impl.hh
@@ -43,8 +43,6 @@
#include "arch/tlb.hh"
#include "arch/vtophys.hh"
#include "base/remote_gdb.hh"
-#include "mem/functional/memory_control.hh"
-#include "mem/functional/physical.hh"
#include "sim/system.hh"
#endif // FULL_SYSTEM
@@ -90,18 +88,7 @@ template<class Impl>
void
DefaultFetch<Impl>::IcachePort::recvRetry()
{
- panic("DefaultFetch doesn't support retry yet.");
- // we shouldn't get a retry unless we have a packet that we're
- // waiting to transmit
-/*
- assert(cpu->dcache_pkt != NULL);
- assert(cpu->_status == DcacheRetry);
- Packet *tmp = cpu->dcache_pkt;
- if (sendTiming(tmp)) {
- cpu->_status = DcacheWaitResponse;
- cpu->dcache_pkt = NULL;
- }
-*/
+ fetch->recvRetry();
}
template<class Impl>
@@ -113,6 +100,9 @@ DefaultFetch<Impl>::DefaultFetch(Params *params)
iewToFetchDelay(params->iewToFetchDelay),
commitToFetchDelay(params->commitToFetchDelay),
fetchWidth(params->fetchWidth),
+ cacheBlocked(false),
+ retryPkt(NULL),
+ retryTid(-1),
numThreads(params->numberOfThreads),
numFetchingThreads(params->smtNumFetchingThreads),
interruptPending(false),
@@ -332,18 +322,6 @@ DefaultFetch<Impl>::setFetchQueue(TimeBuffer<FetchStruct> *fq_ptr)
toDecode = fetchQueue->getWire(0);
}
-#if 0
-template<class Impl>
-void
-DefaultFetch<Impl>::setPageTable(PageTable *pt_ptr)
-{
- DPRINTF(Fetch, "Setting the page table pointer.\n");
-#if !FULL_SYSTEM
- pTable = pt_ptr;
-#endif
-}
-#endif
-
template<class Impl>
void
DefaultFetch<Impl>::initStage()
@@ -391,8 +369,6 @@ DefaultFetch<Impl>::processCacheCompletion(PacketPtr pkt)
fetchStatus[tid] = IcacheAccessComplete;
}
-// memcpy(cacheData[tid], memReq[tid]->data, memReq[tid]->size);
-
// Reset the mem req to NULL.
delete pkt->req;
delete pkt;
@@ -512,9 +488,11 @@ DefaultFetch<Impl>::fetchCacheLine(Addr fetch_PC, Fault &ret_fault, unsigned tid
unsigned flags = 0;
#endif // FULL_SYSTEM
- if (interruptPending && flags == 0 || switchedOut) {
- // Hold off fetch from getting new instructions while an interrupt
- // is pending.
+ if (cacheBlocked || (interruptPending && flags == 0) || switchedOut) {
+ // Hold off fetch from getting new instructions when:
+ // Cache is blocked, or
+ // while an interrupt is pending and we're not in PAL mode, or
+ // fetch is switched out.
return false;
}
@@ -530,11 +508,7 @@ DefaultFetch<Impl>::fetchCacheLine(Addr fetch_PC, Fault &ret_fault, unsigned tid
memReq[tid] = mem_req;
// Translate the instruction request.
-//#if FULL_SYSTEM
- fault = cpu->translateInstReq(mem_req);
-//#else
-// fault = pTable->translate(memReq[tid]);
-//#endif
+ fault = cpu->translateInstReq(mem_req, cpu->thread[tid]);
// In the case of faults, the fetch stage may need to stall and wait
// for the ITB miss to be handled.
@@ -542,7 +516,7 @@ DefaultFetch<Impl>::fetchCacheLine(Addr fetch_PC, Fault &ret_fault, unsigned tid
// If translation was successful, attempt to read the first
// instruction.
if (fault == NoFault) {
-#if FULL_SYSTEM
+#if 0
if (cpu->system->memctrl->badaddr(memReq[tid]->paddr) ||
memReq[tid]->flags & UNCACHEABLE) {
DPRINTF(Fetch, "Fetch: Bad address %#x (hopefully on a "
@@ -565,8 +539,13 @@ DefaultFetch<Impl>::fetchCacheLine(Addr fetch_PC, Fault &ret_fault, unsigned tid
// Now do the timing access to see whether or not the instruction
// exists within the cache.
if (!icachePort->sendTiming(data_pkt)) {
+ assert(retryPkt == NULL);
+ assert(retryTid == -1);
DPRINTF(Fetch, "[tid:%i] Out of MSHRs!\n", tid);
- ret_fault = NoFault;
+ fetchStatus[tid] = IcacheWaitRetry;
+ retryPkt = data_pkt;
+ retryTid = tid;
+ cacheBlocked = true;
return false;
}
@@ -601,11 +580,19 @@ DefaultFetch<Impl>::doSquash(const Addr &new_PC, unsigned tid)
if (fetchStatus[tid] == IcacheWaitResponse) {
DPRINTF(Fetch, "[tid:%i]: Squashing outstanding Icache miss.\n",
tid);
- // Should I delete this here or when it comes back from the cache?
-// delete memReq[tid];
memReq[tid] = NULL;
}
+ // Get rid of the retrying packet if it was from this thread.
+ if (retryTid == tid) {
+ assert(cacheBlocked);
+ cacheBlocked = false;
+ retryTid = -1;
+ retryPkt = NULL;
+ delete retryPkt->req;
+ delete retryPkt;
+ }
+
fetchStatus[tid] = Squashing;
++fetchSquashCycles;
@@ -1105,6 +1092,28 @@ DefaultFetch<Impl>::fetch(bool &status_change)
}
}
+template<class Impl>
+void
+DefaultFetch<Impl>::recvRetry()
+{
+ assert(cacheBlocked);
+ if (retryPkt != NULL) {
+ assert(retryTid != -1);
+ assert(fetchStatus[retryTid] == IcacheWaitRetry);
+
+ if (icachePort->sendTiming(retryPkt)) {
+ fetchStatus[retryTid] = IcacheWaitResponse;
+ retryPkt = NULL;
+ retryTid = -1;
+ cacheBlocked = false;
+ }
+ } else {
+ assert(retryTid == -1);
+ // Access has been squashed since it was sent out. Just clear
+ // the cache being blocked.
+ cacheBlocked = false;
+ }
+}
///////////////////////////////////////
// //
diff --git a/src/cpu/o3/fu_pool.cc b/src/cpu/o3/fu_pool.cc
index b28b5d37f..545deea9b 100644
--- a/src/cpu/o3/fu_pool.cc
+++ b/src/cpu/o3/fu_pool.cc
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2002-2005 The Regents of The University of Michigan
+ * Copyright (c) 2006 The Regents of The University of Michigan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -24,6 +24,8 @@
* 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: Kevin Lim
*/
#include <sstream>
diff --git a/src/cpu/o3/fu_pool.hh b/src/cpu/o3/fu_pool.hh
index 1d4c76690..52d83f056 100644
--- a/src/cpu/o3/fu_pool.hh
+++ b/src/cpu/o3/fu_pool.hh
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2002-2005 The Regents of The University of Michigan
+ * Copyright (c) 2006 The Regents of The University of Michigan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -24,6 +24,8 @@
* 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: Kevin Lim
*/
#ifndef __CPU_O3_FU_POOL_HH__
diff --git a/src/cpu/o3/iew.hh b/src/cpu/o3/iew.hh
index 7e79d5311..2e61af5fc 100644
--- a/src/cpu/o3/iew.hh
+++ b/src/cpu/o3/iew.hh
@@ -155,9 +155,6 @@ class DefaultIEW
/** Returns if IEW is switched out. */
bool isSwitchedOut() { return switchedOut; }
- /** Sets page table pointer within LSQ. */
-// void setPageTable(PageTable *pt_ptr);
-
/** Squashes instructions in IEW for a specific thread. */
void squash(unsigned tid);
diff --git a/src/cpu/o3/iew_impl.hh b/src/cpu/o3/iew_impl.hh
index 23f101517..3929f2e19 100644
--- a/src/cpu/o3/iew_impl.hh
+++ b/src/cpu/o3/iew_impl.hh
@@ -370,15 +370,6 @@ DefaultIEW<Impl>::setScoreboard(Scoreboard *sb_ptr)
scoreboard = sb_ptr;
}
-#if 0
-template<class Impl>
-void
-DefaultIEW<Impl>::setPageTable(PageTable *pt_ptr)
-{
- ldstQueue.setPageTable(pt_ptr);
-}
-#endif
-
template <class Impl>
void
DefaultIEW<Impl>::switchOut()
@@ -1182,9 +1173,8 @@ DefaultIEW<Impl>::executeInsts()
fetchRedirect[tid] = false;
}
-#if 0
- printAvailableInsts();
-#endif
+ // Uncomment this if you want to see all available instructions.
+// printAvailableInsts();
// Execute/writeback any instructions that are available.
int insts_to_execute = fromIssue->size;
@@ -1349,8 +1339,8 @@ DefaultIEW<Impl>::writebackInsts()
DynInstPtr inst = toCommit->insts[inst_num];
int tid = inst->threadNumber;
- DPRINTF(IEW, "Sending instructions to commit, PC %#x.\n",
- inst->readPC());
+ DPRINTF(IEW, "Sending instructions to commit, [sn:%lli] PC %#x.\n",
+ inst->seqNum, inst->readPC());
iewInstsToCommit[tid]++;
diff --git a/src/cpu/o3/inst_queue_impl.hh b/src/cpu/o3/inst_queue_impl.hh
index 2f03c6814..06a052c6f 100644
--- a/src/cpu/o3/inst_queue_impl.hh
+++ b/src/cpu/o3/inst_queue_impl.hh
@@ -1240,11 +1240,11 @@ template <class Impl>
int
InstructionQueue<Impl>::countInsts()
{
+#if 0
//ksewell:This works but definitely could use a cleaner write
//with a more intuitive way of counting. Right now it's
//just brute force ....
-
-#if 0
+ // Change the #if if you want to use this method.
int total_insts = 0;
for (int i = 0; i < numThreads; ++i) {
diff --git a/src/cpu/o3/lsq.cc b/src/cpu/o3/lsq.cc
index 8991ab8f8..de0325920 100644
--- a/src/cpu/o3/lsq.cc
+++ b/src/cpu/o3/lsq.cc
@@ -24,6 +24,8 @@
* 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: Korey Sewell
*/
#include "cpu/o3/alpha_dyn_inst.hh"
diff --git a/src/cpu/o3/lsq.hh b/src/cpu/o3/lsq.hh
index d65510c30..bc4154c85 100644
--- a/src/cpu/o3/lsq.hh
+++ b/src/cpu/o3/lsq.hh
@@ -24,6 +24,8 @@
* 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: Korey Sewell
*/
#ifndef __CPU_O3_LSQ_HH__
@@ -34,10 +36,8 @@
#include "config/full_system.hh"
#include "cpu/inst_seq.hh"
-//#include "cpu/o3/cpu_policy.hh"
#include "cpu/o3/lsq_unit.hh"
#include "mem/port.hh"
-//#include "mem/page_table.hh"
#include "sim/sim_object.hh"
template <class Impl>
@@ -68,8 +68,6 @@ class LSQ {
void setCPU(FullCPU *cpu_ptr);
/** Sets the IEW stage pointer. */
void setIEW(IEW *iew_ptr);
- /** Sets the page table pointer. */
-// void setPageTable(PageTable *pt_ptr);
/** Switches out the LSQ. */
void switchOut();
/** Takes over execution from another CPU's thread. */
@@ -279,9 +277,6 @@ class LSQ {
/** The IEW stage pointer. */
IEW *iewStage;
- /** The pointer to the page table. */
-// PageTable *pTable;
-
/** List of Active Threads in System. */
std::list<unsigned> *activeThreads;
diff --git a/src/cpu/o3/lsq_impl.hh b/src/cpu/o3/lsq_impl.hh
index a6ad27522..27aa0dc3c 100644
--- a/src/cpu/o3/lsq_impl.hh
+++ b/src/cpu/o3/lsq_impl.hh
@@ -24,6 +24,8 @@
* 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: Korey Sewell
*/
#include <algorithm>
@@ -134,17 +136,6 @@ LSQ<Impl>::setIEW(IEW *iew_ptr)
}
}
-#if 0
-template<class Impl>
-void
-LSQ<Impl>::setPageTable(PageTable *pt_ptr)
-{
- for (int tid=0; tid < numThreads; tid++) {
- thread[tid].setPageTable(pt_ptr);
- }
-}
-#endif
-
template <class Impl>
void
LSQ<Impl>::switchOut()
diff --git a/src/cpu/o3/lsq_unit.cc b/src/cpu/o3/lsq_unit.cc
index dd29007bc..e935ffa5c 100644
--- a/src/cpu/o3/lsq_unit.cc
+++ b/src/cpu/o3/lsq_unit.cc
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2004-2005 The Regents of The University of Michigan
+ * Copyright (c) 2004-2006 The Regents of The University of Michigan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -24,6 +24,9 @@
* 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: Kevin Lim
+ * Korey Sewell
*/
#include "cpu/o3/alpha_dyn_inst.hh"
diff --git a/src/cpu/o3/lsq_unit.hh b/src/cpu/o3/lsq_unit.hh
index 414309679..ce0cdd36f 100644
--- a/src/cpu/o3/lsq_unit.hh
+++ b/src/cpu/o3/lsq_unit.hh
@@ -24,6 +24,9 @@
* 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: Kevin Lim
+ * Korey Sewell
*/
#ifndef __CPU_O3_LSQ_UNIT_HH__
@@ -39,9 +42,6 @@
#include "cpu/inst_seq.hh"
#include "mem/packet.hh"
#include "mem/port.hh"
-//#include "mem/page_table.hh"
-//#include "sim/debug.hh"
-//#include "sim/sim_object.hh"
/**
* Class that implements the actual LQ and SQ for each specific
@@ -84,9 +84,6 @@ class LSQUnit {
void setIEW(IEW *iew_ptr)
{ iewStage = iew_ptr; }
- /** Sets the page table pointer. */
-// void setPageTable(PageTable *pt_ptr);
-
/** Switches out LSQ unit. */
void switchOut();
@@ -208,11 +205,18 @@ class LSQUnit {
!isStoreBlocked; }
private:
+ /** Writes back the instruction, sending it to IEW. */
void writeback(DynInstPtr &inst, PacketPtr pkt);
+ /** Handles completing the send of a store to memory. */
+ void storePostSend(Packet *pkt);
+
/** Completes the store at the specified index. */
void completeStore(int store_idx);
+ /** Handles doing the retry. */
+ void recvRetry();
+
/** Increments the given store index (circular queue). */
inline void incrStIdx(int &store_idx);
/** Decrements the given store index (circular queue). */
@@ -233,55 +237,75 @@ class LSQUnit {
/** Pointer to the IEW stage. */
IEW *iewStage;
+ /** Pointer to memory object. */
MemObject *mem;
+ /** DcachePort class for this LSQ Unit. Handles doing the
+ * communication with the cache/memory.
+ * @todo: Needs to be moved to the LSQ level and have some sort
+ * of arbitration.
+ */
class DcachePort : public Port
{
protected:
+ /** Pointer to CPU. */
FullCPU *cpu;
+ /** Pointer to LSQ. */
LSQUnit *lsq;
public:
+ /** Default constructor. */
DcachePort(FullCPU *_cpu, LSQUnit *_lsq)
: Port(_lsq->name() + "-dport"), cpu(_cpu), lsq(_lsq)
{ }
protected:
+ /** Atomic version of receive. Panics. */
virtual Tick recvAtomic(PacketPtr pkt);
+ /** Functional version of receive. Panics. */
virtual void recvFunctional(PacketPtr pkt);
+ /** Receives status change. Other than range changing, panics. */
virtual void recvStatusChange(Status status);
+ /** Returns the address ranges of this device. */
virtual void getDeviceAddressRanges(AddrRangeList &resp,
AddrRangeList &snoop)
{ resp.clear(); snoop.clear(); }
+ /** Timing version of receive. Handles writing back and
+ * completing the load or store that has returned from
+ * memory. */
virtual bool recvTiming(PacketPtr pkt);
+ /** Handles doing a retry of the previous send. */
virtual void recvRetry();
};
/** Pointer to the D-cache. */
DcachePort *dcachePort;
+ /** Derived class to hold any sender state the LSQ needs. */
class LSQSenderState : public Packet::SenderState
{
public:
+ /** Default constructor. */
LSQSenderState()
: noWB(false)
{ }
-// protected:
+ /** Instruction who initiated the access to memory. */
DynInstPtr inst;
+ /** Whether or not it is a load. */
bool isLoad;
+ /** The LQ/SQ index of the instruction. */
int idx;
+ /** Whether or not the instruction will need to writeback. */
bool noWB;
};
- /** Pointer to the page table. */
-// PageTable *pTable;
-
+ /** Writeback event, specifically for when stores forward data to loads. */
class WritebackEvent : public Event {
public:
/** Constructs a writeback event. */
@@ -294,8 +318,10 @@ class LSQUnit {
const char *description();
private:
+ /** Instruction whose results are being written back. */
DynInstPtr inst;
+ /** The packet that would have been sent to memory. */
PacketPtr pkt;
/** The pointer to the LSQ unit that issued the store. */
@@ -396,6 +422,10 @@ class LSQUnit {
/** The index of the above store. */
int stallingLoadIdx;
+ /** The packet that needs to be retried. */
+ PacketPtr retryPkt;
+
+ /** Whehter or not a store is blocked due to the memory system. */
bool isStoreBlocked;
/** Whether or not a load is blocked due to the memory system. */
@@ -501,7 +531,7 @@ LSQUnit<Impl>::read(Request *req, T &data, int load_idx)
"storeHead: %i addr: %#x\n",
load_idx, store_idx, storeHead, req->getPaddr());
-#if 0
+#if FULL_SYSTEM
if (req->getFlags() & LOCKED) {
cpu->lockAddr = req->getPaddr();
cpu->lockFlag = true;
@@ -556,7 +586,7 @@ LSQUnit<Impl>::read(Request *req, T &data, int load_idx)
DPRINTF(LSQUnit, "Forwarding from store idx %i to load to "
"addr %#x, data %#x\n",
- store_idx, req->getVaddr(), *(load_inst->memData));
+ store_idx, req->getVaddr(), data);
PacketPtr data_pkt = new Packet(req, Packet::ReadReq, Packet::Broadcast);
data_pkt->dataStatic(load_inst->memData);
diff --git a/src/cpu/o3/lsq_unit_impl.hh b/src/cpu/o3/lsq_unit_impl.hh
index 2679eb52b..6f32ec304 100644
--- a/src/cpu/o3/lsq_unit_impl.hh
+++ b/src/cpu/o3/lsq_unit_impl.hh
@@ -24,6 +24,9 @@
* 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: Kevin Lim
+ * Korey Sewell
*/
#include "cpu/checker/cpu.hh"
@@ -63,7 +66,7 @@ LSQUnit<Impl>::completeDataAccess(PacketPtr pkt)
LSQSenderState *state = dynamic_cast<LSQSenderState *>(pkt->senderState);
DynInstPtr inst = state->inst;
DPRINTF(IEW, "Writeback event [sn:%lli]\n", inst->seqNum);
-// DPRINTF(Activity, "Activity: Ld Writeback event [sn:%lli]\n", inst->seqNum);
+ DPRINTF(Activity, "Activity: Writeback event [sn:%lli]\n", inst->seqNum);
//iewStage->ldstQueue.removeMSHR(inst->threadNumber,inst->seqNum);
@@ -122,18 +125,7 @@ template <class Impl>
void
LSQUnit<Impl>::DcachePort::recvRetry()
{
- panic("Retry unsupported for now!");
- // we shouldn't get a retry unless we have a packet that we're
- // waiting to transmit
-/*
- assert(cpu->dcache_pkt != NULL);
- assert(cpu->_status == DcacheRetry);
- PacketPtr tmp = cpu->dcache_pkt;
- if (sendTiming(tmp)) {
- cpu->_status = DcacheWaitResponse;
- cpu->dcache_pkt = NULL;
- }
-*/
+ lsq->recvRetry();
}
template <class Impl>
@@ -217,16 +209,6 @@ LSQUnit<Impl>::clearSQ()
storeQueue.clear();
}
-#if 0
-template<class Impl>
-void
-LSQUnit<Impl>::setPageTable(PageTable *pt_ptr)
-{
- DPRINTF(LSQUnit, "Setting the page table pointer.\n");
- pTable = pt_ptr;
-}
-#endif
-
template<class Impl>
void
LSQUnit<Impl>::switchOut()
@@ -612,47 +594,34 @@ LSQUnit<Impl>::writebackStores()
req->getPaddr(), *(inst->memData),
storeQueue[storeWBIdx].inst->seqNum);
+ // @todo: Remove this SC hack once the memory system handles it.
+ if (req->getFlags() & LOCKED) {
+ if (req->getFlags() & UNCACHEABLE) {
+ req->setScResult(2);
+ } else {
+ if (cpu->lockFlag) {
+ req->setScResult(1);
+ } else {
+ req->setScResult(0);
+ // Hack: Instantly complete this store.
+ completeDataAccess(data_pkt);
+ incrStIdx(storeWBIdx);
+ continue;
+ }
+ }
+ } else {
+ // Non-store conditionals do not need a writeback.
+ state->noWB = true;
+ }
+
if (!dcachePort->sendTiming(data_pkt)) {
// Need to handle becoming blocked on a store.
isStoreBlocked = true;
- } else {
- if (isStalled() &&
- storeQueue[storeWBIdx].inst->seqNum == stallingStoreIsn) {
- DPRINTF(LSQUnit, "Unstalling, stalling store [sn:%lli] "
- "load idx:%i\n",
- stallingStoreIsn, stallingLoadIdx);
- stalled = false;
- stallingStoreIsn = 0;
- iewStage->replayMemInst(loadQueue[stallingLoadIdx]);
- }
-
- if (!(req->getFlags() & LOCKED)) {
- assert(!storeQueue[storeWBIdx].inst->isStoreConditional());
- // Non-store conditionals do not need a writeback.
- state->noWB = true;
- }
-
- if (data_pkt->result != Packet::Success) {
- DPRINTF(LSQUnit,"D-Cache Write Miss on idx:%i!\n",
- storeWBIdx);
-
- DPRINTF(Activity, "Active st accessing mem miss [sn:%lli]\n",
- storeQueue[storeWBIdx].inst->seqNum);
-
- //mshrSeqNums.push_back(storeQueue[storeWBIdx].inst->seqNum);
-
- //DPRINTF(LSQUnit, "Added MSHR. count = %i\n",mshrSeqNums.size());
-
- // @todo: Increment stat here.
- } else {
- DPRINTF(LSQUnit,"D-Cache: Write Hit on idx:%i !\n",
- storeWBIdx);
-
- DPRINTF(Activity, "Active st accessing mem hit [sn:%lli]\n",
- storeQueue[storeWBIdx].inst->seqNum);
- }
- incrStIdx(storeWBIdx);
+ assert(retryPkt == NULL);
+ retryPkt = data_pkt;
+ } else {
+ storePostSend(data_pkt);
}
}
@@ -758,6 +727,53 @@ LSQUnit<Impl>::squash(const InstSeqNum &squashed_num)
template <class Impl>
void
+LSQUnit<Impl>::storePostSend(Packet *pkt)
+{
+ if (isStalled() &&
+ storeQueue[storeWBIdx].inst->seqNum == stallingStoreIsn) {
+ DPRINTF(LSQUnit, "Unstalling, stalling store [sn:%lli] "
+ "load idx:%i\n",
+ stallingStoreIsn, stallingLoadIdx);
+ stalled = false;
+ stallingStoreIsn = 0;
+ iewStage->replayMemInst(loadQueue[stallingLoadIdx]);
+ }
+
+ if (!storeQueue[storeWBIdx].inst->isStoreConditional()) {
+ // The store is basically completed at this time. This
+ // only works so long as the checker doesn't try to
+ // verify the value in memory for stores.
+ storeQueue[storeWBIdx].inst->setCompleted();
+ if (cpu->checker) {
+ cpu->checker->tick(storeQueue[storeWBIdx].inst);
+ }
+ }
+
+ if (pkt->result != Packet::Success) {
+ DPRINTF(LSQUnit,"D-Cache Write Miss on idx:%i!\n",
+ storeWBIdx);
+
+ DPRINTF(Activity, "Active st accessing mem miss [sn:%lli]\n",
+ storeQueue[storeWBIdx].inst->seqNum);
+
+ //mshrSeqNums.push_back(storeQueue[storeWBIdx].inst->seqNum);
+
+ //DPRINTF(LSQUnit, "Added MSHR. count = %i\n",mshrSeqNums.size());
+
+ // @todo: Increment stat here.
+ } else {
+ DPRINTF(LSQUnit,"D-Cache: Write Hit on idx:%i !\n",
+ storeWBIdx);
+
+ DPRINTF(Activity, "Active st accessing mem hit [sn:%lli]\n",
+ storeQueue[storeWBIdx].inst->seqNum);
+ }
+
+ incrStIdx(storeWBIdx);
+}
+
+template <class Impl>
+void
LSQUnit<Impl>::writeback(DynInstPtr &inst, PacketPtr pkt)
{
iewStage->wakeCPU();
@@ -829,6 +845,28 @@ LSQUnit<Impl>::completeStore(int store_idx)
}
template <class Impl>
+void
+LSQUnit<Impl>::recvRetry()
+{
+ if (isStoreBlocked) {
+ assert(retryPkt != NULL);
+
+ if (dcachePort->sendTiming(retryPkt)) {
+ storePostSend(retryPkt);
+ retryPkt = NULL;
+ isStoreBlocked = false;
+ } else {
+ // Still blocked!
+ }
+ } else if (isLoadBlocked) {
+ DPRINTF(LSQUnit, "Loads squash themselves and all younger insts, "
+ "no need to resend packet.\n");
+ } else {
+ DPRINTF(LSQUnit, "Retry received but LSQ is no longer blocked.\n");
+ }
+}
+
+template <class Impl>
inline void
LSQUnit<Impl>::incrStIdx(int &store_idx)
{
diff --git a/src/cpu/o3/regfile.hh b/src/cpu/o3/regfile.hh
index a142b7102..ade5e4e56 100644
--- a/src/cpu/o3/regfile.hh
+++ b/src/cpu/o3/regfile.hh
@@ -96,7 +96,7 @@ class PhysRegFile
assert(reg_idx < numPhysicalIntRegs);
DPRINTF(IEW, "RegFile: Access to int register %i, has data "
- "%i\n", int(reg_idx), intRegFile[reg_idx]);
+ "%#x\n", int(reg_idx), intRegFile[reg_idx]);
return intRegFile[reg_idx];
}
@@ -110,7 +110,7 @@ class PhysRegFile
FloatReg floatReg = floatRegFile[reg_idx].d;
DPRINTF(IEW, "RegFile: Access to %d byte float register %i, has "
- "data %8.8d\n", int(reg_idx), (double)floatReg);
+ "data %#x\n", int(reg_idx), floatRegFile[reg_idx].q);
return floatReg;
}
@@ -126,7 +126,7 @@ class PhysRegFile
FloatReg floatReg = floatRegFile[reg_idx].d;
DPRINTF(IEW, "RegFile: Access to float register %i, has "
- "data %8.8d\n", int(reg_idx), (double)floatReg);
+ "data %#x\n", int(reg_idx), floatRegFile[reg_idx].q);
return floatReg;
}
@@ -141,8 +141,8 @@ class PhysRegFile
FloatRegBits floatRegBits = floatRegFile[reg_idx].q;
- DPRINTF(IEW, "RegFile: Access to %d byte float register %i as int, "
- "has data %lli\n", int(reg_idx), (uint64_t)floatRegBits);
+ DPRINTF(IEW, "RegFile: Access to float register %i as int, "
+ "has data %#x\n", int(reg_idx), (uint64_t)floatRegBits);
return floatRegBits;
}
@@ -157,7 +157,7 @@ class PhysRegFile
FloatRegBits floatRegBits = floatRegFile[reg_idx].q;
DPRINTF(IEW, "RegFile: Access to float register %i as int, "
- "has data %lli\n", int(reg_idx), (uint64_t)floatRegBits);
+ "has data %#x\n", int(reg_idx), (uint64_t)floatRegBits);
return floatRegBits;
}
@@ -167,7 +167,7 @@ class PhysRegFile
{
assert(reg_idx < numPhysicalIntRegs);
- DPRINTF(IEW, "RegFile: Setting int register %i to %lli\n",
+ DPRINTF(IEW, "RegFile: Setting int register %i to %#x\n",
int(reg_idx), val);
if (reg_idx != TheISA::ZeroReg)
@@ -182,11 +182,11 @@ class PhysRegFile
assert(reg_idx < numPhysicalFloatRegs + numPhysicalIntRegs);
- DPRINTF(IEW, "RegFile: Setting float register %i to %8.8d\n",
- int(reg_idx), (double)val);
+ DPRINTF(IEW, "RegFile: Setting float register %i to %#x\n",
+ int(reg_idx), (uint64_t)val);
if (reg_idx != TheISA::ZeroReg)
- floatRegFile[reg_idx].d = width;
+ floatRegFile[reg_idx].d = val;
}
/** Sets a double precision floating point register to the given value. */
@@ -197,8 +197,8 @@ class PhysRegFile
assert(reg_idx < numPhysicalFloatRegs + numPhysicalIntRegs);
- DPRINTF(IEW, "RegFile: Setting float register %i to %8.8d\n",
- int(reg_idx), (double)val);
+ DPRINTF(IEW, "RegFile: Setting float register %i to %#x\n",
+ int(reg_idx), (uint64_t)val);
if (reg_idx != TheISA::ZeroReg)
floatRegFile[reg_idx].d = val;
@@ -212,7 +212,7 @@ class PhysRegFile
assert(reg_idx < numPhysicalFloatRegs + numPhysicalIntRegs);
- DPRINTF(IEW, "RegFile: Setting float register %i to %lli\n",
+ DPRINTF(IEW, "RegFile: Setting float register %i to %#x\n",
int(reg_idx), (uint64_t)val);
floatRegFile[reg_idx].q = val;
@@ -225,7 +225,7 @@ class PhysRegFile
assert(reg_idx < numPhysicalFloatRegs + numPhysicalIntRegs);
- DPRINTF(IEW, "RegFile: Setting float register %i to %lli\n",
+ DPRINTF(IEW, "RegFile: Setting float register %i to %#x\n",
int(reg_idx), (uint64_t)val);
floatRegFile[reg_idx].q = val;
@@ -263,10 +263,10 @@ class PhysRegFile
public:
/** (signed) integer register file. */
- std::vector<IntReg> intRegFile;
+ IntReg *intRegFile;
/** Floating point register file. */
- std::vector<PhysFloatReg> floatRegFile;
+ PhysFloatReg *floatRegFile;
/** Miscellaneous register file. */
MiscRegFile miscRegs[Impl::MaxThreads];
@@ -296,15 +296,15 @@ PhysRegFile<Impl>::PhysRegFile(unsigned _numPhysicalIntRegs,
: numPhysicalIntRegs(_numPhysicalIntRegs),
numPhysicalFloatRegs(_numPhysicalFloatRegs)
{
- intRegFile.resize(numPhysicalIntRegs);
- floatRegFile.resize(numPhysicalFloatRegs);
+ intRegFile = new IntReg[numPhysicalIntRegs];
+ floatRegFile = new PhysFloatReg[numPhysicalFloatRegs];
for (int i = 0; i < Impl::MaxThreads; ++i) {
miscRegs[i].clear();
}
- //memset(intRegFile, 0, sizeof(*intRegFile));
- //memset(floatRegFile, 0, sizeof(*floatRegFile));
+ memset(intRegFile, 0, sizeof(IntReg) * numPhysicalIntRegs);
+ memset(floatRegFile, 0, sizeof(PhysFloatReg) * numPhysicalFloatRegs);
}
#endif
diff --git a/src/cpu/o3/rename_impl.hh b/src/cpu/o3/rename_impl.hh
index 8e70c90f7..df33b98ee 100644
--- a/src/cpu/o3/rename_impl.hh
+++ b/src/cpu/o3/rename_impl.hh
@@ -327,18 +327,9 @@ DefaultRename<Impl>::squash(unsigned tid)
if (renameStatus[tid] == Blocked ||
renameStatus[tid] == Unblocking ||
renameStatus[tid] == SerializeStall) {
-#if 0
- // In syscall emulation, we can have both a block and a squash due
- // to a syscall in the same cycle. This would cause both signals to
- // be high. This shouldn't happen in full system.
- if (toDecode->renameBlock[tid]) {
- toDecode->renameBlock[tid] = 0;
- } else {
- toDecode->renameUnblock[tid] = 1;
- }
-#else
+
toDecode->renameUnblock[tid] = 1;
-#endif
+
serializeInst[tid] = NULL;
}
diff --git a/src/cpu/o3/scoreboard.cc b/src/cpu/o3/scoreboard.cc
index b0e433620..1859b35a4 100644
--- a/src/cpu/o3/scoreboard.cc
+++ b/src/cpu/o3/scoreboard.cc
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2004-2005 The Regents of The University of Michigan
+ * Copyright (c) 2005-2006 The Regents of The University of Michigan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -24,6 +24,9 @@
* 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: Korey Sewell
+ * Kevin Lim
*/
#include "cpu/o3/scoreboard.hh"
diff --git a/src/cpu/o3/scoreboard.hh b/src/cpu/o3/scoreboard.hh
index 77f2cf157..f8e4df3b7 100644
--- a/src/cpu/o3/scoreboard.hh
+++ b/src/cpu/o3/scoreboard.hh
@@ -1,5 +1,5 @@
/*
- * Copyright (c) 2004-2005 The Regents of The University of Michigan
+ * Copyright (c) 2005-2006 The Regents of The University of Michigan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@@ -24,6 +24,9 @@
* 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: Korey Sewell
+ * Kevin Lim
*/
#ifndef __CPU_O3_SCOREBOARD_HH__
diff --git a/src/cpu/o3/thread_state.hh b/src/cpu/o3/thread_state.hh
index 38d37ec96..b6535baa1 100644
--- a/src/cpu/o3/thread_state.hh
+++ b/src/cpu/o3/thread_state.hh
@@ -24,6 +24,8 @@
* 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: Kevin Lim
*/
#ifndef __CPU_O3_THREAD_STATE_HH__
@@ -73,7 +75,7 @@ struct O3ThreadState : public ThreadState {
bool trapPending;
#if FULL_SYSTEM
- O3ThreadState(FullCPU *_cpu, int _thread_num, )
+ O3ThreadState(FullCPU *_cpu, int _thread_num)
: ThreadState(-1, _thread_num),
inSyscall(0), trapPending(0)
{ }