arch-arm: Transactional Memory Extension (TME)

This patch extends the generic hardware transactional memory support in
Ruby and the O3/TimingSimpleCPU cores with the Arm-specific hardware
transactional memory architectural extensions (TME).

JIRA: https://gem5.atlassian.net/browse/GEM5-588

Change-Id: I8c663da977ed3e8c94635fcb11834bd001e92054
Reviewed-on: https://gem5-review.googlesource.com/c/public/gem5/+/30329
Reviewed-by: Giacomo Travaglini <giacomo.travaglini@arm.com>
Reviewed-by: Jason Lowe-Power <power.jg@gmail.com>
Tested-by: kokoro <noreply+kokoro@google.com>
Maintainer: Jason Lowe-Power <power.jg@gmail.com>
diff --git a/src/arch/arm/ArmISA.py b/src/arch/arm/ArmISA.py
index f581d4f..ebad774 100644
--- a/src/arch/arm/ArmISA.py
+++ b/src/arch/arm/ArmISA.py
@@ -97,7 +97,7 @@
     id_aa64dfr1_el1 = Param.UInt64(0x0000000000000000,
         "AArch64 Debug Feature Register 1")
 
-    # !CRC32 | !SHA2 | !SHA1 | !AES
+    # !TME | !Atomic | !CRC32 | !SHA2 | !SHA1 | !AES
     id_aa64isar0_el1 = Param.UInt64(0x0000000000000000,
         "AArch64 Instruction Set Attribute Register 0")
 
diff --git a/src/arch/arm/ArmSystem.py b/src/arch/arm/ArmSystem.py
index 333ae5f..0ca782f 100644
--- a/src/arch/arm/ArmSystem.py
+++ b/src/arch/arm/ArmSystem.py
@@ -77,7 +77,8 @@
         "True if Priviledge Access Never is implemented (ARMv8.1)")
     have_secel2 = Param.Bool(True,
         "True if Secure EL2 is implemented (ARMv8)")
-
+    have_tme = Param.Bool(False,
+        "True if transactional memory extension (TME) is implemented")
     semihosting = Param.ArmSemihosting(NULL,
         "Enable support for the Arm semihosting by settings this parameter")
 
diff --git a/src/arch/arm/SConscript b/src/arch/arm/SConscript
index 4aec933..e7781f6 100644
--- a/src/arch/arm/SConscript
+++ b/src/arch/arm/SConscript
@@ -1,6 +1,6 @@
 # -*- mode:python -*-
 
-# Copyright (c) 2009, 2012-2013, 2017-2018 ARM Limited
+# Copyright (c) 2009, 2012-2013, 2017-2018, 2020 ARM Limited
 # All rights reserved.
 #
 # The license below extends only to copyright in the software and shall
@@ -48,6 +48,7 @@
     GTest('aapcs64.test', 'aapcs64.test.cc')
     Source('decoder.cc')
     Source('faults.cc')
+    Source('htm.cc')
     Source('insts/branch.cc')
     Source('insts/branch64.cc')
     Source('insts/data64.cc')
@@ -64,6 +65,11 @@
     Source('insts/vfp.cc')
     Source('insts/fplib.cc')
     Source('insts/crypto.cc')
+    Source('insts/tme64.cc')
+    if env['PROTOCOL'] == 'MESI_Three_Level_HTM':
+        Source('insts/tme64ruby.cc')
+    else:
+        Source('insts/tme64classic.cc')
     Source('interrupts.cc')
     Source('isa.cc')
     Source('isa_device.cc')
@@ -101,6 +107,7 @@
     SimObject('ArmPMU.py')
 
     DebugFlag('Arm')
+    DebugFlag('ArmTme', 'Transactional Memory Extension')
     DebugFlag('Semihosting')
     DebugFlag('Decoder', "Instructions returned by the predecoder")
     DebugFlag('Faults', "Trace Exceptions, interrupts, svc/swi")
