mem-cache: Signature Path Prefetcher

Related paper:
  Lookahead Prefetching with Signature Path
  J Kim, PV Gratz, ALN Reddy
  The 2nd Data Prefetching Championship (DPC2), 2015

Change-Id: I2319be2fa409f955f65e1bf1e1bb2d6d9a4fea11
Reviewed-on: https://gem5-review.googlesource.com/c/14737
Reviewed-by: Nikos Nikoleris <nikos.nikoleris@arm.com>
Reviewed-by: Daniel Carvalho <odanrc@yahoo.com.br>
Maintainer: Nikos Nikoleris <nikos.nikoleris@arm.com>
diff --git a/src/mem/cache/prefetch/Prefetcher.py b/src/mem/cache/prefetch/Prefetcher.py
index df547ed..a868a25 100644
--- a/src/mem/cache/prefetch/Prefetcher.py
+++ b/src/mem/cache/prefetch/Prefetcher.py
@@ -40,6 +40,7 @@
 #          Mitch Hayenga
 
 from ClockedObject import ClockedObject
+from IndexingPolicies import *
 from m5.SimObject import *
 from m5.params import *
 from m5.proxy import *
@@ -139,3 +140,42 @@
     cxx_header = "mem/cache/prefetch/tagged.hh"
 
     degree = Param.Int(2, "Number of prefetches to generate")
+
+class SignaturePathPrefetcher(QueuedPrefetcher):
+    type = 'SignaturePathPrefetcher'
+    cxx_class = 'SignaturePathPrefetcher'
+    cxx_header = "mem/cache/prefetch/signature_path.hh"
+
+    signature_shift = Param.UInt8(3,
+        "Number of bits to shift when calculating a new signature");
+    signature_bits = Param.UInt16(12,
+        "Size of the signature, in bits");
+    signature_table_entries = Param.MemorySize("1024",
+        "Number of entries of the signature table")
+    signature_table_assoc = Param.Unsigned(2,
+        "Associativity of the signature table")
+    signature_table_indexing_policy = Param.BaseIndexingPolicy(
+        SetAssociative(entry_size = 1, assoc = Parent.signature_table_assoc,
+        size = Parent.signature_table_entries),
+        "Indexing policy of the signature table")
+    signature_table_replacement_policy = Param.BaseReplacementPolicy(LRURP(),
+        "Replacement policy of the signature table")
+
+    max_counter_value = Param.UInt8(7, "Maximum pattern counter value")
+    pattern_table_entries = Param.MemorySize("4096",
+        "Number of entries of the pattern table")
+    pattern_table_assoc = Param.Unsigned(1,
+        "Associativity of the pattern table")
+    strides_per_pattern_entry = Param.Unsigned(4,
+        "Number of strides stored in each pattern entry")
+    pattern_table_indexing_policy = Param.BaseIndexingPolicy(
+        SetAssociative(entry_size = 1, assoc = Parent.pattern_table_assoc,
+        size = Parent.pattern_table_entries),
+        "Indexing policy of the pattern table")
+    pattern_table_replacement_policy = Param.BaseReplacementPolicy(LRURP(),
+        "Replacement policy of the pattern table")
+
+    prefetch_confidence_threshold = Param.Float(0.5,
+        "Minimum confidence to issue prefetches")
+    lookahead_confidence_threshold = Param.Float(0.75,
+        "Minimum confidence to continue exploring lookahead entries")
diff --git a/src/mem/cache/prefetch/SConscript b/src/mem/cache/prefetch/SConscript
index 2665d18..ccbc2e3 100644
--- a/src/mem/cache/prefetch/SConscript
+++ b/src/mem/cache/prefetch/SConscript
@@ -34,6 +34,6 @@
 
 Source('base.cc')
 Source('queued.cc')
+Source('signature_path.cc')
 Source('stride.cc')
 Source('tagged.cc')