diff --git a/src/arch/arm/htm.cc b/src/arch/arm/htm.cc
new file mode 100644
index 0000000..276406a
--- /dev/null
+++ b/src/arch/arm/htm.cc
@@ -0,0 +1,163 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 "arch/arm/htm.hh"
+#include "cpu/thread_context.hh"
+
+void
+ArmISA::HTMCheckpoint::reset()
+{
+    rt = 0;
+    nPc = 0;
+    sp = 0;
+    fpcr = 0;
+    fpsr = 0;
+    iccPmrEl1 = 0;
+    nzcv = 0;
+    daif = 0;
+    tcreason = 0;
+    x.fill(0);
+    for (auto i = 0; i < NumVecRegs; ++i) {
+      z[i].zero();
+    }
+    for (auto i = 0; i < NumVecPredRegs; ++i) {
+      p[i].reset();
+    }
+    pcstateckpt = PCState();
+
+    BaseHTMCheckpoint::reset();
+}
+
+void
+ArmISA::HTMCheckpoint::save(ThreadContext *tc)
+{
+    sp = tc->readIntReg(INTREG_SPX);
+    // below should be enabled on condition that GICV3 is enabled
+    //tme_checkpoint->iccPmrEl1 = tc->readMiscReg(MISCREG_ICC_PMR_EL1);
+    nzcv = tc->readMiscReg(MISCREG_NZCV);
+    daif = tc->readMiscReg(MISCREG_DAIF);
+    for (auto n = 0; n < NumIntArchRegs; n++) {
+        x[n] = tc->readIntReg(n);
+    }
+    // TODO first detect if FP is enabled at this EL
+    for (auto n = 0; n < NumVecRegs; n++) {
+        RegId idx = RegId(VecRegClass, n);
+        z[n] = tc->readVecReg(idx);
+    }
+    for (auto n = 0; n < NumVecPredRegs; n++) {
+        RegId idx = RegId(VecPredRegClass, n);
+        p[n] = tc->readVecPredReg(idx);
+    }
+    fpcr = tc->readMiscReg(MISCREG_FPCR);
+    fpsr = tc->readMiscReg(MISCREG_FPSR);
+    pcstateckpt = tc->pcState();
+
+    BaseHTMCheckpoint::save(tc);
+}
+
+void
+ArmISA::HTMCheckpoint::restore(ThreadContext *tc, HtmFailureFaultCause cause)
+{
+    tc->setIntReg(INTREG_SPX, sp);
+    // below should be enabled on condition that GICV3 is enabled
+    //tc->setMiscReg(MISCREG_ICC_PMR_EL1, tme_checkpoint->iccPmrEl1);
+    tc->setMiscReg(MISCREG_NZCV, nzcv);
+    tc->setMiscReg(MISCREG_DAIF, daif);
+    for (auto n = 0; n < NumIntArchRegs; n++) {
+        tc->setIntReg(n, x[n]);
+    }
+    // TODO first detect if FP is enabled at this EL
+    for (auto n = 0; n < NumVecRegs; n++) {
+        RegId idx = RegId(VecRegClass, n);
+        tc->setVecReg(idx, z[n]);
+    }
+    for (auto n = 0; n < NumVecPredRegs; n++) {
+        RegId idx = RegId(VecPredRegClass, n);
+        tc->setVecPredReg(idx, p[n]);
+    }
+    tc->setMiscReg(MISCREG_FPCR, fpcr);
+    tc->setMiscReg(MISCREG_FPSR, fpsr);
+
+    // this code takes the generic HTM failure reason
+    // and prepares an Arm/TME-specific error code
+    // which is written to a destination register
+
+    bool interrupt = false; // TODO get this from threadcontext
+    bool retry = false;
+    uint64_t error_code = 0;
+    switch (cause) {
+      case HtmFailureFaultCause::EXPLICIT:
+        replaceBits(error_code, 14, 0, tcreason);
+        replaceBits(error_code, 16, 1);
+        retry = bits(15, tcreason);
+        break;
+      case HtmFailureFaultCause::MEMORY:
+        replaceBits(error_code, 17, 1);
+        retry = true;
+        break;
+      case HtmFailureFaultCause::OTHER:
+        replaceBits(error_code, 18, 1);
+        break;
+      case HtmFailureFaultCause::EXCEPTION:
+        replaceBits(error_code, 19, 1);
+        break;
+      case HtmFailureFaultCause::SIZE:
+        replaceBits(error_code, 20, 1);
+        break;
+      case HtmFailureFaultCause::NEST:
+        replaceBits(error_code, 21, 1);
+        break;
+        // case HtmFailureFaultCause_DEBUG:
+        //     replaceBits(error_code, 22, 1);
+        //     break;
+      default:
+        panic("Unknown HTM failure reason\n");
+    }
+    assert(!retry || !interrupt);
+    if (retry)
+        replaceBits(error_code, 15, 1);
+    if (interrupt)
+        replaceBits(error_code, 23, 1);
+    tc->setIntReg(rt, error_code);
+
+    // set next PC
+    pcstateckpt.uReset();
+    pcstateckpt.advance();
+    tc->pcState(pcstateckpt);
+
+    BaseHTMCheckpoint::restore(tc, cause);
+}
diff --git a/src/arch/arm/htm.hh b/src/arch/arm/htm.hh
new file mode 100644
index 0000000..3fa7c1d
--- /dev/null
+++ b/src/arch/arm/htm.hh
@@ -0,0 +1,88 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 __ARCH_ARM_HTM_HH__
+#define __ARCH_ARM_HTM_HH__
+
+/**
+ * @file
+ *
+ * ISA-specific types for hardware transactional memory.
+ */
+
+#include "arch/arm/registers.hh"
+#include "arch/generic/htm.hh"
+#include "base/types.hh"
+
+namespace ArmISA
+{
+
+class HTMCheckpoint : public BaseHTMCheckpoint
+{
+  public:
+    HTMCheckpoint()
+      : BaseHTMCheckpoint()
+    {}
+
+    const static int MAX_HTM_DEPTH = 255;
+
+    void reset() override;
+    void save(ThreadContext *tc) override;
+    void restore(ThreadContext *tc, HtmFailureFaultCause cause) override;
+
+    void destinationRegister(RegIndex dest) { rt = dest; }
+    void cancelReason(uint16_t reason) { tcreason = reason; }
+
+  private:
+    uint8_t rt; // TSTART destination register
+    Addr nPc; // Fallback instruction address
+    std::array<RegVal, NumIntArchRegs> x; // General purpose registers
+    std::array<VecRegContainer, NumVecRegs> z; // Vector registers
+    std::array<VecPredRegContainer, NumVecRegs> p; // Predicate registers
+    Addr sp; // Stack Pointer at current EL
+    uint16_t tcreason; // TCANCEL reason
+    uint32_t fpcr; // Floating-point Control Register
+    uint32_t fpsr; // Floating-point Status Register
+    uint32_t iccPmrEl1; // Interrupt Controller Interrupt Priority Mask
+    uint8_t nzcv; // Condition flags
+    uint8_t daif;
+    PCState pcstateckpt;
+};
+
+} // namespace ArmISA
+
+#endif
diff --git a/src/arch/arm/insts/misc64.cc b/src/arch/arm/insts/misc64.cc
index cdf3ece..3b3ef5d 100644
--- a/src/arch/arm/insts/misc64.cc
+++ b/src/arch/arm/insts/misc64.cc
@@ -868,3 +868,13 @@
 {
     return csprintf("%-10s (implementation defined)", fullMnemonic.c_str());
 }
+
+std::string
+RegNone::generateDisassembly(
+    Addr pc, const Loader::SymbolTable *symtab) const
+{
+    std::stringstream ss;
+    printMnemonic(ss);
+    printIntReg(ss, dest);
+    return ss.str();
+}
diff --git a/src/arch/arm/insts/misc64.hh b/src/arch/arm/insts/misc64.hh
index 30dd916..47d5d32 100644
--- a/src/arch/arm/insts/misc64.hh
+++ b/src/arch/arm/insts/misc64.hh
@@ -231,4 +231,19 @@
             Addr pc, const Loader::SymbolTable *symtab) const override;
 };
 
+class RegNone : public ArmStaticInst
+{
+  protected:
+    IntRegIndex dest;
+
+    RegNone(const char *mnem, ExtMachInst _machInst,
+                     OpClass __opClass, IntRegIndex _dest) :
+        ArmStaticInst(mnem, _machInst, __opClass),
+        dest(_dest)
+    {}
+
+    std::string generateDisassembly(
+        Addr pc, const Loader::SymbolTable *symtab) const;
+};
+
 #endif
diff --git a/src/arch/arm/insts/tme64.cc b/src/arch/arm/insts/tme64.cc
new file mode 100644
index 0000000..da228c4
--- /dev/null
+++ b/src/arch/arm/insts/tme64.cc
@@ -0,0 +1,242 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 "arch/arm/insts/tme64.hh"
+ #include "debug/ArmTme.hh"
+
+ #include <sstream>
+
+namespace ArmISAInst {
+
+std::string
+TmeImmOp64::generateDisassembly(
+    Addr pc, const Loader::SymbolTable *symtab) const
+{
+    std::stringstream ss;
+    printMnemonic(ss, "", false);
+    ccprintf(ss, "#0x%x", imm);
+    return ss.str();
+}
+
+std::string
+TmeRegNone64::generateDisassembly(
+    Addr pc, const Loader::SymbolTable *symtab) const
+{
+    std::stringstream ss;
+    printMnemonic(ss);
+    printIntReg(ss, dest);
+    return ss.str();
+}
+
+std::string
+MicroTmeBasic64::generateDisassembly(
+    Addr pc, const Loader::SymbolTable *symtab) const
+{
+    std::stringstream ss;
+    printMnemonic(ss);
+    return ss.str();
+}
+
+MicroTfence64::MicroTfence64(ExtMachInst machInst)
+    : MicroTmeBasic64("utfence", machInst, MemReadOp)
+{
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+    flags[IsMemBarrier] = true;
+    flags[IsMicroop] = true;
+    flags[IsReadBarrier] = true;
+    flags[IsWriteBarrier] = true;
+}
+
+Fault
+MicroTfence64::execute(
+    ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    return NoFault;
+}
+
+Fault
+MicroTfence64::initiateAcc(ExecContext *xc,
+                           Trace::InstRecord *traceData) const
+{
+    panic("tfence should not have memory semantics");
+
+    return NoFault;
+}
+
+Fault
+MicroTfence64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                           Trace::InstRecord *traceData) const
+{
+    panic("tfence should not have memory semantics");
+
+    return NoFault;
+}
+
+Tstart64::Tstart64(ExtMachInst machInst, IntRegIndex _dest)
+    : TmeRegNone64("tstart", machInst, MemReadOp, _dest)
+{
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+    _destRegIdx[_numDestRegs++] = RegId(IntRegClass, dest);
+    _numIntDestRegs++;
+    flags[IsHtmStart] = true;
+    flags[IsInteger] = true;
+    flags[IsLoad] = true;
+    flags[IsMemRef] = true;
+    flags[IsMicroop] = true;
+    flags[IsNonSpeculative] = true;
+}
+
+Fault
+Tstart64::execute(
+    ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    panic("TME is not supported with atomic memory");
+
+    return NoFault;
+}
+
+Ttest64::Ttest64(ExtMachInst machInst, IntRegIndex _dest)
+    : TmeRegNone64("ttest", machInst, MemReadOp, _dest)
+{
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+    _destRegIdx[_numDestRegs++] = RegId(IntRegClass, dest);
+    _numIntDestRegs++;
+    flags[IsInteger] = true;
+    flags[IsMicroop] = true;
+}
+
+Tcancel64::Tcancel64(ExtMachInst machInst, uint64_t _imm)
+    : TmeImmOp64("tcancel", machInst, MemReadOp, _imm)
+{
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+    flags[IsLoad] = true;
+    flags[IsMemRef] = true;
+    flags[IsMicroop] = true;
+    flags[IsNonSpeculative] = true;
+    flags[IsHtmCancel] = true;
+}
+
+Fault
+Tcancel64::execute(
+    ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    panic("TME is not supported with atomic memory");
+
+    return NoFault;
+}
+
+MacroTmeOp::MacroTmeOp(const char *mnem,
+                       ExtMachInst _machInst,
+                       OpClass __opClass) :
+  PredMacroOp(mnem, machInst, __opClass) {
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+
+    numMicroops = 0;
+    microOps = nullptr;
+}
+
+MicroTcommit64::MicroTcommit64(ExtMachInst machInst)
+    : MicroTmeBasic64("utcommit", machInst, MemReadOp)
+{
+    _numSrcRegs = 0;
+    _numDestRegs = 0;
+    _numFPDestRegs = 0;
+    _numVecDestRegs = 0;
+    _numVecElemDestRegs = 0;
+    _numIntDestRegs = 0;
+    _numCCDestRegs = 0;
+    flags[IsHtmStop] = true;
+    flags[IsLoad] = true;
+    flags[IsMemRef] = true;
+    flags[IsMicroop] = true;
+    flags[IsNonSpeculative] = true;
+}
+
+Fault
+MicroTcommit64::execute(ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    panic("TME is not supported with atomic memory");
+
+    return NoFault;
+}
+
+Tcommit64::Tcommit64(ExtMachInst _machInst) :
+                     MacroTmeOp("tcommit", machInst, MemReadOp)
+{
+    numMicroops = 2;
+    microOps = new StaticInstPtr[numMicroops];
+
+    microOps[0] = new ArmISAInst::MicroTfence64(_machInst);
+    microOps[0]->setDelayedCommit();
+    microOps[0]->setFirstMicroop();
+
+    microOps[1] = new ArmISAInst::MicroTcommit64(_machInst);
+    microOps[1]->setDelayedCommit();
+    microOps[1]->setLastMicroop();
+}
+
+} // namespace
diff --git a/src/arch/arm/insts/tme64.hh b/src/arch/arm/insts/tme64.hh
new file mode 100644
index 0000000..dada664
--- /dev/null
+++ b/src/arch/arm/insts/tme64.hh
@@ -0,0 +1,160 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 __ARCH_ARM_INSTS_TME64_HH__
+#define __ARCH_ARM_INSTS_TME64_HH__
+
+#include "arch/arm/insts/macromem.hh"
+#include "arch/arm/insts/pred_inst.hh"
+#include "arch/arm/insts/static_inst.hh"
+
+namespace ArmISAInst {
+
+class MicroTmeOp : public MicroOp
+{
+  protected:
+    MicroTmeOp(const char *mnem, ExtMachInst machInst, OpClass __opClass) :
+               MicroOp(mnem, machInst, __opClass)
+    {}
+};
+
+class MicroTmeBasic64 : public MicroTmeOp
+{
+  protected:
+    MicroTmeBasic64(const char *mnem, ExtMachInst machInst,
+                    OpClass __opClass) :
+                    MicroTmeOp(mnem, machInst, __opClass)
+    {}
+
+    std::string generateDisassembly(Addr pc,
+                                    const Loader::SymbolTable *symtab) const;
+};
+
+class TmeImmOp64 : public ArmStaticInst
+{
+  protected:
+    uint64_t imm;
+
+    TmeImmOp64(const char *mnem, ExtMachInst machInst,
+               OpClass __opClass, uint64_t _imm) :
+                 ArmStaticInst(mnem, machInst, __opClass),
+                 imm(_imm)
+    {}
+
+    std::string generateDisassembly(Addr pc,
+                                    const Loader::SymbolTable *symtab) const;
+};
+
+class TmeRegNone64 : public ArmStaticInst
+{
+  protected:
+    IntRegIndex dest;
+
+    TmeRegNone64(const char *mnem, ExtMachInst machInst,
+                 OpClass __opClass, IntRegIndex _dest) :
+                   ArmStaticInst(mnem, machInst, __opClass),
+                   dest(_dest)
+    {}
+
+    std::string generateDisassembly(Addr pc,
+                                    const Loader::SymbolTable *symtab) const;
+};
+
+class Tstart64 : public TmeRegNone64
+{
+  public:
+    Tstart64(ExtMachInst, IntRegIndex);
+
+    Fault execute(ExecContext *, Trace::InstRecord *) const;
+    Fault initiateAcc(ExecContext *, Trace::InstRecord *) const;
+    Fault completeAcc(PacketPtr, ExecContext *, Trace::InstRecord *) const;
+};
+
+class Ttest64 : public TmeRegNone64
+{
+  public:
+    Ttest64(ExtMachInst, IntRegIndex);
+
+    Fault execute(ExecContext *, Trace::InstRecord *) const;
+};
+
+class Tcancel64 : public TmeImmOp64
+{
+  public:
+    Tcancel64(ExtMachInst, uint64_t);
+
+    Fault execute(ExecContext *, Trace::InstRecord *) const;
+    Fault initiateAcc(ExecContext *, Trace::InstRecord *) const;
+    Fault completeAcc(PacketPtr, ExecContext *, Trace::InstRecord *) const;
+};
+
+class MicroTfence64 : public MicroTmeBasic64
+{
+  public:
+    MicroTfence64(ExtMachInst);
+
+    Fault execute(ExecContext *, Trace::InstRecord *) const;
+    Fault initiateAcc(ExecContext *, Trace::InstRecord *) const;
+    Fault completeAcc(PacketPtr, ExecContext *, Trace::InstRecord *) const;
+};
+
+class MicroTcommit64 : public MicroTmeBasic64
+{
+  public:
+    MicroTcommit64(ExtMachInst);
+
+    Fault execute(ExecContext *, Trace::InstRecord *) const;
+    Fault initiateAcc(ExecContext *, Trace::InstRecord *) const;
+    Fault completeAcc(PacketPtr, ExecContext *, Trace::InstRecord *) const;
+};
+
+
+class MacroTmeOp : public PredMacroOp
+{
+  protected:
+    MacroTmeOp(const char *mnem, ExtMachInst _machInst, OpClass __opClass);
+};
+
+class Tcommit64 : public MacroTmeOp
+{
+  public:
+    Tcommit64(ExtMachInst _machInst);
+};
+
+} // namespace
+
+#endif
diff --git a/src/arch/arm/insts/tme64classic.cc b/src/arch/arm/insts/tme64classic.cc
new file mode 100644
index 0000000..3ad6e0a
--- /dev/null
+++ b/src/arch/arm/insts/tme64classic.cc
@@ -0,0 +1,107 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 "arch/arm/faults.hh"
+#include "arch/arm/insts/tme64.hh"
+
+namespace ArmISAInst {
+
+Fault
+Tstart64::initiateAcc(ExecContext *xc,
+                      Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+Tstart64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                      Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+Ttest64::execute(
+    ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+Tcancel64::initiateAcc(ExecContext *xc,
+                       Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+Tcancel64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                       Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+MicroTcommit64::initiateAcc(ExecContext *xc,
+                            Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+}
+
+Fault
+MicroTcommit64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                            Trace::InstRecord *traceData) const
+{
+    return std::make_shared<UndefinedInstruction>(machInst,
+                                                  false,
+                                                  mnemonic);
+
+}
+
+} // namespace
diff --git a/src/arch/arm/insts/tme64ruby.cc b/src/arch/arm/insts/tme64ruby.cc
new file mode 100644
index 0000000..a28c4e4
--- /dev/null
+++ b/src/arch/arm/insts/tme64ruby.cc
@@ -0,0 +1,268 @@
+/*
+ * Copyright (c) 2020 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder.  You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 "arch/arm/faults.hh"
+#include "arch/arm/htm.hh"
+#include "arch/arm/insts/tme64.hh"
+#include "arch/arm/registers.hh"
+#include "arch/generic/memhelpers.hh"
+#include "arch/locked_mem.hh"
+#include "debug/ArmTme.hh"
+#include "mem/packet_access.hh"
+#include "mem/request.hh"
+
+namespace ArmISAInst {
+
+
+Fault
+Tstart64::initiateAcc(ExecContext *xc,
+                      Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    const uint64_t htm_depth = xc->getHtmTransactionalDepth();
+
+    DPRINTF(ArmTme, "tme depth is %d\n", htm_depth);
+
+    // Maximum TME nesting depth exceeded
+    if (htm_depth > ArmISA::HTMCheckpoint::MAX_HTM_DEPTH) {
+        const uint64_t htm_uid = xc->getHtmTransactionUid();
+        fault = std::make_shared<GenericHtmFailureFault>(
+            htm_uid, HtmFailureFaultCause::NEST);
+    }
+
+    if (fault == NoFault) {
+        Request::Flags memAccessFlags =
+            Request::STRICT_ORDER|Request::PHYSICAL|Request::HTM_START;
+
+        // Nested transaction start/stops never leave the core.
+        // These Requests are marked as NO_ACCESS to indicate that the request
+        // should not be sent to the cache controller.
+        if (htm_depth > 1) {
+            memAccessFlags = memAccessFlags | Request::NO_ACCESS;
+        }
+
+        fault = xc->initiateHtmCmd(memAccessFlags);
+    }
+
+    return fault;
+}
+
+Fault
+Tstart64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                      Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    uint64_t Mem;
+    uint64_t Dest64 = 0;
+    ThreadContext *tc = xc->tcBase();
+    const uint64_t htm_depth = xc->getHtmTransactionalDepth();
+
+    getMemLE(pkt, Mem, traceData);
+
+    // sanity check
+    if (Mem != 0) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    // sanity check
+    if (!xc->inHtmTransactionalState()) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    if (fault == NoFault) {
+        Dest64 = 0x0; // tstart returns 0 on success
+
+        // checkpointing occurs in the outer transaction only
+        if (htm_depth == 1) {
+            auto new_cpt = new HTMCheckpoint();
+
+            new_cpt->save(tc);
+            new_cpt->destinationRegister(dest);
+
+            ArmISA::globalClearExclusive(tc);
+
+            xc->tcBase()->setHtmCheckpointPtr(
+                std::unique_ptr<BaseHTMCheckpoint>(new_cpt));
+        }
+
+        xc->setIntRegOperand(this, 0, (Dest64) & mask(intWidth));
+
+
+        uint64_t final_val = Dest64;
+        if (traceData) { traceData->setData(final_val); }
+    }
+
+    return fault;
+}
+
+Fault
+Ttest64::execute(ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    uint64_t Dest64 = 0;
+    const uint64_t htm_depth = xc->getHtmTransactionalDepth();
+
+    // sanity check
+    if (htm_depth > ArmISA::HTMCheckpoint::MAX_HTM_DEPTH) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    Dest64 = htm_depth;
+
+
+    // sanity check
+    if (Dest64 == 0)
+        assert(!xc->inHtmTransactionalState());
+    else
+        assert(xc->inHtmTransactionalState());
+
+    if (fault == NoFault) {
+        uint64_t final_val = Dest64;
+        xc->setIntRegOperand(this, 0, (Dest64) & mask(intWidth));
+        if (traceData) { traceData->setData(final_val); }
+    }
+
+    return fault;
+}
+
+Fault
+Tcancel64::initiateAcc(ExecContext *xc, Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+
+    // sanity check
+    if (!xc->inHtmTransactionalState()) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    Request::Flags memAccessFlags =
+        Request::STRICT_ORDER|Request::PHYSICAL|Request::HTM_CANCEL;
+
+    fault = xc->initiateHtmCmd(memAccessFlags);
+
+    return fault;
+}
+
+Fault
+Tcancel64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                       Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    uint64_t Mem;
+
+    getMemLE(pkt, Mem, traceData);
+
+    // sanity check
+    if (Mem != 0) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    if (fault == NoFault) {
+        auto tme_checkpoint = static_cast<HTMCheckpoint*>(
+            xc->tcBase()->getHtmCheckpointPtr().get());
+        tme_checkpoint->cancelReason(imm);
+
+        fault = std::make_shared<GenericHtmFailureFault>(
+            xc->getHtmTransactionUid(),
+            HtmFailureFaultCause::EXPLICIT);
+    }
+
+    return fault;
+}
+
+Fault
+MicroTcommit64::initiateAcc(ExecContext *xc,
+                            Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    const uint64_t htm_depth = xc->getHtmTransactionalDepth();
+
+    // sanity check
+    if (!xc->inHtmTransactionalState()) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    DPRINTF(ArmTme, "tme depth is %d\n", htm_depth);
+
+    Request::Flags memAccessFlags =
+        Request::STRICT_ORDER|Request::PHYSICAL|Request::HTM_COMMIT;
+
+    // Nested transaction start/stops never leave the core.
+    // These Requests are marked as NO_ACCESS to indicate that the request
+    // should not be sent to the cache controller.
+    if (htm_depth > 1) {
+        memAccessFlags = memAccessFlags | Request::NO_ACCESS;
+    }
+
+    fault = xc->initiateHtmCmd(memAccessFlags);
+
+    return fault;
+}
+
+Fault
+MicroTcommit64::completeAcc(PacketPtr pkt, ExecContext *xc,
+                            Trace::InstRecord *traceData) const
+{
+    Fault fault = NoFault;
+    uint64_t Mem;
+    ThreadContext *tc = xc->tcBase();
+    const uint64_t htm_depth = xc->getHtmTransactionalDepth();
+
+    getMemLE(pkt, Mem, traceData);
+
+    // sanity check
+    if (Mem != 0) {
+        fault = std::make_shared<IllegalInstSetStateFault>();
+    }
+
+    if (fault == NoFault) {
+        if (htm_depth == 1) {
+            auto tme_checkpoint = static_cast<HTMCheckpoint*>(
+                xc->tcBase()->getHtmCheckpointPtr().get());
+
+            assert(tme_checkpoint);
+            assert(tme_checkpoint->valid());
+
+            tme_checkpoint->reset();
+            ArmISA::globalClearExclusive(tc);
+        }
+    }
+
+    return fault;
+}
+
+} // namespace
diff --git a/src/arch/arm/isa.cc b/src/arch/arm/isa.cc
index 0c312d0..3c6a3a2 100644
--- a/src/arch/arm/isa.cc
+++ b/src/arch/arm/isa.cc
@@ -91,6 +91,7 @@
         haveSecEL2 = system->haveSecEL2();
         sveVL = system->sveVL();
         haveLSE = system->haveLSE();
+        haveTME = system->haveTME();
     } else {
         highestELIs64 = true; // ArmSystem::highestELIs64 does the same
         haveSecurity = haveLPAE = haveVirtualization = false;
@@ -102,6 +103,7 @@
         haveSecEL2 = true;
         sveVL = p->sve_vl_se;
         haveLSE = true;
+        haveTME = true;
     }
 
     // Initial rename mode depends on highestEL
@@ -426,6 +428,10 @@
     miscRegs[MISCREG_ID_AA64MMFR1_EL1] = insertBits(
         miscRegs[MISCREG_ID_AA64MMFR1_EL1], 23, 20,
         havePAN ? 0x1 : 0x0);
+    // TME
+    miscRegs[MISCREG_ID_AA64ISAR0_EL1] = insertBits(
+        miscRegs[MISCREG_ID_AA64ISAR0_EL1], 27, 24,
+        haveTME ? 0x1 : 0x0);
 }
 
 void
diff --git a/src/arch/arm/isa.hh b/src/arch/arm/isa.hh
index c4ba063..910dc2c 100644
--- a/src/arch/arm/isa.hh
+++ b/src/arch/arm/isa.hh
@@ -96,6 +96,7 @@
         bool haveLSE;
         bool havePAN;
         bool haveSecEL2;
+        bool haveTME;
 
         /** SVE vector length in quadwords */
         unsigned sveVL;
diff --git a/src/arch/arm/isa/formats/aarch64.isa b/src/arch/arm/isa/formats/aarch64.isa
index 2730e42..f1a0cdb 100644
--- a/src/arch/arm/isa/formats/aarch64.isa
+++ b/src/arch/arm/isa/formats/aarch64.isa
@@ -1,4 +1,4 @@
-// Copyright (c) 2011-2019 ARM Limited
+// Copyright (c) 2011-2020 ARM Limited
 // All rights reserved
 //
 // The license below extends only to copyright in the software and shall
@@ -268,6 +268,8 @@
                     return new Brk64(machInst, imm16);
                   case 0x08:
                     return new Hlt64(machInst, imm16);
+                  case 0x0c:
+                    return new Tcancel64(machInst, imm16);
                   case 0x15:
                     return new FailUnimplemented("dcps1", machInst);
                   case 0x16:
@@ -288,7 +290,21 @@
                 IntRegIndex rt = (IntRegIndex)(uint8_t)bits(machInst, 4, 0);
                 switch (op0) {
                   case 0x0:
-                    if (rt != 0x1f || l)
+                    // early out for TME
+                    if (crn == 0x3 && op1 == 0x3 && op2 == 0x3) {
+                        switch (crm) {
+                            case 0x0:
+                              if (rt == 0b11111)
+                                return new Tcommit64(machInst);
+                              else
+                                return new Tstart64(machInst, rt);
+                            case 0x1:
+                              return new Ttest64(machInst, rt);
+                            default:
+                              return new Unknown64(machInst);
+                        }
+                    }
+                    else if (rt != 0x1f || l)
                         return new Unknown64(machInst);
                     if (crn == 0x2 && op1 == 0x3) {
                         switch (crm) {
diff --git a/src/arch/arm/isa/includes.isa b/src/arch/arm/isa/includes.isa
index 89c7200..11de6d8 100644
--- a/src/arch/arm/isa/includes.isa
+++ b/src/arch/arm/isa/includes.isa
@@ -1,6 +1,6 @@
 // -*- mode:c++ -*-
 
-// Copyright (c) 2010, 2012, 2017-2018 ARM Limited
+// Copyright (c) 2010, 2012, 2017-2018, 2020 ARM Limited
 // All rights reserved
 //
 // The license below extends only to copyright in the software and shall
@@ -64,6 +64,7 @@
 #include "arch/arm/insts/static_inst.hh"
 #include "arch/arm/insts/sve.hh"
 #include "arch/arm/insts/sve_mem.hh"
+#include "arch/arm/insts/tme64.hh"
 #include "arch/arm/insts/vfp.hh"
 #include "arch/arm/isa_traits.hh"
 #include "enums/DecoderFlavor.hh"
@@ -96,6 +97,7 @@
 #include "arch/arm/faults.hh"
 #include "arch/arm/interrupts.hh"
 #include "arch/arm/isa.hh"
+#include "arch/arm/htm.hh"
 #include "arch/arm/isa_traits.hh"
 #include "arch/arm/pauth_helpers.hh"
 #include "arch/arm/semihosting.hh"
@@ -119,4 +121,3 @@
 using namespace ArmISA;
 
 }};
-
diff --git a/src/arch/arm/isa/insts/branch64.isa b/src/arch/arm/isa/insts/branch64.isa
index 1c00e12..9cbeebc 100644
--- a/src/arch/arm/isa/insts/branch64.isa
+++ b/src/arch/arm/isa/insts/branch64.isa
@@ -1,6 +1,6 @@
 // -*- mode:c++ -*-
 
-// Copyright (c) 2011-2013, 2016,2018 ARM Limited
+// Copyright (c) 2011-2013, 2016, 2018, 2020 ARM Limited
 // All rights reserved
 //
 // The license below extends only to copyright in the software and shall
@@ -193,7 +193,14 @@
     exec_output += BasicExecute.subst(bIop)
 
     # ERET
-    bCode = '''Addr newPc;
+    bCode = '''
+                if (xc->inHtmTransactionalState()) {
+                    fault = std::make_shared<GenericHtmFailureFault>(
+                        xc->getHtmTransactionUid(),
+                        HtmFailureFaultCause::EXCEPTION);
+                    return fault;
+                }
+                Addr newPc;
                 CPSR cpsr = Cpsr;
                 CPSR spsr = Spsr;
 
diff --git a/src/arch/arm/isa/insts/misc.isa b/src/arch/arm/isa/insts/misc.isa
index 5439baa..6a9b048 100644
--- a/src/arch/arm/isa/insts/misc.isa
+++ b/src/arch/arm/isa/insts/misc.isa
@@ -143,6 +143,12 @@
     exec_output += PredOpExecute.subst(hvcIop)
 
     eretCode = '''
+        if (xc->inHtmTransactionalState()) {
+            fault = std::make_shared<GenericHtmFailureFault>(
+                xc->getHtmTransactionUid(),
+                HtmFailureFaultCause::EXCEPTION);
+            return fault;
+        }
         SCTLR sctlr   = Sctlr;
         CPSR old_cpsr = Cpsr;
         old_cpsr.nz   = CondCodesNZ;
@@ -754,6 +760,12 @@
     exec_output += QuiescePredOpExecuteWithFixup.subst(wfeIop)
 
     wfiCode = '''
+    if (xc->inHtmTransactionalState()) {
+        fault = std::make_shared<GenericHtmFailureFault>(
+            xc->getHtmTransactionUid(),
+            HtmFailureFaultCause::EXCEPTION);
+        return fault;
+    }
     HCR  hcr  = Hcr;
     CPSR cpsr = Cpsr;
     SCR  scr  = Scr64;
diff --git a/src/arch/arm/isa/insts/misc64.isa b/src/arch/arm/isa/insts/misc64.isa
index a8a8be6..7911ec9 100644
--- a/src/arch/arm/isa/insts/misc64.isa
+++ b/src/arch/arm/isa/insts/misc64.isa
@@ -1,6 +1,6 @@
 // -*- mode:c++ -*-
 
-// Copyright (c) 2011-2013, 2016-2018 ARM Limited
+// Copyright (c) 2011-2013, 2016-2018, 2020 ARM Limited
 // All rights reserved
 //
 // The license below extends only to copyright in the software and shall
@@ -37,6 +37,12 @@
 
 let {{
     svcCode = '''
+    if (xc->inHtmTransactionalState()) {
+        fault = std::make_shared<GenericHtmFailureFault>(
+            xc->getHtmTransactionUid(),
+            HtmFailureFaultCause::EXCEPTION);
+        return fault;
+    }
     fault = std::make_shared<SupervisorCall>(machInst, bits(machInst, 20, 5));
     '''
 
@@ -48,6 +54,12 @@
     exec_output = BasicExecute.subst(svcIop)
 
     hvcCode = '''
+    if (xc->inHtmTransactionalState()) {
+        fault = std::make_shared<GenericHtmFailureFault>(
+            xc->getHtmTransactionUid(),
+            HtmFailureFaultCause::EXCEPTION);
+        return fault;
+    }
     SCR scr = Scr64;
     HCR hcr = Hcr64;
     CPSR cpsr = Cpsr;
@@ -78,6 +90,12 @@
 
     # @todo: extend to take into account Virtualization.
     smcCode = '''
+    if (xc->inHtmTransactionalState()) {
+        fault = std::make_shared<GenericHtmFailureFault>(
+            xc->getHtmTransactionUid(),
+            HtmFailureFaultCause::EXCEPTION);
+        return fault;
+    }
     SCR scr = Scr64;
     CPSR cpsr = Cpsr;
 
diff --git a/src/arch/arm/isa/templates/misc64.isa b/src/arch/arm/isa/templates/misc64.isa
index 766f699..7a38494 100644
--- a/src/arch/arm/isa/templates/misc64.isa
+++ b/src/arch/arm/isa/templates/misc64.isa
@@ -1,6 +1,6 @@
 // -*- mode:c++ -*-
 
-// Copyright (c) 2011,2017-2019 ARM Limited
+// Copyright (c) 2011,2017-2020 ARM Limited
 // All rights reserved
 //
 // The license below extends only to copyright in the software and shall
@@ -201,3 +201,22 @@
         %(constructor)s;
     }
 }};
+
+def template RegNoneDeclare {{
+class %(class_name)s : public %(base_class)s
+{
+    public:
+        // Constructor
+        %(class_name)s(ExtMachInst machInst, IntRegIndex _dest);
+
+        Fault execute(ExecContext *, Trace::InstRecord *) const;
+};
+}};
+
+def template RegNoneConstructor {{
+    %(class_name)s::%(class_name)s(ExtMachInst machInst, IntRegIndex _dest)
+        : %(base_class)s("%(mnemonic)s", machInst, %(op_class)s, _dest)
+    {
+        %(constructor)s;
+    }
+}};
diff --git a/src/arch/arm/system.cc b/src/arch/arm/system.cc
index 3db13d7..9145b95 100644
--- a/src/arch/arm/system.cc
+++ b/src/arch/arm/system.cc
@@ -66,6 +66,7 @@
       _highestELIs64(p->highest_el_is_64),
       _physAddrRange64(p->phys_addr_range_64),
       _haveLargeAsid64(p->have_large_asid_64),
+      _haveTME(p->have_tme),
       _haveSVE(p->have_sve),
       _sveVL(p->sve_vl),
       _haveLSE(p->have_lse),
@@ -146,6 +147,12 @@
     }
 }
 