-
diff --git a/src/mem/cache/prefetch/associative_set.hh b/src/mem/cache/prefetch/associative_set.hh
new file mode 100644
index 0000000..99b6a6d
--- /dev/null
+++ b/src/mem/cache/prefetch/associative_set.hh
@@ -0,0 +1,200 @@
+/**
+ * Copyright (c) 2018 Metempsy Technology Consulting
+ * 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: Javier Bueno
+ */
+
+#ifndef __CACHE_PREFETCH_ASSOCIATIVE_SET_HH__
+#define __CACHE_PREFETCH_ASSOCIATIVE_SET_HH__
+
+#include "mem/cache/replacement_policies/base.hh"
+#include "mem/cache/replacement_policies/replaceable_entry.hh"
+#include "mem/cache/tags/indexing_policies/base.hh"
+
+/**
+ * Entry used for set-associative tables, usable with replacement policies
+ */
+class TaggedEntry : public ReplaceableEntry {
+    /** Tag for the entry */
+    Addr tag;
+    /** Valid bit */
+    bool valid;
+    /** Whether this entry refers to a memory area in the secure space */
+    bool secure;
+  public:
+    TaggedEntry() : tag(0), valid(false), secure(false) {}
+    virtual ~TaggedEntry() {}
+
+    /**
+     * Consult the valid bit
+     * @return True if the entry is valid
+     */
+    bool isValid() const
+    {
+        return valid;
+    }
+
+    /**
+     * Sets the entry to valid
+     */
+    void setValid()
+    {
+        valid = true;
+    }
+
+    /**
+     * Sets the entry to invalid
+     */
+    void setInvalid() {
+        valid = false;
+    }
+
+    /**
+     * Obtain the entry tag
+     * @return the tag value
+     */
+    Addr getTag() const
+    {
+        return tag;
+    }
+
+    /**
+     * Sets the tag of the entry
+     * @param t the tag value
+     */
+    void setTag(Addr t)
+    {
+        tag = t;
+    }
+
+    /**
+     * Consult if this entry refers to a memory in the secure area
+     * @return True if this entry refers to secure memory area
+     */
+    bool isSecure() const
+    {
+        return secure;
+    }
+
+    /**
+     * Sets the secure value bit
+     * @param s secure bit value
+     */
+    void setSecure(bool s)
+    {
+        secure = s;
+    }
+
+    /**
+     * Resets the entry, this is called when an entry is evicted to allocate
+     * a new one. Types inheriting this class should provide its own
+     * implementation
+     */
+    virtual void reset () {
+    }
+};
+
+/**
+ * Associative container based on the previosuly defined Entry type
+ * Each element is indexed by a key of type Addr, an additional
+ * bool value is used as an additional tag data of the entry.
+ */
+template<class Entry>
+class AssociativeSet {
+    static_assert(std::is_base_of<TaggedEntry, Entry>::value,
+                  "Entry must derive from TaggedEntry");
+
+    /** Associativity of the container */
+    const int associativity;
+    /**
+     * Total number of entries, entries are organized in sets of the provided
+     * associativity. The number of associative sets is obtained by dividing
+     * numEntries by associativity.
+     */
+    const int numEntries;
+    /** Pointer to the indexing policy */
+    BaseIndexingPolicy* const indexingPolicy;
+    /** Pointer to the replacement policy */
+    BaseReplacementPolicy* const replacementPolicy;
+    /** Vector containing the entries of the container */
+    std::vector<Entry> entries;
+
+  public:
+    /**
+     * Public constructor
+     * @param assoc number of elements in each associative set
+     * @param num_entries total number of entries of the container, the number
+     *   of sets can be calculated dividing this balue by the 'assoc' value
+     * @param idx_policy indexing policy
+     * @param rpl_policy replacement policy
+     * @param initial value of the elements of the set
+     */
+    AssociativeSet(int assoc, int num_entries, BaseIndexingPolicy *idx_policy,
+                   BaseReplacementPolicy *rpl_policy, Entry const &init_value =
+                   Entry());
+
+    /**
+     * Find an entry within the set
+     * @param addr key element
+     * @param is_secure tag element
+     * @return returns a pointer to the wanted entry or nullptr if it does not
+     *  exist.
+     */
+    Entry* findEntry(Addr addr, bool is_secure) const;
+
+    /**
+     * Do an access to the entry, this is required to
+     * update the replacement information data.
+     * @param entry the accessed entry
+     */
+    void accessEntry(Entry *entry);
+
+    /**
+     * Find a victim to be replaced
+     * @param addr key to select the possible victim
+     * @result entry to be victimized
+     */
+    Entry* findVictim(Addr addr);
+
+    /**
+     * Find the set of entries that could be replaced given
+     * that we want to add a new entry with the provided key
+     * @param addr key to select the set of entries
+     * @result vector of candidates matching with the provided key
+     */
+    std::vector<Entry *> getPossibleEntries(const Addr addr) const;
+
+    /**
+     * Indicate that an entry has just been inserted
+     * @param addr key of the container
+     * @param is_secure tag component of the container
+     * @param entry pointer to the container entry to be inserted
+     */
+    void insertEntry(Addr addr, bool is_secure, Entry* entry);
+};
+
+#endif//__CACHE_PREFETCH_ASSOCIATIVE_SET_HH__
diff --git a/src/mem/cache/prefetch/associative_set_impl.hh b/src/mem/cache/prefetch/associative_set_impl.hh
new file mode 100644
index 0000000..5e6e7c5
--- /dev/null
+++ b/src/mem/cache/prefetch/associative_set_impl.hh
@@ -0,0 +1,119 @@
+/**
+ * Copyright (c) 2018 Metempsy Technology Consulting
+ * 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: Javier Bueno
+ */
+
+#ifndef __CACHE_PREFETCH_ASSOCIATIVE_SET_IMPL_HH__
+#define __CACHE_PREFETCH_ASSOCIATIVE_SET_IMPL_HH__
+
+#include "mem/cache/prefetch/associative_set.hh"
+
+template<class Entry>
+AssociativeSet<Entry>::AssociativeSet(int assoc, int num_entries,
+        BaseIndexingPolicy *idx_policy, BaseReplacementPolicy *rpl_policy,
+        Entry const &init_value)
+  : associativity(assoc), numEntries(num_entries), indexingPolicy(idx_policy),
+    replacementPolicy(rpl_policy), entries(numEntries, init_value)
+{
+    fatal_if(!isPowerOf2(num_entries), "The number of entries of an "
+             "AssociativeSet<> must be a power of 2");
+    fatal_if(!isPowerOf2(assoc), "The associativity of an AssociativeSet<> "
+             "must be a power of 2");
+    for (unsigned int entry_idx = 0; entry_idx < numEntries; entry_idx += 1) {
+        Entry* entry = &entries[entry_idx];
+        indexingPolicy->setEntry(entry, entry_idx);
+        entry->replacementData = replacementPolicy->instantiateEntry();
+    }
+}
+
+template<class Entry>
+Entry*
+AssociativeSet<Entry>::findEntry(Addr addr, bool is_secure) const
+{
+    Addr tag = indexingPolicy->extractTag(addr);
+    const std::vector<ReplaceableEntry*> selected_entries =
+        indexingPolicy->getPossibleEntries(addr);
+
+    for (const auto& location : selected_entries) {
+        Entry* entry = static_cast<Entry *>(location);
+        if ((entry->getTag() == tag) && entry->isValid() &&
+            entry->isSecure() == is_secure) {
+            return entry;
+        }
+    }
+    return nullptr;
+}
+
+template<class Entry>
+void
+AssociativeSet<Entry>::accessEntry(Entry *entry)
+{
+    replacementPolicy->touch(entry->replacementData);
+}
+
+template<class Entry>
+Entry*
+AssociativeSet<Entry>::findVictim(Addr addr)
+{
+    // Get possible entries to be victimized
+    const std::vector<ReplaceableEntry*> selected_entries =
+        indexingPolicy->getPossibleEntries(addr);
+    Entry* victim = static_cast<Entry*>(replacementPolicy->getVictim(
+                            selected_entries));
+    // There is only one eviction for this replacement
+    victim->reset();
+    return victim;
+}
+
+
+template<class Entry>
+std::vector<Entry *>
+AssociativeSet<Entry>::getPossibleEntries(const Addr addr) const
+{
+    std::vector<ReplaceableEntry *> selected_entries =
+        indexingPolicy->getPossibleEntries(addr);
+    std::vector<Entry *> entries(selected_entries.size(), nullptr);
+
+    unsigned int idx = 0;
+    for (auto &entry : selected_entries) {
+        entries[idx++] = static_cast<Entry *>(entry);
+    }
+    return entries;
+}
+
+template<class Entry>
+void
+AssociativeSet<Entry>::insertEntry(Addr addr, bool is_secure, Entry* entry)
+{
+   entry->setValid();
+   entry->setTag(indexingPolicy->extractTag(addr));
+   entry->setSecure(is_secure);
+   replacementPolicy->reset(entry->replacementData);
+}
+
+#endif//__CACHE_PREFETCH_ASSOCIATIVE_SET_IMPL_HH__
diff --git a/src/mem/cache/prefetch/signature_path.cc b/src/mem/cache/prefetch/signature_path.cc
new file mode 100644
index 0000000..a0356b1
--- /dev/null
+++ b/src/mem/cache/prefetch/signature_path.cc
@@ -0,0 +1,275 @@
+/**
+ * Copyright (c) 2018 Metempsy Technology Consulting
+ * 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: Javier Bueno
+ */
+
+#include "mem/cache/prefetch/signature_path.hh"
+
+#include <cassert>
+
+#include "debug/HWPrefetch.hh"
+#include "mem/cache/prefetch/associative_set_impl.hh"
+#include "params/SignaturePathPrefetcher.hh"
+
+SignaturePathPrefetcher::SignaturePathPrefetcher(
+    const SignaturePathPrefetcherParams *p)
+    : QueuedPrefetcher(p),
+      stridesPerPatternEntry(p->strides_per_pattern_entry),
+      signatureShift(p->signature_shift),
+      signatureBits(p->signature_bits),
+      maxCounterValue(p->max_counter_value),
+      prefetchConfidenceThreshold(p->prefetch_confidence_threshold),
+      lookaheadConfidenceThreshold(p->lookahead_confidence_threshold),
+      signatureTable(p->signature_table_assoc, p->signature_table_entries,
+                     p->signature_table_indexing_policy,
+                     p->signature_table_replacement_policy),
+      patternTable(p->pattern_table_assoc, p->pattern_table_entries,
+                   p->pattern_table_indexing_policy,
+                   p->pattern_table_replacement_policy,
+                   PatternEntry(stridesPerPatternEntry))
+{
+}
+
+SignaturePathPrefetcher::PatternStrideEntry &
+SignaturePathPrefetcher::PatternEntry::getStrideEntry(stride_t stride,
+                                                     uint8_t max_counter_value)
+{
+    PatternStrideEntry *pstride_entry = findStride(stride);
+    if (pstride_entry == nullptr) {
+        // Specific replacement algorithm for this table,
+        // pick the entry with the lowest counter value,
+        // then decrease the counter of all entries
+
+        // If all counters have the max value, this will be the pick
+        PatternStrideEntry *victim_pstride_entry = &(strideEntries[0]);
+
+        uint8_t current_counter = max_counter_value;
+        for (auto &entry : strideEntries) {
+            if (entry.counter < current_counter) {
+                victim_pstride_entry = &entry;
+                current_counter = entry.counter;
+            }
+            if (entry.counter > 0) {
+                entry.counter -= 1;
+            }
+        }
+        pstride_entry = victim_pstride_entry;
+        pstride_entry->counter = 0;
+        pstride_entry->stride = stride;
+    }
+    return *pstride_entry;
+}
+
+void
+SignaturePathPrefetcher::addPrefetch(Addr ppn, stride_t block,
+    bool is_secure, std::vector<AddrPriority> &addresses)
+{
+    /**
+     * block is relative to the provided ppn. Assuming a page size of 4kB and
+     * a block size of 64B, the range of the stride of this prefetcher is
+     * -63,63 (pageBytes/blkSize) as the last accessed block also ranges from
+     * 0,63, the block value is expected to be between -63 and 126
+     * Negative block means that we are accessing the lower contiguous page,
+     * 64 or greater point to the next contiguous.
+     */
+    assert(block > -((stride_t)(pageBytes/blkSize)));
+    assert(block < 2*((stride_t)(pageBytes/blkSize)));
+
+    Addr pf_ppn;
+    stride_t pf_block;
+    if (block < 0) {
+        pf_ppn = ppn - 1;
+        pf_block = block + (pageBytes/blkSize);
+    } else if (block >= (pageBytes/blkSize)) {
+        pf_ppn = ppn + 1;
+        pf_block = block - (pageBytes/blkSize);
+    } else {
+        pf_ppn = ppn;
+        pf_block = block;
+    }
+
+    Addr new_addr = pf_ppn * pageBytes;
+    new_addr += pf_block * (Addr)blkSize;
+
+    DPRINTF(HWPrefetch, "Queuing prefetch to %#x.\n", new_addr);
+    addresses.push_back(AddrPriority(new_addr, 0));
+}
+
+void
+SignaturePathPrefetcher::updatePatternTable(Addr signature, stride_t stride)
+{
+    assert(stride != 0);
+    // The pattern table is indexed by signatures
+    PatternEntry &p_entry = getPatternEntry(signature);
+    PatternStrideEntry &ps_entry = p_entry.getStrideEntry(stride,
+                                                          maxCounterValue);
+    if (ps_entry.counter < maxCounterValue) {
+        ps_entry.counter += 1;
+    }
+}
+
+SignaturePathPrefetcher::SignatureEntry &
+SignaturePathPrefetcher::getSignatureEntry(Addr ppn, bool is_secure,
+                                           stride_t block, bool &miss)
+{
+    SignatureEntry* signature_entry = signatureTable.findEntry(ppn, is_secure);
+    if (signature_entry != nullptr) {
+        signatureTable.accessEntry(signature_entry);
+        miss = false;
+    } else {
+        signature_entry = signatureTable.findVictim(ppn);
+        assert(signature_entry != nullptr);
+
+        signatureTable.insertEntry(ppn, is_secure, signature_entry);
+        signature_entry->signature = block;
+        signature_entry->lastBlock = block;
+        miss = true;
+    }
+    return *signature_entry;
+}
+
+SignaturePathPrefetcher::PatternEntry &
+SignaturePathPrefetcher::getPatternEntry(Addr signature)
+{
+    PatternEntry* pattern_entry = patternTable.findEntry(signature, false);
+    if (pattern_entry != nullptr) {
+        // Signature found
+        patternTable.accessEntry(pattern_entry);
+    } else {
+        // Signature not found
+        pattern_entry = patternTable.findVictim(signature);
+        assert(pattern_entry != nullptr);
+
+        patternTable.insertEntry(signature, false, pattern_entry);
+    }
+    return *pattern_entry;
+}
+
+void
+SignaturePathPrefetcher::calculatePrefetch(const PrefetchInfo &pfi,
+                                 std::vector<AddrPriority> &addresses)
+{
+    Addr request_addr = pfi.getAddr();
+    Addr ppn = request_addr / pageBytes;
+    stride_t current_block = (request_addr % pageBytes) / blkSize;
+    stride_t stride;
+    bool is_secure = pfi.isSecure();
+
+    // Get the SignatureEntry of this page to:
+    // - compute the current stride
+    // - obtain the current signature of accesses
+    bool miss;
+    SignatureEntry &signature_entry = getSignatureEntry(ppn, is_secure,
+                                                        current_block, miss);
+    if (miss) {
+        // No history for this page, can't continue
+        return;
+    }
+
+    stride = current_block - signature_entry.lastBlock;
+    if (stride == 0) {
+        // Can't continue with a stride 0
+        return;
+    }
+
+    // Update the confidence of the current signature
+    updatePatternTable(signature_entry.signature, stride);
+
+    // Update the current SignatureEntry signature and lastBlock
+    signature_entry.signature =
+        updateSignature(signature_entry.signature, stride);
+    signature_entry.lastBlock = current_block;
+
+    signature_t current_signature = signature_entry.signature;
+    double current_confidence = 1.0;
+    stride_t current_stride = signature_entry.lastBlock;
+
+    do {
+        // With the updated signature, attempt to generate prefetches
+        // - search the PatternTable and select all entries with enough
+        //   confidence, these are prefetch candidates
+        // - select the entry with the highest counter as the "lookahead"
+        PatternEntry *current_pattern_entry =
+            patternTable.findEntry(current_signature, false);
+        PatternStrideEntry const *lookahead = nullptr;
+        if (current_pattern_entry != nullptr) {
+            uint8_t max_counter = 0;
+            for (auto const &entry : current_pattern_entry->strideEntries) {
+                //select the entry with the maximum counter value as lookahead
+                if (max_counter < entry.counter) {
+                    max_counter = entry.counter;
+                    lookahead = &entry;
+                }
+                double prefetch_confidence =
+                    (double) entry.counter / maxCounterValue;
+
+                if (prefetch_confidence >= prefetchConfidenceThreshold) {
+                    assert(entry.stride != 0);
+                    //prefetch candidate
+                    addPrefetch(ppn, current_stride + entry.stride,
+                                         is_secure, addresses);
+                }
+            }
+        }
+        if (lookahead != nullptr) {
+            // If a lookahead was selected, compute its confidence using
+            // the counter of its entry and the accumulated confidence
+            // if the confidence is high enough, generate a new signature
+            double lookahead_confidence;
+            if (lookahead->counter == maxCounterValue) {
+                // maximum confidence is 0.95, guaranteeing that
+                // current confidence will eventually fall beyond
+                // the threshold
+                lookahead_confidence = 0.95;
+            } else {
+                lookahead_confidence =
+                    ((double) lookahead->counter / maxCounterValue);
+            }
+            current_confidence *= lookahead_confidence;
+            current_signature =
+                updateSignature(current_signature, lookahead->stride);
+            current_stride += lookahead->stride;
+        } else {
+            current_confidence = 0.0;
+        }
+        // If the accumulated confidence is high enough, keep repeating
+        // this process with the updated signature
+    }
+    while (current_confidence > lookaheadConfidenceThreshold);
+
+    if (addresses.empty()) {
+        // Enable the next line prefetcher if no prefetch candidates are found
+        addPrefetch(ppn, current_block + 1, is_secure, addresses);
+    }
+}
+
+SignaturePathPrefetcher*
+SignaturePathPrefetcherParams::create()
+{
+    return new SignaturePathPrefetcher(this);
+}
diff --git a/src/mem/cache/prefetch/signature_path.hh b/src/mem/cache/prefetch/signature_path.hh
new file mode 100644
index 0000000..0371b56
--- /dev/null
+++ b/src/mem/cache/prefetch/signature_path.hh
@@ -0,0 +1,204 @@
+/**
+ * Copyright (c) 2018 Metempsy Technology Consulting
+ * 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: Javier Bueno
+ */
+
+ /**
+  * Implementation of the Signature Path Prefetcher
+  *
+  * References:
+  *     Lookahead prefetching with signature path
+  *     J Kim, PV Gratz, ALN Reddy
+  *     The 2nd Data Prefetching Championship (DPC2)
+  * The filter feature described in the paper is not implemented, as it
+  * redundant prefetches are dropped by the cache.
+  */
+
+#ifndef __MEM_CACHE_PREFETCH_SIGNATURE_PATH_HH__
+#define __MEM_CACHE_PREFETCH_SIGNATURE_PATH_HH__
+
+#include "mem/cache/prefetch/associative_set.hh"
+#include "mem/cache/prefetch/queued.hh"
+#include "mem/packet.hh"
+
+struct SignaturePathPrefetcherParams;
+
+class SignaturePathPrefetcher : public QueuedPrefetcher
+{
+    /** Signature type */
+    typedef uint16_t signature_t;
+    /** Stride type */
+    typedef int16_t stride_t;
+
+    /** Number of strides stored in each pattern entry */
+    const unsigned stridesPerPatternEntry;
+    /** Number of bits to shift when generating a new signature */
+    const uint8_t signatureShift;
+    /** Size of the signature, in bits */
+    const signature_t signatureBits;
+    /** Maximum pattern entries counter value */
+    const uint8_t maxCounterValue;
+    /** Minimum confidence to issue a prefetch */
+    const double prefetchConfidenceThreshold;
+    /** Minimum confidence to keep navigating lookahead entries */
+    const double lookaheadConfidenceThreshold;
+
+    /** Signature entry data type */
+    struct SignatureEntry : public TaggedEntry
+    {
+        /** Path signature */
+        signature_t signature;
+        /** Last accessed block within a page */
+        stride_t lastBlock;
+        SignatureEntry() : signature(0), lastBlock(0)
+        {}
+    };
+    /** Signature table */
+    AssociativeSet<SignatureEntry> signatureTable;
+
+    /** A stride entry with its counter */
+    struct PatternStrideEntry
+    {
+        /** stride in a page in blkSize increments */
+        stride_t stride;
+        /** counter value (max value defined by maxCounterValue) */
+        uint8_t counter;
+        PatternStrideEntry() : stride(0), counter(0)
+        {}
+    };
+    /** Pattern entry data type, a set of stride and counter entries */
+    struct PatternEntry : public TaggedEntry
+    {
+        /** group of stides */
+        std::vector<PatternStrideEntry> strideEntries;
+        PatternEntry(size_t num_strides) : strideEntries(num_strides)
+        {}
+
+        /** Reset the entries to their initial values */
+        void reset() override
+        {
+            for (auto &entry : strideEntries) {
+                entry.counter = 0;
+                entry.stride = 0;
+            }
+        }
+
+        /**
+         * Returns the entry with the desired stride
+         * @param stride the stride to find
+         * @result a pointer to the entry, if the stride was found, or nullptr,
+         *         if the stride was not found
+         */
+        PatternStrideEntry *findStride(stride_t stride)
+        {
+            PatternStrideEntry *found_entry = nullptr;
+            for (auto &entry : strideEntries) {
+                if (entry.stride == stride) {
+                    found_entry = &entry;
+                    break;
+                }
+            }
+            return found_entry;
+        }
+
+        /**
+         * Gets the entry with the provided stride, if there is no entry with
+         * the associated stride, it replaces one of them.
+         * @param stride the stride to find
+         * @param max_counter_value maximum value of the confidence counters,
+         *        it is used when no strides are found and an entry needs to be
+         *        replaced
+         * @result reference to the selected entry
+         */
+        PatternStrideEntry &getStrideEntry(stride_t stride,
+                                           uint8_t max_counter_value);
+    };
+    /** Pattern table */
+    AssociativeSet<PatternEntry> patternTable;
+
+    /**
+     * Generates a new signature from an existing one and a new stride
+     * @param sig current signature
+     * @param str stride to add to the new signature
+     * @result the new signature
+     */
+    inline signature_t updateSignature(signature_t sig, stride_t str) const {
+        sig <<= signatureShift;
+        sig ^= str;
+        sig &= mask(signatureBits);
+        return sig;
+    }
+
+    /**
+     * Generates an address to be prefetched.
+     * @param ppn page number to prefetch from
+     * @param block block number within the page, this value can be negative,
+     *        which means that the block refered is actualy in the previous
+     *        page (ppn-1), if the value is greater than (pageBytes/blkSize-1)
+     *        then the block refers to a block within the next page (ppn+1)
+     * @param is_secure whether this page is inside the secure memory area
+     * @param addresses if allowed, the address will be added to this vector
+     */
+    void addPrefetch(Addr ppn, stride_t block, bool is_secure,
+                              std::vector<AddrPriority> &addresses);
+
+    /**
+     * Obtains the SignatureEntry of the given page, if the page is not found,
+     * it allocates a new one, replacing an existing entry if needed
+     * @param ppn physical page number of the page
+     * @param is_secure whether this page is inside the secure memory area
+     * @param block accessed block within the page
+     * @param miss output, if the entry is not found, this will be set to true
+     * @result a reference to the SignatureEntry
+     */
+    SignatureEntry & getSignatureEntry(Addr ppn, bool is_secure,
+                                       stride_t block, bool &miss);
+    /**
+     * Obtains the PatternEntry of the given signature, if the signature is
+     * not found, it allocates a new one, replacing an existing entry if needed
+     * @param signature the signature of the desired entry
+     * @result a reference to the PatternEntry
+     */
+    PatternEntry & getPatternEntry(Addr signature);
+
+    /**
+     * Updates the pattern table with the provided signature and stride
+     * @param signature the signature to use to index the pattern table
+     * @param stride the stride to use to index the set of strides of the
+     *        pattern table entry
+     */
+    void updatePatternTable(Addr signature, stride_t stride);
+
+  public:
+    SignaturePathPrefetcher(const SignaturePathPrefetcherParams* p);
+    ~SignaturePathPrefetcher() {}
+    void calculatePrefetch(const PrefetchInfo &pfi,
+                           std::vector<AddrPriority> &addresses) override;
+};
+
+#endif//__MEM_CACHE_PREFETCH_SIGNATURE_PATH_HH__