+bool
+ArmSystem::haveTME(ThreadContext *tc)
+{
+    return getArmSystem(tc)->haveTME();
+}
+
 Addr
 ArmSystem::resetAddr(ThreadContext *tc)
 {
diff --git a/src/arch/arm/system.hh b/src/arch/arm/system.hh
index e76245e..6422e5a 100644
--- a/src/arch/arm/system.hh
+++ b/src/arch/arm/system.hh
@@ -113,6 +113,11 @@
     const bool _haveLargeAsid64;
 
     /**
+     * True if system implements the transactional memory extension (TME)
+     */
+    const bool _haveTME;
+
+    /**
      * True if SVE is implemented (ARMv8)
      */
     const bool _haveSVE;
@@ -217,6 +222,11 @@
     /** Returns true if ASID is 16 bits in AArch64 (ARMv8) */
     bool haveLargeAsid64() const { return _haveLargeAsid64; }
 
+    /** Returns true if this system implements the transactional
+      * memory extension (ARMv9)
+      */
+    bool haveTME() const { return _haveTME; }
+
     /** Returns true if SVE is implemented (ARMv8) */
     bool haveSVE() const { return _haveSVE; }
 
@@ -292,6 +302,11 @@
     /** Return true if the system implements a specific exception level */
     static bool haveEL(ThreadContext *tc, ExceptionLevel el);
 
+    /** Returns true if the system of a specific thread context implements the
+     * transactional memory extension (TME)
+     */
+    static bool haveTME(ThreadContext *tc);
+
     /** Returns the reset address if the highest implemented exception level
      * for the system of a specific thread context is 64 bits (ARMv8)
      */