diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
index 036d27d2bf49f7d5ac9f84e940bf7e1e88b033b1..3678ecd55d64e033e03c1e5f7400db875054cc87 100644
--- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
+++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
@@ -34,6 +34,7 @@
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/operations.h>
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 #include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h>
@@ -257,7 +258,6 @@ namespace armarx
 
         armem::client::QueryResult qResult = memoryReader.query(builder.buildQueryInput());
         ARMARX_INFO << qResult;
-
         if (qResult.success)
         {
             ARMARX_IMPORTANT << "Getting entity via ID";
@@ -266,7 +266,8 @@ namespace armarx
             ARMARX_CHECK_GREATER_EQUAL(memory.size(), 1);
 
             const armem::wm::Entity* entity = memory.findEntity(entityID);
-            ARMARX_CHECK_NOT_NULL(entity);
+            ARMARX_CHECK_NOT_NULL(entity)
+                    << "Entity " << entityID << " was not found in " << armem::print(memory);
             ARMARX_CHECK_GREATER_EQUAL(entity->size(), 1);
 
             const armem::wm::EntitySnapshot& snapshot = entity->getLatestSnapshot();
diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
index e007e8f5e3ad47c57f9bb71c75e517d57af1addf..879809064b9cdb1429b49925e54ba5765cb534cf 100644
--- a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
+++ b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
@@ -60,8 +60,7 @@ namespace armarx
 
     void ExampleMemory::onInitComponent()
     {
-        workingMemory.name() = p.memoryName;
-        longtermMemory.name() = p.memoryName;
+        this->setMemoryName(p.memoryName);
 
         // Usually, the memory server will specify a number of core segments with a specific aron type.
         workingMemory.addCoreSegment("ExampleData", armem::example::ExampleData::toAronType());
@@ -70,7 +69,11 @@ namespace armarx
         bool trim = true;
         p.core.defaultCoreSegments = simox::alg::split(p.core._defaultSegmentsStr, ",", trim);
         p.core._defaultSegmentsStr.clear();
-        workingMemory.addCoreSegments(p.core.defaultCoreSegments);
+
+        for (const std::string& name : p.core.defaultCoreSegments)
+        {
+            workingMemory.addCoreSegment(name);
+        }
     }
 
     void ExampleMemory::onConnectComponent()
diff --git a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp
index 350810558ce9d2200e61bda865dd1633da15c128..15253dffb3eb8c7e49c114d2a7659627cd797071 100644
--- a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp
+++ b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp
@@ -55,8 +55,7 @@ namespace armarx
 
     void MotionMemory::onInitComponent()
     {
-        workingMemory.name() = memoryName;
-        longtermMemory.name() = memoryName;
+        this->setMemoryName(memoryName);
 
         mdbMotions.onInit();
     }
diff --git a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
index 4dde0d39cfc4d248188e9af772af470914c73290..582cf20586d119f1ef232cb32c706bbd1eef1e4e 100644
--- a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
+++ b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
@@ -68,8 +68,7 @@ namespace armarx::armem::server::robot_state
 
         const std::string prefix = "mem.";
 
-        workingMemory.name() = "RobotState";
-        longtermMemory.name() = "RobotState";
+        this->setMemoryName("RobotState");
         defs->optional(workingMemory.name(), prefix + "MemoryName", "Name of this memory server.");
 
         const std::string robotUnitPrefix{sensorValuePrefix};
diff --git a/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidget.ui b/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidget.ui
index 819331b5f27f58c036bb867e8a17dda8a0c8b977..58bead75ff15f27b039c50e712c1406f83e2fa32 100644
--- a/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidget.ui
+++ b/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidget.ui
@@ -34,7 +34,7 @@
       </layout>
      </item>
      <item>
-      <layout class="QHBoxLayout" name="ltmControlWidgetLayout">
+      <layout class="QHBoxLayout" name="diskControlWidgetLayout">
        <property name="spacing">
         <number>6</number>
        </property>
diff --git a/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidgetController.cpp b/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidgetController.cpp
index 83d1d8743a3b6ed0ebfeca5c704c96334b22108a..780dec62f846b619ca75b683eae884593237a2f1 100644
--- a/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidgetController.cpp
+++ b/source/RobotAPI/gui-plugins/ArMemMemoryViewer/ArMemMemoryViewerWidgetController.cpp
@@ -43,7 +43,6 @@ namespace armarx
         viewer = std::make_unique<MemoryViewer>(
 
                      widget.updateWidgetLayout,
-                     widget.ltmControlWidgetLayout,
 
                      widget.memoryGroupBox,
                      widget.treesLayout,
@@ -51,6 +50,8 @@ namespace armarx
                      widget.instanceGroupBox,
                      widget.treesLayout,
 
+                     widget.diskControlWidgetLayout,
+
                      widget.statusLabel
                  );
         viewer->setLogTag(getName());
diff --git a/source/RobotAPI/interface/armem/server/LoadingMemoryInterface.ice b/source/RobotAPI/interface/armem/server/LoadingMemoryInterface.ice
index bb1e7f221856b4505184fdeb380683c6f8cb917b..68a3ff2ef6fc06114eaff88dcb3e0393002b1160 100644
--- a/source/RobotAPI/interface/armem/server/LoadingMemoryInterface.ice
+++ b/source/RobotAPI/interface/armem/server/LoadingMemoryInterface.ice
@@ -11,7 +11,7 @@ module armarx
         {
             interface LoadingMemoryInterface
             {
-                armem::query::data::Result load(armem::query::data::Input query);
+
             };
         };
     };
diff --git a/source/RobotAPI/libraries/armem/CMakeLists.txt b/source/RobotAPI/libraries/armem/CMakeLists.txt
index b08141a6ef60148532ce3f1097eafacb6ae384b9..1050253cf3728945f245c1a6496b749cc0b0d7c9 100644
--- a/source/RobotAPI/libraries/armem/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/CMakeLists.txt
@@ -17,6 +17,9 @@ set(LIBS
     ArmarXCoreInterfaces ArmarXCore
     RemoteGui
     aron
+
+    # Needed for LTM
+    RobotAPI::aron::converter::json
     ${LIBMONGOCXX_LIBRARIES}
     ${LIBBSONCXX_LIBRARIES}
 )
@@ -34,9 +37,9 @@ set(LIB_FILES
 
     core/base/detail/MemoryItem.cpp
     core/base/detail/MemoryContainerBase.cpp
-    core/base/detail/EntityContainerBase.cpp
     core/base/detail/AronTyped.cpp
     core/base/detail/iteration_mixins.cpp
+    core/base/detail/lookup_mixins.cpp
     core/base/detail/negative_index_semantics.cpp
 
     # core/base/CoreSegmentBase.cpp
@@ -48,28 +51,12 @@ set(LIB_FILES
     core/base/ice_conversions.cpp
 
     core/wm/memory_definitions.cpp
-    core/wm/ice_conversions.cpp
-    core/wm/json_conversions.cpp
     core/wm/aron_conversions.cpp
+    core/wm/ice_conversions.cpp
+    core/wm/detail/data_lookup_mixins.cpp
     core/wm/visitor/Visitor.cpp
     core/wm/visitor/FunctionalVisitor.cpp
 
-    core/longtermmemory/CoreSegment.cpp
-    core/longtermmemory/Entity.cpp
-    core/longtermmemory/EntityInstance.cpp
-    core/longtermmemory/EntitySnapshot.cpp
-    core/longtermmemory/Memory.cpp
-    core/longtermmemory/ProviderSegment.cpp
-    core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
-
-    core/diskmemory/TypeIO.cpp
-    core/diskmemory/CoreSegment.cpp
-    core/diskmemory/Entity.cpp
-    core/diskmemory/EntityInstance.cpp
-    core/diskmemory/EntitySnapshot.cpp
-    core/diskmemory/Memory.cpp
-    core/diskmemory/ProviderSegment.cpp
-
     core/error/ArMemError.cpp
     core/error/mns.cpp
 
@@ -94,6 +81,11 @@ set(LIB_FILES
     server/MemoryRemoteGui.cpp
     server/RemoteGuiAronDataVisitor.cpp
 
+    server/ltm/LongtermMemoryBase.cpp
+    server/ltm/disk/MemoryManager.cpp
+    server/ltm/mongodb/MemoryManager.cpp
+    server/ltm/mongodb/ConnectionManager.cpp
+
     server/wm/memory_definitions.cpp
     server/wm/ice_conversions.cpp
     server/wm/detail/MaxHistorySize.cpp
@@ -107,7 +99,6 @@ set(LIB_FILES
     server/query_proc/base/CoreSegmentQueryProcessorBase.cpp
     server/query_proc/base/MemoryQueryProcessorBase.cpp
 
-    server/query_proc/diskmemory.cpp
     server/query_proc/ltm.cpp
     server/query_proc/wm.cpp
 
@@ -129,8 +120,8 @@ set(LIB_HEADERS
     core/SuccessHeader.h
     core/Time.h
     core/aron_conversions.h
-    core/json_conversions.h
     core/ice_conversions.h
+    core/json_conversions.h
     core/ice_conversions_boost_templates.h
     core/ice_conversions_templates.h
 
@@ -140,9 +131,10 @@ set(LIB_HEADERS
 
     core/base/detail/MemoryItem.h
     core/base/detail/MemoryContainerBase.h
-    core/base/detail/EntityContainerBase.h
     core/base/detail/AronTyped.h
+    core/base/detail/derived.h
     core/base/detail/iteration_mixins.h
+    core/base/detail/lookup_mixins.h
     core/base/detail/negative_index_semantics.h
 
     core/base/CoreSegmentBase.h
@@ -157,29 +149,10 @@ set(LIB_HEADERS
     core/wm/memory_definitions.h
     core/wm/aron_conversions.h
     core/wm/ice_conversions.h
-    core/wm/json_conversions.h
+    core/wm/detail/data_lookup_mixins.h
     core/wm/visitor/Visitor.h
     core/wm/visitor/FunctionalVisitor.h
 
-    core/longtermmemory/CoreSegment.h
-    core/longtermmemory/Entity.h
-    core/longtermmemory/EntityInstance.h
-    core/longtermmemory/EntitySnapshot.h
-    core/longtermmemory/Memory.h
-    core/longtermmemory/ProviderSegment.h
-    core/longtermmemory/mongodb/MongoDBConnectionManager.h
-
-    core/diskmemory/TypeIO.h
-    core/diskmemory/CoreSegment.h
-    core/diskmemory/Entity.h
-    core/diskmemory/EntityInstance.h
-    core/diskmemory/EntitySnapshot.h
-    core/diskmemory/Memory.h
-    core/diskmemory/ProviderSegment.h
-
-    core/ice_conversions_templates.h
-    core/ice_conversions.h
-
     client.h
     client/ComponentPlugin.h
     client/MemoryNameSystem.h
@@ -209,6 +182,11 @@ set(LIB_HEADERS
     server/MemoryRemoteGui.h
     server/RemoteGuiAronDataVisitor.h
 
+    server/ltm/LongtermMemoryBase.h
+    server/ltm/disk/MemoryManager.h
+    server/ltm/mongodb/MemoryManager.h
+    server/ltm/mongodb/ConnectionManager.h
+
     server/wm/memory_definitions.h
     server/wm/ice_conversions.h
     server/wm/detail/MaxHistorySize.h
@@ -225,7 +203,6 @@ set(LIB_HEADERS
     server/query_proc/base/CoreSegmentQueryProcessorBase.h
     server/query_proc/base/MemoryQueryProcessorBase.h
 
-    server/query_proc/diskmemory.h
     server/query_proc/ltm.h
     server/query_proc/wm.h
 
diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
index 4395b55fd45e6bdb019ee1285fbc5cc3dac648f9..cbacda1eb33a06e8ce202e2716f61adf4e53b1f6 100644
--- a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
+++ b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
@@ -272,11 +272,11 @@ namespace armarx::armem::client
                     {
                         if (id.hasInstanceIndex())
                         {
-                            result[id] = queryResult.memory.getEntityInstance(id);
+                            result[id] = queryResult.memory.getInstance(id);
                         }
                         else if (id.hasTimestamp())
                         {
-                            result[id] = queryResult.memory.getEntitySnapshot(id).getInstance(0);
+                            result[id] = queryResult.memory.getSnapshot(id).getInstance(0);
                         }
                         else if (id.hasEntityName())
                         {
diff --git a/source/RobotAPI/libraries/armem/client/Reader.cpp b/source/RobotAPI/libraries/armem/client/Reader.cpp
index 1f0e2ee51717e011de75f9fad4dd9c2c598ada88..2662f86e0d7f36827f9d5cff67f963ac29613de9 100644
--- a/source/RobotAPI/libraries/armem/client/Reader.cpp
+++ b/source/RobotAPI/libraries/armem/client/Reader.cpp
@@ -5,7 +5,6 @@
 #include <ArmarXCore/core/logging/Logging.h>
 
 #include <RobotAPI/libraries/armem/core/MemoryID_operators.h>
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/util/util.h>
@@ -116,7 +115,7 @@ namespace armarx::armem::client
             {
                 try
                 {
-                    wm::EntitySnapshot& snapshot = result.memory.getEntitySnapshot(snapshotID);
+                    wm::EntitySnapshot& snapshot = result.memory.getSnapshot(snapshotID);
                     return snapshot;
                 }
                 catch (const armem::error::ArMemError&)
diff --git a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp
index 3ac9f7438408460c157f7484d313ef0d6a3808a6..c2e4d5ed6df5c3e12c0d3e2ada0b93c91e232133 100644
--- a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp
@@ -45,16 +45,4 @@ namespace armarx::armem::client
         memoryReader.setReadingMemory(memory);
     }
 
-
-    armem::data::WaitForMemoryResult ReaderComponentPluginUser::useMemoryServer(const std::string& memoryName)
-    {
-        armem::data::WaitForMemoryResult result;
-        result.proxy = memoryNameSystem.useServer(memoryName);
-        if (result.proxy)
-        {
-            setReadingMemoryServer(result.proxy);
-        }
-        return result;
-    }
-
 }
diff --git a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h
index c0139e609e830e2c07517837f6cc3d48aff434db..059c5f93d5e8d872ecdc9bff86593db2c3de1163 100644
--- a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h
+++ b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h
@@ -50,10 +50,6 @@ namespace armarx::armem::client
         ReaderComponentPluginUser();
         ~ReaderComponentPluginUser() override;
 
-        [[deprecated("Use memoryNameSystem member instead of function inherited by ReaderComponentPluginUser.")]]
-        virtual armem::data::WaitForMemoryResult useMemoryServer(const std::string& memoryName) override;
-        using MemoryNameSystemComponentPluginUser::useMemoryServer;
-
 
     protected:
 
diff --git a/source/RobotAPI/libraries/armem/core/Commit.cpp b/source/RobotAPI/libraries/armem/core/Commit.cpp
index fed012450b059f50159c659217694c160e8f636a..db5f1b630e84ff276901f3321dd2a3fbbccc0442 100644
--- a/source/RobotAPI/libraries/armem/core/Commit.cpp
+++ b/source/RobotAPI/libraries/armem/core/Commit.cpp
@@ -14,7 +14,7 @@ namespace armarx::armem
     {
         return os << "Entity update: "
                << "\n- success:    \t" << rhs.entityID
-               << "\n- timestamp:  \t" << rhs.timeCreated
+               << "\n- timestamp:  \t" << toDateTimeMilliSeconds(rhs.timeCreated)
                << "\n- #instances: \t" << rhs.instancesData.size()
                << "\n"
                ;
@@ -25,7 +25,7 @@ namespace armarx::armem
         return os << "Entity update result: "
                << "\n- success:       \t" << (rhs.success ? "true" : "false")
                << "\n- snapshotID:    \t" << rhs.snapshotID
-               << "\n- time arrived:  \t" << rhs.timeArrived.toDateTime()
+               << "\n- time arrived:  \t" << toDateTimeMilliSeconds(rhs.timeArrived)
                << "\n- error message: \t" << rhs.errorMessage
                << "\n"
                ;
diff --git a/source/RobotAPI/libraries/armem/core/MemoryID.cpp b/source/RobotAPI/libraries/armem/core/MemoryID.cpp
index f8d7c832401a4ebf335347c67745c1ce82af4e03..f3b8c662ddef099b18dc09e03a81f21bd7de2bde 100644
--- a/source/RobotAPI/libraries/armem/core/MemoryID.cpp
+++ b/source/RobotAPI/libraries/armem/core/MemoryID.cpp
@@ -245,6 +245,31 @@ namespace armarx::armem
         return id;
     }
 
+    MemoryID MemoryID::removeLeafItem() const
+    {
+        if (instanceIndex != -1)
+        {
+            return getEntitySnapshotID();
+        }
+        if (timestamp != Time::microSeconds(-1))
+        {
+            return getEntityID();
+        }
+        if (!entityName.empty())
+        {
+            return getProviderSegmentID();
+        }
+        if (!providerSegmentName.empty())
+        {
+            return getCoreSegmentID();
+        }
+        if (!coreSegmentName.empty())
+        {
+            return getMemoryID();
+        }
+        return {};  // return empty if already empty. Client needs to check (Avoids using optional as additional include)
+    }
+
     void MemoryID::setMemoryID(const MemoryID& id)
     {
         memoryName = id.memoryName;
diff --git a/source/RobotAPI/libraries/armem/core/MemoryID.h b/source/RobotAPI/libraries/armem/core/MemoryID.h
index f9d3d5b58ca4670a8abb4333e417a9a2109843ae..d583e752258d69e8271e30be2a2d091493aa18cc 100644
--- a/source/RobotAPI/libraries/armem/core/MemoryID.h
+++ b/source/RobotAPI/libraries/armem/core/MemoryID.h
@@ -138,7 +138,11 @@ namespace armarx::armem
         MemoryID getEntitySnapshotID() const;
         MemoryID getEntityInstanceID() const;
 
-        // Slice setters: Set upper part of the ID.
+        // Slice getter: remove the last set name
+        MemoryID removeLeafItem() const;
+
+
+        // Slice setters: Set part of the ID.
 
         void setMemoryID(const MemoryID& id);
         void setCoreSegmentID(const MemoryID& id);
diff --git a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
index 0de79cccd0af6a85dd396b8891e91c572ee24fb2..f4d0b530f43afcfa7f7aeba95389bdb8a5371918 100644
--- a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
@@ -5,8 +5,9 @@
 
 #include "ProviderSegmentBase.h"
 #include "detail/AronTyped.h"
-#include "detail/EntityContainerBase.h"
+#include "detail/MemoryContainerBase.h"
 #include "detail/iteration_mixins.h"
+#include "detail/lookup_mixins.h"
 
 
 namespace armarx::armem::base
@@ -17,13 +18,16 @@ namespace armarx::armem::base
      */
     template <class _ProviderSegmentT, class _Derived>
     class CoreSegmentBase :
-        public detail::EntityContainerBase<_ProviderSegmentT, typename _ProviderSegmentT::EntityT, _Derived>,
-        public detail::AronTyped,
-        public detail::ForEachEntityInstanceMixin<_Derived>,
-        public detail::ForEachEntitySnapshotMixin<_Derived>,
-        public detail::ForEachEntityMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>
+        , public detail::AronTyped
+        , public detail::ForEachEntityInstanceMixin<_Derived>
+        , public detail::ForEachEntitySnapshotMixin<_Derived>
+        , public detail::ForEachEntityMixin<_Derived>
+        , public detail::GetFindInstanceMixin<_Derived>
+        , public detail::GetFindSnapshotMixin<_Derived>
+        , public detail::GetFindEntityMixin<_Derived>
     {
-        using Base = detail::EntityContainerBase<_ProviderSegmentT, typename _ProviderSegmentT::EntityT, _Derived>;
+        using Base = detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>;
 
     public:
 
@@ -35,6 +39,9 @@ namespace armarx::armem::base
         using EntitySnapshotT = typename EntityT::EntitySnapshotT;
         using EntityInstanceT = typename EntitySnapshotT::EntityInstanceT;
 
+        using ChildT = ProviderSegmentT;
+
+
         struct UpdateResult
         {
             armarx::armem::UpdateType coreSegmentUpdateType;
@@ -80,69 +87,92 @@ namespace armarx::armem::base
 
         // READ ACCESS
 
-        inline const std::string& name() const
+        // Get key
+        inline std::string& name()
         {
             return this->id().coreSegmentName;
         }
-        inline std::string& name()
+        inline const std::string& name() const
         {
-            return const_cast<std::string&>(const_cast<const CoreSegmentBase*>(this)->name());
+            return this->id().coreSegmentName;
         }
 
 
+        // Has child by key
         bool hasProviderSegment(const std::string& name) const
         {
-            return this->_container.count(name) > 0;
+            return this->findProviderSegment(name) != nullptr;
+        }
+        // Has child by memory ID
+        bool hasProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            return this->findProviderSegment(providerSegmentID) != nullptr;
         }
 
-        std::vector<std::string> getProviderSegmentNames() const
+
+        // Find child by key
+        ProviderSegmentT* findProviderSegment(const std::string& name)
         {
-            return simox::alg::get_keys(this->_container);
+            return detail::findChildByKey(name, this->_container);
+        }
+        const ProviderSegmentT* findProviderSegment(const std::string& name) const
+        {
+            return detail::findChildByKey(name, this->_container);
         }
 
+        // Get child by key
         ProviderSegmentT& getProviderSegment(const std::string& name)
         {
-            return const_cast<ProviderSegmentT&>(const_cast<const CoreSegmentBase*>(this)->getProviderSegment(name));
+            return detail::getChildByKey(name, this->_container, *this);
         }
-
         const ProviderSegmentT& getProviderSegment(const std::string& name) const
         {
-            auto it = this->_container.find(name);
-            if (it != this->_container.end())
-            {
-                return it->second;
-            }
-            else
-            {
-                throw armem::error::MissingEntry::create<ProviderSegmentT>(name, *this);
-            }
+            return detail::getChildByKey(name, this->_container, *this);
         }
 
-        using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const
+        // Find child by MemoryID
+        ProviderSegmentT* findProviderSegment(const MemoryID& providerSegmentID)
         {
-            this->_checkContainerName(id.coreSegmentName, this->getKeyString());
-            return getProviderSegment(id.providerSegmentName).getEntity(id);
+            detail::checkHasProviderSegmentName(providerSegmentID);
+            return this->findProviderSegment(providerSegmentID.providerSegmentName);
+        }
+        const ProviderSegmentT* findProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            detail::checkHasProviderSegmentName(providerSegmentID);
+            return this->findProviderSegment(providerSegmentID.providerSegmentName);
         }
 
-        const EntityT* findEntity(const MemoryID& id) const
+        // Get child by MemoryID
+        ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID)
         {
-            this->_checkContainerName(id.coreSegmentName, this->getKeyString());
-            if (id.hasProviderSegmentName())
-            {
-                return getProviderSegment(id.providerSegmentName).findEntity(id);
-            }
-            else
-            {
-                for (const auto& [_, providerSegment] : this->_container)
-                {
-                    if (auto entity = providerSegment.findEntity(id))
-                    {
-                        return entity;
-                    }
-                }
-                return nullptr;
-            }
+            detail::checkHasProviderSegmentName(providerSegmentID);
+            return this->getProviderSegment(providerSegmentID.providerSegmentName);
+        }
+        const ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            detail::checkHasProviderSegmentName(providerSegmentID);
+            return this->getProviderSegment(providerSegmentID.providerSegmentName);
+        }
+
+        // get/findInstance are provided by GetFindInstanceMixin
+        // get/findSnapshot are provided by GetFindSnapshotMixin
+        // get/findEntity are provided by GetFindEntityMixin
+        using detail::GetFindEntityMixin<DerivedT>::hasEntity;
+        using detail::GetFindEntityMixin<DerivedT>::findEntity;
+
+        // Search all provider segments for the first matching entity.
+
+        bool hasEntity(const std::string& entityName) const
+        {
+            return this->findEntity(entityName) != nullptr;
+        }
+        EntityT* findEntity(const std::string& entityName)
+        {
+            return _findEntity(*this, entityName);
+        }
+        const EntityT* findEntity(const std::string& entityName) const
+        {
+            return _findEntity(*this, entityName);
         }
 
 
@@ -170,6 +200,13 @@ namespace armarx::armem::base
         // forEachInstance() is provided by ForEachEntityInstanceMixin.
 
 
+        // Get child keys
+        std::vector<std::string> getProviderSegmentNames() const
+        {
+            return simox::alg::get_keys(this->_container);
+        }
+
+
         [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         inline const auto& providerSegments() const
         {
@@ -193,7 +230,7 @@ namespace armarx::armem::base
         {
             this->_checkContainerName(update.entityID.coreSegmentName, this->name());
 
-            auto [inserted, provSeg] = addProviderSegmentIfMissing(update.entityID.providerSegmentName);
+            auto [inserted, provSeg] = _addProviderSegmentIfMissing(update.entityID.providerSegmentName);
 
 
             // Update entry.
@@ -209,30 +246,6 @@ namespace armarx::armem::base
             return ret;
         }
 
-        std::pair<bool, ProviderSegmentT*> addProviderSegmentIfMissing(const std::string& providerSegmentName)
-        {
-            ProviderSegmentT* provSeg;
-
-            auto it = this->_container.find(providerSegmentName);
-            if (it == this->_container.end())
-            {
-                if (_addMissingProviderSegmentDuringUpdate)
-                {
-                    // Insert into map.
-                    provSeg = &addProviderSegment(providerSegmentName);
-                    return {true, provSeg};
-                }
-                else
-                {
-                    throw error::MissingEntry::create<ProviderSegmentT>(providerSegmentName, *this);
-                }
-            }
-            else
-            {
-                provSeg = &it->second;
-                return {false, provSeg};
-            }
-        }
 
         void append(const _Derived& m)
         {
@@ -259,27 +272,29 @@ namespace armarx::armem::base
         ProviderSegmentT& addProviderSegment(const std::string& name, aron::typenavigator::ObjectNavigatorPtr providerSegmentType = nullptr)
         {
             aron::typenavigator::ObjectNavigatorPtr type = providerSegmentType ? providerSegmentType : this->aronType();
-            return addProviderSegment(ProviderSegmentT(name, this->id(), type));
+            return this->_derived().addProviderSegment(name, name, type);
         }
 
         /// Copy and insert a provider segment.
         ProviderSegmentT& addProviderSegment(const ProviderSegmentT& providerSegment)
         {
-            return addProviderSegment(ProviderSegment(providerSegment));
+            return this->_derived().addProviderSegment(providerSegment.name(), ProviderSegmentT(providerSegment));
         }
 
         /// Move and insert a provider segment.
         ProviderSegmentT& addProviderSegment(ProviderSegmentT&& providerSegment)
         {
-            if (hasProviderSegment(providerSegment.name()))
-            {
-                throw armem::error::ContainerEntryAlreadyExists(
-                    ProviderSegmentT::getLevelName(), providerSegment.name(), getLevelName(), this->getKeyString());
-            }
+            const std::string name = providerSegment.name();  // Copy before move.
+            return this->_derived().addProviderSegment(name, std::move(providerSegment));
+        }
 
-            auto it = this->_container.emplace(providerSegment.name(), std::move(providerSegment)).first;
-            it->second.id().setCoreSegmentID(this->id());
-            return it->second;
+        /// Insert a provider segment in-place.
+        template <class ...Args>
+        ProviderSegmentT& addProviderSegment(const std::string& name, Args... args)
+        {
+            ChildT& child = this->template _addChild<ChildT>(name, args...);
+            child.id() = this->id().withProviderSegmentName(name);
+            return child;
         }
 
 
@@ -317,6 +332,50 @@ namespace armarx::armem::base
         }
 
 
+    protected:
+
+        template <class ParentT>
+        static
+        auto*
+        _findEntity(ParentT&& parent, const std::string& entityName)
+        {
+            decltype(parent.findEntity(entityName)) result = nullptr;
+            parent.forEachProviderSegment([&result, &entityName](auto & provSeg)
+            {
+                result = provSeg.findEntity(entityName);
+                return result == nullptr;  // Keep going if null, break if not null.
+            });
+            return result;
+        }
+
+
+        std::pair<bool, ProviderSegmentT*>
+        _addProviderSegmentIfMissing(const std::string& providerSegmentName)
+        {
+            ProviderSegmentT* provSeg;
+
+            auto it = this->_container.find(providerSegmentName);
+            if (it == this->_container.end())
+            {
+                if (_addMissingProviderSegmentDuringUpdate)
+                {
+                    // Insert into map.
+                    provSeg = &addProviderSegment(providerSegmentName);
+                    return {true, provSeg};
+                }
+                else
+                {
+                    throw error::MissingEntry::create<ProviderSegmentT>(providerSegmentName, *this);
+                }
+            }
+            else
+            {
+                provSeg = &it->second;
+                return {false, provSeg};
+            }
+        }
+
+
     private:
 
         bool _addMissingProviderSegmentDuringUpdate = true;
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityBase.h b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
index 05cbf780d1e95611d629d320581122b59c5f358c..ca9fdd8d63babff5ed51f7b731966b3ee91829df 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
@@ -11,6 +11,7 @@
 #include "EntitySnapshotBase.h"
 #include "detail/MemoryContainerBase.h"
 #include "detail/iteration_mixins.h"
+#include "detail/lookup_mixins.h"
 #include "detail/negative_index_semantics.h"
 
 
@@ -38,8 +39,9 @@ namespace armarx::armem::base
      */
     template <class _EntitySnapshotT, class _Derived>
     class EntityBase :
-        public detail::MemoryContainerBase<std::map<Time, _EntitySnapshotT>, _Derived>,
-        public detail::ForEachEntityInstanceMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<Time, _EntitySnapshotT>, _Derived>
+        , public detail::ForEachEntityInstanceMixin<_Derived>
+        , public detail::GetFindInstanceMixin<_Derived>
     {
         using Base = detail::MemoryContainerBase<std::map<Time, _EntitySnapshotT>, _Derived>;
 
@@ -51,6 +53,8 @@ namespace armarx::armem::base
         using EntitySnapshotT = _EntitySnapshotT;
         using EntityInstanceT = typename EntitySnapshotT::EntityInstanceT;
 
+        using ChildT = EntitySnapshotT;
+
         struct UpdateResult
         {
             armarx::armem::UpdateType entityUpdateType;
@@ -83,50 +87,43 @@ namespace armarx::armem::base
 
         // READING
 
-        inline const std::string& name() const
+        // Get key
+        inline std::string& name()
         {
             return this->id().entityName;
         }
-        inline std::string& name()
+        inline const std::string& name() const
         {
-            return const_cast<std::string&>(const_cast<const EntityBase*>(this)->name());
+            return this->id().entityName;
         }
 
-        /**
-         * @brief Indicates whether a history entry for the given time exists.
-         */
-        bool hasSnapshot(const Time& time)
-        {
-            return const_cast<const EntityBase*>(this)->hasSnapshot(time);
-        }
+
+        // Has child by key
+        /// Indicates whether a history entry for the given time exists.
         bool hasSnapshot(const Time& time) const
         {
-            return this->_container.count(time) > 0;
+            return this->findSnapshot(time) != nullptr;
         }
-
-        /**
-         * @brief Get the latest timestamp.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         */
-        Time getLatestTimestamp()
+        // Has child by MemoryID
+        bool hasSnapshot(const MemoryID& snapshotID) const
         {
-            return const_cast<const EntityBase*>(this)->getLatestTimestamp();
+            return this->findSnapshot(snapshotID) != nullptr;
         }
 
-        Time getLatestTimestamp() const
+
+        // Find child via key
+        EntitySnapshotT*
+        findSnapshot(const Time& timestamp)
         {
-            return getLatestItem().first;
+            return detail::findChildByKey(timestamp, this->_container);
         }
-
-        /**
-         * @brief Get all timestamps in the history.
-         */
-        std::vector<Time> getTimestamps() const
+        const EntitySnapshotT*
+        findSnapshot(const Time& timestamp) const
         {
-            return simox::alg::get_keys(this->_container);
+            return detail::findChildByKey(timestamp, this->_container);
         }
 
-
+        // Get child via key
         /**
          * @brief Get a snapshot.
          * @param time The time.
@@ -134,33 +131,85 @@ namespace armarx::armem::base
          *
          * @throws `armem::error::MissingEntry` If there is no such entry.
          */
-        EntitySnapshotT& getSnapshot(const Time& time)
+        EntitySnapshotT&
+        getSnapshot(const Time& time)
         {
-            return const_cast<EntitySnapshotT&>(const_cast<const EntityBase*>(this)->getSnapshot(time));
+            return detail::getChildByKey(time, this->_container, *this, [](const Time & time)
+            {
+                return toDateTimeMilliSeconds(time);
+            });
         }
-
-        const EntitySnapshotT& getSnapshot(const Time& time) const
+        const EntitySnapshotT&
+        getSnapshot(const Time& time) const
         {
-            auto it = this->_container.find(time);
-            if (it != this->_container.end())
-            {
-                return it->second;
-            }
-            else
+            return detail::getChildByKey(time, this->_container, *this, [](const Time & time)
             {
-                throw armem::error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
-            }
+                return toDateTimeMilliSeconds(time);
+            });
+        }
+
+        // Find child via MemoryID
+        EntitySnapshotT*
+        findSnapshot(const MemoryID& snapshotID)
+        {
+            detail::checkHasTimestamp(snapshotID);
+            return this->findSnapshot(snapshotID.timestamp);
+        }
+        const EntitySnapshotT*
+        findSnapshot(const MemoryID& snapshotID) const
+        {
+            detail::checkHasTimestamp(snapshotID);
+            return this->findSnapshot(snapshotID.timestamp);
+        }
+
+        // Get child via MemoryID
+        EntitySnapshotT&
+        getSnapshot(const MemoryID& snapshotID)
+        {
+            detail::checkHasTimestamp(snapshotID);
+            return this->getSnapshot(snapshotID.timestamp);
+        }
+        const EntitySnapshotT&
+        getSnapshot(const MemoryID& snapshotID) const
+        {
+            detail::checkHasTimestamp(snapshotID);
+            return this->getSnapshot(snapshotID.timestamp);
+
         }
 
-        EntitySnapshotT& getSnapshot(const MemoryID& id)
+        // get/findInstance are provided by GetFindInstanceMixin
+
+
+        // More getter/finder for snapshots
+
+        /**
+         * @brief Get the latest timestamp.
+         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
+         */
+        Time getLatestTimestamp() const
         {
-            return const_cast<EntitySnapshotT&>(const_cast<const EntityBase*>(this)->getSnapshot(id));
+            return this->getLatestSnapshot().time();
+        }
+        /**
+         * @brief Get the oldest timestamp.
+         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
+         */
+        Time getFirstTimestamp() const
+        {
+            return this->getFirstSnapshot().time();
         }
 
-        const EntitySnapshotT& getSnapshot(const MemoryID& id) const
+        /**
+         * @brief Return the snapshot with the most recent timestamp.
+         * @return The latest snapshot or nullptr if the entity is empty.
+         */
+        EntitySnapshotT* findLatestSnapshot()
         {
-            this->_checkContainerName(id.entityName, this->name());
-            return getSnapshot(id.timestamp);
+            return this->empty() ? nullptr : &this->_container.rbegin()->second;
+        }
+        const EntitySnapshotT* findLatestSnapshot() const
+        {
+            return this->empty() ? nullptr : &this->_container.rbegin()->second;
         }
 
         /**
@@ -174,12 +223,33 @@ namespace armarx::armem::base
         }
         const EntitySnapshotT& getLatestSnapshot() const
         {
-            return getLatestItem().second;
+            if (const EntitySnapshotT* snapshot = this->findLatestSnapshot())
+            {
+                return *snapshot;
+            }
+            else
+            {
+                throw armem::error::EntityHistoryEmpty(name(), "when getting the latest snapshot.");
+            }
         }
 
+
         /**
-         * @brief Return the snapshot with the most recent timestamp.
-         * @return The latest snapshot.
+         * @brief Return the snapshot with the least recent timestamp.
+         * @return The first snapshot or nullptr if the entity is empty.
+         */
+        EntitySnapshotT* findFirstSnapshot()
+        {
+            return this->empty() ? nullptr : &this->_container.begin()->second;
+        }
+        const EntitySnapshotT* findFirstSnapshot() const
+        {
+            return this->empty() ? nullptr : &this->_container.begin()->second;
+        }
+
+        /**
+         * @brief Return the snapshot with the least recent timestamp.
+         * @return The first snapshot.
          * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
          */
         EntitySnapshotT& getFirstSnapshot()
@@ -188,22 +258,27 @@ namespace armarx::armem::base
         }
         const EntitySnapshotT& getFirstSnapshot() const
         {
-            return getFirstItem().second;
+            if (const EntitySnapshotT* snapshot = this->findFirstSnapshot())
+            {
+                return *snapshot;
+            }
+            else
+            {
+                throw armem::error::EntityHistoryEmpty(name(), "when getting the first snapshot.");
+            }
         }
 
 
         /**
          * @brief Return the lastest snapshot before time.
          * @param time The time.
-         * @return The latest snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         * @throw `armem::error::MissingEntry` If no such snapshot
+         * @return The latest snapshot < time or nullptr if none was found.
          */
-        const EntitySnapshotT& getLatestSnapshotBefore(const Time& time) const
+        const EntitySnapshotT* findLatestSnapshotBefore(const Time& time) const
         {
             if (this->empty())
             {
-                throw error::EntityHistoryEmpty(this->name());
+                return nullptr;
             }
 
             // We want the rightmost element < time
@@ -213,7 +288,7 @@ namespace armarx::armem::base
             // refIt = begin() => no element < time
             if (greaterEq == this->_container.begin())
             {
-                throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+                return nullptr;
             }
 
             // end(): No element >= time, we can still have one < time (rbegin()) => std::prev(end())
@@ -223,29 +298,25 @@ namespace armarx::armem::base
             typename ContainerT::const_iterator less = std::prev(greaterEq);
 
             // we return the element before if possible
-            return less->second;
+            return &less->second;
         }
 
         /**
-         * @brief Return the lastest snapshot before or at time.
+         * @brief Return the latest snapshot before or at time.
          * @param time The time.
-         * @return The latest snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         * @throw `armem::error::MissingEntry` If no such snapshot
+         * @return The latest snapshot <= time or nullptr if none was found.
          */
-        const EntitySnapshotT& getLatestSnapshotBeforeOrAt(const Time& time) const
+        const EntitySnapshotT* findLatestSnapshotBeforeOrAt(const Time& time) const
         {
-            return getLatestSnapshotBefore(time + Time::microSeconds(1));
+            return findLatestSnapshotBefore(time + Time::microSeconds(1));
         }
 
         /**
          * @brief Return first snapshot after or at time.
          * @param time The time.
-         * @return The first snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         * @throw `armem::error::MissingEntry` If no such snapshot
+         * @return The first snapshot >= time or nullptr if none was found.
          */
-        const EntitySnapshotT& getFirstSnapshotAfterOrAt(const Time& time) const
+        const EntitySnapshotT* findFirstSnapshotAfterOrAt(const Time& time) const
         {
             // We want the leftmost element >= time.
             // That's lower bound.
@@ -253,21 +324,19 @@ namespace armarx::armem::base
 
             if (greaterEq == this->_container.end())
             {
-                throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+                return nullptr;
             }
-            return greaterEq->second;
+            return &greaterEq->second;
         }
 
         /**
          * @brief Return first snapshot after time.
          * @param time The time.
-         * @return The first snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         * @throw `armem::error::MissingEntry` If no such snapshot
+         * @return The first snapshot >= time or nullptr if none was found.
          */
-        const EntitySnapshotT& getFirstSnapshotAfter(const Time& time) const
+        const EntitySnapshotT* findFirstSnapshotAfter(const Time& time) const
         {
-            return getFirstSnapshotAfter(time - Time::microSeconds(1));
+            return findFirstSnapshotAfter(time - Time::microSeconds(1));
         }
 
 
@@ -386,6 +455,14 @@ namespace armarx::armem::base
         }
 
 
+        // Get child keys
+        /// @brief Get all timestamps in the history.
+        std::vector<Time> getTimestamps() const
+        {
+            return simox::alg::get_keys(this->_container);
+        }
+
+
         [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         inline const ContainerT& history() const
         {
@@ -452,26 +529,33 @@ namespace armarx::armem::base
             });
         }
 
-        /**
-         * @brief Add a single snapshot with data.
-         * @param snapshot The snapshot.
-         * @return The stored snapshot.
-         */
+
+        /// Add a snapshot at the given time.
+        EntitySnapshotT& addSnapshot(const Time& timestamp)
+        {
+            return this->addSnapshot(timestamp, EntitySnapshotT(timestamp));
+        }
+
+        /// Copy and insert a snapshot
         EntitySnapshotT& addSnapshot(const EntitySnapshotT& snapshot)
         {
-            return addSnapshot(EntitySnapshotT(snapshot));
+            return this->addSnapshot(snapshot.time(), EntitySnapshotT(snapshot));
         }
 
+        /// Move and insert a snapshot
         EntitySnapshotT& addSnapshot(EntitySnapshotT&& snapshot)
         {
-            auto it = this->_container.emplace_hint(this->_container.end(), snapshot.time(), std::move(snapshot));
-            it->second.id().setEntityID(this->id());
-            return it->second;
+            Time timestamp = snapshot.time();  // Copy before move.
+            return this->addSnapshot(timestamp, std::move(snapshot));
         }
 
-        EntitySnapshotT& addSnapshot(const Time& timestamp)
+        /// Insert a snapshot in-place.
+        template <class ...Args>
+        EntitySnapshotT& addSnapshot(const Time& timestamp, Args... args)
         {
-            return addSnapshot(EntitySnapshotT(timestamp, this->id()));
+            auto it = this->_container.emplace_hint(this->_container.end(), timestamp, args...);
+            it->second.id() = this->id().withTimestamp(timestamp);
+            return it->second;
         }
 
 
@@ -508,40 +592,6 @@ namespace armarx::armem::base
             return "entity";
         }
 
-
-    protected:
-
-        /**
-         * @brief Return the snapshot with the most recent timestamp.
-         * @return The latest snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         */
-        const typename ContainerT::value_type&
-        getLatestItem() const
-        {
-            if (this->_container.empty())
-            {
-                throw armem::error::EntityHistoryEmpty(name(), "when getting the latest snapshot.");
-            }
-            return *this->_container.rbegin();
-        }
-
-        /**
-         * @brief Return the snapshot with the least recent timestamp.
-         * @return The first snapshot.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         */
-        const typename ContainerT::value_type&
-        getFirstItem() const
-        {
-            if (this->_container.empty())
-            {
-                throw armem::error::EntityHistoryEmpty(name(), "when getting the first snapshot.");
-            }
-            return *this->_container.begin();
-        }
-
-
     };
 
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
index fcb1869f791d9094fd793ff3af721e5fb942f111..8f7b8aafc4cebd74c241bfb1245388a943897e01 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
@@ -72,6 +72,7 @@ namespace armarx::armem::base
         }
 
 
+        // Key
         inline int& index()
         {
             return id().instanceIndex;
@@ -82,6 +83,8 @@ namespace armarx::armem::base
         }
 
 
+        // Data
+
         EntityInstanceMetadata& metadata()
         {
             return _metadata;
@@ -102,6 +105,8 @@ namespace armarx::armem::base
         }
 
 
+        // Misc
+
         static std::string getLevelName()
         {
             return "entity instance";
@@ -113,7 +118,6 @@ namespace armarx::armem::base
         }
 
 
-
     protected:
 
         /// The metadata.
@@ -122,7 +126,6 @@ namespace armarx::armem::base
         /// The data. May be nullptr.
         DataT _data;
 
-
     };
 
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
index 7653136447dbe968d3d53f878ba47619481594fc..0d0f091f59847cabd2b9d5f0982d634daaa2723a 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
@@ -8,6 +8,7 @@
 #include "EntityInstanceBase.h"
 #include "detail/MemoryContainerBase.h"
 #include "detail/iteration_mixins.h"
+#include "detail/lookup_mixins.h"
 
 
 namespace armarx::armem::base::detail
@@ -55,37 +56,60 @@ namespace armarx::armem::base
 
         // READING
 
+        // Get key
         inline Time& time()
         {
             return this->id().timestamp;
         }
-
         inline const Time& time() const
         {
             return this->id().timestamp;
         }
 
+
+        // Has child by key
         bool hasInstance(int index) const
         {
-            size_t si = size_t(index);
-            return index >= 0 && si < this->_container.size();
+            return this->findInstance(index) != nullptr;
+        }
+        // Has child by ID
+        bool hasInstance(const MemoryID& instanceID) const
+        {
+            return this->findInstance(instanceID) != nullptr;
+        }
+
+
+        // Find child by key
+        EntityInstanceT* findInstance(int index)
+        {
+            return const_cast<EntityInstanceT*>(const_cast<const EntitySnapshotBase*>(this)->findInstance(index));
+        }
+        const EntityInstanceT* findInstance(int index) const
+        {
+            const size_t si = static_cast<size_t>(index);
+            return (index >= 0 && si < this->_container.size())
+                   ? &this->_container[si]
+                   : nullptr;
         }
 
+        // Get child by key
         /**
          * @brief Get the given instance.
          * @param index The instance's index.
          * @return The instance.
          * @throw `armem::error::MissingEntry` If the given index is invalid.
          */
-        EntityInstanceT& getInstance(int index)
+        EntityInstanceT&
+        getInstance(int index)
         {
             return const_cast<EntityInstanceT&>(const_cast<const EntitySnapshotBase*>(this)->getInstance(index));
         }
-        const EntityInstanceT& getInstance(int index) const
+        const EntityInstanceT&
+        getInstance(int index) const
         {
-            if (hasInstance(index))
+            if (const EntityInstanceT* instance = findInstance(index))
             {
-                return this->_container[static_cast<size_t>(index)];
+                return *instance;
             }
             else
             {
@@ -93,23 +117,21 @@ namespace armarx::armem::base
             }
         }
 
-        EntityInstanceT* findInstance(int index)
+        // Find child by MemoryID
+        EntityInstanceT*
+        findInstance(const MemoryID& instanceID)
         {
-            return const_cast<EntityInstanceT*>(const_cast<const EntitySnapshotBase*>(this)->findInstance(index));
+            detail::checkHasInstanceIndex(instanceID);
+            return this->findInstance(instanceID.instanceIndex);
         }
-        const EntityInstanceT* findInstance(int index) const
+        const EntityInstanceT*
+        findInstance(const MemoryID& instanceID) const
         {
-            if (hasInstance(index))
-            {
-                return &this->_container[static_cast<size_t>(index)];
-            }
-            else
-            {
-                return nullptr;
-            }
+            detail::checkHasInstanceIndex(instanceID);
+            return this->findInstance(instanceID.instanceIndex);
         }
 
-
+        // Get child by MemoryID
         /**
          * @brief Get the given instance.
          * @param index The instance's index.
@@ -117,18 +139,17 @@ namespace armarx::armem::base
          * @throw `armem::error::MissingEntry` If the given index is invalid.
          * @throw `armem::error::InvalidMemoryID` If memory ID does not have an instance index.
          */
-        EntityInstanceT& getInstance(const MemoryID& id)
+        EntityInstanceT&
+        getInstance(const MemoryID& instanceID)
         {
-            return const_cast<EntityInstanceT&>(const_cast<const EntitySnapshotBase*>(this)->getInstance(id));
+            detail::checkHasInstanceIndex(instanceID);
+            return this->getInstance(instanceID.instanceIndex);
         }
-
-        const EntityInstanceT& getInstance(const MemoryID& id) const
+        const EntityInstanceT&
+        getInstance(const MemoryID& instanceID) const
         {
-            if (!id.hasInstanceIndex())
-            {
-                throw armem::error::InvalidMemoryID(id, "ID has no instance index.");
-            }
-            return getInstance(id.instanceIndex);
+            detail::checkHasInstanceIndex(instanceID);
+            return this->getInstance(instanceID.instanceIndex);
         }
 
 
@@ -151,6 +172,20 @@ namespace armarx::armem::base
             return this->forEachChild(func);
         }
 
+
+        // Get child keys
+        std::vector<int> getInstanceIndices() const
+        {
+            std::vector<int> indices;
+            indices.reserve(this->size());
+            for (size_t i = 0; i < this->size(); ++i)
+            {
+                indices.push_back(static_cast<int>(i));
+            }
+            return indices;
+        }
+
+
         [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         inline const std::vector<EntityInstanceT>& instances() const
         {
diff --git a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
index 9865f6da1398ac78dda2c704eff1d621b00442f4..e1729bbcd90cc6062e93b8e62ed8db29e3bb4387 100644
--- a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
@@ -4,8 +4,9 @@
 #include <string>
 
 #include "CoreSegmentBase.h"
-#include "detail/EntityContainerBase.h"
+#include "detail/MemoryContainerBase.h"
 #include "detail/iteration_mixins.h"
+#include "detail/lookup_mixins.h"
 
 
 namespace armarx::armem::base
@@ -16,13 +17,17 @@ namespace armarx::armem::base
      */
     template <class _CoreSegmentT, class _Derived>
     class MemoryBase :
-        public detail::EntityContainerBase<_CoreSegmentT, typename _CoreSegmentT::ProviderSegmentT::EntityT, _Derived>,
-        public detail::ForEachEntityInstanceMixin<_Derived>,
-        public detail::ForEachEntitySnapshotMixin<_Derived>,
-        public detail::ForEachEntityMixin<_Derived>,
-        public detail::ForEachProviderSegmentMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<std::string, _CoreSegmentT>, _Derived>
+        , public detail::ForEachEntityInstanceMixin<_Derived>
+        , public detail::ForEachEntitySnapshotMixin<_Derived>
+        , public detail::ForEachEntityMixin<_Derived>
+        , public detail::ForEachProviderSegmentMixin<_Derived>
+        , public detail::GetFindInstanceMixin<_Derived>
+        , public detail::GetFindSnapshotMixin<_Derived>
+        , public detail::GetFindEntityMixin<_Derived>
+        , public detail::GetFindProviderSegmentMixin<_Derived>
     {
-        using Base = detail::EntityContainerBase<_CoreSegmentT, typename _CoreSegmentT::ProviderSegmentT::EntityT, _Derived>;
+        using Base = detail::MemoryContainerBase<std::map<std::string, _CoreSegmentT>, _Derived>;
 
     public:
 
@@ -35,6 +40,8 @@ namespace armarx::armem::base
         using EntitySnapshotT = typename EntityT::EntitySnapshotT;
         using EntityInstanceT = typename EntitySnapshotT::EntityInstanceT;
 
+        using ChildT = CoreSegmentT;
+
 
         struct UpdateResult
         {
@@ -77,95 +84,77 @@ namespace armarx::armem::base
 
         // READ ACCESS
 
-        inline const std::string& name() const
+        // Get key
+        inline std::string& name()
         {
             return this->id().memoryName;
         }
-        inline std::string& name()
+        inline const std::string& name() const
         {
-            return const_cast<std::string&>(const_cast<const MemoryBase*>(this)->name());
+            return this->id().memoryName;
         }
 
 
+        // Has child by key
         bool hasCoreSegment(const std::string& name) const
         {
-            return this->_container.count(name) > 0;
+            return this->findCoreSegment(name) != nullptr;
+        }
+        // Has child by MemoryID
+        bool hasCoreSegment(const MemoryID& coreSegmentID) const
+        {
+            return this->findCoreSegment(coreSegmentID) != nullptr;
         }
 
-        std::vector<std::string> getCoreSegmentNames() const
+        // Find child by key
+        CoreSegmentT* findCoreSegment(const std::string& name)
         {
-            return simox::alg::get_keys(this->_container);
+            return detail::findChildByKey(name, this->_container);
+        }
+        const CoreSegmentT* findCoreSegment(const std::string& name) const
+        {
+            return detail::findChildByKey(name, this->_container);
         }
 
+        // Get child by key
         CoreSegmentT& getCoreSegment(const std::string& name)
         {
-            return const_cast<CoreSegmentT&>(const_cast<const MemoryBase*>(this)->getCoreSegment(name));
+            return detail::getChildByKey(name, this->_container, *this);
         }
-
         const CoreSegmentT& getCoreSegment(const std::string& name) const
         {
-            auto it = this->_container.find(name);
-            if (it != this->_container.end())
-            {
-                return it->second;
-            }
-            else
-            {
-                throw armem::error::MissingEntry::create<CoreSegmentT>(name, *this);
-            }
+            return detail::getChildByKey(name, this->_container, *this);
         }
 
-
-        bool hasProviderSegment(const MemoryID& providerSegmentID) const
+        // Find child by MemoryID
+        CoreSegmentT* findCoreSegment(const MemoryID& coreSegmentID)
         {
-            auto it = this->_container.find(providerSegmentID.coreSegmentName);
-            if (it != this->_container.end())
-            {
-                return it->second.hasProviderSegment(providerSegmentID.providerSegmentName);
-            }
-            else
-            {
-                return false;
-            }
+            detail::checkHasCoreSegmentName(coreSegmentID);
+            return this->findCoreSegment(coreSegmentID.coreSegmentName);
         }
-
-        ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID)
+        const CoreSegmentT* findCoreSegment(const MemoryID& coreSegmentID) const
         {
-            return getCoreSegment(providerSegmentID.coreSegmentName).getProviderSegment(providerSegmentID.providerSegmentName);
+            detail::checkHasCoreSegmentName(coreSegmentID);
+            return this->findCoreSegment(coreSegmentID.coreSegmentName);
         }
 
-        const ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID) const
+        // Get child by MemoryID
+        CoreSegmentT& getCoreSegment(const MemoryID& coreSegmentID)
         {
-            return getCoreSegment(providerSegmentID.coreSegmentName).getProviderSegment(providerSegmentID.providerSegmentName);
+            detail::checkHasCoreSegmentName(coreSegmentID);
+            return this->getCoreSegment(coreSegmentID.coreSegmentName);
         }
-
-
-        using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const
+        const CoreSegmentT& getCoreSegment(const MemoryID& coreSegmentID) const
         {
-            this->_checkContainerName(id.memoryName, this->name());
-            return getCoreSegment(id.coreSegmentName).getEntity(id);
+            detail::checkHasCoreSegmentName(coreSegmentID);
+            return this->getCoreSegment(coreSegmentID.coreSegmentName);
         }
 
-        const EntityT* findEntity(const MemoryID& id) const
-        {
-            this->_checkContainerName(id.memoryName, this->name());
-            if (id.hasCoreSegmentName())
-            {
-                return getCoreSegment(id.coreSegmentName).findEntity(id);
-            }
-            else
-            {
-                for (const auto& [_, coreSegment] : this->_container)
-                {
-                    if (auto entity = coreSegment.findEntity(id))
-                    {
-                        return entity;
-                    }
-                }
-                return nullptr;
-            }
-        }
+        // get/findInstance are provided by GetFindInstanceMixin
+        // get/findSnapshot are provided by GetFindSnapshotMixin
+        // get/findEntity are provided by GetFindEntityMixin
+        // get/findProviderSegment are provided by GetFindProviderSegmentMixin
+
 
 
         // ITERATION
@@ -193,6 +182,12 @@ namespace armarx::armem::base
         // forEachInstance() is provided by ForEachEntityInstanceMixin.
 
 
+        std::vector<std::string> getCoreSegmentNames() const
+        {
+            return simox::alg::get_keys(this->_container);
+        }
+
+
         [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         inline auto& coreSegments() const
         {
@@ -216,39 +211,29 @@ namespace armarx::armem::base
         CoreSegmentT& addCoreSegment(
             const std::string& name, aron::typenavigator::ObjectNavigatorPtr coreSegmentType = nullptr)
         {
-            return _addCoreSegment(name, name, this->id(), coreSegmentType);
+            return this->_derived().addCoreSegment(name, name, coreSegmentType);
         }
+
         /// Copy and insert a core segment.
         CoreSegmentT& addCoreSegment(const CoreSegmentT& coreSegment)
         {
-            return _addCoreSegment(coreSegment.name(), CoreSegmentT(coreSegment));
+            return this->_derived().addCoreSegment(coreSegment.name(), CoreSegmentT(coreSegment));
         }
+
         /// Move and insert a core segment.
         CoreSegmentT& addCoreSegment(CoreSegmentT&& coreSegment)
         {
-            return _addCoreSegment(coreSegment.name(), coreSegment);
+            const std::string name = coreSegment.name();  // Copy before move.
+            return this->_derived().addCoreSegment(name, std::move(coreSegment));
         }
 
-        /**
-         * @brief Add multiple core segments.
-         * @param The core segment names.
-         * @return The core segments. The contained pointers are never null.
-         */
-        std::vector<CoreSegmentT*> addCoreSegments(const std::vector<std::string>& names)
+        /// Move and insert a core segment.
+        template <class ...Args>
+        CoreSegmentT& addCoreSegment(const std::string& name, Args... args)
         {
-            std::vector<CoreSegmentT*> segments;
-            for (const auto& name : names)
-            {
-                try
-                {
-                    segments.push_back(&addCoreSegment(name));
-                }
-                catch (const armem::error::ContainerEntryAlreadyExists& e)
-                {
-                    // ARMARX_INFO << e.what() << "\nIgnoring multiple addition.";
-                }
-            }
-            return segments;
+            CoreSegmentT& child = this->template _addChild<ChildT>(name, args...);
+            child.id() = this->id().withCoreSegmentName(name);
+            return child;
         }
 
 
@@ -343,58 +328,12 @@ namespace armarx::armem::base
             return this->name();
         }
 
-        std::string dump() const
-        {
-            std::stringstream ss;
-            ss << "Memory '" << this->name() << "': \n";
-            forEachCoreSegment([&ss](const CoreSegmentT & cseg)
-            {
-                ss << "+- Core segment '" << cseg.name() << "' (" << cseg.size() << "): \n";
-                cseg.forEachProviderSegment([&ss](const ProviderSegmentT & pseg)
-                {
-                    ss << "|  +- Provider segment '" << pseg.name() << "' (" << pseg.size() << "): \n";
-                    pseg.forEachEntity([&ss](const EntityT & entity)
-                    {
-                        ss << "|  |  +- Entity '" << entity.name() << "' (" << entity.size() << "): \n";
-                        return true;
-                    });
-                    return true;
-                });
-                return true;
-            });
-            return ss.str();
-        }
-
-
-    private:
-
-        /**
-         * This function allows to emplace a CoreSegment directly in the
-         * container from its constructor arguments, instead of constructing
-         * it outside and moving it.
-         * This is necessary if CoreSegmentT is not movable.
-         */
-        template <class ...Args>
-        CoreSegmentT& _addCoreSegment(const std::string& name, Args... args)
-        {
-            auto [it, inserted] = this->_container.try_emplace(name, args...);
-            if (not inserted)
-            {
-                throw armem::error::ContainerEntryAlreadyExists(
-                    CoreSegmentT::getLevelName(), name, DerivedT::getLevelName(), this->name());
-            }
-            else
-            {
-                it->second.id().setMemoryID(this->id());
-                it->second.id().coreSegmentName = name;
-                return it->second;
-            }
-        }
 
+    protected:
 
         std::pair<bool, CoreSegmentT*> _addCoreSegmentIfMissing(const std::string& coreSegmentName)
         {
-            CoreSegmentT* coreSeg;
+            CoreSegmentT* coreSeg = nullptr;
 
             auto it = this->_container.find(coreSegmentName);
             if (it == this->_container.end())
diff --git a/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h b/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
index e5163241738a0e8dbba5edbd35f8e5a568060746..6a5497444c9e5959ac7d59300e1bc99e0fac2018 100644
--- a/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
@@ -5,8 +5,9 @@
 
 #include "EntityBase.h"
 #include "detail/AronTyped.h"
-#include "detail/EntityContainerBase.h"
+#include "detail/MemoryContainerBase.h"
 #include "detail/iteration_mixins.h"
+#include "detail/lookup_mixins.h"
 
 
 namespace armarx::armem::base
@@ -17,12 +18,14 @@ namespace armarx::armem::base
      */
     template <class _EntityT, class _Derived>
     class ProviderSegmentBase :
-        public detail::EntityContainerBase<_EntityT, _EntityT, _Derived>,
-        public detail::AronTyped,
-        public detail::ForEachEntityInstanceMixin<_Derived>,
-        public detail::ForEachEntitySnapshotMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<std::string, _EntityT>, _Derived>
+        , public detail::AronTyped
+        , public detail::ForEachEntityInstanceMixin<_Derived>
+        , public detail::ForEachEntitySnapshotMixin<_Derived>
+        , public detail::GetFindInstanceMixin<_Derived>
+        , public detail::GetFindSnapshotMixin<_Derived>
     {
-        using Base = detail::EntityContainerBase<_EntityT, _EntityT, _Derived>;
+        using Base = detail::MemoryContainerBase<std::map<std::string, _EntityT>, _Derived>;
 
     public:
 
@@ -33,6 +36,8 @@ namespace armarx::armem::base
         using EntitySnapshotT = typename EntityT::EntitySnapshotT;
         using EntityInstanceT = typename EntitySnapshotT::EntityInstanceT;
 
+        using ChildT = EntityT;
+
         struct UpdateResult
         {
             armarx::armem::UpdateType providerSegmentUpdateType;
@@ -48,6 +53,7 @@ namespace armarx::armem::base
             {}
         };
 
+
     public:
 
         ProviderSegmentBase()
@@ -76,65 +82,76 @@ namespace armarx::armem::base
 
         // READ ACCESS
 
-        inline const std::string& name() const
+        // Get key
+        inline std::string& name()
         {
             return this->id().providerSegmentName;
         }
-        inline std::string& name()
+        inline const std::string& name() const
         {
-            return const_cast<std::string&>(const_cast<const ProviderSegmentBase*>(this)->name());
+            return this->id().providerSegmentName;
         }
 
 
+        // Has child by key
         bool hasEntity(const std::string& name) const
         {
-            return this->_container.count(name) > 0;
+            return this->findEntity(name) != nullptr;
         }
-
-        std::vector<std::string> getEntityNames() const
+        // Has child by ID
+        bool hasEntity(const MemoryID& entityID) const
         {
-            return simox::alg::get_keys(this->_container);
+            return this->findEntity(entityID) != nullptr;
         }
 
-        using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const
+
+        // Find child by key
+        EntityT* findEntity(const std::string& name)
         {
-            this->_checkContainerName(id.providerSegmentName, this->getKeyString());
-            return getEntity(id.entityName);
+            return detail::findChildByKey(name, this->_container);
+        }
+        const EntityT* findEntity(const std::string& name) const
+        {
+            return detail::findChildByKey(name, this->_container);
         }
 
+        // Get child by key
         EntityT& getEntity(const std::string& name)
         {
-            return const_cast<EntityT&>(const_cast<const ProviderSegmentBase*>(this)->getEntity(name));
+            return detail::getChildByKey(name, this->_container, *this);
         }
-
         const EntityT& getEntity(const std::string& name) const
         {
-            auto it = this->_container.find(name);
-            if (it != this->_container.end())
-            {
-                return it->second;
-            }
-            else
-            {
-                throw armem::error::MissingEntry::create<EntityT>(name, *this);
-            }
+            return detail::getChildByKey(name, this->_container, *this);
         }
 
-        const EntityT* findEntity(const MemoryID& id) const
+        // Find child by MemoryID
+        EntityT* findEntity(const MemoryID& entityID)
         {
-            this->_checkContainerName(id.providerSegmentName, this->getKeyString());
-            auto it = this->_container.find(id.entityName);
-            if (it != this->_container.end())
-            {
-                return &it->second;
-            }
-            else
-            {
-                return nullptr;
-            }
+            detail::checkHasEntityName(entityID);
+            return this->findEntity(entityID.entityName);
+        }
+        const EntityT* findEntity(const MemoryID& entityID) const
+        {
+            detail::checkHasEntityName(entityID);
+            return this->findEntity(entityID.entityName);
         }
 
+        // Get child by MemoryID
+        EntityT& getEntity(const MemoryID& entityID)
+        {
+            detail::checkHasEntityName(entityID);
+            return this->getEntity(entityID.entityName);
+        }
+        const EntityT& getEntity(const MemoryID& entityID) const
+        {
+            detail::checkHasEntityName(entityID);
+            return this->getEntity(entityID.entityName);
+        }
+
+        // get/findInstance are provided by GetFindInstanceMixin
+        // get/findSnapshot are provided by GetFindSnapshotMixin
+
 
         // ITERATION
 
@@ -157,8 +174,15 @@ namespace armarx::armem::base
             return this->forEachChild(func);
         }
 
-        // forEachSnapshot() is provided by ForEachEntitySnapshotMixin.
-        // forEachInstance() is provided by ForEachEntityInstanceMixin.
+        // forEachSnapshot() is provided by ForEachEntitySnapshotMixin
+        // forEachInstance() is provided by ForEachEntityInstanceMixin
+
+
+        // Get child keys
+        std::vector<std::string> getEntityNames() const
+        {
+            return simox::alg::get_keys(this->_container);
+        }
 
 
         [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
@@ -205,10 +229,8 @@ namespace armarx::armem::base
             return ret;
         }
 
-        void append(const _Derived& m)
+        void append(const DerivedT& m)
         {
-            // ARMARX_INFO << "ProviderSegment: Merge name '" << m.name() << "' into '" << name() << "'";
-
             m.forEachEntity([this](const EntityT & entity)
             {
                 auto it = this->_container.find(entity.name());
@@ -221,22 +243,33 @@ namespace armarx::armem::base
             });
         }
 
+
         /// Add an empty entity with the given name.
         EntityT& addEntity(const std::string& name)
         {
-            return addEntity(EntityT(name, this->id()));
+            return this->_derived().addEntity(name, name);
         }
+
         /// Copy and insert an entity.
         EntityT& addEntity(const EntityT& entity)
         {
-            return addEntity(EntityT(entity));
+            return this->_derived().addEntity(entity.name(), EntityT(entity));
         }
+
         /// Move and insert an entity.
         EntityT& addEntity(EntityT&& entity)
         {
-            auto it = this->_container.emplace(entity.name(), std::move(entity)).first;
-            it->second.id().setProviderSegmentID(this->id());
-            return it->second;
+            const std::string name = entity.name();  // Copy before move.
+            return this->_derived().addEntity(name, std::move(entity));
+        }
+
+        /// Insert an entity in-place.
+        template <class ...Args>
+        EntityT& addEntity(const std::string& name, Args... args)
+        {
+            ChildT& child = this->template _addChild<ChildT>(name, args...);
+            child.id() = this->id().withEntityName(name);
+            return child;
         }
 
 
@@ -244,7 +277,6 @@ namespace armarx::armem::base
 
         bool equalsDeep(const DerivedT& other) const
         {
-            //std::cout << "ProviderSegment::equalsDeep" << std::endl;
             if (this->size() != other.size())
             {
                 return false;
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.cpp b/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.cpp
deleted file mode 100644
index 05a23bc12fea34e175218498beca73e01b6f1b13..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "EntityContainerBase.h"
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h b/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h
deleted file mode 100644
index 53cddfff656cdf0fb000323afc4aefcc18c2f50f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h
+++ /dev/null
@@ -1,124 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/Commit.h>
-#include <RobotAPI/libraries/armem/core/error/ArMemError.h>
-
-#include "MemoryContainerBase.h"
-
-#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
-#include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
-
-
-namespace armarx::armem::base::detail
-{
-
-    /**
-     * @brief A container of entities at some point in the hierarchy.
-     *
-     * Can be updated by multiple entity updates.
-     */
-    template <class _ValueT, class _EntityT, class _Derived>
-    class EntityContainerBase :
-        public MemoryContainerBase<std::map<std::string, _ValueT>, _Derived>
-    {
-        using Base = MemoryContainerBase<std::map<std::string, _ValueT>, _Derived>;
-
-    public:
-
-        using DerivedT = _Derived;
-        using ValueT = _ValueT;
-
-        using EntityT = _EntityT;
-        using EntitySnapshotT = typename EntityT::EntitySnapshotT;
-        using EntityInstanceT = typename EntitySnapshotT::EntityInstanceT;
-
-    public:
-
-        // `using Base::MemoryContainerBase` breaks code completion of QtCreator.
-        using MemoryContainerBase<std::map<std::string, _ValueT>, _Derived>::MemoryContainerBase;
-        using MemoryContainerBase<std::map<std::string, _ValueT>, _Derived>::operator=;
-
-        /**
-         * @brief Retrieve an entity.
-         * @param id The entity ID.
-         * @return The entity.
-         * @throw An exception deriving from `armem::error::ArMemError` if the entity is missing.
-         */
-        // const EntityT& getEntity(const MemoryID& id) const;
-        EntityT& getEntity(const MemoryID& id)
-        {
-            return const_cast<EntityT&>(const_cast<const EntityContainerBase*>(this)->_derived().getEntity(id));
-        }
-
-        /**
-         * @brief Find an entity.
-         *
-         * Search for the entity with the given ID and return a pointer to the
-         * first match. If `id` is underspecified (e.g. no provider segment name),
-         * search all children until the first match is found.
-         *
-         * If no matching entity is found, return `nullptr`.
-         *
-         * @param id The entities ID.
-         * @return A pointer to the first matching entity or `nullptr` if none was found.
-         */
-        // const EntityT* findEntity(const MemoryID& id) const;
-        EntityT* findEntity(const MemoryID& id)
-        {
-            return const_cast<EntityT*>(const_cast<const EntityContainerBase*>(this)->_derived().findEntity(id));
-        }
-
-
-        /**
-         * @brief Retrieve an entity snapshot.
-         *
-         * Uses `getEntity()` to retrieve the respective entity.
-         *
-         * @param id The snapshot ID.
-         * @return The entity snapshot.
-         * @throw An exception deriving from `armem::error::ArMemError` if the snapshot is missing.
-         */
-        EntitySnapshotT& getEntitySnapshot(const MemoryID& id)
-        {
-            return const_cast<EntitySnapshotT&>(const_cast<const EntityContainerBase*>(this)->_derived().getEntitySnapshot(id));
-        }
-
-        const EntitySnapshotT& getEntitySnapshot(const MemoryID& id) const
-        {
-            const EntityT& entity = _derived().getEntity(id);
-
-            if (id.hasTimestamp())
-            {
-                return entity.getSnapshot(id);
-            }
-            else
-            {
-                return entity.getLatestSnapshot();
-            }
-        }
-
-        EntityInstanceT& getEntityInstance(const MemoryID& id)
-        {
-            return getEntitySnapshot(id).getInstance(id);
-        }
-
-        const EntityInstanceT& getEntityInstance(const MemoryID& id) const
-        {
-            return getEntitySnapshot(id).getInstance(id);
-        }
-
-
-    private:
-
-        DerivedT& _derived()
-        {
-            return static_cast<DerivedT&>(*this);
-        }
-        const DerivedT& _derived() const
-        {
-            return static_cast<const DerivedT&>(*this);
-        }
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h b/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
index 4d7cbec1877176f511e854eeefa60a9d6159aded..3e22caa31456c6a2afab30a721d064bb661427f5 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
@@ -108,6 +108,15 @@ namespace armarx::armem::base::detail
             return _container;
         }
 
+        DerivedT& _derived()
+        {
+            return static_cast<DerivedT&>(*this);
+        }
+        const DerivedT& _derived() const
+        {
+            return static_cast<DerivedT&>(*this);
+        }
+
 
         /**
          * @throw `armem::error::ContainerNameMismatch` if `gottenName` does not match `actualName`.
@@ -123,6 +132,19 @@ namespace armarx::armem::base::detail
         }
 
 
+        template <class ChildT, class KeyT, class ...ChildArgs>
+        ChildT& _addChild(const KeyT& key, ChildArgs... childArgs)
+        {
+            auto [it, inserted] = this->_container.try_emplace(key, childArgs...);
+            if (not inserted)
+            {
+                throw armem::error::ContainerEntryAlreadyExists(
+                    ChildT::getLevelName(), key, DerivedT::getLevelName(), this->_derived().name());
+            }
+            return it->second;
+        }
+
+
     protected:
 
         mutable ContainerT _container;
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/derived.h b/source/RobotAPI/libraries/armem/core/base/detail/derived.h
new file mode 100644
index 0000000000000000000000000000000000000000..721becfa05e34e603f2c1bdb852cea191faf42a5
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/derived.h
@@ -0,0 +1,22 @@
+#pragma once
+
+
+namespace armarx::armem::base::detail
+{
+
+    template <class DerivedT, class ThisT>
+    DerivedT&
+    derived(ThisT* t)
+    {
+        return static_cast<DerivedT&>(*t);
+    }
+
+
+    template <class DerivedT, class ThisT>
+    const DerivedT&
+    derived(const ThisT* t)
+    {
+        return static_cast<const DerivedT&>(*t);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.cpp b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2b35f0b895cf6e4ef3e53a81a8af3ac0eb31a89d
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.cpp
@@ -0,0 +1,63 @@
+#include "lookup_mixins.h"
+
+#include <RobotAPI/libraries/armem/core/error/ArMemError.h>
+
+
+namespace armarx::armem::base
+{
+
+    void detail::checkHasInstanceIndex(const MemoryID& instanceID)
+    {
+        if (not instanceID.hasInstanceIndex())
+        {
+            throw armem::error::InvalidMemoryID(instanceID, "Instance ID has no instance index.");
+        }
+    }
+
+
+    void detail::checkHasTimestamp(const MemoryID& snapshotID)
+    {
+        if (not snapshotID.hasTimestamp())
+        {
+            throw armem::error::InvalidMemoryID(snapshotID, "Snapshot ID has no timestamp.");
+        }
+    }
+
+
+    void detail::checkHasEntityName(const MemoryID& entityID)
+    {
+        if (not entityID.hasEntityName())
+        {
+            throw armem::error::InvalidMemoryID(entityID, "Entity ID has no entity name.");
+        }
+    }
+
+
+    void detail::checkHasProviderSegmentName(const MemoryID& providerSegmentID)
+    {
+        if (not providerSegmentID.hasProviderSegmentName())
+        {
+            throw armem::error::InvalidMemoryID(providerSegmentID, "Provider segment ID has no provider segment name.");
+        }
+    }
+
+
+    void detail::checkHasCoreSegmentName(const MemoryID& coreSegmentID)
+    {
+        if (not coreSegmentID.hasCoreSegmentName())
+        {
+            throw armem::error::InvalidMemoryID(coreSegmentID, "Core segment ID has no core segment name.");
+        }
+    }
+
+
+    void detail::checkHasMemoryName(const MemoryID& memoryID)
+    {
+        if (not memoryID.hasMemoryName())
+        {
+            throw armem::error::InvalidMemoryID(memoryID, "Memory ID has no memory name.");
+        }
+    }
+
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h
new file mode 100644
index 0000000000000000000000000000000000000000..030db150d382a2f61d671c27ee017031fb06679b
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h
@@ -0,0 +1,274 @@
+#pragma once
+
+#include "derived.h"
+
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/error/ArMemError.h>
+
+
+namespace armarx::armem::base::detail
+{
+
+    void checkHasInstanceIndex(const MemoryID& instanceID);
+    void checkHasTimestamp(const MemoryID& snapshotID);
+    void checkHasEntityName(const MemoryID& entityID);
+    void checkHasProviderSegmentName(const MemoryID& providerSegmentID);
+    void checkHasCoreSegmentName(const MemoryID& coreSegmentID);
+    void checkHasMemoryName(const MemoryID& memory);
+
+
+    template <class KeyT, class ContainerT>
+    auto* findChildByKey(const KeyT& key, ContainerT&& container)
+    {
+        auto it = container.find(key);
+        return it != container.end() ? &it->second : nullptr;
+    }
+
+    template <class KeyT, class ContainerT, class ParentT, class KeyStringFn>
+    auto&
+    getChildByKey(
+        const KeyT& key,
+        ContainerT&& container,
+        const ParentT& parent,
+        KeyStringFn&& keyStringFn)
+    {
+        if (auto* child = findChildByKey(key, container))
+        {
+            return *child;
+        }
+        else
+        {
+            throw armem::error::MissingEntry::create<typename ParentT::ChildT>(keyStringFn(key), parent);
+        }
+    }
+    template <class KeyT, class ContainerT, class ParentT>
+    auto&
+    getChildByKey(
+        const KeyT& key,
+        ContainerT&& container,
+        const ParentT& parent)
+    {
+        return getChildByKey(key, container, parent, [](const KeyT & key)
+        {
+            return key;
+        });
+    }
+
+
+    template <class DerivedT>
+    struct GetFindInstanceMixin
+    {
+        // Relies on this->find/getSnapshot()
+
+        bool hasInstance(const MemoryID& instanceID) const
+        {
+            return derived<DerivedT>(this).findInstance(instanceID) != nullptr;
+        }
+
+        /**
+         * @brief Find an entity instance.
+         * @param id The instance ID.
+         * @return The instance or nullptr if it is missing.
+         */
+        auto*
+        findInstance(const MemoryID& instanceID)
+        {
+            auto* snapshot = derived<DerivedT>(this).findSnapshot(instanceID);
+            return snapshot ? snapshot->findInstance(instanceID) : nullptr;
+        }
+        const auto*
+        findInstance(const MemoryID& instanceID) const
+        {
+            const auto* snapshot = derived<DerivedT>(this).findSnapshot(instanceID);
+            return snapshot ? snapshot->findInstance(instanceID) : nullptr;
+        }
+
+        /**
+         * @brief Retrieve an entity instance.
+         * @param id The instance ID.
+         * @return The instance if it is found.
+         * @throw `armem::error::ArMemError` if it is missing.
+         */
+        auto&
+        getInstance(const MemoryID& instanceID)
+        {
+            return derived<DerivedT>(this).getSnapshot(instanceID).getInstance(instanceID);
+        }
+        const auto&
+        getInstance(const MemoryID& instanceID) const
+        {
+            return derived<DerivedT>(this).getSnapshot(instanceID).getInstance(instanceID);
+        }
+    };
+
+
+    template <class DerivedT>
+    struct GetFindSnapshotMixin
+    {
+        // Relies on this->find/getEntity()
+
+        bool hasSnapshot(const MemoryID& snapshotID) const
+        {
+            return derived<DerivedT>(this).findSnapshot(snapshotID) != nullptr;
+        }
+
+        /**
+         * @brief Find an entity snapshot.
+         * @param id The snapshot ID.
+         * @return The snapshot or nullptr if it is missing.
+         */
+        auto*
+        findSnapshot(const MemoryID& snapshotID)
+        {
+            auto* entity = derived<DerivedT>(this).findEntity(snapshotID);
+            return entity ? entity->findSnapshot(snapshotID) : nullptr;
+        }
+        const auto*
+        findSnapshot(const MemoryID& snapshotID) const
+        {
+            auto* entity = derived<DerivedT>(this).findEntity(snapshotID);
+            return entity ? entity->findSnapshot(snapshotID) : nullptr;
+        }
+
+        /**
+         * @brief Retrieve an entity snapshot.
+         * @param id The snapshot ID.
+         * @return The snapshot if it is found.
+         * @throw `armem::error::ArMemError` if it is missing.
+         */
+        auto&
+        getSnapshot(const MemoryID& snapshotID)
+        {
+            return derived<DerivedT>(this).getEntity(snapshotID).getSnapshot(snapshotID);
+        }
+        const auto&
+        getSnapshot(const MemoryID& snapshotID) const
+        {
+            return derived<DerivedT>(this).getEntity(snapshotID).getSnapshot(snapshotID);
+        }
+
+
+        // More elaborate cases
+
+        auto* findLatestEntitySnapshot(const MemoryID& entityID)
+        {
+            auto* entity = derived<DerivedT>(this).findEntity(entityID);
+            return entity ? entity->findLatestSnapshot() : nullptr;
+        }
+        const auto* findLatestEntitySnapshot(const MemoryID& entityID) const
+        {
+            auto* entity = derived<DerivedT>(this).findEntity(entityID);
+            return entity ? entity->findLatestSnapshot() : nullptr;
+        }
+
+        auto* findLatestInstance(const MemoryID& entityID, int instanceIndex = 0)
+        {
+            auto* snapshot = derived<DerivedT>(this).findLatestEntitySnapshot(entityID);
+            return snapshot ? snapshot->findInstance(instanceIndex) : nullptr;
+        }
+        const auto* findLatestInstance(const MemoryID& entityID, int instanceIndex = 0) const
+        {
+            auto* snapshot = derived<DerivedT>(this).findLatestEntitySnapshot(entityID);
+            return snapshot ? snapshot->findInstance(instanceIndex) : nullptr;
+        }
+
+    };
+
+
+
+    template <class DerivedT>
+    struct GetFindEntityMixin
+    {
+        // Relies on this->find/getProviderSegment()
+
+        bool hasEntity(const MemoryID& entityID) const
+        {
+            return derived<DerivedT>(this).findEntity(entityID) != nullptr;
+        }
+
+        /**
+         * @brief Find an entity.
+         * @param id The entity ID.
+         * @return The entity or nullptr if it is missing.
+         */
+        auto*
+        findEntity(const MemoryID& entityID)
+        {
+            auto* provSeg = derived<DerivedT>(this).findProviderSegment(entityID);
+            return provSeg ? provSeg->findEntity(entityID) : nullptr;
+        }
+        const auto*
+        findEntity(const MemoryID& entityID) const
+        {
+            auto* provSeg = derived<DerivedT>(this).findProviderSegment(entityID);
+            return provSeg ? provSeg->findEntity(entityID) : nullptr;
+        }
+
+        /**
+         * @brief Retrieve an entity.
+         * @param id The entity ID.
+         * @return The entity if it is found.
+         * @throw `armem::error::ArMemError` if it is missing.
+         */
+        auto&
+        getEntity(const MemoryID& entityID)
+        {
+            return derived<DerivedT>(this).getProviderSegment(entityID).getEntity(entityID);
+        }
+        const auto&
+        getEntity(const MemoryID& entityID) const
+        {
+            return derived<DerivedT>(this).getProviderSegment(entityID).getEntity(entityID);
+        }
+    };
+
+
+
+    template <class DerivedT>
+    struct GetFindProviderSegmentMixin
+    {
+        // Relies on this->find/getCoreSegment()
+
+        bool hasProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            return derived<DerivedT>(this).findProviderSegment(providerSegmentID) != nullptr;
+        }
+
+        /**
+         * @brief Retrieve a provider segment.
+         * @param id The provider segment ID.
+         * @return The provider segment if it is found or nullptr if it missing.
+         */
+        auto*
+        findProviderSegment(const MemoryID& providerSegmentID)
+        {
+            auto* provSeg = derived<DerivedT>(this).findCoreSegment(providerSegmentID);
+            return provSeg ? provSeg->findProviderSegment(providerSegmentID) : nullptr;
+        }
+        const auto*
+        findProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            auto* provSeg = derived<DerivedT>(this).findCoreSegment(providerSegmentID);
+            return provSeg ? provSeg->findProviderSegment(providerSegmentID) : nullptr;
+        }
+
+        /**
+         * @brief Retrieve a provider segment.
+         * @param id The provider segment ID.
+         * @return The provider segment if it is found.
+         * @throw `armem::error::ArMemError` if it is missing.
+         */
+        auto&
+        getProviderSegment(const MemoryID& providerSegmentID)
+        {
+            return derived<DerivedT>(this).getCoreSegment(providerSegmentID).getProviderSegment(providerSegmentID);
+        }
+        const auto&
+        getProviderSegment(const MemoryID& providerSegmentID) const
+        {
+            return derived<DerivedT>(this).getCoreSegment(providerSegmentID).getProviderSegment(providerSegmentID);
+        }
+
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/ice_conversions.h b/source/RobotAPI/libraries/armem/core/base/ice_conversions.h
index 646754cc4cbfc3d61c0ce0b1e19c333ee2d7f92b..182e0c0a47aff1a75b356b9cc0b3930450de75e4 100644
--- a/source/RobotAPI/libraries/armem/core/base/ice_conversions.h
+++ b/source/RobotAPI/libraries/armem/core/base/ice_conversions.h
@@ -110,7 +110,6 @@ namespace armarx::armem::base
         detail::toIce(ice.aronType, providerSegment.aronType());
         ARMARX_CHECK(!providerSegment.aronType() || ice.aronType);
 
-        // toIce(ice.entities, providerSegment.entities());
         ice.entities.clear();
         providerSegment.forEachEntity([&ice](const auto & entity)
         {
@@ -125,7 +124,6 @@ namespace armarx::armem::base
         detail::fromIce(ice.aronType, providerSegment.aronType());
         ARMARX_CHECK(!providerSegment.aronType() || ice.aronType);
 
-        // fromIce(ice.entities, providerSegment.entities());
         providerSegment.clear();
         for (const auto& [key, entity] : ice.entities)
         {
@@ -142,12 +140,10 @@ namespace armarx::armem::base
         detail::toIce(ice.aronType, coreSegment.aronType());
         ARMARX_CHECK(!coreSegment.aronType() || ice.aronType);
 
-        // toIce(ice.providerSegments, coreSegment.providerSegments());
         ice.providerSegments.clear();
         coreSegment.forEachProviderSegment([&ice](const auto & providerSegment)
         {
             armem::toIce(ice.providerSegments[providerSegment.name()], providerSegment);
-            return true;
         });
     }
     template <class ...Args>
@@ -176,7 +172,6 @@ namespace armarx::armem::base
         memory.forEachCoreSegment([&ice](const auto & coreSegment)
         {
             armem::toIce(ice.coreSegments[coreSegment.name()], coreSegment);
-            return true;
         });
     }
     template <class ...Args>
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp
deleted file mode 100644
index 204aa8f86e20d99df852abbdc79be3d1a07ef39f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp
+++ /dev/null
@@ -1,106 +0,0 @@
-#include "CoreSegment.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "TypeIO.h"
-
-
-namespace armarx::armem::d_ltm
-{
-
-    std::filesystem::path CoreSegment::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path CoreSegment::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName / id().coreSegmentName;
-    }
-
-    wm::CoreSegment CoreSegment::convert() const
-    {
-        wm::CoreSegment m(id());
-        for (const auto& [_, s] : _container)
-        {
-            m.addProviderSegment(s.convert(_aronType));
-        }
-        return m;
-    }
-
-    void CoreSegment::reload(const std::shared_ptr<std::filesystem::path>& p_ptr)
-    {
-        if (!p_ptr)
-        {
-            ARMARX_WARNING << "The entered is NULL.";
-        }
-        std::filesystem::path p = _fullPath(*p_ptr);
-        if (std::filesystem::is_regular_file(p))
-        {
-            ARMARX_ERROR << "The entered path is leading to a file! Abort due to error.";
-        }
-
-        _container.clear();
-        path = p_ptr;
-
-        if (!std::filesystem::exists(p))
-        {
-            ARMARX_INFO << "The entered path does not exist. Assuming an empty container.";
-        }
-        else
-        {
-            for (const auto& d : std::filesystem::directory_iterator(p))
-            {
-                if (d.is_directory())
-                {
-                    std::string k = d.path().filename();
-                    auto wms = _container.emplace(k, id().withProviderSegmentName(k));
-                    wms.first->second.reload(p_ptr);
-                }
-
-                if (d.is_regular_file())
-                {
-                    if (auto type = TypeIO::readAronType(d.path()))
-                    {
-                        _aronType = type;
-                    }
-                }
-            }
-        }
-    }
-
-    void CoreSegment::append(const wm::CoreSegment& m)
-    {
-        std::filesystem::create_directories(_fullPath());
-        TypeIO::writeAronType(_aronType, _fullPath());
-
-        m.forEachProviderSegment([this](const wm::ProviderSegment & s)
-        {
-            if (auto it = _container.find(s.name()); it != _container.end())
-            {
-                it->second.append(s);
-            }
-            else
-            {
-                try
-                {
-                    std::filesystem::create_directory(_fullPath() / s.name());
-                }
-                catch (...)
-                {
-                    ARMARX_WARNING << GetHandledExceptionString();
-                    return false;
-                }
-
-                auto wms = _container.emplace(s.name(), id().withProviderSegmentName(s.name()));
-                wms.first->second.path = path;
-                wms.first->second.append(s);
-            }
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.h b/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.h
deleted file mode 100644
index 2d8bd8f29e7027ea63b797d0a19f4b96e116898e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.h
+++ /dev/null
@@ -1,42 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include "ProviderSegment.h"
-
-
-namespace armarx::armem::d_ltm
-{
-
-    /**
-     * @brief Data of a core segment containing multiple provider segments.
-     */
-    class CoreSegment :
-        public base::CoreSegmentBase<ProviderSegment, CoreSegment>
-    {
-        using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
-
-    public:
-
-        using Base::CoreSegmentBase;
-
-
-        // Conversion
-        wm::CoreSegment convert() const;
-
-        // Filesystem connection
-        void reload(const std::shared_ptr<std::filesystem::path>&);
-        void append(const wm::CoreSegment&);
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp
deleted file mode 100644
index d4d0ac233f1fac1e910869f56cc12541928798ce..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp
+++ /dev/null
@@ -1,86 +0,0 @@
-#include "Entity.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
-
-
-namespace armarx::armem::d_ltm
-{
-    std::filesystem::path Entity::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path Entity::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName / id().coreSegmentName / id().providerSegmentName / id().entityName;
-    }
-
-    wm::Entity Entity::convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const
-    {
-        wm::Entity m(id());
-        for (const auto& [_, s] : _container)
-        {
-            m.addSnapshot(s.convert(expectedStructure));
-        }
-        return m;
-    }
-
-    void Entity::reload(const std::shared_ptr<std::filesystem::path>& p_ptr)
-    {
-        if (!p_ptr)
-        {
-            ARMARX_WARNING << "The entered is NULL.";
-        }
-        std::filesystem::path p = _fullPath(*p_ptr);
-        if (std::filesystem::is_regular_file(p))
-        {
-            ARMARX_ERROR << "The entered path is leading to a file! Abort due to error.";
-        }
-
-        _container.clear();
-        path = p_ptr;
-
-        if (!std::filesystem::exists(p))
-        {
-            ARMARX_INFO << "The entered path does not exist. Assuming an empty container.";
-        }
-        else
-        {
-            for (const auto& d : std::filesystem::directory_iterator(p))
-            {
-                if (d.is_directory())
-                {
-                    std::string k = d.path().filename();
-                    armem::Time t = armem::Time::microSeconds(std::stol(k));
-                    auto wms = _container.emplace(std::make_pair(t, id().withTimestamp(t)));
-                    wms.first->second.reload(p_ptr);
-                }
-            }
-        }
-    }
-
-    void Entity::append(const wm::Entity& m)
-    {
-        std::filesystem::create_directories(_fullPath());
-        m.forEachSnapshot([this](const wm::EntitySnapshot & s)
-        {
-            if (auto it = _container.find(s.time()); it != _container.end())
-            {
-                // timestamp already exists
-                // We assume that a snapshot does not change, so ignore
-            }
-            else
-            {
-                std::filesystem::create_directory(_fullPath() / std::to_string(s.time().toMicroSeconds()));
-                auto wms = _container.emplace(std::make_pair(s.time(), id().withTimestamp(s.time())));
-                wms.first->second.path = path;
-                wms.first->second.setTo(s);
-            }
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.h b/source/RobotAPI/libraries/armem/core/diskmemory/Entity.h
deleted file mode 100644
index 63011ceff58a0ec7ff4b77bf2afeaa0252bbcec0..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.h
+++ /dev/null
@@ -1,58 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include "EntitySnapshot.h"
-
-
-
-namespace armarx::armem::d_ltm
-{
-    /**
-     * @brief An entity over a period of time.
-     *
-     * An entity should be a physical thing or abstract concept existing
-     * (and potentially evolving) over some time.
-     *
-     * Examples are:
-     * - objects (the green box)
-     * - agents (robot, human)
-     * - locations (frige, sink)
-     * - grasp affordances (general, or for a specific object)
-     * - images
-     * - point clouds
-     * - other sensory values
-     *
-     * At each point in time (`EntitySnapshot`), the entity can have a
-     * (potentially variable) number of instances (`EntityInstance`),
-     * each containing a single `AronData` object of a specific `AronType`.
-     */
-    class Entity :
-        public base::EntityBase<EntitySnapshot, Entity>
-    {
-        using Base = base::EntityBase<EntitySnapshot, Entity>;
-
-    public:
-
-        using Base::EntityBase;
-
-
-        // Conversion
-        wm::Entity convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const;
-
-        // Filesystem connection
-        void reload(const std::shared_ptr<std::filesystem::path>&);
-        void append(const wm::Entity&);
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp
deleted file mode 100644
index 56786756655453bb97952a206ff642b9f65174cb..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp
+++ /dev/null
@@ -1,120 +0,0 @@
-#include "EntityInstance.h"
-
-#include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/wm/json_conversions.h>
-
-#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <SimoxUtility/json/json.hpp>
-
-#include <iostream>
-#include <fstream>
-
-
-namespace armarx::armem::d_ltm
-{
-
-    bool EntityInstance::equalsDeep(const EntityInstance& other) const
-    {
-        return id() == other.id();
-    }
-
-
-
-    void EntityInstance::update(const EntityUpdate& update)
-    {
-        ARMARX_CHECK_FITS_SIZE(this->index(), update.instancesData.size());
-    }
-
-
-    std::filesystem::path EntityInstance::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        ARMARX_WARNING << "The path of the disk memory instance with id '" << id().str() << "' is not set. This may lead to errors.";
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path EntityInstance::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName / id().coreSegmentName / id().providerSegmentName / id().entityName / std::to_string(id().timestamp.toMicroSeconds()) / std::to_string(id().instanceIndex);
-    }
-
-    wm::EntityInstance EntityInstance::convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const
-    {
-        std::filesystem::path p = _fullPath(); // here we assume that "reload" has been called first
-        std::filesystem::path d = p / (std::string(DATA_FILENAME) + ".json");
-
-        if (std::filesystem::is_regular_file(d))
-        {
-            std::ifstream ifs(d);
-            std::string file_content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>()));
-
-            nlohmann::json j = nlohmann::json::parse(file_content);
-            auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
-            to_aron(aron, j, expectedStructure);
-            wm::EntityInstance e(id());
-            from_aron(aron, e);
-            return e;
-        }
-        else
-        {
-            throw error::ArMemError("An diskMemory EntityInstance is not leading to a regular file. The path was: " + d.string());
-        }
-    }
-
-    void EntityInstance::reload(const std::shared_ptr<std::filesystem::path>& p_ptr)
-    {
-        if (!p_ptr)
-        {
-            ARMARX_WARNING << "The entered path is NULL.";
-        }
-        std::filesystem::path p = _fullPath(*p_ptr);
-        if (!std::filesystem::is_directory(p))
-        {
-            ARMARX_ERROR << "The entered path is not leading to a file! This is an error since if the folder for an EntityInstance exists there must be a data file in it (containing at least the metadata).";
-        }
-        else
-        {
-            path = p_ptr;
-        }
-    }
-
-    void EntityInstance::setTo(const wm::EntityInstance& m)
-    {
-        std::filesystem::path p = _fullPath();
-
-        try
-        {
-            std::filesystem::create_directories(p);
-        }
-        catch (...)
-        {
-            ARMARX_WARNING << GetHandledExceptionString();
-            return;
-        }
-
-        std::filesystem::path d = p / (std::string(DATA_FILENAME) + ".json");
-
-        if (std::filesystem::is_regular_file(d))
-        {
-            std::filesystem::remove(d);
-        }
-
-        std::ofstream ofs;
-        ofs.open(d);
-
-        auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
-        to_aron(aron, m);
-        nlohmann::json j;
-        from_aron(aron, j);
-
-        ofs << j.dump(2);
-        ofs.close();
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h
deleted file mode 100644
index c56a944f264c08e1f26b35df1ecb622dff92c0e6..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h
+++ /dev/null
@@ -1,54 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
-
-
-namespace armarx::armem::d_ltm
-{
-    /**
-     * @brief Data of a single entity instance.
-     */
-    class EntityInstance :
-        public base::EntityInstanceBase<base::NoData, base::NoData>
-    {
-        using Base = base::EntityInstanceBase<base::NoData, base::NoData>;
-
-    public:
-
-        using Base::EntityInstanceBase;
-
-
-        /**
-         * @brief Fill `*this` with the update's values.
-         * @param update The update.
-         * @param index The instances index.
-         */
-        void update(const EntityUpdate& update);
-
-        bool equalsDeep(const EntityInstance& other) const;
-
-
-        // Conversion
-        wm::EntityInstance convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const;
-
-        // Filesystem connection
-        void reload(const std::shared_ptr<std::filesystem::path>&);
-        void setTo(const wm::EntityInstance&);
-
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-
-    private:
-        static const constexpr char* DATA_FILENAME = "data";
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp
deleted file mode 100644
index 9354ab7d52e0dcbd058aec022892132b753b51ab..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp
+++ /dev/null
@@ -1,105 +0,0 @@
-#include "EntitySnapshot.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "error.h"
-
-
-namespace armarx::armem::d_ltm
-{
-
-    std::filesystem::path EntitySnapshot::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path EntitySnapshot::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName / id().coreSegmentName / id().providerSegmentName
-               / id().entityName
-               / std::to_string(id().timestamp.toMicroSeconds());
-    }
-
-    wm::EntitySnapshot EntitySnapshot::convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const
-    {
-        wm::EntitySnapshot m(id());
-        for (const auto& s : _container)
-        {
-            m.addInstance(s.convert(expectedStructure));
-        }
-        return m;
-    }
-
-    void EntitySnapshot::reload(const std::shared_ptr<std::filesystem::path>& p_ptr)
-    {
-        if (!p_ptr)
-        {
-            ARMARX_WARNING << "The entered is NULL.";
-        }
-        std::filesystem::path p = _fullPath(*p_ptr);
-        if (!std::filesystem::is_directory(p))
-        {
-            ARMARX_ERROR << "The entered path is not leading to a directory! Every EntitySnapshot must at least contain one EntityInstance.";
-        }
-        else
-        {
-            _container.clear();
-            path = p_ptr;
-
-            // todo
-            for (int i = 0; i < 1000; ++i)
-            {
-                std::filesystem::path d = p / std::to_string(i);
-                if (std::filesystem::is_directory(d))
-                {
-                    auto& wms = _container.emplace_back(id().withInstanceIndex(i));
-                    wms.reload(p_ptr);
-                }
-                else
-                {
-                    break;
-                }
-            }
-        }
-    }
-
-    void EntitySnapshot::setTo(const wm::EntitySnapshot& m)
-    {
-        try
-        {
-            std::filesystem::create_directories(_fullPath());
-        }
-        catch (...)
-        {
-            ARMARX_WARNING << GetHandledExceptionString();
-            return;
-        }
-
-        // We remove the content here and reset it with new values
-        _container.clear();
-
-        int i = 0;
-        m.forEachInstance([this, &i](wm::EntityInstance & s)
-        {
-            try
-            {
-                std::filesystem::create_directory(_fullPath() / std::to_string(i));
-            }
-            catch (...)
-            {
-                ARMARX_WARNING << GetHandledExceptionString();
-                return true;
-            }
-
-            auto& wms = _container.emplace_back(id().withInstanceIndex(i++));
-            wms.path = path;
-            wms.setTo(s);
-
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.h b/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.h
deleted file mode 100644
index 9587e3be44435814d4709979a1fb394c67b953c7..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.h
+++ /dev/null
@@ -1,43 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include "EntityInstance.h"
-
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
-
-
-namespace armarx::armem::d_ltm
-{
-
-    /**
-     * @brief Data of an entity at one point in time.
-     */
-    class EntitySnapshot :
-        public base::EntitySnapshotBase<EntityInstance, EntitySnapshot>
-    {
-        using Base = base::EntitySnapshotBase<EntityInstance, EntitySnapshot>;
-
-    public:
-
-        using Base::EntitySnapshotBase;
-
-
-        // Conversion
-        void reload(const std::shared_ptr<std::filesystem::path>&);
-        wm::EntitySnapshot convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const;
-
-        // FS connection
-        void setTo(const wm::EntitySnapshot&);
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp
deleted file mode 100644
index 3fc60e0496aa21c441cf5e8a60443e43ef741a46..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp
+++ /dev/null
@@ -1,94 +0,0 @@
-#include "Memory.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "error.h"
-
-
-namespace armarx::armem::d_ltm
-{
-    std::filesystem::path Memory::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path Memory::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName;
-    }
-
-    wm::Memory Memory::convert() const
-    {
-        wm::Memory m(id());
-        for (const auto& [k, s] : _container)
-        {
-            m.addCoreSegment(s.convert());
-        }
-        return m;
-    }
-
-    void Memory::reload(const std::filesystem::path& p)
-    {
-        if (std::filesystem::is_regular_file(p))
-        {
-            ARMARX_ERROR << "The entered path is leading to a file! Abort due to error.";
-        }
-
-        _container.clear();
-        path = std::make_shared<std::filesystem::path>(p.parent_path());
-
-        if (!std::filesystem::exists(p))
-        {
-            ARMARX_INFO << "The entered path does not exist. Returning empty memory.";
-        }
-        else
-        {
-            id() = MemoryID().withMemoryName(p.filename());
-
-            for (const auto& d : std::filesystem::directory_iterator(p))
-            {
-                if (d.is_directory())
-                {
-                    std::string k = d.path().filename();
-                    auto wms = _container.emplace(k, id().withCoreSegmentName(k));
-                    wms.first->second.reload(path);
-                }
-            }
-        }
-    }
-
-    void Memory::append(const wm::Memory& m)
-    {
-        std::filesystem::create_directories(_fullPath());
-        m.forEachCoreSegment([this](const wm::CoreSegment & s) -> bool
-        {
-            if (auto it = _container.find(s.name()); it != _container.end())
-            {
-                it->second.append(s);
-            }
-            else
-            {
-                try
-                {
-                    std::filesystem::create_directory(_fullPath() / s.name());
-                }
-                catch (...)
-                {
-                    ARMARX_WARNING << GetHandledExceptionString();
-                    return false;
-                }
-
-                auto wms = _container.emplace(s.name(), id().withCoreSegmentName(s.name()));
-                wms.first->second.path = path;
-                wms.first->second.append(s);
-            }
-
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.h b/source/RobotAPI/libraries/armem/core/diskmemory/Memory.h
deleted file mode 100644
index aaa1e460a5bff94195ae6da7662a7e53b33861e4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.h
+++ /dev/null
@@ -1,41 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include "CoreSegment.h"
-
-
-namespace armarx::armem::d_ltm
-{
-
-    /**
-     * @brief Data of a memory consisting of multiple core segments.
-     */
-    class Memory :
-        public base::MemoryBase<CoreSegment, Memory>
-    {
-        using Base = base::MemoryBase<CoreSegment, Memory>;
-
-    public:
-
-        using Base::MemoryBase;
-
-
-        // Conversion
-        wm::Memory convert() const;
-
-        // Filesystem connection
-        void reload(const std::filesystem::path&);
-        void append(const wm::Memory&);
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp
deleted file mode 100644
index 08ed0c2b07edc156764f02dc88c5f76160f9d355..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp
+++ /dev/null
@@ -1,125 +0,0 @@
-#include "ProviderSegment.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "TypeIO.h"
-
-
-namespace armarx::armem::d_ltm
-{
-    std::filesystem::path ProviderSegment::_fullPath() const
-    {
-        if (path)
-        {
-            return _fullPath(*path);
-        }
-        return std::filesystem::path();
-    }
-
-    std::filesystem::path ProviderSegment::_fullPath(const std::filesystem::path& path) const
-    {
-        return path / id().memoryName / id().coreSegmentName / id().providerSegmentName;
-    }
-
-    wm::ProviderSegment ProviderSegment::convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const
-    {
-        wm::ProviderSegment m(id());
-        for (const auto& [_, s] : _container)
-        {
-            if (hasAronType())
-            {
-                m.addEntity(s.convert(_aronType));
-            }
-            else
-            {
-                m.addEntity(s.convert(expectedStructure));
-            }
-        }
-        return m;
-    }
-
-    void ProviderSegment::reload(const std::shared_ptr<std::filesystem::path>& p_ptr)
-    {
-        if (!p_ptr)
-        {
-            ARMARX_WARNING << "The entered is NULL.";
-        }
-        std::filesystem::path p = _fullPath(*p_ptr);
-        if (std::filesystem::is_regular_file(p))
-        {
-            ARMARX_ERROR << "The entered path is leading to a file! Abort due to error.";
-        }
-
-        _container.clear();
-        path = p_ptr;
-
-        if (!std::filesystem::exists(p))
-        {
-            ARMARX_INFO << "The entered path does not exist. Assuming an empty container.";
-        }
-        else
-        {
-            for (const auto& d : std::filesystem::directory_iterator(p))
-            {
-                if (d.is_directory())
-                {
-                    std::string k = d.path().filename();
-                    auto wms = _container.emplace(k, id().withEntityName(k));
-                    wms.first->second.reload(p_ptr);
-                }
-
-                if (d.is_regular_file())
-                {
-                    if (auto type = TypeIO::readAronType(d.path()))
-                    {
-                        _aronType = type;
-                    }
-                }
-            }
-        }
-    }
-
-    void ProviderSegment::append(const wm::ProviderSegment& m)
-    {
-
-        try
-        {
-            std::filesystem::create_directories(_fullPath());
-
-        }
-        catch (...)
-        {
-            ARMARX_WARNING << GetHandledExceptionString();
-            return;
-        }
-
-        TypeIO::writeAronType(_aronType, _fullPath());
-
-        m.forEachEntity([this](const wm::Entity & s)
-        {
-            if (auto it = _container.find(s.name()); it != _container.end())
-            {
-                it->second.append(s);
-            }
-            else
-            {
-
-                try
-                {
-                    std::filesystem::create_directory(_fullPath() / s.name());
-                }
-                catch (...)
-                {
-                    ARMARX_WARNING << GetHandledExceptionString();
-                    return false;
-                }
-
-                auto wms = _container.emplace(s.name(), id().withEntityName(s.name()));
-                wms.first->second.path = path;
-                wms.first->second.append(s);
-            }
-
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.h b/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.h
deleted file mode 100644
index 0e866b08cc5c50f623fd9b5676136834078c953a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.h
+++ /dev/null
@@ -1,42 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include "Entity.h"
-
-
-namespace armarx::armem::d_ltm
-{
-
-    /**
-     * @brief Data of a provider segment containing multiple entities.
-     */
-    class ProviderSegment :
-        public base::ProviderSegmentBase<Entity, ProviderSegment>
-    {
-        using Base = base::ProviderSegmentBase<Entity, ProviderSegment>;
-
-    public:
-
-        using Base::ProviderSegmentBase;
-
-
-        // Conversion
-        wm::ProviderSegment convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const;
-
-        // Filesystem connection
-        void reload(const std::shared_ptr<std::filesystem::path>&);
-        void append(const wm::ProviderSegment&);
-
-    private:
-        std::filesystem::path _fullPath() const;
-        std::filesystem::path _fullPath(const std::filesystem::path&) const;
-
-    public:
-        std::shared_ptr<std::filesystem::path> path;
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.cpp
deleted file mode 100644
index dc7f7a83706c7b9f69cc05a6e81bcf810c10a249..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.cpp
+++ /dev/null
@@ -1,71 +0,0 @@
-#include "TypeIO.h"
-
-#include <iostream>
-#include <fstream>
-#include <filesystem>
-
-#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
-#include <RobotAPI/libraries/aron/core/io/typeIO/visitor/Visitor.h>
-#include <RobotAPI/libraries/aron/core/io/typeIO/converter/Converter.h>
-#include <RobotAPI/libraries/aron/core/io/typeIO/reader/nlohmannJSON/NlohmannJSONReader.h>
-#include <RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h>
-#include <RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h>
-
-
-namespace armarx::armem::d_ltm
-{
-
-    aron::typenavigator::ObjectNavigatorPtr TypeIO::unwrapType(const aron::typenavigator::ObjectNavigatorPtr& type)
-    {
-        return aron::typenavigator::ObjectNavigator::DynamicCastAndCheck(type->getMemberType(TYPE_WRAPPER_DATA_FIELD));
-    }
-
-    aron::typenavigator::ObjectNavigatorPtr TypeIO::wrapType(const aron::typenavigator::ObjectNavigatorPtr& type)
-    {
-        aron::typenavigator::ObjectNavigatorPtr typeWrapped(new aron::typenavigator::ObjectNavigator());
-        typeWrapped->setObjectName(type->getObjectName() + "__ltm_type_export");
-        typeWrapped->addMemberType(TYPE_WRAPPER_DATA_FIELD, type);
-
-        typeWrapped->addMemberType(TYPE_WRAPPER_TIME_STORED_FIELD, std::make_shared<aron::typenavigator::LongNavigator>());
-        typeWrapped->addMemberType(TYPE_WRAPPER_TIME_CREATED_FIELD, std::make_shared<aron::typenavigator::LongNavigator>());
-        typeWrapped->addMemberType(TYPE_WRAPPER_TIME_SENT_FIELD, std::make_shared<aron::typenavigator::LongNavigator>());
-        typeWrapped->addMemberType(TYPE_WRAPPER_TIME_ARRIVED_FIELD, std::make_shared<aron::typenavigator::LongNavigator>());
-        typeWrapped->addMemberType(TYPE_WRAPPER_CONFIDENCE_FIELD, std::make_shared<aron::typenavigator::DoubleNavigator>());
-
-        return typeWrapped;
-    }
-
-    aron::typenavigator::ObjectNavigatorPtr TypeIO::readAronType(const std::filesystem::__cxx11::path& filepath)
-    {
-        if (std::filesystem::is_regular_file(filepath))
-        {
-            if (filepath.filename() == (std::string(TYPE_FILENAME) + ".json"))
-            {
-                std::ifstream ifs(filepath);
-                std::string file_content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>()));
-
-                aron::typeIO::reader::NlohmannJSONReader typeReader(file_content);
-                aron::typeIO::writer::NavigatorWriter navWriter;
-                aron::typeIO::Converter::ReadAndConvert(typeReader, navWriter);
-                return aron::typenavigator::ObjectNavigator::DynamicCastAndCheck(navWriter.getResult());
-            }
-        }
-        return nullptr;
-    }
-
-    void TypeIO::writeAronType(const aron::typenavigator::ObjectNavigatorPtr& type, const std::filesystem::__cxx11::path& filepath)
-    {
-        if (type)
-        {
-            std::ofstream ofs(filepath);
-
-            aron::typeIO::writer::NlohmannJSONWriter typeWriter;
-            aron::typeIO::Visitor::VisitAndSetup(typeWriter, type);
-            std::string new_file_full_content = typeWriter.getResult().dump(2);
-
-            ofs << new_file_full_content;
-        }
-    }
-
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.h b/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.h
deleted file mode 100644
index 4311bdcd7034a08b30b7c7f6ae9ee3eab0952fac..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/diskmemory/TypeIO.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
-
-
-namespace armarx::armem::d_ltm
-{
-
-    /**
-     * @brief An entity container with a specific (Aron) type.
-     */
-    class TypeIO
-    {
-    public:
-
-        static aron::typenavigator::ObjectNavigatorPtr unwrapType(const aron::typenavigator::ObjectNavigatorPtr& type);
-        static aron::typenavigator::ObjectNavigatorPtr wrapType(const aron::typenavigator::ObjectNavigatorPtr& type);
-
-        static aron::typenavigator::ObjectNavigatorPtr readAronType(const std::filesystem::path& filepath);
-        static void writeAronType(const aron::typenavigator::ObjectNavigatorPtr& type, const std::filesystem::path& filepath);
-
-
-    private:
-
-        static const constexpr char* TYPE_FILENAME = "type";
-        static constexpr const char* TYPE_WRAPPER_DATA_FIELD            = "__ARON_DATA";
-        static constexpr const char* TYPE_WRAPPER_TIME_STORED_FIELD     = "__WRITER_METADATA__TIME_STORED";
-        static constexpr const char* TYPE_WRAPPER_TIME_CREATED_FIELD    = "__ENTITY_METADATA__TIME_CREATED";
-        static constexpr const char* TYPE_WRAPPER_TIME_SENT_FIELD       = "__ENTITY_METADATA__TIME_SENT";
-        static constexpr const char* TYPE_WRAPPER_TIME_ARRIVED_FIELD    = "__ENTITY_METADATA__TIME_ARRIVED";
-        static constexpr const char* TYPE_WRAPPER_CONFIDENCE_FIELD      = "__ENTITY_METADATA__CONFIDENCE";
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/error/ArMemError.cpp b/source/RobotAPI/libraries/armem/core/error/ArMemError.cpp
index 8936fab6fe953bc3b7fee870a97ffee598234ea7..003ef9fb5496b92814ad68cd9904987498460c46 100644
--- a/source/RobotAPI/libraries/armem/core/error/ArMemError.cpp
+++ b/source/RobotAPI/libraries/armem/core/error/ArMemError.cpp
@@ -59,7 +59,7 @@ namespace armarx::armem::error
     {
         std::stringstream ss;
         ss << simox::alg::capitalize_words(existingTerm) << " with name '" << existingName << "' "
-           << " already exists in " << ownTerm << " '" << ownName << "'.";
+           << "already exists in " << ownTerm << " '" << ownName << "'.";
         return ss.str();
     }
 
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp
deleted file mode 100644
index 1fc021d65fe460b4b91331196446ef8661337aa6..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp
+++ /dev/null
@@ -1,86 +0,0 @@
-#include "CoreSegment.h"
-
-#include "error.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <SimoxUtility/json/json.hpp>
-
-
-namespace armarx::armem::ltm
-{
-
-    wm::CoreSegment CoreSegment::convert() const
-    {
-        wm::CoreSegment m(id());
-        for (const auto& [_, s] : _container)
-        {
-            m.addProviderSegment(s.convert());
-        }
-        return m;
-    }
-
-    void CoreSegment::reload()
-    {
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-
-        mongocxx::cursor cursor = coll.find({});
-        for (auto doc : cursor)
-        {
-            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
-            ARMARX_INFO << "CoreSegment: Found foreign key: " << json.at("foreign_key");
-
-            MemoryID i = MemoryID::fromString(json.at("foreign_key").get<std::string>());
-            if (i.coreSegmentName != id().coreSegmentName)
-            {
-                throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong coreSegment name. Expected " + id().coreSegmentName);
-            }
-
-            std::string k = i.providerSegmentName;
-
-            if (auto it = _container.find(k); it != _container.end())
-            {
-                throw error::ArMemError("Somehow after clearing the (core) container a key k = " + k + " was found. Do you have double entries in mongodb?");
-            }
-            else
-            {
-                auto wms = _container.emplace(k, id().withProviderSegmentName(k));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.reload();
-            }
-        }
-
-        ARMARX_INFO << "After reload has core segment " << id().str() << " size: " << _container.size();
-    }
-
-    void CoreSegment::append(const wm::CoreSegment& m)
-    {
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        m.forEachProviderSegment([this, &coll](const wm::ProviderSegment & provSeg)
-        {
-            auto it = _container.find(provSeg.name());
-            if (it == _container.end())
-            {
-                bsoncxx::builder::stream::document builder;
-                bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << provSeg.id().str()
-                                                       << bsoncxx::builder::stream::finalize;
-                coll.insert_one(foreign_key.view());
-
-                it = _container.emplace(provSeg.name(), id().withProviderSegmentName(provSeg.name())).first;
-                it->second.dbsettings = dbsettings;
-            }
-            it->second.append(provSeg);
-
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.h b/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.h
deleted file mode 100644
index 32f05ef2f773388b6006c573b7017064193d80c3..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.h
+++ /dev/null
@@ -1,39 +0,0 @@
-#pragma once
-
-#include "ProviderSegment.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    /**
-     * @brief Data of a core segment containing multiple provider segments.
-     */
-    class CoreSegment :
-        public base::CoreSegmentBase<ProviderSegment, CoreSegment>
-    {
-        using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
-
-    public:
-
-        using Base::CoreSegmentBase;
-
-
-        // Conversion
-        wm::CoreSegment convert() const;
-
-        // MongoDB connection
-        void reload();
-        void append(const wm::CoreSegment&);
-
-    public:
-
-        MongoDBConnectionManager::MongoDBSettings dbsettings;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp
deleted file mode 100644
index 6604c26e935cb4619fc7439d8e9a1f318a14ff63..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp
+++ /dev/null
@@ -1,151 +0,0 @@
-#include "Entity.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
-
-#include <SimoxUtility/json/json.hpp>
-
-
-namespace armarx::armem::ltm
-{
-
-    wm::Entity Entity::convert() const
-    {
-        wm::Entity m(id());
-        for (const auto& [_, s] : _container)
-        {
-            m.addSnapshot(s.convert());
-        }
-        return m;
-    }
-
-    void Entity::reload()
-    {
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        mongocxx::cursor cursor = coll.find({});
-        int i = 0;
-        for (auto doc : cursor)
-        {
-            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
-
-            auto k = armem::Time::microSeconds(json.at("timestamp"));
-            //ARMARX_INFO << "Entity: Found timestamp: " << std::to_string(k.toMicroSeconds());
-
-            if (auto it = _container.find(k); it != _container.end())
-            {
-                throw error::ArMemError("Somehow after clearing the (entity) container a key k = " + std::to_string(k.toMicroSeconds()) + " was found. Do you have double entries in mongodb?");
-            }
-            else
-            {
-                auto wms = _container.emplace(std::make_pair(k, id().withTimestamp(k)));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.reload();
-            }
-            ++i;
-        }
-
-        ARMARX_INFO << "After reload has entity " << id().str() << " size: " << _container.size();
-    }
-
-    void Entity::append(const wm::Entity& m)
-    {
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        m.forEachSnapshot([this](const wm::EntitySnapshot & snapshot)
-        {
-            if (auto it = _container.find(snapshot.time()); it != _container.end())
-            {
-                // timestamp already exists
-                // We assume that a snapshot does not change, so ignore
-            }
-            else
-            {
-                auto wms = _container.emplace(std::make_pair(snapshot.time(), id().withTimestamp(snapshot.time())));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.setTo(snapshot, snapshot.time());
-                //truncateHistoryToSize();
-            }
-            return true;
-        });
-    }
-
-    bool Entity::hasSnapshot(const Time& time) const
-    {
-        // check cache
-        if (Base::hasSnapshot(time))
-        {
-            return true;
-        }
-        // check mongodb
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        bsoncxx::stdx::optional<bsoncxx::document::value> maybe_result =
-            coll.find_one(document{} << "timestamp" << time.toMicroSeconds() << finalize);
-        if (!maybe_result)
-        {
-            return false;
-        }
-
-        nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(*maybe_result));
-        MemoryID id = MemoryID::fromString(json["id"].get<std::string>());
-        nlohmann::json instances = json["instances"];
-        EntitySnapshot snapshot(id);
-        snapshot.dbsettings = dbsettings;
-
-        for (size_t i = 0; i < instances.size(); ++i)
-        {
-            EntityInstance instance(id.withInstanceIndex(static_cast<int>(i)));
-            snapshot.addInstance(instance);
-        }
-
-        _container.emplace(time, snapshot);
-        //truncateHistoryToSize();
-        return true;
-    }
-
-    std::vector<Time> Entity::getTimestamps() const
-    {
-        // get from cache
-        std::vector<Time> ret; // = Base::getTimestamps();
-
-        // get missing from mongodb
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        auto cursor = coll.find({});
-        for (auto doc : cursor)
-        {
-            auto json = nlohmann::json::parse(bsoncxx::to_json(doc));
-            auto ts = json["timestamp"].get<long>();
-            ret.push_back(Time::microSeconds(ts));
-        }
-        return ret;
-    }
-
-    const EntitySnapshot& Entity::getSnapshot(const Time& time) const
-    {
-        if (!hasSnapshot(time))
-        {
-            throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
-        }
-
-        // the above command already puts the reference to the cache
-        return Base::getSnapshot(time);
-    }
-
-    auto Entity::getLatestItem() const -> const ContainerT::value_type&
-    {
-        // Directly query mongodb (cache cant know whether it is the latest or not)
-        // TODO
-        return Base::getLatestItem();
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h
deleted file mode 100644
index 99bc3a736f0abe803ec101a81f4b1ac75b87d92e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h
+++ /dev/null
@@ -1,63 +0,0 @@
-#pragma once
-
-#include "EntitySnapshot.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-
-namespace armarx::armem::ltm
-{
-    /**
-     * @brief An entity over a period of time.
-     *
-     * An entity should be a physical thing or abstract concept existing
-     * (and potentially evolving) over some time.
-     *
-     * Examples are:
-     * - objects (the green box)
-     * - agents (robot, human)
-     * - locations (frige, sink)
-     * - grasp affordances (general, or for a specific object)
-     * - images
-     * - point clouds
-     * - other sensory values
-     *
-     * At each point in time (`EntitySnapshot`), the entity can have a
-     * (potentially variable) number of instances (`EntityInstance`),
-     * each containing a single `AronData` object of a specific `AronType`.
-     */
-    class Entity :
-        public base::EntityBase<EntitySnapshot, Entity>
-    {
-        using Base = base::EntityBase<EntitySnapshot, Entity>;
-
-    public:
-
-        using Base::EntityBase;
-
-
-        // Conversion
-        wm::Entity convert() const;
-
-        // MongoDB connection
-        void reload();
-        void append(const wm::Entity&);
-
-        // overrides for LTM lookups
-        bool hasSnapshot(const Time& time) const;
-        std::vector<Time> getTimestamps() const;
-        const EntitySnapshot& getSnapshot(const Time& time) const;
-
-
-    protected:
-        // overrides for LTM storage
-        const ContainerT::value_type& getLatestItem() const;
-
-    public:
-        MongoDBConnectionManager::MongoDBSettings dbsettings;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp
deleted file mode 100644
index 63fe18145c561e9efda0ba2a14cb07175b029d1c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "EntityInstance.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    bool EntityInstance::equalsDeep(const EntityInstance& other) const
-    {
-        return id() == other.id() && _metadata == other.metadata();
-    }
-
-    void EntityInstance::update(const EntityUpdate& update)
-    {
-        ARMARX_CHECK_FITS_SIZE(this->index(), update.instancesData.size());
-
-        this->_metadata.confidence = update.confidence;
-        this->_metadata.timeCreated = update.timeCreated;
-        this->_metadata.timeSent = update.timeSent;
-        this->_metadata.timeArrived = update.timeArrived;
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h
deleted file mode 100644
index 6046f6ac50902d6f7f770361915dbd30d5a15ec1..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    using EntityInstanceMetadata = base::EntityInstanceMetadata;
-
-
-    /**
-     * @brief Data of a single entity instance.
-     */
-    class EntityInstance :
-        public base::EntityInstanceBase<base::NoData, EntityInstanceMetadata>
-    {
-        using Base = base::EntityInstanceBase<base::NoData, EntityInstanceMetadata>;
-
-    public:
-
-        using Base::EntityInstanceBase;
-
-
-        /**
-         * @brief Fill `*this` with the update's values.
-         * @param update The update.
-         * @param index The instances index.
-         */
-        void update(const EntityUpdate& update);
-
-        bool equalsDeep(const EntityInstance& other) const;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp
deleted file mode 100644
index 8cbe688125a7571a3e8f0a19031b25722bb79bbf..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp
+++ /dev/null
@@ -1,109 +0,0 @@
-#include "EntitySnapshot.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
-
-#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/wm/json_conversions.h>
-
-
-#include "error.h"
-
-
-namespace armarx::armem::ltm
-{
-
-    wm::EntitySnapshot EntitySnapshot::convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const
-    {
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().getEntityID().str()];
-
-        auto res = coll.find_one(document{} << "id" << id().getEntitySnapshotID().str() << finalize);
-        if (!res)
-        {
-            throw error::ArMemError("Could not load an instance from the memory '" + id().getEntityID().str() + "'. Tried to access: " + id().getEntitySnapshotID().str());
-        }
-
-        nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(*res));
-        nlohmann::json instances = json["instances"];
-
-        if (instances.size() != _container.size())
-        {
-            throw error::ArMemError("The size of the mongodb entity entry at id " + id().getEntitySnapshotID().str() + " has wrong size. Expected: " + std::to_string(_container.size()) + " but got: " + std::to_string(instances.size()));
-        }
-
-        wm::EntitySnapshot m(id());
-        for (unsigned int i = 0; i < _container.size(); ++i)
-        {
-            nlohmann::json doc = instances[i++];
-
-            auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
-            to_aron(aron, doc, expectedStructure);
-            wm::EntityInstance e(id());
-            from_aron(aron, e);
-            m.addInstance(e);
-        }
-        return m;
-    }
-
-    void EntitySnapshot::reload()
-    {
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().getEntityID().str()];
-
-        auto res = coll.find_one(document{} << "id" << id().getEntitySnapshotID().str() << finalize);
-
-        if (!res)
-        {
-            throw error::ArMemError("Could not load an instance from the memory '" + id().getEntityID().str() + "'. Tried to access: " + id().getEntitySnapshotID().str());
-        }
-
-        nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(*res));
-        for (unsigned int i = 0; i < json.at("instances").size(); ++i)
-        {
-            _container.emplace_back(id().withInstanceIndex(i));
-        }
-    }
-
-    void EntitySnapshot::setTo(const wm::EntitySnapshot& m, const armem::Time& t)
-    {
-        // We remove the contente here and reset it with new values
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().getEntityID().str()];
-
-        bsoncxx::builder::stream::document builder{};
-        auto in_array = builder
-                        << "id" << id().getEntitySnapshotID().str()
-                        << "timestamp" << t.toMicroSeconds()
-                        << "instances";
-        auto array_builder = bsoncxx::builder::basic::array{};
-
-        int i = 0;
-        m.forEachInstance([this, &array_builder, &i](const wm::EntityInstance & instance)
-        {
-            auto wms = _container.emplace_back(id().withInstanceIndex(i++));
-
-            auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
-            to_aron(aron, instance);
-            nlohmann::json j;
-            from_aron(aron, j);
-
-            auto doc_value = bsoncxx::from_json(j.dump(2));
-            array_builder.append(doc_value);
-
-            return true;
-        });
-
-        auto after_array = in_array << array_builder;
-        bsoncxx::document::value doc = after_array << bsoncxx::builder::stream::finalize;
-        coll.insert_one(doc.view());
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h
deleted file mode 100644
index 3029f8a7ca0278b9a505ee2fa5a744cfab327359..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h
+++ /dev/null
@@ -1,41 +0,0 @@
-#pragma once
-
-#include "EntityInstance.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    /**
-     * @brief Data of an entity at one point in time.
-     */
-    class EntitySnapshot :
-        public base::EntitySnapshotBase<EntityInstance, EntitySnapshot>
-    {
-        using Base = base::EntitySnapshotBase<EntityInstance, EntitySnapshot>;
-
-    public:
-
-        using Base::EntitySnapshotBase;
-
-
-        // Conversion
-        wm::EntitySnapshot convert(const aron::typenavigator::NavigatorPtr& = nullptr) const;
-
-        // MongoDB connection
-        void reload();
-        void setTo(const wm::EntitySnapshot&, const armem::Time& t);
-
-
-    public:
-
-        MongoDBConnectionManager::MongoDBSettings dbsettings;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp
deleted file mode 100644
index ab4cb5d13ec0a30c0e8dc04125b61bd4b031df99..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp
+++ /dev/null
@@ -1,236 +0,0 @@
-#include "Memory.h"
-
-#include "error.h"
-
-#include <ArmarXCore/core/application/properties/PluginAll.h>
-#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/time/TimeUtil.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    Memory::Memory(const Memory& other) :
-        Base(other),
-        dbsettings(other.dbsettings),
-        periodicTransferSettings(other.periodicTransferSettings),
-        onFullTransferSettings(other.onFullTransferSettings),
-        mongoDBMutex()
-    {
-        // Do not copy _mutex.
-    }
-
-
-    Memory::Memory(Memory&& other) :
-        Base(std::move(other)),
-        dbsettings(other.dbsettings),
-        periodicTransferSettings(other.periodicTransferSettings),
-        onFullTransferSettings(other.onFullTransferSettings),
-        reloaded(other.reloaded)
-    {
-        // Do not move _mutex.
-    }
-
-
-    Memory& Memory::operator=(const Memory& other)
-    {
-        Base::operator=(other);
-
-        dbsettings = other.dbsettings;
-        periodicTransferSettings = other.periodicTransferSettings;
-        onFullTransferSettings = other.onFullTransferSettings;
-
-        // Don't copy _mutex.
-        return *this;
-    }
-
-
-    Memory& Memory::operator=(Memory&& other)
-    {
-        Base::operator=(std::move(other));
-
-        dbsettings = std::move(other.dbsettings);
-        periodicTransferSettings = std::move(other.periodicTransferSettings);
-        onFullTransferSettings = std::move(other.onFullTransferSettings);
-        reloaded = other.reloaded;
-
-        // Don't move _mutex.
-        return *this;
-    }
-
-    bool Memory::checkConnection() const
-    {
-        // Check connection:
-        ARMARX_INFO << "Checking connection";
-        if (!MongoDBConnectionManager::ConnectionIsValid(dbsettings))
-        {
-            ARMARX_WARNING << deactivateSpam("ConnectionIsNotValid")
-                           << "The connection to mongocxx for memory '" << name() << "' is not valid. Settings are: " << dbsettings.toString()
-                           << "\nTo start it, run e.g.: \n"
-                           << "armarx memory start"
-                           << "\n\n";
-            return false;
-        }
-        return true;
-    }
-
-    void Memory::defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix)
-    {
-        defs->optional(dbsettings.host, prefix + ".ltm.10_host");
-        defs->optional(dbsettings.port, prefix + "ltm.11_port");
-        defs->optional(dbsettings.user, prefix + "ltm.20_user");
-        defs->optional(dbsettings.password, prefix + "ltm.21_password");
-        defs->optional(dbsettings.database, prefix + "ltm.22_database");
-        defs->optional(periodicTransferSettings.enabled, prefix + "ltm.30_enablePeriodicTransfer", "Enable transfer based on periodic interval.");
-        defs->optional(onFullTransferSettings.enabled, prefix + "ltm.31_enableOnFullTransfer", "Enable transfer whenever the wm is full (see maxHistorySize).");
-    }
-
-    wm::Memory Memory::convert() const
-    {
-        wm::Memory m(id());
-
-        std::lock_guard l(mongoDBMutex);
-        if (!checkConnection())
-        {
-            return m;
-        }
-
-        ARMARX_INFO << "Converting Memory with connection to: " << dbsettings.toString();
-
-        TIMING_START(LTM_Convert);
-
-        for (const auto& [_, s] : _container)
-        {
-            m.addCoreSegment(s.convert());
-        }
-
-        TIMING_END(LTM_Convert);
-        return m;
-    }
-
-    void Memory::reload()
-    {
-        std::lock_guard l(mongoDBMutex);
-        reloaded = false;
-
-        if (!checkConnection())
-        {
-            return;
-        }
-
-        ARMARX_INFO << "(Re)Establishing connection to: " << dbsettings.toString();
-
-        TIMING_START(LTM_Reload);
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        if (!client)
-        {
-            ARMARX_ERROR << "A client has died. Could not reload.";
-            return;
-        }
-
-        auto databases = client.list_databases();
-        for (const auto& doc : databases)
-        {
-            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
-            ARMARX_INFO << "Found the database: " << json.at("name");
-        }
-
-        mongocxx::database db = client[dbsettings.database];
-        ARMARX_INFO << "Getting collection for id: " << id().str();
-        mongocxx::collection coll = db[id().str()];
-
-        ARMARX_IMPORTANT << "Memory Container size is: " << _container.size();
-
-        mongocxx::cursor cursor = coll.find({});
-        for (const auto& doc : cursor)
-        {
-            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
-            ARMARX_INFO << "Memory: Found foreign key: " << json.at("foreign_key");
-
-            MemoryID i((std::string) json.at("foreign_key"));
-            if (i.memoryName != id().memoryName)
-            {
-                throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong memory name. Expected " + id().memoryName);
-            }
-
-            std::string k = i.coreSegmentName;
-
-            if (auto it = _container.find(k); it != _container.end())
-            {
-                throw error::ArMemError("Somehow after clearing the (memory) container a key k = " + k + " was found. Do you have double entries in mongodb?");
-            }
-            else
-            {
-                auto wms = _container.emplace(k, id().withCoreSegmentName(k));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.reload();
-            }
-        }
-
-        reloaded = true;
-        for (const auto& m : toAppendQueue)
-        {
-            _append(m);
-        }
-
-        TIMING_END(LTM_Reload);
-        ARMARX_INFO << "After reload memory " << id().str() << " size: " << _container.size() << ". Setting reloaded: " << reloaded;
-    }
-
-    void Memory::_append(const wm::Memory& m)
-    {
-        if (!checkConnection() || !reloaded)
-        {
-            // We ignore if not fully loaded yet
-            return;
-        }
-
-        //ARMARX_INFO << "Merge memory with name '" << m.name() << "' into the LTM with name '" << name() << "'";
-
-        TIMING_START(LTM_Append);
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        m.forEachCoreSegment([this, &coll](const wm::CoreSegment & s)
-        {
-            if (auto it = _container.find(s.name()); it != _container.end())
-            {
-                // TODO check if foreign key exists
-                it->second.append(s);
-            }
-            else
-            {
-                auto builder = bsoncxx::builder::stream::document{};
-                bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << s.id().withCoreSegmentName(s.name()).str()
-                                                       << bsoncxx::builder::stream::finalize;
-                coll.insert_one(foreign_key.view());
-
-                auto wms = _container.emplace(s.name(), id().withCoreSegmentName(s.name()));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.append(s);
-            }
-
-            return true;
-        });
-
-        TIMING_END(LTM_Append);
-    }
-
-    void Memory::append(const wm::Memory& m)
-    {
-        std::lock_guard l(mongoDBMutex);
-        if (!checkConnection() || !reloaded)
-        {
-            toAppendQueue.push_back(m);
-            return;
-        }
-        _append(m);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.h b/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.h
deleted file mode 100644
index 41e82bce38b50f9e122e34056c2b5fd74cec4bac..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.h
+++ /dev/null
@@ -1,87 +0,0 @@
-#pragma once
-
-#include "CoreSegment.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-#include <ArmarXCore/core/application/properties/forward_declarations.h>
-
-#include <mutex>
-
-
-namespace armarx::armem::ltm
-{
-    /**
-     * @brief Data of a memory consisting of multiple core segments.
-     */
-    class Memory :
-        public base::MemoryBase<CoreSegment, Memory>
-    {
-        using Base = base::MemoryBase<CoreSegment, Memory>;
-
-    public:
-
-        struct TransferSettings
-        {
-            bool enabled = false;
-        };
-
-        struct PeriodicTransferSettings : public TransferSettings
-        {
-            bool deleteFromWMOnTransfer = false;
-            int frequencyHz = 1;
-        };
-
-        struct OnFullTransferSettings : public TransferSettings
-        {
-            enum class Mode
-            {
-                TRANSFER_LATEST,
-                TRANSFER_LEAST_USED
-            };
-
-            Mode mode;
-            int batch_size = 20;
-        };
-
-
-    public:
-
-        using Base::MemoryBase;
-
-        Memory(const Memory& other);
-        Memory(Memory&& other);
-        Memory& operator=(const Memory& other);
-        Memory& operator=(Memory&& other);
-
-        // PropertyDefinitions related to LTM
-        void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "");
-
-        // Conversion
-        wm::Memory convert() const;
-
-        // MongoDB connection
-        void reload();
-        void append(const wm::Memory&);
-
-
-    private:
-        bool checkConnection() const;
-
-        void _append(const wm::Memory&);
-
-    public:
-        MongoDBConnectionManager::MongoDBSettings dbsettings;
-
-        PeriodicTransferSettings periodicTransferSettings;
-        OnFullTransferSettings onFullTransferSettings;
-
-    private:
-        bool reloaded = false;
-        mutable std::mutex mongoDBMutex;
-
-        std::vector<wm::Memory> toAppendQueue;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp
deleted file mode 100644
index 8126867e4db4be01c91dfb582b67c94303751927..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp
+++ /dev/null
@@ -1,87 +0,0 @@
-#include "ProviderSegment.h"
-
-#include "error.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <SimoxUtility/json/json.hpp>
-
-
-namespace armarx::armem::ltm
-{
-
-    wm::ProviderSegment ProviderSegment::convert() const
-    {
-        wm::ProviderSegment m(id());
-        for (const auto& [_, s] : _container)
-        {
-            m.addEntity(s.convert());
-        }
-        return m;
-    }
-
-    void ProviderSegment::reload()
-    {
-        _container.clear();
-
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        mongocxx::cursor cursor = coll.find({});
-        for (auto doc : cursor)
-        {
-            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
-
-            MemoryID i((std::string) json.at("foreign_key"));
-            if (i.providerSegmentName != id().providerSegmentName)
-            {
-                throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong providerSegment name. Expected " + id().providerSegmentName);
-            }
-
-            std::string k = i.entityName;
-
-            if (auto it = _container.find(k); it != _container.end())
-            {
-                throw error::ArMemError("Somehow after clearing the (provvider) container a key k = " + k + " was found. Do you have double entries in mongodb?");
-            }
-            else
-            {
-                auto wms = _container.emplace(k, id().withEntityName(k));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.reload();
-            }
-        }
-
-        ARMARX_INFO << "After reload has provider segment " << id().str() << " size: " << _container.size();
-    }
-
-    void ProviderSegment::append(const wm::ProviderSegment& m)
-    {
-        mongocxx::client& client = MongoDBConnectionManager::EstablishConnection(dbsettings);
-        mongocxx::database db = client[dbsettings.database];
-        mongocxx::collection coll = db[id().str()];
-
-        m.forEachEntity([this, &coll](const wm::Entity & s)
-        {
-            if (auto it = _container.find(s.name()); it != _container.end())
-            {
-                it->second.append(s);
-            }
-            else
-            {
-                auto builder = bsoncxx::builder::stream::document{};
-                bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << s.id().withEntityName(s.name()).str()
-                                                       << bsoncxx::builder::stream::finalize;
-                coll.insert_one(foreign_key.view());
-
-                auto wms = _container.emplace(s.name(), id().withEntityName(s.name()));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.append(s);
-            }
-
-            return true;
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.h b/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.h
deleted file mode 100644
index bf1d5e3a9f4cbd816e087957d0bb3d6351b0b6cd..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include "Entity.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-
-
-namespace armarx::armem::ltm
-{
-
-    /**
-     * @brief Data of a provider segment containing multiple entities.
-     */
-    class ProviderSegment :
-        public base::ProviderSegmentBase<Entity, ProviderSegment>
-    {
-        using Base = base::ProviderSegmentBase<Entity, ProviderSegment>;
-
-    public:
-
-        using Base::ProviderSegmentBase;
-
-
-        // Conversion
-        wm::ProviderSegment convert() const;
-
-        // MongoDB connection
-        void reload();
-        void append(const wm::ProviderSegment&);
-
-    public:
-        MongoDBConnectionManager::MongoDBSettings dbsettings;
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.h b/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.h
deleted file mode 100644
index 0cd3cb5ba8f6c575d6d3dd9357f16884f508914c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.h
+++ /dev/null
@@ -1,75 +0,0 @@
-#pragma once
-
-#include <string>
-#include <vector>
-#include <map>
-#include <memory>
-#include <iostream>
-
-#include <bsoncxx/json.hpp>
-#include <mongocxx/client.hpp>
-#include <mongocxx/stdx.hpp>
-#include <mongocxx/uri.hpp>
-#include <mongocxx/instance.hpp>
-#include <bsoncxx/builder/stream/helpers.hpp>
-#include <bsoncxx/builder/stream/document.hpp>
-#include <bsoncxx/builder/stream/array.hpp>
-
-
-namespace armarx::armem::ltm
-{
-
-    using bsoncxx::builder::stream::close_array;
-    using bsoncxx::builder::stream::close_document;
-    using bsoncxx::builder::stream::document;
-    using bsoncxx::builder::stream::finalize;
-    using bsoncxx::builder::stream::open_array;
-    using bsoncxx::builder::stream::open_document;
-
-
-    /**
-     * @brief Data of a memory consisting of multiple core segments.
-     */
-    class MongoDBConnectionManager
-    {
-    public:
-        struct MongoDBSettings
-        {
-            std::string host = "localhost";
-            unsigned int port = 25270;
-            std::string user = "";
-            std::string password = "";
-            std::string database = "Test";
-
-
-            bool isSet() const
-            {
-                // we always need a user and a host
-                return !host.empty() and port != 0 and !user.empty();
-            }
-
-            std::string uri() const
-            {
-                return "mongodb://" + host + ":" + std::to_string(port) + user;
-            }
-
-            std::string toString() const
-            {
-                return uri() + ":" + password + "/" + database;
-            }
-        };
-
-        static mongocxx::client& EstablishConnection(const MongoDBSettings& settings);
-        static bool ConnectionIsValid(const MongoDBSettings& settings, bool force = false);
-        static bool ConnectionExists(const MongoDBSettings& settings);
-
-    private:
-        static void initialize_if();
-
-
-    private:
-        static bool initialized;
-        static std::map<std::string, mongocxx::client> Connections;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/operations.cpp b/source/RobotAPI/libraries/armem/core/operations.cpp
index b9ebedd316a41494d93bf99b1700fd83c475ba71..533bc623f3844a06ab7b87d858c00942a637fcbc 100644
--- a/source/RobotAPI/libraries/armem/core/operations.cpp
+++ b/source/RobotAPI/libraries/armem/core/operations.cpp
@@ -1,5 +1,9 @@
 #include "operations.h"
 
+#include <RobotAPI/libraries/armem/core/Time.h>
+
+#include <SimoxUtility/algorithm/string/string_tools.h>
+
 
 namespace armarx
 {
@@ -26,7 +30,72 @@ namespace armarx
         return up;
     }
 
-}
 
+    template <class DataT>
+    static std::string makeLine(int depth, const DataT& data, std::optional<size_t> size = std::nullopt)
+    {
+        std::stringstream ss;
+        while (depth > 1)
+        {
+            ss << "|  ";
+            depth--;
+        }
+        if (depth > 0)
+        {
+            ss << "+- ";
+        }
+        ss << simox::alg::capitalize_words(DataT::getLevelName());
+        ss << " '" << simox::alg::capitalize_words(data.getKeyString()) << "'";
+        if (size.has_value())
+        {
+            ss << " (size " << size.value() << ")";
+        }
+        ss << "\n";
+        return ss.str();
+    }
+
+
+    template <class DataT>
+    static std::string _print(const DataT& data, int maxDepth, int depth)
+    {
+        std::stringstream ss;
+        ss << makeLine(depth, data, data.size());
+        if (maxDepth < 0 || maxDepth > 0)
+        {
+            data.forEachChild([&ss, maxDepth, depth](const auto& instance)
+            {
+                ss << armem::print(instance, maxDepth - 1, depth + 1);
+            });
+        }
+        return ss.str();
+    }
 
+    std::string armem::print(const wm::Memory& data, int maxDepth, int depth)
+    {
+        return _print(data, maxDepth, depth);
+    }
+    std::string armem::print(const wm::CoreSegment& data, int maxDepth, int depth)
+    {
+        return _print(data, maxDepth, depth);
+    }
+    std::string armem::print(const wm::ProviderSegment& data, int maxDepth, int depth)
+    {
+        return _print(data, maxDepth, depth);
+    }
+    std::string armem::print(const wm::Entity& data, int maxDepth, int depth)
+    {
+        return _print(data, maxDepth, depth);
+    }
+    std::string armem::print(const wm::EntitySnapshot& data, int maxDepth, int depth)
+    {
+        return _print(data, maxDepth, depth);
+    }
 
+    std::string armem::print(const wm::EntityInstance& data, int maxDepth, int depth)
+    {
+        (void) maxDepth;
+        std::stringstream ss;
+        ss << makeLine(depth, data);
+        return ss.str();
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/core/operations.h b/source/RobotAPI/libraries/armem/core/operations.h
index 3b0182e324f32b832c97aaafa04ada90e604c9fa..775b6dd07216a13dcffafc73f8651f6722b56b09 100644
--- a/source/RobotAPI/libraries/armem/core/operations.h
+++ b/source/RobotAPI/libraries/armem/core/operations.h
@@ -2,6 +2,8 @@
 
 #include "wm/memory_definitions.h"
 
+#include <string>
+
 
 /*
  * Functions performing some "advanced" operations on the memory
@@ -15,11 +17,14 @@ namespace armarx::armem
     std::vector<aron::datanavigator::DictNavigatorPtr>
     getAronData(const wm::EntitySnapshot& snapshot);
 
-    EntityUpdate toEntityUpdate(const wm::EntitySnapshot& snapshot);
+
+    EntityUpdate
+    toEntityUpdate(const wm::EntitySnapshot& snapshot);
 
 
     template <class ContainerT>
-    Commit toCommit(const ContainerT& container)
+    Commit
+    toCommit(const ContainerT& container)
     {
         Commit commit;
         container.forEachSnapshot([&commit](const wm::EntitySnapshot & snapshot)
@@ -30,5 +35,27 @@ namespace armarx::armem
         return commit;
     }
 
+
+    template <class ContainerT>
+    const typename ContainerT::EntityInstanceT*
+    findFirstInstance(const ContainerT& container)
+    {
+        const typename ContainerT::EntityInstanceT* instance = nullptr;
+        container.forEachInstance([&instance](const wm::EntityInstance & i)
+        {
+            instance = &i;
+            return false;
+        });
+        return instance;
+    }
+
+
+    std::string print(const wm::Memory& data, int maxDepth = -1, int depth = 0);
+    std::string print(const wm::CoreSegment& data, int maxDepth = -1, int depth = 0);
+    std::string print(const wm::ProviderSegment& data, int maxDepth = -1, int depth = 0);
+    std::string print(const wm::Entity& data, int maxDepth = -1, int depth = 0);
+    std::string print(const wm::EntitySnapshot& data, int maxDepth = -1, int depth = 0);
+    std::string print(const wm::EntityInstance& data, int maxDepth = -1, int depth = 0);
+
 }
 
diff --git a/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.cpp b/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..50fd63bf64dabfedbab4e980f9450563d301e02b
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.cpp
@@ -0,0 +1,7 @@
+#include "data_lookup_mixins.h"
+
+
+namespace armarx::armem::base
+{
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.h b/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.h
new file mode 100644
index 0000000000000000000000000000000000000000..280a465cbaac7408259e2c439c827bdbc0fc19e5
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.h
@@ -0,0 +1,45 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/forward_declarations.h>
+#include <RobotAPI/libraries/armem/core/base/detail/derived.h>
+
+#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
+
+#include <optional>
+
+
+namespace armarx::armem::wm::detail
+{
+    using base::detail::derived;
+
+
+    template <class DerivedT>
+    struct FindInstanceDataMixin
+    {
+        aron::datanavigator::DictNavigatorPtr
+        findLatestInstanceData(const MemoryID& entityID, int instanceIndex = 0) const
+        {
+            const auto* instance = derived<DerivedT>(this).findLatestInstance(entityID, instanceIndex);
+            return instance ? instance->data() : nullptr;
+        }
+
+
+        template <class AronDtoT>
+        std::optional<AronDtoT>
+        findLatestInstanceDataAs(const MemoryID& entityID, int instanceIndex = 0) const
+        {
+            if (aron::datanavigator::DictNavigatorPtr data = derived<DerivedT>(this).findLatestInstanceData(entityID, instanceIndex))
+            {
+                AronDtoT aron;
+                aron.fromAron(data);
+                return aron;
+            }
+            else
+            {
+                return std::nullopt;
+            }
+        }
+
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp
index 70a905a931fd331a6ecdfbc2c278924b0da9144a..ba6c9782e0e2663ee9395fde31956d5fdbfc2ad2 100644
--- a/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp
@@ -15,7 +15,6 @@ namespace armarx::armem
         base::fromIce(ice, data);
     }
 
-
     void wm::toIce(data::EntitySnapshot& ice, const EntitySnapshot& snapshot)
     {
         base::toIce(ice, snapshot);
diff --git a/source/RobotAPI/libraries/armem/core/wm/json_conversions.h b/source/RobotAPI/libraries/armem/core/wm/json_conversions.h
deleted file mode 100644
index 4ce93812b606688e642eecc0b7856210adce1a90..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/wm/json_conversions.h
+++ /dev/null
@@ -1,14 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
-
-#include <SimoxUtility/json/json.hpp>
-
-
-namespace armarx::armem
-{
-    void from_aron(const aron::datanavigator::DictNavigatorPtr&, nlohmann::json&);
-    void to_aron(aron::datanavigator::DictNavigatorPtr&, const nlohmann::json&,
-                 const aron::typenavigator::NavigatorPtr& expectedStructure = nullptr);
-}
diff --git a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
index c9516fc3b74ce05797d7d8c39b12f83b0bdf740d..de5ad02c2e9e4f24304c2ae9b9eb97f0cd3e53ee 100644
--- a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
@@ -9,6 +9,7 @@
 #include <vector>
 
 
+
 namespace armarx::armem::wm
 {
 
@@ -41,52 +42,4 @@ namespace armarx::armem::wm
         this->_metadata.timeArrived = update.timeArrived;
     }
 
-
-
-    std::optional<wm::EntitySnapshot> CoreSegment::getLatestEntitySnapshot(const MemoryID& entityID) const
-    {
-        const wm::Entity& entity = this->getEntity(entityID);
-        if (entity.empty())
-        {
-            return std::nullopt;
-        }
-        else
-        {
-            return entity.getLatestSnapshot();
-        }
-    }
-
-
-    std::optional<wm::EntityInstance> CoreSegment::getLatestEntityInstance(
-        const MemoryID& entityID, int instanceIndex) const
-    {
-        auto snapshot = getLatestEntitySnapshot(entityID);
-        if (snapshot.has_value()
-            and instanceIndex >= 0
-            and static_cast<size_t>(instanceIndex) < snapshot->size())
-        {
-            return snapshot->getInstance(instanceIndex);
-        }
-        else
-        {
-            return std::nullopt;
-        }
-    }
-
-
-    armarx::aron::datanavigator::DictNavigatorPtr
-    CoreSegment::getLatestEntityInstanceData(const MemoryID& entityID, int instanceIndex) const
-    {
-        auto instance = getLatestEntityInstance(entityID, instanceIndex);
-        if (instance.has_value())
-        {
-            return instance->data();
-        }
-        else
-        {
-            return nullptr;
-        }
-    }
-
-
 }
diff --git a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.h b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.h
index 679153b47809682fec38adb5baea609dd99c5c28..5bfc4aa3ee3893b2b0086ffeb0a6dc03520e392b 100644
--- a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.h
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.h
@@ -1,5 +1,7 @@
 #pragma once
 
+#include "detail/data_lookup_mixins.h"
+
 #include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
 #include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
 #include <RobotAPI/libraries/armem/core/base/EntityBase.h>
@@ -7,7 +9,7 @@
 #include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
 #include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
 
-#include <optional>
+#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
 
 
 namespace armarx::armem::wm
@@ -56,6 +58,7 @@ namespace armarx::armem::wm
     /// @see base::EntityBase
     class Entity :
         public base::EntityBase<EntitySnapshot, Entity>
+        , public detail::FindInstanceDataMixin<Entity>
     {
     public:
 
@@ -68,10 +71,13 @@ namespace armarx::armem::wm
     /// @see base::ProviderSegmentBase
     class ProviderSegment :
         public base::ProviderSegmentBase<Entity, ProviderSegment>
+        , public detail::FindInstanceDataMixin<ProviderSegment>
     {
+        using Base = base::ProviderSegmentBase<Entity, ProviderSegment>;
+
     public:
 
-        using base::ProviderSegmentBase<Entity, ProviderSegment>::ProviderSegmentBase;
+        using Base::ProviderSegmentBase;
 
     };
 
@@ -80,6 +86,7 @@ namespace armarx::armem::wm
     /// @see base::CoreSegmentBase
     class CoreSegment :
         public base::CoreSegmentBase<ProviderSegment, CoreSegment>
+        , public detail::FindInstanceDataMixin<CoreSegment>
     {
         using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
 
@@ -87,34 +94,6 @@ namespace armarx::armem::wm
 
         using Base::CoreSegmentBase;
 
-
-        // Non-locking interface
-
-        std::optional<wm::EntitySnapshot> getLatestEntitySnapshot(
-            const MemoryID& entityID) const;
-        std::optional<wm::EntityInstance> getLatestEntityInstance(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-        armarx::aron::datanavigator::DictNavigatorPtr getLatestEntityInstanceData(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-
-
-        template <class AronDtoT>
-        std::optional<AronDtoT> getLatestEntityInstanceDataAs(
-            const MemoryID& entityID, int instanceIndex = 0) const
-        {
-            wm::EntityInstanceDataPtr data = getLatestEntityInstanceData(entityID, instanceIndex);
-            if (data)
-            {
-                AronDtoT aron;
-                aron.fromAron(data);
-                return aron;
-            }
-            else
-            {
-                return std::nullopt;
-            }
-        }
-
     };
 
 
@@ -122,6 +101,7 @@ namespace armarx::armem::wm
     /// @see base::MemoryBase
     class Memory :
         public base::MemoryBase<CoreSegment, Memory>
+        , public detail::FindInstanceDataMixin<Memory>
     {
         using Base = base::MemoryBase<CoreSegment, Memory>;
 
diff --git a/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp b/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp
index 1140bc11be0a43e41e2e5c690ae8a73132440a6b..9448f55f8f68385d716f9b8e7da26e890ffb48fd 100644
--- a/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp
@@ -3,6 +3,7 @@
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 
 
diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp b/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
index ae847a803dc64e68b53c432b222cb6ddbe2fcd86..86b1d93ef683c19bf169a6fb447673eef656472e 100644
--- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
@@ -20,8 +20,7 @@ namespace armarx::armem::server::plugins
         ComponentPluginUser& parent = this->parent<ComponentPluginUser>();
         properties->topic(memoryListener, parent.memoryListenerDefaultName);
 
-        properties->optional(parent.longtermMemoryEnabled, "memory.ltm.00_enabled");
-        parent.longtermMemory.defineProperties(properties, "memory");
+        properties->optional(parent.longtermMemoryEnabled, "mem.ltm.00_enabled");
     }
 
 
@@ -38,7 +37,7 @@ namespace armarx::armem::server::plugins
         // establishing connection to ltm and mongodb
         if (parent.longtermMemoryEnabled)
         {
-            parent.longtermMemory.reload();
+            parent.longtermMemoryManager.reload();
         }
     }
 
@@ -114,17 +113,25 @@ namespace armarx::armem::server
 
     ComponentPluginUser::~ComponentPluginUser() = default;
 
+    // Set the name of a memory
+    void ComponentPluginUser::setMemoryName(const std::string& name)
+    {
+        workingMemory.name() = name;
+        longtermMemoryManager.setName(name);
+    }
+
 
     // WRITING
     data::AddSegmentsResult ComponentPluginUser::addSegments(const data::AddSegmentsInput& input, const Ice::Current&)
     {
+        ARMARX_TRACE;
         bool addCoreSegmentOnUsage = false;
         return addSegments(input, addCoreSegmentOnUsage);
     }
 
     data::AddSegmentsResult ComponentPluginUser::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments)
     {
-        // std::scoped_lock lock(workingMemoryMutex);
+        ARMARX_TRACE;
         data::AddSegmentsResult result = iceMemory.addSegments(input, addCoreSegments);
         return result;
     }
@@ -132,7 +139,7 @@ namespace armarx::armem::server
 
     data::CommitResult ComponentPluginUser::commit(const data::Commit& commitIce, const Ice::Current&)
     {
-        // std::scoped_lock lock(workingMemoryMutex);
+        ARMARX_TRACE;
         return iceMemory.commit(commitIce);
     }
 
@@ -140,7 +147,7 @@ namespace armarx::armem::server
     // READING
     armem::query::data::Result ComponentPluginUser::query(const armem::query::data::Input& input, const Ice::Current&)
     {
-        // std::scoped_lock lock(workingMemoryMutex);
+        ARMARX_TRACE;
         return iceMemory.query(input);
     }
 
@@ -148,16 +155,11 @@ namespace armarx::armem::server
     // LTM STORING
     data::StoreResult ComponentPluginUser::store(const data::StoreInput& input, const Ice::Current&)
     {
-        std::scoped_lock lock(/*workingMemoryMutex,*/ longtermMemoryMutex);
+        ARMARX_TRACE;
         return iceMemory.store(input);
     }
 
 
     // LTM LOADING
-    armem::query::data::Result ComponentPluginUser::load(const armem::query::data::Input& input, const Ice::Current&)
-    {
-        std::scoped_lock lock(longtermMemoryMutex);
-        return iceMemory.load(input);
-    }
 
 }
diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h b/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
index 0b2b872c1ff4686eecefd8ae8508bcfc45600d5f..35a03e7b0a3ddd4f8aafebadbbd60474dc613c8e 100644
--- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
+++ b/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
@@ -9,7 +9,7 @@
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
+#include <RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h>
 #include <RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h>
 
 #include "MemoryToIceAdapter.h"
@@ -75,6 +75,9 @@ namespace armarx::armem::server
         ComponentPluginUser();
         virtual ~ComponentPluginUser() override;
 
+        /// Set the name of the wm and the ltm (if enabled)
+        void setMemoryName(const std::string&);
+
 
         // WritingInterface interface
         virtual data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, const Ice::Current& = Ice::emptyCurrent) override;
@@ -92,7 +95,6 @@ namespace armarx::armem::server
 
 
         // LoadingInterface interface
-        virtual armem::query::data::Result load(const armem::query::data::Input&, const Ice::Current& = Ice::emptyCurrent) override;
 
 
     public:
@@ -102,15 +104,17 @@ namespace armarx::armem::server
         // [[deprecated ("The global working memory mutex is deprecated. Use the core segment mutexes instead.")]]
         // std::mutex workingMemoryMutex;
 
+        /// Parameter to indicate whether to use or not to use the ltm feature
         bool longtermMemoryEnabled = true;
-        ltm::Memory longtermMemory;
-        std::mutex longtermMemoryMutex;
+
+        /// A manager class for the ltm. It internally holds a normal wm instance
+        server::ltm::mongodb::MemoryManager longtermMemoryManager;
 
         /// property defaults
         std::string memoryListenerDefaultName = "MemoryUpdates";
 
         /// Helps connecting `memory` to ice. Used to handle Ice callbacks.
-        MemoryToIceAdapter iceMemory { &workingMemory, &longtermMemory};
+        MemoryToIceAdapter iceMemory { &workingMemory, &longtermMemoryManager};
 
 
     private:
diff --git a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
index 6664288a0fa5f86da4df906819cba3be385cbcb9..57b495a527d07924176314edc70fbfa1c53f1cae 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
@@ -3,6 +3,7 @@
 #include "RemoteGuiAronDataVisitor.h"
 
 #include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
 #include <RobotAPI/libraries/aron/core/navigator/visitors/DataVisitor.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
@@ -32,11 +33,27 @@ namespace armarx::armem::server
         return group;
     }
 
+
+    static std::string getTypeString(const armem::base::detail::AronTyped& typed)
+    {
+        std::stringstream type;
+        if (typed.aronType())
+        {
+            type << " (" << typed.aronType()->getName() << ")";
+        }
+        else
+        {
+            type << " (no Aron type)";
+        }
+        return type.str();
+    }
+
     template <class ...Args>
     MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::CoreSegmentBase<Args...>& coreSegment) const
     {
         GroupBox group;
-        group.setLabel(makeGroupLabel("Core Segment", coreSegment.name(), coreSegment.size()));
+        group.setLabel(makeGroupLabel("Core Segment", coreSegment.name(), coreSegment.size())
+                       + getTypeString(coreSegment));
 
         if (coreSegment.empty())
         {
@@ -49,11 +66,13 @@ namespace armarx::armem::server
         return group;
     }
 
+
     template <class ...Args>
     MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::ProviderSegmentBase<Args...>& providerSegment) const
     {
         GroupBox group;
-        group.setLabel(makeGroupLabel("Provider Segment", providerSegment.name(), providerSegment.size()));
+        group.setLabel(makeGroupLabel("Provider Segment", providerSegment.name(), providerSegment.size())
+                       + getTypeString(providerSegment));
 
         if (providerSegment.empty())
         {
@@ -66,6 +85,7 @@ namespace armarx::armem::server
         return group;
     }
 
+
     template <class ...Args>
     MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::EntityBase<Args...>& entity) const
     {
@@ -111,8 +131,10 @@ namespace armarx::armem::server
 
     MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::server::wm::CoreSegment& coreSegment) const
     {
-        std::scoped_lock lock(coreSegment.mutex());
-        return this->_makeGroupBox(coreSegment);
+        return coreSegment.doLocked([this, &coreSegment]()
+        {
+            return this->_makeGroupBox(coreSegment);
+        });
     }
 
 
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
index 52fb496592390a1f7df893d0709c73937da55ae5..73d00c3a370fd14e40771df77d0d96cc6b9dbf42 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
@@ -17,8 +17,8 @@
 namespace armarx::armem::server
 {
 
-    MemoryToIceAdapter::MemoryToIceAdapter(wm::Memory* workingMemory, ltm::Memory* longtermMemory) :
-        workingMemory(workingMemory), longtermMemory(longtermMemory)
+    MemoryToIceAdapter::MemoryToIceAdapter(wm::Memory* workingMemory, server::ltm::mongodb::MemoryManager* longtermMemory) :
+        workingMemory(workingMemory), longtermMemoryManager(longtermMemory)
     {
     }
 
@@ -34,6 +34,7 @@ namespace armarx::armem::server
     data::AddSegmentResult
     MemoryToIceAdapter::addSegment(const data::AddSegmentInput& input, bool addCoreSegments)
     {
+        ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
 
         data::AddSegmentResult output;
@@ -60,20 +61,22 @@ namespace armarx::armem::server
 
         if (input.providerSegmentName.size() > 0)
         {
-            std::scoped_lock lock(coreSegment->mutex());
-            try
-            {
-                coreSegment->addProviderSegment(input.providerSegmentName);
-            }
-            catch (const armem::error::ContainerEntryAlreadyExists&)
+            coreSegment->doLocked([&coreSegment, &input]()
             {
-                // This is ok.
-                if (input.clearWhenExists)
+                try
                 {
-                    server::wm::ProviderSegment& provider = coreSegment->getProviderSegment(input.providerSegmentName);
-                    provider.clear();
+                    coreSegment->addProviderSegment(input.providerSegmentName);
                 }
-            }
+                catch (const armem::error::ContainerEntryAlreadyExists&)
+                {
+                    // This is ok.
+                    if (input.clearWhenExists)
+                    {
+                        server::wm::ProviderSegment& provider = coreSegment->getProviderSegment(input.providerSegmentName);
+                        provider.clear();
+                    }
+                }
+            });
         }
 
         armem::MemoryID segmentID;
@@ -90,6 +93,7 @@ namespace armarx::armem::server
     data::AddSegmentsResult
     MemoryToIceAdapter::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments)
     {
+        ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
 
         data::AddSegmentsResult output;
@@ -104,6 +108,7 @@ namespace armarx::armem::server
     data::CommitResult
     MemoryToIceAdapter::commit(const data::Commit& commitIce, Time timeArrived)
     {
+        ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
         auto handleException = [](const std::string & what)
         {
@@ -141,6 +146,7 @@ namespace armarx::armem::server
     data::CommitResult
     MemoryToIceAdapter::commit(const data::Commit& commitIce)
     {
+        ARMARX_TRACE;
         return commit(commitIce, armem::Time::now());
     }
 
@@ -148,18 +154,21 @@ namespace armarx::armem::server
     armem::CommitResult
     MemoryToIceAdapter::commit(const armem::Commit& commit)
     {
+        ARMARX_TRACE;
         return this->_commit(commit, false);
     }
 
 
     armem::CommitResult MemoryToIceAdapter::commitLocking(const armem::Commit& commit)
     {
+        ARMARX_TRACE;
         return this->_commit(commit, true);
     }
 
 
     armem::CommitResult MemoryToIceAdapter::_commit(const armem::Commit& commit, bool locking)
     {
+        ARMARX_TRACE;
         std::vector<data::MemoryID> updatedIDs;
         const bool publishUpdates = bool(memoryListenerTopic);
 
@@ -179,7 +188,7 @@ namespace armarx::armem::server
 
                 // also store in ltm if transfermode is set to always
                 // TODO: Move outside of loop?
-                if (longtermMemory)
+                if (longtermMemoryManager)
                 {
 
                 }
@@ -226,6 +235,7 @@ namespace armarx::armem::server
     armem::query::data::Result
     MemoryToIceAdapter::query(const armem::query::data::Input& input)
     {
+        ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
 
         // Core segment processors will aquire the core segment locks.
@@ -234,25 +244,16 @@ namespace armarx::armem::server
         armem::wm::Memory wmResult = wmServerProcessor.process(input.memoryQueries, *workingMemory);
 
         query_proc::ltm::MemoryQueryProcessor ltmProcessor;
-        ltm::Memory ltmResult = ltmProcessor.process(input, *longtermMemory);
+        armem::wm::Memory ltmResult = ltmProcessor.process(input, longtermMemoryManager->getCacheAndLutNotConverted());
 
         armem::query::data::Result result;
         if (not ltmResult.empty())
         {
             ARMARX_INFO << "The LTM returned data after query";
 
-            // ATTENTION: This code block moves data from LTM back into WM.
-            // However, since some segments are constrained, the WM might send data back to LTM.
-            // This may also affect the data returned by the current query.
-            // However, this is expected behavior, since we copy the data in the processor (copyEmpty) we can safely return the copy and
-            // remove the original memory reference from WM here.
-            armem::wm::Memory ltmConverted = ltmResult.convert();
-            if (ltmConverted.empty())
-            {
-                ARMARX_ERROR << "A converted memory contains no data although the original memory contained data. This indicates that something is wrong.";
-            }
+            longtermMemoryManager->convert(ltmResult); // convert memory ==> meaning resolving lut references to e.g. mongodb
 
-            wmResult.append(ltmConverted);
+            wmResult.append(ltmResult);
             if (wmResult.empty())
             {
                 ARMARX_ERROR << "A merged Memory has no data although at least the LTM result contains data. This indicates that something is wrong.";
@@ -264,13 +265,13 @@ namespace armarx::armem::server
 
             query_proc::wm::MemoryQueryProcessor wm2wmProcessor(
                 input.withData ? armem::DataMode::WithData : armem::DataMode::NoData);
-            armem::wm::Memory merged_result = wm2wmProcessor.process(queryInput.toIce(), wmResult);
-            if (merged_result.empty())
+            armem::wm::Memory mergedResult = wm2wmProcessor.process(queryInput.toIce(), wmResult);
+            if (mergedResult.empty())
             {
                 ARMARX_ERROR << "A merged and postprocessed Memory has no data although at least the LTM result contains data. This indicates that something is wrong.";
             }
 
-            result.memory = toIce<data::MemoryPtr>(merged_result);
+            result.memory = toIce<data::MemoryPtr>(mergedResult);
 
             // also move results of ltm to wm
             //this->commit(toCommit(ltm_converted));
@@ -296,26 +297,19 @@ namespace armarx::armem::server
 
     client::QueryResult MemoryToIceAdapter::query(const client::QueryInput& input)
     {
+        ARMARX_TRACE;
         return client::QueryResult::fromIce(query(input.toIce()));
     }
 
 
     // LTM LOADING FROM LTM
-    query::data::Result MemoryToIceAdapter::load(const armem::query::data::Input& query)
-    {
-        ARMARX_CHECK_NOT_NULL(longtermMemory);
-        query::data::Result output;
-
-        output.success = true;
-        return output;
-    }
-
 
     // LTM STORING
     data::StoreResult MemoryToIceAdapter::store(const armem::data::StoreInput& input)
     {
+        ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
-        ARMARX_CHECK_NOT_NULL(longtermMemory);
+        ARMARX_CHECK_NOT_NULL(longtermMemoryManager);
         data::StoreResult output;
 
         for (const auto& query : input.query.memoryQueries)
@@ -332,14 +326,10 @@ namespace armarx::armem::server
         {
             armem::wm::Memory m;
             fromIce(queryResult.memory, m);
-            longtermMemory->append(m);
+            longtermMemoryManager->append(m);
         }
 
         return output;
     }
 
-
-
-
-
 }
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
index 6aa68b5714ad369e3b2bbad08d7c1ca06ab04bb8..f924399c7eb749f8404f28c1c2a9bd7945112a7c 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
@@ -4,7 +4,7 @@
 #include <RobotAPI/interface/armem/client/MemoryListenerInterface.h>
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
+#include <RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h>
 #include <RobotAPI/libraries/armem/client/Query.h>
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
@@ -24,7 +24,7 @@ namespace armarx::armem::server
 
         /// Construct an MemoryToIceAdapter from an existing Memory.
         MemoryToIceAdapter(server::wm::Memory* workingMemory = nullptr,
-                           ltm::Memory* longtermMemory = nullptr);
+                           server::ltm::mongodb::MemoryManager* longtermMemory = nullptr);
 
         void setMemoryListener(client::MemoryListenerInterfacePrx memoryListenerTopic);
 
@@ -48,7 +48,6 @@ namespace armarx::armem::server
         client::QueryResult query(const client::QueryInput& input);
 
         // LTM LOADING
-        query::data::Result load(const armem::query::data::Input& input);
 
         // LTM STORING
         data::StoreResult store(const armem::data::StoreInput& input);
@@ -56,7 +55,7 @@ namespace armarx::armem::server
     public:
 
         server::wm::Memory* workingMemory;
-        ltm::Memory* longtermMemory;
+        server::ltm::mongodb::MemoryManager* longtermMemoryManager;
 
         client::MemoryListenerInterfacePrx memoryListenerTopic;
 
diff --git a/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2e8c64d64121eccc007cad7ba2d55c2e361b94e2
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.cpp
@@ -0,0 +1,134 @@
+// Header
+#include "LongtermMemoryBase.h"
+
+// ArmarX
+#include <ArmarXCore/core/time/TimeUtil.h>
+#include <ArmarXCore/core/logging/Logging.h>
+
+
+namespace armarx::armem::server::ltm
+{
+    void LongtermMemoryBase::setName(const std::string& name)
+    {
+        cache.name() = name;
+        lut.name() = name;
+    }
+
+    armem::wm::Memory LongtermMemoryBase::getCacheAndLutNotConverted() const
+    {
+        std::lock_guard l(cache_mutex);
+        std::lock_guard l2(lut_mutex);
+
+        armem::wm::Memory m(lut.name());
+        m.append(cache);
+        m.append(lut);
+
+        // debug output
+        //lut.forEachSnapshot([](const auto & e)
+        //{
+        //    ARMARX_INFO << "The SNapshot: " << e.id().str() << " has size: " << e.size();
+        //});
+
+        return m;
+    }
+
+    void LongtermMemoryBase::append(const armem::wm::Memory& m)
+    {
+        TIMING_START(LTM_Append);
+        ARMARX_INFO << "Append memory with name '" << m.name() << "' into the LTM with name '" << cache.name() << "'";
+
+        std::lock_guard l(cache_mutex);
+        cache.append(m);
+
+        encodeAndStore();
+
+        TIMING_END(LTM_Append);
+    }
+
+    void LongtermMemoryBase::checkUpdateLatestSnapshot(const armem::wm::EntitySnapshot& newSnapshot)
+    {
+        // update map of latestSnapshots
+        if (auto it = latestSnapshots.find(newSnapshot.id().getEntityID().str()); it != latestSnapshots.end())
+        {
+            auto ptr = it->second;
+            if (ptr->id().timestamp > newSnapshot.id().timestamp)
+            {
+                ptr = &newSnapshot;
+            }
+            // else ignore ==> no update
+        }
+        else
+        {
+            // no entry yet
+            latestSnapshots.emplace(newSnapshot.id().getEntityID().str(), &newSnapshot);
+        }
+    }
+
+    bool LongtermMemoryBase::containsCoreSegment(const MemoryID& coreSegmentID) const
+    {
+        //ARMARX_INFO << "Check if lut has core seg";
+        if (lut.hasCoreSegment(coreSegmentID.coreSegmentName))
+        {
+            //ARMARX_INFO << "lus has core seg";
+            return true;
+        }
+        return false;
+    }
+
+    bool LongtermMemoryBase::containsProviderSegment(const MemoryID& providerSegmentID) const
+    {
+        //ARMARX_INFO << "Check if lut has prov seg";
+        if (lut.hasCoreSegment(providerSegmentID.coreSegmentName))
+        {
+            auto core = lut.getCoreSegment(providerSegmentID.coreSegmentName);
+            if (core.hasProviderSegment(providerSegmentID.providerSegmentName))
+            {
+                //ARMARX_INFO << "lus has prov seg";
+                return true;
+            }
+        }
+        return false;
+    }
+
+    bool LongtermMemoryBase::containsEntity(const MemoryID& entityID) const
+    {
+        //ARMARX_INFO << "Check if lut has entity";
+        if (lut.hasCoreSegment(entityID.coreSegmentName))
+        {
+            auto core = lut.getCoreSegment(entityID.coreSegmentName);
+            if (core.hasProviderSegment(entityID.providerSegmentName))
+            {
+                auto prov = core.getProviderSegment(entityID.providerSegmentName);
+                if (prov.hasEntity(entityID.entityName))
+                {
+                    //ARMARX_INFO << "lus has entity";
+                    return true;
+                }
+            }
+        }
+        return false;
+    }
+
+    bool LongtermMemoryBase::containsSnapshot(const MemoryID& snapshotID) const
+    {
+        //ARMARX_INFO << "Check if lut has snapshot";
+        if (lut.hasCoreSegment(snapshotID.coreSegmentName))
+        {
+            auto core = lut.getCoreSegment(snapshotID.coreSegmentName);
+            if (core.hasProviderSegment(snapshotID.providerSegmentName))
+            {
+                auto prov = core.getProviderSegment(snapshotID.providerSegmentName);
+                if (prov.hasEntity(snapshotID.entityName))
+                {
+                    auto entity = prov.getEntity(snapshotID.entityName);
+                    if (entity.hasSnapshot(snapshotID.timestamp))
+                    {
+                        //ARMARX_INFO << "lut has snapshot";
+                        return true;
+                    }
+                }
+            }
+        }
+        return false;
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.h b/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.h
new file mode 100644
index 0000000000000000000000000000000000000000..097f951548cc777fa03cedbc5f425e867439cd48
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.h
@@ -0,0 +1,65 @@
+#pragma once
+
+// STD / STL
+#include <optional>
+#include <mutex>
+
+// Memory
+#include "../../core/wm/memory_definitions.h"
+
+namespace armarx::armem::server::ltm
+{
+    /// @brief Interface functions for the longterm memory classes
+    class LongtermMemoryBase
+    {
+    public:
+        struct AppendResult
+        {
+            std::vector<MemoryID> addedCoreSegments;
+            std::vector<MemoryID> addedProviderSegments;
+            std::vector<MemoryID> addedEntities;
+
+            std::vector<MemoryID> addedSnapshots;
+            std::vector<MemoryID> replacedSnapshots;
+            std::vector<MemoryID> ignoredSnapshots;
+        };
+
+        struct ReloadResult
+        {
+
+        };
+
+        void append(const armem::wm::Memory&);
+
+        virtual void reload() = 0;
+        virtual void convert(armem::wm::Memory&) = 0;
+        virtual void encodeAndStore() = 0;
+
+        // pass through to internal memory
+        void setName(const std::string& name);
+
+        // get merged internal memory
+        armem::wm::Memory getCacheAndLutNotConverted() const;
+
+    protected:
+        void checkUpdateLatestSnapshot(const armem::wm::EntitySnapshot& newSnapshot);
+
+        bool containsCoreSegment(const MemoryID&) const;
+        bool containsProviderSegment(const MemoryID&) const;
+        bool containsEntity(const MemoryID&) const;
+        bool containsSnapshot(const MemoryID&) const;
+
+    protected:
+        /// Internal memory for data consolidated from wm to ltm (cache)
+        armem::wm::Memory cache;
+        mutable std::recursive_mutex cache_mutex;
+
+        /// Internal memory for indexes (lut)
+        armem::wm::Memory lut;
+        mutable std::recursive_mutex lut_mutex;
+
+        /// A map from entityID to its latest snapshot stored. When adding a new snapshot we compare it to the last one stored.
+        std::map<std::string, const armem::wm::EntitySnapshot*> latestSnapshots;
+
+    };
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d3a018d44acd587cd1c020127652c54a59a076e7
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.cpp
@@ -0,0 +1,401 @@
+// Header
+#include "MemoryManager.h"
+
+// STD / STL
+#include <iostream>
+#include <fstream>
+
+// Simox
+#include <SimoxUtility/json.h>
+
+// ArmarX
+#include <ArmarXCore/core/time/TimeUtil.h>
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+namespace
+{
+    // check whether a string is a number (timestamp folders)
+    bool isNumber(const std::string& s)
+    {
+        for (char const& ch : s)
+        {
+            if (std::isdigit(ch) == 0)
+            {
+                return false;
+            }
+        }
+        return true;
+    }
+}
+
+namespace armarx::armem::server::ltm::disk
+{
+    namespace fs = std::filesystem;
+
+    bool MemoryManager::checkPath() const
+    {
+        // Check connection:
+        ARMARX_INFO << "Checking Path";
+        if (!fs::exists(basePathToMemory) || !fs::is_directory(basePathToMemory) || basePathToMemory.filename() != lut.name())
+        {
+            ARMARX_WARNING << deactivateSpam("PathIsNotValid")
+                           << "The entered path is not valid. Please use a path leading to a memory folder with name: " << lut.name() << "."
+                           << "\n\n";
+            return false;
+        }
+
+        return true;
+    }
+
+    void MemoryManager::reload()
+    {
+        TIMING_START(LTM_Reload);
+        ARMARX_INFO << "(Re)Loading a memory from: " << basePathToMemory.string();
+
+        if (!checkPath())
+        {
+            // abort
+            ARMARX_WARNING << "Could not (pre)load a memory from the filesystem.";
+            return;
+        }
+
+        armem::wm::Memory temp(lut.id()); // a temporary client wm. We will append temp to the lut at the end of this metho (append ignores duplicate entries)
+        ARMARX_INFO << "Loading memory: " << temp.id().str();
+
+        // ///////////////////////////////
+        // Iterate over core segments
+        // ///////////////////////////////
+        for (const auto& d : std::filesystem::directory_iterator(basePathToMemory))
+            // Although this looks like code duplication, we need a distinguition between memories,
+            // core, prov and entities because of a different structure
+            // (only core and prov have same structure)
+        {
+
+            if (!d.is_directory())
+            {
+                continue;
+            }
+
+            std::string k = d.path().filename();
+            if (temp.hasCoreSegment(k))
+            {
+                throw error::ArMemError("Somehow the (memory) container already contains the key k = " + k + ". This should not happen.");
+            }
+
+            // ///////////////////////////////
+            // Add and iterate over core segments
+            // ///////////////////////////////
+            auto& cSeg = temp.addCoreSegment(k);
+            for (const auto& d : std::filesystem::directory_iterator(d))
+            {
+                if (!d.is_directory())
+                {
+                    continue;
+                }
+
+                std::string k = d.path().filename();
+                if (cSeg.hasProviderSegment(k))
+                {
+                    throw error::ArMemError("Somehow the (core) container already contains the key k = " + k + ". This should not happen.");
+                }
+
+                // ///////////////////////////////
+                // Add and iterate over provider segments
+                // ///////////////////////////////
+                auto& pSeg = cSeg.addProviderSegment(k);
+                for (const auto& d : std::filesystem::directory_iterator(d))
+                {
+                    if (!d.is_directory())
+                    {
+                        continue;
+                    }
+
+                    std::string k = d.path().filename();
+                    if (pSeg.hasEntity(k))
+                    {
+                        throw error::ArMemError("Somehow the (provider) container already contains the key k = " + k + ". This should not happen.");
+                    }
+
+                    // ///////////////////////////////
+                    // Add and iterate over entities
+                    // ///////////////////////////////
+                    auto& eSeg = pSeg.addEntity(k);
+                    for (const auto& d : std::filesystem::directory_iterator(d))
+                    {
+                        if (!d.is_directory())
+                        {
+                            continue;
+                        }
+
+                        std::string k = d.path().filename();
+                        if (!isNumber(k))
+                        {
+                            continue;
+                        }
+
+                        auto ts = armem::Time::microSeconds(std::stol(k));
+                        // TODO catch exceptions?
+
+                        if (eSeg.hasSnapshot(ts))
+                        {
+                            throw error::ArMemError("Somehow the (entity) container already contains the key k = " + k + ". This should not happen.");
+                        }
+
+                        // ///////////////////////////////
+                        // Add and iterate over entities
+                        // ///////////////////////////////
+                        auto& sSeg = eSeg.addSnapshot(ts);
+                        for (unsigned int i = 0; i < 10000; ++i) // ugly workaround to get the folders in the correct order
+                        {
+                            fs::path p = d / std::to_string(i);
+                            if (!fs::exists(p) || !fs::is_directory(p))
+                            {
+                                // early stopping
+                                break;
+                            }
+
+                            fs::path data = p / DATA_FILENAME;
+                            if (!fs::exists(data) || !fs::is_regular_file(data))
+                            {
+                                // do not set data
+                                continue;
+                            }
+
+                            // else we have an instance
+                            /*std::ifstream ifs(data);
+                            std::string file_content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>()));
+
+                            nlohmann::json j = nlohmann::json::parse(file_content);
+                            auto aron = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSON(j);*/
+
+                            sSeg.addInstance();
+                            //from_aron(aron, instance);
+                        }
+                    }
+                }
+            }
+        }
+
+        std::lock_guard l(cache_mutex); // we always take the cache mutex BEFORE the lut mutex! (otherwise we may have deadlocks)
+        std::lock_guard l2(lut_mutex);
+        lut.append(temp);
+        ARMARX_INFO << "After reload memory " << lut.id().str() << " has size: " << lut.size();
+
+        TIMING_END(LTM_Reload);
+    }
+
+    void MemoryManager::convert(armem::wm::Memory& m)
+    {
+        TIMING_START(LTM_Convert);
+        if (!checkPath())
+        {
+            // abort
+            ARMARX_WARNING << "Could not convert a memory from the filesystem.";
+            return;
+        }
+
+        // update emtpy data ptr
+        m.forEachCoreSegment([this](armem::wm::CoreSegment & e)
+        {
+            e.forEachProviderSegment([this](armem::wm::ProviderSegment & e)
+            {
+                e.forEachEntity([this](armem::wm::Entity & e)
+                {
+                    e.forEachSnapshot([this](armem::wm::EntitySnapshot & e)
+                    {
+                        // check whether data is nullptr
+                        bool allDataIsNull = e.size() > 0;
+                        e.forEachInstance([&allDataIsNull](armem::wm::EntityInstance & e)
+                        {
+                            if (e.data())
+                            {
+                                allDataIsNull = false;
+                                return false; // means break
+                            }
+                            return true;
+                        });
+
+                        if (allDataIsNull) // an entry from the lut (probably... for now we assume that every entry either has data (cache) or has null (lut))
+                        {
+                            // Get data from mongodb
+                            auto p = basePathToMemory / e.id().coreSegmentName / e.id().providerSegmentName / e.id().entityName / std::to_string(e.id().timestamp.toMicroSeconds());
+
+                            if (fs::exists(p) && fs::is_directory(p))
+                            {
+                                for (unsigned int i = 0; i < e.size(); ++i)
+                                {
+                                    auto data = p / std::to_string(i) / DATA_FILENAME;
+
+                                    if (fs::exists(data) && fs::is_regular_file(data))
+                                    {
+                                        auto& ins = e.getInstance(i);
+
+                                        std::ifstream ifs(data);
+                                        std::string file_content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>()));
+                                        nlohmann::json doc = nlohmann::json::parse(file_content);
+
+                                        auto aron = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSON(doc);
+
+                                        wm::EntityInstance tmp(e.id().withInstanceIndex(i));
+                                        from_aron(aron, tmp);
+
+                                        ins.data() = tmp.data();
+                                    }
+                                }
+                            }
+                            // else leave snapshot untouched
+                        }
+                    });
+                });
+            });
+        });
+        TIMING_END(LTM_Convert);
+    }
+
+    void MemoryManager::encodeAndStore()
+    {
+        TIMING_START(LTM_Encode);
+        if (!checkPath())
+        {
+            // abort
+            ARMARX_WARNING << "Could not (pre)load a memory from the filesystem.";
+            return;
+        }
+
+        std::lock_guard l(cache_mutex);
+
+        // ///////////////////////////////
+        // Iterate over core segments
+        // ///////////////////////////////
+        fs::path mPath = basePathToMemory;
+        cache.forEachCoreSegment([&mPath](armem::wm::CoreSegment & e)
+        {
+            fs::path cPath = mPath / e.id().coreSegmentName;
+            if (!fs::exists(cPath))
+            {
+                // not found
+                fs::create_directory(cPath);
+            }
+            if (!fs::is_directory(cPath))
+            {
+                throw error::ArMemError("Could not create the (core) folder: " + cPath.string());
+            }
+
+            // ///////////////////////////////
+            // Iterate over provider segments
+            // ///////////////////////////////
+            e.forEachProviderSegment([&cPath](armem::wm::ProviderSegment & e)
+            {
+                fs::path pPath = cPath / e.id().providerSegmentName;
+                if (!fs::exists(pPath))
+                {
+                    // not found
+                    fs::create_directory(pPath);
+                }
+                if (!fs::is_directory(pPath))
+                {
+                    throw error::ArMemError("Could not create the (provider) folder: " + pPath.string());
+                }
+
+                // ///////////////////////////////
+                // Iterate over entities
+                // ///////////////////////////////
+                e.forEachEntity([&pPath](armem::wm::Entity & e)
+                {
+                    fs::path ePath = pPath / e.id().entityName;
+                    if (!fs::exists(ePath))
+                    {
+                        // not found
+                        fs::create_directory(ePath);
+                    }
+                    if (!fs::is_directory(ePath))
+                    {
+                        throw error::ArMemError("Could not create the (entity) folder: " + ePath.string());
+                    }
+
+                    // ///////////////////////////////
+                    // Iterate over snapshots
+                    // ///////////////////////////////
+                    e.forEachSnapshot([&ePath](armem::wm::EntitySnapshot & e)
+                    {
+                        fs::path sPath = ePath / std::to_string(e.id().timestamp.toMicroSeconds());
+                        if (!fs::exists(sPath))
+                        {
+                            // not found
+                            fs::create_directory(sPath);
+                        }
+                        else
+                        {
+                            ARMARX_INFO << "The snapshot " << sPath.string() << " already exists. Ingoring it.";
+                            return; // continue if already exists
+                        }
+
+                        if (!fs::is_directory(sPath))
+                        {
+                            throw error::ArMemError("Could not create the (timestamp) folder: " + sPath.string());
+                        }
+
+                        // ///////////////////////////////
+                        // Iterate over instances
+                        // ///////////////////////////////
+                        e.forEachInstance([&sPath](armem::wm::EntityInstance & e)
+                        {
+                            fs::path iPath = sPath / std::to_string(e.id().instanceIndex);
+                            if (!fs::exists(iPath))
+                            {
+                                // not found
+                                fs::create_directory(iPath);
+                            }
+                            else
+                            {
+                                // This is strange, since we know, that the snapshot folder did not exist.
+                                // However, we ignore and continue
+                                ARMARX_INFO << "Somehow the instance folder " << iPath.string() << " already exists, although the snapshot folder was newly created. Ignore this.";
+                                return;
+                            }
+                            if (!fs::is_directory(iPath))
+                            {
+                                throw error::ArMemError("Could not create the (instance) folder: " + iPath.string());
+                            }
+
+                            fs::path data = iPath / DATA_FILENAME;
+                            if (fs::exists(data))
+                            {
+                                // Should not be the case. Anyway, if it happens, create new file!
+                                fs::remove(data);
+                            }
+
+                            std::ofstream ofs;
+                            ofs.open(data);
+
+                            auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
+                            to_aron(aron, e);
+                            nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(aron);
+
+                            ofs << j.dump(2);
+                            ofs.close();
+                        });
+                    });
+                });
+            });
+
+        });
+
+        // what to do with clear text data after encoding?
+        // TODO!
+
+        // Finaly clear cache and put reference to lut
+        cache.forEachInstance([](armem::wm::EntityInstance & i)
+        {
+            i.data() = nullptr;
+        });
+
+        std::lock_guard l2(lut_mutex);
+        lut.append(cache);
+        cache.clear();
+
+        TIMING_END(LTM_Encode);
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.h b/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.h
new file mode 100644
index 0000000000000000000000000000000000000000..227d419119e3889006a3f0f30a4789e3b9e76dfe
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.h
@@ -0,0 +1,44 @@
+#pragma once
+
+// STD / STL
+#include <mutex>
+#include <optional>
+#include <filesystem>
+
+// Base Class
+#include "../LongtermMemoryBase.h"
+
+namespace armarx::armem::server::ltm::disk
+{
+    /// @brief A memory storing data in mongodb (needs 'armarx memory start' to start the mongod instance)
+    class MemoryManager :
+        public LongtermMemoryBase
+    {
+        using Base = LongtermMemoryBase;
+
+    public:
+        MemoryManager() = default;
+
+        void reload() override;
+        void convert(armem::wm::Memory&) override;
+        void encodeAndStore() override;
+
+        void setBasePath(const std::filesystem::path& p)
+        {
+            basePathToMemory = p;
+        }
+
+    protected:
+
+
+    private:
+        bool checkPath() const;
+
+    public:
+        std::filesystem::path basePathToMemory;
+
+    private:
+        static const constexpr char* TYPE_FILENAME = "type.aron.ltm.json";
+        static const constexpr char* DATA_FILENAME = "data.aron.ltm.json";
+    };
+}
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp b/source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.cpp
similarity index 51%
rename from source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.cpp
index fd2bbbb6ccb8aee93c4d343b818dc55872f7838a..ad2d95b0fed35991ae99e050a9939537a840a2a2 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.cpp
@@ -1,13 +1,15 @@
-#include "MongoDBConnectionManager.h"
+#include "ConnectionManager.h"
 
-namespace armarx::armem::ltm
+namespace armarx::armem::server::ltm::mongodb
 {
-    bool MongoDBConnectionManager::initialized = false;
-    std::map<std::string, mongocxx::client> MongoDBConnectionManager::Connections = {};
+    std::mutex ConnectionManager::initializationMutex;
+    bool ConnectionManager::initialized = false;
+    std::map<std::string, std::unique_ptr<mongocxx::pool>> ConnectionManager::Connections = {};
 
 
-    void MongoDBConnectionManager::initialize_if()
+    void ConnectionManager::initialize_if()
     {
+        std::lock_guard l(initializationMutex); // all others have to wait until the initialization is complete
         if (!initialized)
         {
             initialized = true;
@@ -15,7 +17,7 @@ namespace armarx::armem::ltm
         }
     }
 
-    mongocxx::client& MongoDBConnectionManager::EstablishConnection(const MongoDBSettings& settings)
+    mongocxx::pool& ConnectionManager::Connect(const MongoDBSettings& settings)
     {
         initialize_if();
 
@@ -24,36 +26,36 @@ namespace armarx::armem::ltm
         if (it == Connections.end())
         {
             mongocxx::uri uri(uri_str);
-            auto con = Connections.emplace(uri_str, mongocxx::client(uri));
-            return con.first->second;
+            auto pool = std::make_unique<mongocxx::pool>(uri);
+            auto con = Connections.emplace(settings.key(), std::move(pool));
+            return *con.first->second;
         }
         else
         {
             // A connection already exists. We do not need to open another one.
-            return it->second;
+            return *it->second;
         }
     }
 
-    bool MongoDBConnectionManager::ConnectionIsValid(const MongoDBSettings& settings, bool force)
+    bool ConnectionManager::ConnectionIsValid(const MongoDBSettings& settings, bool forceNewConnection)
     {
         initialize_if();
 
         try
         {
-            if (!force)
+            if (!forceNewConnection)
             {
-                const auto uri_str = settings.uri();
-                auto it = Connections.find(uri_str);
+                auto it = Connections.find(settings.key());
                 if (it != Connections.end())
                 {
-                    auto admin = it->second["admin"];
+                    auto client = it->second->acquire();
+                    auto admin = client->database("admin");
                     auto result = admin.run_command(bsoncxx::builder::basic::make_document(bsoncxx::builder::basic::kvp("isMaster", 1)));
                     return true;
                 }
             }
 
-            const auto uri_str = settings.uri();
-            mongocxx::uri uri(uri_str);
+            mongocxx::uri uri(settings.uri());
             auto client = mongocxx::client(uri);
             auto admin = client["admin"];
             auto result = admin.run_command(bsoncxx::builder::basic::make_document(bsoncxx::builder::basic::kvp("isMaster", 1)));
@@ -65,12 +67,11 @@ namespace armarx::armem::ltm
         }
     }
 
-    bool MongoDBConnectionManager::ConnectionExists(const MongoDBSettings& settings)
+    bool ConnectionManager::ConnectionExists(const MongoDBSettings& settings)
     {
         initialize_if();
 
-        const auto uri_str = settings.uri();
-        auto it = Connections.find(uri_str);
+        auto it = Connections.find(settings.key());
         return it != Connections.end();
     }
 }
diff --git a/source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.h b/source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.h
new file mode 100644
index 0000000000000000000000000000000000000000..15fac008d7963c034ce40fe55a4606ffe3fead3f
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/mongodb/ConnectionManager.h
@@ -0,0 +1,97 @@
+#pragma once
+
+#include <string>
+#include <mutex>
+#include <map>
+#include <memory>
+#include <sstream>
+
+#include <bsoncxx/json.hpp>
+#include <mongocxx/client.hpp>
+#include <mongocxx/pool.hpp>
+#include <mongocxx/stdx.hpp>
+#include <mongocxx/uri.hpp>
+#include <mongocxx/instance.hpp>
+#include <bsoncxx/builder/stream/helpers.hpp>
+#include <bsoncxx/builder/stream/document.hpp>
+#include <bsoncxx/builder/stream/array.hpp>
+
+
+namespace armarx::armem::server::ltm::mongodb
+{
+
+    using PoolClientPtr = mongocxx::pool::entry;
+
+    /**
+     * @brief A manager of multiple mongodb connection
+     */
+    class ConnectionManager
+    {
+    public:
+        struct MongoDBSettings
+        {
+            std::string host = "localhost";
+            unsigned int port = 25276;
+            std::string user = "";
+            std::string password = "";
+            std::string database = "Test";
+            int minPoolSize = 5;
+            int maxPoolSize = 100;
+
+
+            bool isSet() const
+            {
+                // we always need a host and a port
+                return !host.empty() and port != 0;
+            }
+
+            std::string baseUri() const
+            {
+                std::stringstream ss;
+                ss << "mongodb://";
+
+                if (!user.empty())
+                {
+                    ss << user;
+                    if (!password.empty())
+                    {
+                        ss << ":" << password;
+                    }
+                    ss << "@";
+                }
+                ss << host;
+                return ss.str();
+            }
+
+            std::string key() const
+            {
+                // TODO: What happens if a connection exists and you would like to open another one with a different user (e.g. that sees different things)?
+                return "mongodb://" + host + ":" + std::to_string(port);
+            }
+
+            std::string uri() const
+            {
+                return baseUri() + ":" + std::to_string(port) + "/?minPoolSize=" + std::to_string(minPoolSize) + "&maxPoolSize=" + std::to_string(maxPoolSize);
+            }
+
+            std::string toString() const
+            {
+                return uri() + "&database=" + database;
+            }
+        };
+
+        static mongocxx::pool& Connect(const MongoDBSettings& settings);
+        static bool ConnectionIsValid(const MongoDBSettings& settings, bool forceNewConnection = false);
+        static bool ConnectionExists(const MongoDBSettings& settings);
+
+    private:
+        static void initialize_if();
+
+
+    private:
+        static std::mutex initializationMutex;
+        static bool initialized;
+        static std::map<std::string, std::unique_ptr<mongocxx::pool>> Connections;
+
+    };
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.cpp b/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..6419584d4a1bd0e870a4dc48ff703c938c0a7789
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.cpp
@@ -0,0 +1,424 @@
+// Header
+#include "MemoryManager.h"
+
+// Simox
+#include <SimoxUtility/json.h>
+
+// ArmarX
+#include <ArmarXCore/core/time/TimeUtil.h>
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+
+namespace armarx::armem::server::ltm::mongodb
+{
+    namespace bsoncxxbuilder = bsoncxx::builder::stream;
+    namespace bsoncxxdoc = bsoncxx::document;
+
+    PoolClientPtr MemoryManager::checkConnection() const
+    {
+        // Check connection:
+        ARMARX_INFO << "Checking connection";
+        if (!ConnectionManager::ConnectionIsValid(dbsettings))
+        {
+            ARMARX_WARNING << deactivateSpam("ConnectionIsNotValid")
+                           << "The connection to mongocxx for ltm '" << cache.name() << "' is not valid. Settings are: " << dbsettings.toString()
+                           << "\nTo start it, run e.g.: \n"
+                           << "armarx memory start"
+                           << "\n\n";
+            return nullptr;
+        }
+
+        auto& pool = ConnectionManager::Connect(dbsettings);
+        auto client = pool.acquire();
+
+        return client;
+    }
+
+    void MemoryManager::reload()
+    {
+        TIMING_START(LTM_Reload);
+        ARMARX_INFO << "(Re)Establishing connection to: " << dbsettings.toString();
+
+        auto client = checkConnection();
+        if (!client)
+        {
+            // abort
+            ARMARX_WARNING << "A connection to: " << dbsettings.toString() << " is not possible. Could not (pre)load data from mongodb.";
+            return;
+        }
+
+        auto databases = client->list_databases();
+        for (const auto& doc : databases)
+        {
+            auto el = doc["name"];
+            ARMARX_INFO << "Found Memory-Collection in MongoDB: " << el.get_utf8().value;
+        }
+
+        armem::wm::Memory temp(lut.id()); // a temporary client wm. We will append temp to the lut at the end of this metho (append ignores duplicate entries)
+        mongocxx::database db = client->database(dbsettings.database);
+
+        ARMARX_INFO << "Loading memory: " << temp.id().str();
+
+        // ///////////////////////////////
+        // Iterate over core segments
+        // ///////////////////////////////
+        mongocxx::collection mColl = db.collection(temp.id().str());
+        mongocxx::cursor cursor = mColl.find({});
+        for (const auto& doc : cursor)  // Although this looks like code duplication, we need a distinguition between memories,
+            // core, prov and entities because of a different structure
+            // (only core and prov have same structure)
+        {
+            auto el = doc[MONGO_FOREIGN_KEY];
+            auto foreignKey = el.get_utf8().value;
+
+            MemoryID i((std::string) foreignKey);
+            if (i.memoryName != temp.id().memoryName)
+            {
+                throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong memory name: " + i.str());
+            }
+
+            std::string k = i.coreSegmentName;
+
+            if (temp.hasCoreSegment(k))
+            {
+                throw error::ArMemError("Somehow the (memory) container already contains the key k = " + k + ". Do you have double entries in mongodb?");
+            }
+            else
+            {
+                // ///////////////////////////////
+                // Add and iterate over provider segments
+                // ///////////////////////////////
+                auto& cSeg = temp.addCoreSegment(k);
+                mongocxx::collection cColl = db.collection(cSeg.id().str());
+                mongocxx::cursor cursor = cColl.find({});
+                for (const auto& doc : cursor)
+                {
+                    auto el = doc[MONGO_FOREIGN_KEY];
+                    auto foreignKey = el.get_utf8().value;
+
+                    MemoryID i((std::string) foreignKey);
+                    if (i.coreSegmentName != cSeg.id().coreSegmentName || i.memoryName != cSeg.id().memoryName)
+                    {
+                        throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong memory name: " + i.str());
+                    }
+
+                    std::string k = i.providerSegmentName;
+                    if (cSeg.hasProviderSegment(k))
+                    {
+                        throw error::ArMemError("Somehow the (core segment) container already contains the key k = " + k + ". Do you have double entries in mongodb?");
+                    }
+                    else
+                    {
+                        // ///////////////////////////////
+                        // Add and iterate over entities
+                        // ///////////////////////////////
+                        auto& pSeg = cSeg.addProviderSegment(k);
+                        mongocxx::collection pColl = db.collection(pSeg.id().str());
+                        mongocxx::cursor cursor = pColl.find({});
+                        for (const auto& doc : cursor)
+                        {
+                            auto el = doc[MONGO_FOREIGN_KEY];
+                            auto foreignKey = el.get_utf8().value;
+
+                            MemoryID i((std::string) foreignKey);
+                            if (i.providerSegmentName != pSeg.id().providerSegmentName || i.coreSegmentName != pSeg.id().coreSegmentName || i.memoryName != pSeg.id().memoryName)
+                            {
+                                throw error::InvalidMemoryID(i, "A MemoryID in mongodb was invalid. Found the wrong memory name: " + i.str());
+                            }
+
+                            std::string k = i.entityName;
+                            if (pSeg.hasEntity(k))
+                            {
+                                throw error::ArMemError("Somehow the (provider segment) container already contains the key k = " + k + ". Do you have double entries in mongodb?");
+                            }
+                            else
+                            {
+                                // ///////////////////////////////
+                                // Add and iterate over snapshots
+                                // ///////////////////////////////
+                                auto& eSeg = pSeg.addEntity(k);
+                                mongocxx::collection eColl = db.collection(eSeg.id().str());
+                                mongocxx::cursor cursor = eColl.find({});
+                                for (const auto& doc : cursor)
+                                {
+                                    auto ts = armem::Time::microSeconds(doc[MONGO_TIMESTAMP].get_int64().value);
+                                    auto& newSnapshot = eSeg.addSnapshot(ts);
+
+                                    auto i = doc[MONGO_INSTANCES];
+                                    unsigned long length = std::distance(i.get_array().value.begin(), i.get_array().value.end());
+                                    ARMARX_INFO << "The array legth for an snapshot '" << newSnapshot.id().str() << "' is: " << length;
+
+                                    for (unsigned long i = 0; i < length; ++i)
+                                    {
+                                        // add an empty instance as reference
+                                        newSnapshot.addInstance({});
+                                    }
+
+
+                                    // check to update lastSnapshot map
+                                    checkUpdateLatestSnapshot(newSnapshot);
+                                }
+                            }
+                        }
+                    }
+                }
+            }
+        }
+
+        std::lock_guard l(cache_mutex); // we always take the cache mutex BEFORE the lut mutex! (otherwise we may have deadlocks)
+        std::lock_guard l2(lut_mutex);
+        lut.append(temp);
+        ARMARX_INFO << "After reload memory " << lut.id().str() << " has size: " << lut.size();
+
+        TIMING_END(LTM_Reload);
+    }
+
+    void MemoryManager::convert(armem::wm::Memory& m)
+    {
+        TIMING_START(LTM_Convert);
+
+        auto client = checkConnection();
+        if (!client)
+        {
+            // abort
+            ARMARX_WARNING << "A connection to: " << dbsettings.toString() << " is not possible. Could not convert information, therefore returning leaving input untouched.";
+            return;
+        }
+        mongocxx::database db = client->database(dbsettings.database);
+
+        // update emtpy data ptr
+        m.forEachCoreSegment([&db](armem::wm::CoreSegment & e)
+        {
+            e.forEachProviderSegment([&db](armem::wm::ProviderSegment & e)
+            {
+                e.forEachEntity([&db](armem::wm::Entity & e)
+                {
+                    e.forEachSnapshot([&db](armem::wm::EntitySnapshot & e)
+                    {
+                        // check whether data is nullptr
+                        bool allDataIsNull = e.size() > 0;
+                        e.forEachInstance([&allDataIsNull](armem::wm::EntityInstance & e)
+                        {
+                            if (e.data())
+                            {
+                                allDataIsNull = false;
+                                return false; // means break
+                            }
+                            return true;
+                        });
+
+                        if (allDataIsNull) // an entry from the lut (probably... for now we assume that every entry either has data (cache) or has null (lut))
+                        {
+                            // Get data from mongodb
+                            auto eColl = db.collection(e.id().getEntityID().str());
+                            auto q = bsoncxxbuilder::document{} << std::string(MONGO_TIMESTAMP) << e.id().timestamp.toMicroSeconds() << bsoncxxbuilder::finalize;
+                            auto res = eColl.find_one(q.view());
+
+                            if (!res)
+                            {
+                                throw error::ArMemError("Could not load an instance from the memory '" + e.id().getEntityID().str() + "'. Tried to access: " + e.id().getEntitySnapshotID().str());
+                            }
+
+                            // convert full json of this entry
+                            nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(*res));
+                            nlohmann::json instances = json[MONGO_INSTANCES];
+
+                            if (instances.size() != e.size())
+                            {
+                                throw error::ArMemError("The size of the mongodb entity entry at id " + e.id().getEntitySnapshotID().str() + " has wrong size. Expected: " + std::to_string(e.size()) + " but got: " + std::to_string(instances.size()));
+                            }
+
+                            for (unsigned int i = 0; i < e.size(); ++i)
+                            {
+                                auto& ins = e.getInstance(i);
+
+                                // get ionstance json
+                                nlohmann::json doc = instances[i];
+                                auto aron = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSON(doc);
+
+                                // remove metadata
+                                wm::EntityInstance tmp(e.id().withInstanceIndex(i));
+                                from_aron(aron, tmp);
+
+                                // set data
+                                ins.data() = tmp.data();
+                            }
+                        }
+                    });
+                });
+            });
+        });
+        TIMING_END(LTM_Convert);
+    }
+
+    void MemoryManager::encodeAndStore()
+    {
+        TIMING_START(LTM_Encode);
+        ARMARX_INFO << "Encode cache " << cache.id().str() << " with size: " << cache.size();
+
+        auto client = checkConnection();
+        if (!client)
+        {
+            // abort
+            ARMARX_WARNING << "A connection to: " << dbsettings.toString() << " is not possible. Could not consolidate data from cache to mongodb.";
+            return;
+        }
+
+        std::lock_guard l(cache_mutex);
+        mongocxx::database db = client->database(dbsettings.database);
+        auto mColl = db.collection(cache.id().str());
+
+        // ///////////////////////////////
+        // Iterate over core segments
+        // ///////////////////////////////
+        cache.forEachCoreSegment([this, &db, &mColl](armem::wm::CoreSegment & e)
+        {
+            auto cColl = db.collection(e.id().str());
+
+            if (!containsCoreSegment(mColl, e.id()))
+            {
+                // not found
+                mongodbInsertForeignKey(mColl, e.id().str());
+            }
+
+            // ///////////////////////////////
+            // Iterate over provider segments
+            // ///////////////////////////////
+            e.forEachProviderSegment([this, &db, &cColl](armem::wm::ProviderSegment & e)
+            {
+                auto pColl = db.collection(e.id().str());
+
+                if (!containsProviderSegment(cColl, e.id()))
+                {
+                    // not found
+                    mongodbInsertForeignKey(cColl, e.id().str());
+                }
+
+                // ///////////////////////////////
+                // Iterate over each segments
+                // ///////////////////////////////
+                e.forEachEntity([this, &db, &pColl](armem::wm::Entity & e)
+                {
+                    auto eColl = db.collection(e.id().str());
+
+                    if (!containsEntity(pColl, e.id()))
+                    {
+                        // not found
+                        mongodbInsertForeignKey(pColl, e.id().str());
+                    }
+
+                    // ///////////////////////////////
+                    // Iterate over snapshots
+                    // ///////////////////////////////
+                    e.forEachSnapshot([this, &eColl](armem::wm::EntitySnapshot & e)
+                    {
+                        if (!this->containsSnapshot(eColl, e.id()))
+                        {
+                            // timestamp not found in mongodb ==> new entry
+                            bsoncxxbuilder::document builder{};
+                            auto in_array = builder
+                                            << std::string(MONGO_ID) << e.id().str()
+                                            << std::string(MONGO_TIMESTAMP) << e.id().timestamp.toMicroSeconds()
+                                            << std::string(MONGO_INSTANCES);
+                            auto array_builder = bsoncxx::builder::basic::array{};
+
+                            e.forEachInstance([&array_builder](const wm::EntityInstance & e)
+                            {
+                                auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
+                                to_aron(aron, e);
+                                nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(aron);
+
+                                auto doc_value = bsoncxx::from_json(j.dump(2));
+                                array_builder.append(doc_value);
+                            });
+
+                            auto after_array = in_array << array_builder;
+                            bsoncxx::document::value doc = after_array << bsoncxx::builder::stream::finalize;
+                            ARMARX_INFO << "Insert into mongodb: " << e.id().timestamp.toMicroSeconds();
+                            eColl.insert_one(doc.view());
+
+                            // check to update lastSnapshot map
+                            checkUpdateLatestSnapshot(e);
+                        }
+                        else
+                        {
+                            ARMARX_INFO << "Timestamp already found for id: " << e.id().str();
+                            // timestamp already in mongodb. Ignore it
+                        }
+                    });
+                });
+            });
+        });
+
+        // what to do with clear text data after encoding?
+        // TODO!
+
+        // Finaly clear cache and put reference to lut
+        cache.forEachInstance([](armem::wm::EntityInstance & i)
+        {
+            i.data() = nullptr;
+        });
+
+        std::lock_guard l2(lut_mutex);
+        lut.append(cache);
+        cache.clear();
+
+        TIMING_END(LTM_Encode);
+    }
+
+    void MemoryManager::mongodbInsertForeignKey(mongocxx::collection& coll, const std::string& key)
+    {
+        auto q = bsoncxxbuilder::document{} << std::string(MONGO_FOREIGN_KEY) << key << bsoncxxbuilder::finalize;
+        coll.insert_one(q.view());
+    }
+
+    bool MemoryManager::mongodbContainsForeignKey(mongocxx::collection& coll, const std::string& key) const
+    {
+        // check mongodb
+        auto q = bsoncxxbuilder::document{} << std::string(MONGO_FOREIGN_KEY) << key << bsoncxxbuilder::finalize;
+        auto res = coll.find_one(q.view());
+        return (bool) res;
+    }
+
+    bool MemoryManager::containsCoreSegment(mongocxx::collection& mColl, const MemoryID& coreSegmentID) const
+    {
+        if (Base::containsCoreSegment(coreSegmentID))
+        {
+            return true;
+        }
+        return mongodbContainsForeignKey(mColl, coreSegmentID.str());
+    }
+
+    bool MemoryManager::containsProviderSegment(mongocxx::collection& cColl, const MemoryID& providerSegmentID) const
+    {
+        if (Base::containsProviderSegment(providerSegmentID))
+        {
+            return true;
+        }
+        return mongodbContainsForeignKey(cColl, providerSegmentID.str());
+    }
+
+    bool MemoryManager::containsEntity(mongocxx::collection& pColl, const MemoryID& entityID) const
+    {
+        if (Base::containsEntity(entityID))
+        {
+            return true;
+        }
+        return mongodbContainsForeignKey(pColl, entityID.str());
+    }
+
+    bool MemoryManager::containsSnapshot(mongocxx::collection& eColl, const MemoryID& snapshotID) const
+    {
+        if (Base::containsSnapshot(snapshotID))
+        {
+            return true;
+        }
+
+        // check mongodb
+        auto q = bsoncxxbuilder::document{} << std::string(MONGO_TIMESTAMP) << snapshotID.timestamp.toMicroSeconds() << bsoncxxbuilder::finalize;
+        auto res = eColl.find_one(q.view());
+        return (bool) res;
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h b/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h
new file mode 100644
index 0000000000000000000000000000000000000000..189ccc42563d17dd63116dc3210d99d648b28c31
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h
@@ -0,0 +1,51 @@
+#pragma once
+
+// STD / STL
+#include <mutex>
+#include <optional>
+
+// Base Class
+#include "../LongtermMemoryBase.h"
+
+// Data
+# include "ConnectionManager.h"
+
+namespace armarx::armem::server::ltm::mongodb
+{
+    /// @brief A memory storing data in mongodb (needs 'armarx memory start' to start the mongod instance)
+    class MemoryManager :
+        public LongtermMemoryBase
+    {
+        using Base = LongtermMemoryBase;
+
+    public:
+        MemoryManager() = default;
+
+        void reload() override;
+        void convert(armem::wm::Memory&) override;
+        void encodeAndStore() override;
+
+    protected:
+
+
+    private:
+        PoolClientPtr checkConnection() const; // return nullptr if not possible
+
+        void mongodbInsertForeignKey(mongocxx::collection&, const std::string& key);
+
+        bool mongodbContainsForeignKey(mongocxx::collection&, const std::string& key) const;
+        bool containsCoreSegment(mongocxx::collection&, const MemoryID&) const;
+        bool containsProviderSegment(mongocxx::collection&, const MemoryID&) const;
+        bool containsEntity(mongocxx::collection&, const MemoryID&) const;
+        bool containsSnapshot(mongocxx::collection&, const MemoryID&) const;
+
+    public:
+        ConnectionManager::MongoDBSettings dbsettings;
+
+    private:
+        static const constexpr char* MONGO_FOREIGN_KEY = "foreign_key";
+        static const constexpr char* MONGO_ID = "id";
+        static const constexpr char* MONGO_TIMESTAMP = "timestamp";
+        static const constexpr char* MONGO_INSTANCES = "instances";
+    };
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h
index 3050e6e4e91a90bfbfa97feff7f3afc6cb804f41..0c6199eac95465a27da8bc0d59b4fcd40607d139 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h
@@ -1,14 +1,11 @@
 #pragma once
 
-#include <regex>
-
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include "BaseQueryProcessorBase.h"
 
-#include <RobotAPI/interface/armem/query.h>
 #include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/interface/armem/query.h>
 
-#include "BaseQueryProcessorBase.h"
+#include <regex>
 
 
 namespace armarx::armem::server::query_proc::base
@@ -74,7 +71,7 @@ namespace armarx::armem::server::query_proc::base
         {
             coreSegment.forEachProviderSegment([this, &query, &result](const ProviderSegmentT & providerSegment)
             {
-                childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
+                this->_processResult(result, providerSegment, query);
             });
         }
 
@@ -82,14 +79,10 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::core::Single& query,
                      const CoreSegmentT& coreSegment) const
         {
-            try
+            const ProviderSegmentT* providerSegment = coreSegment.findProviderSegment(query.providerSegmentName);
+            if (providerSegment)
             {
-                const ProviderSegmentT& providerSegment = coreSegment.getProviderSegment(query.providerSegmentName);
-                childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
-            }
-            catch (const error::MissingEntry&)
-            {
-                // Leave empty.
+                this->_processResult(result, *providerSegment, query);
             }
         }
 
@@ -97,18 +90,29 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::core::Regex& query,
                      const CoreSegmentT& coreSegment) const
         {
-            std::regex regex(query.providerSegmentNameRegex);
+            const std::regex regex(query.providerSegmentNameRegex);
             coreSegment.forEachProviderSegment(
                 [this, &result, &query, &regex](const ProviderSegmentT & providerSegment)
             {
                 if (std::regex_search(providerSegment.name(), regex))
                 {
-                    childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
+                    this->_processResult(result, providerSegment, query);
                 }
             });
         }
 
 
+    private:
+
+        void _processResult(ResultCoreSegmentT& result,
+                            const ProviderSegmentT& providerSegment,
+                            const armem::query::data::CoreSegmentQuery& query) const
+        {
+            ResultProviderSegmentT& added = result.addProviderSegment(providerSegment.name(), providerSegment.aronType());
+            childProcessor.process(added, query.providerSegmentQueries, providerSegment);
+        }
+
+
     protected:
 
         ChildProcessorT childProcessor;
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.cpp b/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.cpp
index 5cbac85a8dc5f8899e7c72434516063121a2b4c1..d9df528842d11fd66ba38877318785d6c4dd5263 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.cpp
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.cpp
@@ -1 +1,12 @@
 #include "EntityQueryProcessorBase.h"
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+
+namespace armarx::armem::server::query_proc::base
+{
+    void detail::checkReferenceTimestampNonNegative(const Time& timestamp)
+    {
+        ARMARX_CHECK_NONNEGATIVE(timestamp.toMicroSeconds()) << "Reference timestamp must be non-negative.";
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h
index 0c4a842fa2772ae18b475b9e28ad3b13077bb49d..b0210c37e4ed71b64875a79453e56d928852b54f 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h
@@ -8,13 +8,14 @@
 
 #include <RobotAPI/interface/armem/query.h>
 
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-#include <ArmarXCore/core/logging/Logging.h>
-
 #include <cstdint>
 #include <iterator>
 
 
+namespace armarx::armem::server::query_proc::base::detail
+{
+    void checkReferenceTimestampNonNegative(const Time& timestamp);
+}
 namespace armarx::armem::server::query_proc::base
 {
 
@@ -93,43 +94,33 @@ namespace armarx::armem::server::query_proc::base
         {
             if (query.timestamp < 0)
             {
-                try
+                if (const ResultSnapshotT* snapshot = entity.findLatestSnapshot())
                 {
-                    addResultSnapshot(result, entity.getLatestSnapshot());
-                }
-                catch (const armem::error::EntityHistoryEmpty&)
-                {
-                    if (false)
-                    {
-                        ARMARX_IMPORTANT << "Failed to retrieve latest snapshot from entity " << entity.id() << ". "
-                                         << "Entity has not timestamps.";
-                    }
+                    addResultSnapshot(result, *snapshot);
                 }
             }
             else
             {
                 const Time time = fromIce<Time>(query.timestamp);
-                try
+                if (const ResultSnapshotT* snapshot = entity.findSnapshot(time))
                 {
-                    auto snapshot = entity.getSnapshot(time);
-                    addResultSnapshot(result, snapshot);
+                    addResultSnapshot(result, *snapshot);
                 }
-                catch (const armem::error::MissingEntry&)
+                else
                 {
                     // Leave empty.
-                    if (false)
+#if 0
+                    std::stringstream ss;
+                    ss << "Failed to retrieve snapshot with timestamp "
+                       << armem::toDateTimeMilliSeconds(time)
+                       << " from entity " << entity.id() << ".\n"
+                       << "Entity has timestamps: ";
+                    for (const Time& t : entity.getTimestamps())
                     {
-                        std::stringstream ss;
-                        ss << "Failed to retrieve snapshot with timestamp "
-                           << armem::toDateTimeMilliSeconds(time)
-                           << " from entity " << entity.id() << ".\n"
-                           << "Entity has timestamps: ";
-                        for (const Time& t : entity.getTimestamps())
-                        {
-                            ss << "\n- " << armem::toDateTimeMilliSeconds(t);
-                        }
-                        ARMARX_IMPORTANT << ss.str();
+                        ss << "\n- " << armem::toDateTimeMilliSeconds(t);
                     }
+                    ARMARX_IMPORTANT << ss.str();
+#endif
                 }
             }
         }
@@ -181,17 +172,12 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::entity::BeforeOrAtTime& query,
                      const EntityT& entity) const
         {
-            const auto referenceTimestamp = fromIce<Time>(query.timestamp);
-            ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp is negative!";
+            const Time referenceTimestamp = fromIce<Time>(query.timestamp);
+            detail::checkReferenceTimestampNonNegative(referenceTimestamp);
 
-            try
+            if (auto* beforeOrAt = entity.findLatestSnapshotBeforeOrAt(referenceTimestamp))
             {
-                auto beforeOrAt = entity.getLatestSnapshotBeforeOrAt(referenceTimestamp);
-                addResultSnapshot(result, beforeOrAt);
-            }
-            catch (const armem::error::MissingEntry&)
-            {
-                // Leave empty.
+                addResultSnapshot(result, *beforeOrAt);
             }
         }
 
@@ -200,8 +186,8 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::entity::BeforeTime& query,
                      const EntityT& entity) const
         {
-            const armem::Time referenceTimestamp = fromIce<Time>(query.timestamp);
-            ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp must be non-negative.";
+            const Time referenceTimestamp = fromIce<Time>(query.timestamp);
+            detail::checkReferenceTimestampNonNegative(referenceTimestamp);
 
             std::vector<const EntitySnapshotT*> befores;
             entity.forEachSnapshotBefore(referenceTimestamp, [&befores](const EntitySnapshotT & s)
@@ -231,11 +217,11 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::entity::TimeApprox& query,
                      const EntityT& entity) const
         {
-            const auto referenceTimestamp = fromIce<Time>(query.timestamp);
-            ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp is negative!";
+            const Time referenceTimestamp = fromIce<Time>(query.timestamp);
+            detail::checkReferenceTimestampNonNegative(referenceTimestamp);
 
-            const auto referenceTimestampMicroSeconds = referenceTimestamp.toMicroSeconds();
-            const auto epsDuration = fromIce<Time>(query.eps).toMicroSeconds();
+            const float referenceTimestampMicroSeconds = referenceTimestamp.toMicroSeconds();
+            const float epsDuration = fromIce<Time>(query.eps).toMicroSeconds();
 
             // elements have to be in range [t_ref - eps, t_ref + eps] if eps is positive
             const auto isInRange = [&](const Time & t) -> bool
@@ -248,15 +234,14 @@ namespace armarx::armem::server::query_proc::base
                 return std::abs(t.toMicroSeconds() - referenceTimestampMicroSeconds) <= epsDuration;
             };
 
-            try
+            // last element before or at timestamp
+            if (auto* beforeOrAt = entity.findLatestSnapshotBeforeOrAt(referenceTimestamp))
             {
-                // last element before or at timestamp
-                auto beforeOrAt = entity.getLatestSnapshotBeforeOrAt(referenceTimestamp);
-                const auto timestampOfMatchBefore = beforeOrAt.id().timestamp;
+                const auto timestampOfMatchBefore = beforeOrAt->id().timestamp;
                 const auto isPerfectMatch = timestampOfMatchBefore == referenceTimestamp;
                 if (isInRange(timestampOfMatchBefore))
                 {
-                    addResultSnapshot(result, beforeOrAt);
+                    addResultSnapshot(result, *beforeOrAt);
                 }
 
                 // earsly stop, not necessary to also get the next since the match is perfect
@@ -266,16 +251,16 @@ namespace armarx::armem::server::query_proc::base
                 }
 
                 // first element after or at timestamp (or at because of fewer checks, we can assure that there is not element at)
-                const auto after = entity.getFirstSnapshotAfterOrAt(referenceTimestamp);
-                const auto timestampOfMatchAfter = after.id().timestamp;
-                if (isInRange(timestampOfMatchAfter))
+                const auto* after = entity.findFirstSnapshotAfterOrAt(referenceTimestamp);
+                if (after)
                 {
-                    addResultSnapshot(result, after);
+                    const auto timestampOfMatchAfter = after->id().timestamp;
+                    if (isInRange(timestampOfMatchAfter))
+                    {
+                        addResultSnapshot(result, *after);
+                    }
                 }
             }
-            catch (const armem::error::MissingEntry&)
-            {
-            }
         }
 
 
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h
index df71683c29f2cb17db976e8be971725934b03348..91c41d9f54cb762654db9763dfe6d9c3af1aa60d 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h
@@ -5,9 +5,6 @@
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/interface/armem/query.h>
 
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
 #include <regex>
 
 
@@ -76,7 +73,7 @@ namespace armarx::armem::server::query_proc::base
         {
             memory.forEachCoreSegment([this, &result, &query](const CoreSegmentT & coreSegment)
             {
-                childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
+                this->_processResult(result, coreSegment, query);
             });
         }
 
@@ -84,13 +81,9 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::memory::Single& query,
                      const MemoryT& memory) const
         {
-            try
-            {
-                const CoreSegmentT& coreSegment = memory.getCoreSegment(query.coreSegmentName);
-                childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
-            }
-            catch (const error::MissingEntry&)
+            if (const CoreSegmentT* coreSegment = memory.findCoreSegment(query.coreSegmentName))
             {
+                this->_processResult(result, *coreSegment, query);
             }
         }
 
@@ -103,12 +96,23 @@ namespace armarx::armem::server::query_proc::base
             {
                 if (std::regex_search(coreSegment.name(), regex))
                 {
-                    childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
+                    this->_processResult(result, coreSegment, query);
                 }
             });
         }
 
 
+    private:
+
+        void _processResult(ResultMemoryT& result,
+                            const CoreSegmentT& coreSegment,
+                            const armem::query::data::MemoryQuery& query) const
+        {
+            ResultCoreSegmentT& added = result.addCoreSegment(coreSegment.name(), coreSegment.aronType());
+            childProcessor.process(added, query.coreSegmentQueries, coreSegment);
+        }
+
+
     protected:
 
         ChildProcessorT childProcessor;
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h
index 5102a12829c106e58159e7dcc35a7df0890f93d5..46f146694825936d4834b579093881e8452db3ca 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h
@@ -70,7 +70,7 @@ namespace armarx::armem::server::query_proc::base
         {
             providerSegment.forEachEntity([this, &result, &query](const EntityT & entity)
             {
-                childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
+                this->_processResult(result, entity, query);
             });
         }
 
@@ -78,14 +78,9 @@ namespace armarx::armem::server::query_proc::base
                      const armem::query::data::provider::Single& query,
                      const ProviderSegmentT& providerSegment) const
         {
-            try
+            if (const EntityT* entity = providerSegment.findEntity(query.entityName))
             {
-                const EntityT& entity = providerSegment.getEntity(query.entityName);
-                childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
-            }
-            catch (const error::MissingEntry&)
-            {
-                // Leave empty.
+                this->_processResult(result, *entity, query);
             }
         }
 
@@ -98,13 +93,24 @@ namespace armarx::armem::server::query_proc::base
             {
                 if (std::regex_search(entity.name(), regex))
                 {
-                    childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
+                    this->_processResult(result, entity, query);
                 }
                 return true;
             });
         }
 
 
+    private:
+
+        void _processResult(ResultProviderSegmentT& result,
+                            const EntityT& entity,
+                            const armem::query::data::ProviderSegmentQuery& query) const
+        {
+            ResultEntityT& added = result.addEntity(entity.name());
+            childProcessor.process(added, query.entityQueries, entity);
+        }
+
+
     protected:
 
         ChildProcessorT childProcessor;
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp
deleted file mode 100644
index a695cf43d51dcbbc2329fa1c48fbe8e63565c24f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp
+++ /dev/null
@@ -1,7 +0,0 @@
-#include "diskmemory.h"
-
-
-namespace armarx::armem::server::query_proc::d_ltm
-{
-}
-
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.h
deleted file mode 100644
index 0f2ffe791d192b9bc2b5f2a2be311735808427a4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/diskmemory/Memory.h>
-#include <RobotAPI/libraries/armem/server/query_proc/base.h>
-
-
-namespace armarx::armem::server::query_proc::d_ltm
-{
-    static const base::QueryTarget queryTarget = query::data::QueryTarget::LTM;
-
-
-    class EntityQueryProcessor :
-        public base::EntityQueryProcessorBase<queryTarget, armem::d_ltm::Entity, armem::d_ltm::Entity>
-    {
-    };
-
-    class ProviderSegmentQueryProcessor :
-        public base::ProviderSegmentQueryProcessorBase <queryTarget, armem::d_ltm::ProviderSegment, armem::d_ltm::ProviderSegment, EntityQueryProcessor >
-    {
-    };
-
-    class CoreSegmentQueryProcessor :
-        public base::CoreSegmentQueryProcessorBase<queryTarget, armem::d_ltm::CoreSegment, armem::d_ltm::CoreSegment, ProviderSegmentQueryProcessor>
-    {
-    };
-
-    class MemoryQueryProcessor :
-        public base::MemoryQueryProcessorBase <queryTarget, armem::d_ltm::Memory, armem::d_ltm::Memory, CoreSegmentQueryProcessor >
-    {
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/ltm.h b/source/RobotAPI/libraries/armem/server/query_proc/ltm.h
index ae0dc778c821ae138c98b8554a22237bf26e5989..05734c2e15d6836b69719283805fcfc5c1d7702d 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/ltm.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/ltm.h
@@ -1,6 +1,6 @@
 #pragma once
 
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
+#include <RobotAPI/libraries/armem/server/ltm/LongtermMemoryBase.h>
 #include <RobotAPI/libraries/armem/server/query_proc/base.h>
 
 
@@ -10,22 +10,22 @@ namespace armarx::armem::server::query_proc::ltm
 
 
     class EntityQueryProcessor :
-        public base::EntityQueryProcessorBase<queryTarget, armem::ltm::Entity, armem::ltm::Entity>
+        public base::EntityQueryProcessorBase<queryTarget, armem::wm::Entity, armem::wm::Entity>
     {
     };
 
     class ProviderSegmentQueryProcessor :
-        public base::ProviderSegmentQueryProcessorBase <queryTarget, armem::ltm::ProviderSegment, armem::ltm::ProviderSegment, EntityQueryProcessor >
+        public base::ProviderSegmentQueryProcessorBase <queryTarget, armem::wm::ProviderSegment, armem::wm::ProviderSegment, EntityQueryProcessor >
     {
     };
 
     class CoreSegmentQueryProcessor :
-        public base::CoreSegmentQueryProcessorBase <queryTarget, armem::ltm::CoreSegment, armem::ltm::CoreSegment, ProviderSegmentQueryProcessor>
+        public base::CoreSegmentQueryProcessorBase <queryTarget, armem::wm::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor>
     {
     };
 
     class MemoryQueryProcessor :
-        public base::MemoryQueryProcessorBase <queryTarget, armem::ltm::Memory, armem::ltm::Memory, CoreSegmentQueryProcessor >
+        public base::MemoryQueryProcessorBase <queryTarget, armem::wm::Memory, armem::wm::Memory, CoreSegmentQueryProcessor >
     {
     };
 
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp b/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp
index 4e968623d63aa57213507879608c81823d31c7d6..0ace705be878087b9023ea574f50769489514cb5 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp
+++ b/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp
@@ -55,8 +55,10 @@ namespace armarx::armem::server::query_proc::wm_server
         const armem::query::data::CoreSegmentQuery& query,
         const CoreSegment& coreSegment) const
     {
-        std::scoped_lock lock(coreSegment.mutex());
-        CoreSegmentQueryProcessorBase::process(result, query, coreSegment);
+        coreSegment.doLocked([&]()
+        {
+            CoreSegmentQueryProcessorBase::process(result, query, coreSegment);
+        });
     }
 
 
diff --git a/source/RobotAPI/libraries/armem/server/segment/Segment.cpp b/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
index 050e77d392da77bc5c4e4edfcf11f76ee6e1e051..d538568c2430c9ffbd00c9b48bebcd46086280ea 100644
--- a/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
+++ b/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
@@ -48,14 +48,6 @@ namespace armarx::armem::server::segment
     }
 
 
-    std::mutex& wm::CoreSegmentBase::mutex() const
-    {
-        ARMARX_CHECK_NOT_NULL(segment);
-        return segment->mutex();
-    }
-
-
-
     wm::ProviderSegmentBase::ProviderSegmentBase(
         armem::server::MemoryToIceAdapter& iceMemory,
         const std::string& defaultProviderSegmentName,
diff --git a/source/RobotAPI/libraries/armem/server/segment/Segment.h b/source/RobotAPI/libraries/armem/server/segment/Segment.h
index 7808e99d31f4df3543bfbd5b882a408dda143ed5..dc35846aa89d14c125e5a6f3093e1a19ee85c6e2 100644
--- a/source/RobotAPI/libraries/armem/server/segment/Segment.h
+++ b/source/RobotAPI/libraries/armem/server/segment/Segment.h
@@ -1,29 +1,16 @@
 #pragma once
 
-// STD/STL
-#include <mutex>
-#include <string>
+#include <RobotAPI/libraries/armem/server/forward_declarations.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
-// ArmarX
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/application/properties/forward_declarations.h>
 
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
+#include <string>
 
 
-namespace armarx::armem
-{
-    namespace server
-    {
-        class MemoryToIceAdapter;
-
-        namespace wm
-        {
-            class CoreSegment;
-            class ProviderSegment;
-        }
-    }
-}
 namespace armarx::armem::server::segment
 {
     namespace detail
@@ -88,7 +75,11 @@ namespace armarx::armem::server::segment
             // virtual void onConnect() override;
 
 
-            std::mutex& mutex() const;
+            template <class FunctionT>
+            auto doLocked(FunctionT&& function) const
+            {
+                return segment->doLocked(function);
+            }
 
 
         protected:
diff --git a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.cpp b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.cpp
index 8184e27c985877a19aaa873db07883685140b17b..50f5ae6451bb49f9a4356579d78618a865297881 100644
--- a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.cpp
+++ b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.cpp
@@ -12,11 +12,11 @@ namespace armarx::armem::server::segment
 {
 
     SpecializedSegment::SpecializedSegment(
-            server::MemoryToIceAdapter& iceMemory,
-            aron::typenavigator::ObjectNavigatorPtr aronType,
-            const std::string& defaultCoreSegmentName,
-            int64_t defaultMaxHistorySize
-            ) :
+        server::MemoryToIceAdapter& iceMemory,
+        aron::typenavigator::ObjectNavigatorPtr aronType,
+        const std::string& defaultCoreSegmentName,
+        int64_t defaultMaxHistorySize
+    ) :
         iceMemory(iceMemory), aronType(aronType)
     {
         setDefaultCoreSegmentName(defaultCoreSegmentName);
@@ -52,13 +52,6 @@ namespace armarx::armem::server::segment
     }
 
 
-    std::mutex& SpecializedSegment::mutex() const
-    {
-        ARMARX_CHECK_NOT_NULL(coreSegment);
-        return coreSegment->mutex();
-    }
-
-
     void SpecializedSegment::setDefaultCoreSegmentName(const std::string& coreSegmentName)
     {
         this->properties.coreSegmentName = coreSegmentName;
diff --git a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
index 460fbf3f0f0cd4ea6c2835d499071f2e43bf2a7d..271536db21ffdfadb3fba874f60bdd8a33d21f44 100644
--- a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
+++ b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
@@ -1,26 +1,14 @@
 #pragma once
 
-#include <mutex>
-#include <string>
+#include <RobotAPI/libraries/armem/server/forward_declarations.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
 #include <ArmarXCore/core/application/properties/forward_declarations.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
-#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
-
-
-namespace armarx::armem
-{
-    namespace server
-    {
-        class MemoryToIceAdapter;
+#include <string>
 
-        namespace wm
-        {
-            class CoreSegment;
-        }
-    }
-}
 
 namespace armarx::armem::server::segment
 {
@@ -46,7 +34,12 @@ namespace armarx::armem::server::segment
         virtual void init();
         // void connect();
 
-        std::mutex& mutex() const;
+
+        template <class FunctionT>
+        auto doLocked(FunctionT&& function) const
+        {
+            return coreSegment->doLocked(function);
+        }
 
 
     protected:
diff --git a/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h
index e2f2d498c2945f4456c281abafe0f1ad66074e72..962179a68aeb601dc261eb6d496389295597a2ea 100644
--- a/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h
+++ b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h
@@ -1,6 +1,5 @@
 #pragma once
 
-
 namespace armarx::armem::server::detail
 {
     // TODO: Replace by ConstrainedHistorySize (not only max entries, e.g. delete oldest / delete least accessed / ...)
@@ -50,7 +49,6 @@ namespace armarx::armem::server::detail
             static_cast<DerivedT&>(*this).forEachChild([maxSize](auto & child)
             {
                 child.setMaxHistorySize(maxSize);
-                return true;
             });
         }
 
diff --git a/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp
index 58be8027db2561979d3510b7d481715678b61eae..6f031a4d62811d871a5cd627081ad3741cfd3d4b 100644
--- a/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp
+++ b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp
@@ -43,98 +43,6 @@ namespace armarx::armem::server::wm
     }
 
 
-
-    Entity& ProviderSegment::addEntity(Entity&& entity)
-    {
-        Entity& added = ProviderSegmentBase::addEntity(std::move(entity));
-        added.setMaxHistorySize(this->getMaxHistorySize());
-        return added;
-    }
-
-
-
-    std::mutex& CoreSegment::mutex() const
-    {
-        return _mutex;
-    }
-
-
-    std::optional<wm::EntitySnapshot> CoreSegment::getLatestEntitySnapshot(const MemoryID& entityID) const
-    {
-        const wm::Entity& entity = this->getEntity(entityID);
-        if (entity.empty())
-        {
-            return std::nullopt;
-        }
-        else
-        {
-            return entity.getLatestSnapshot();
-        }
-    }
-
-
-    std::optional<wm::EntityInstance> CoreSegment::getLatestEntityInstance(
-        const MemoryID& entityID, int instanceIndex) const
-    {
-        auto snapshot = getLatestEntitySnapshot(entityID);
-        if (snapshot.has_value()
-            and instanceIndex >= 0
-            and static_cast<size_t>(instanceIndex) < snapshot->size())
-        {
-            return snapshot->getInstance(instanceIndex);
-        }
-        else
-        {
-            return std::nullopt;
-        }
-    }
-
-
-    armarx::aron::datanavigator::DictNavigatorPtr
-    CoreSegment::getLatestEntityInstanceData(const MemoryID& entityID, int instanceIndex) const
-    {
-        auto instance = getLatestEntityInstance(entityID, instanceIndex);
-        if (instance.has_value())
-        {
-            return instance->data();
-        }
-        else
-        {
-            return nullptr;
-        }
-    }
-
-
-    ProviderSegment& CoreSegment::addProviderSegment(ProviderSegment&& providerSegment)
-    {
-        ProviderSegmentT& added = CoreSegmentBase::addProviderSegment(std::move(providerSegment));
-        added.setMaxHistorySize(this->getMaxHistorySize());
-        return added;
-    }
-
-
-    std::optional<wm::EntitySnapshot>
-    CoreSegment::getLatestEntitySnapshotLocking(const MemoryID& entityID) const
-    {
-        std::scoped_lock lock(_mutex);
-        return getLatestEntitySnapshot(entityID);
-    }
-
-    std::optional<wm::EntityInstance>
-    CoreSegment::getLatestEntityInstanceLocking(const MemoryID& entityID, int instanceIndex) const
-    {
-        std::scoped_lock lock(_mutex);
-        return getLatestEntityInstance(entityID, instanceIndex);
-    }
-
-    armarx::aron::datanavigator::DictNavigatorPtr
-    CoreSegment::getLatestEntityInstanceDataLocking(const MemoryID& entityID, int instanceIndex) const
-    {
-        std::scoped_lock lock(_mutex);
-        return getLatestEntityInstanceData(entityID, instanceIndex);
-    }
-
-
     // TODO: add core segment if param is set
     std::vector<Memory::Base::UpdateResult>
     Memory::updateLocking(const Commit& commit)
@@ -157,15 +65,16 @@ namespace armarx::armem::server::wm
                 CoreSegment& coreSegment = it->second;
 
                 // Lock the core segment for the whole batch.
-                std::scoped_lock lock(coreSegment.mutex());
-
-                for (const EntityUpdate* update : updates)
+                coreSegment.doLocked([&result, &coreSegment, updates = &updates]()
                 {
-                    auto r = coreSegment.update(*update);
-                    Base::UpdateResult ret { r };
-                    ret.memoryUpdateType = UpdateType::UpdatedExisting;
-                    result.push_back(ret);
-                }
+                    for (const EntityUpdate* update : *updates)
+                    {
+                        auto r = coreSegment.update(*update);
+                        Base::UpdateResult ret { r };
+                        ret.memoryUpdateType = UpdateType::UpdatedExisting;
+                        result.push_back(ret);
+                    }
+                });
             }
             else
             {
@@ -191,10 +100,10 @@ namespace armarx::armem::server::wm
 
         CoreSegment& segment = getCoreSegment(update.entityID.coreSegmentName);
         Base::UpdateResult result;
+        segment.doLocked([&result, &segment, &update]()
         {
-            std::scoped_lock lock(segment.mutex());
             result = segment.update(update);
-        }
+        });
         result.memoryUpdateType = UpdateType::UpdatedExisting;
         return result;
     }
diff --git a/source/RobotAPI/libraries/armem/server/wm/memory_definitions.h b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.h
index 4eb6fdbb3105b0ae2ce3148c8457b915040a170a..5d2036f054d287e90869de8c9d535dc694da9734 100644
--- a/source/RobotAPI/libraries/armem/server/wm/memory_definitions.h
+++ b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.h
@@ -10,8 +10,9 @@
 #include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
 #include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
 
+#include <RobotAPI/libraries/armem/core/wm/detail/data_lookup_mixins.h>
+
 #include <mutex>
-#include <optional>
 
 
 namespace armarx::armem::server::wm
@@ -26,8 +27,9 @@ namespace armarx::armem::server::wm
 
     /// @see base::EntityBase
     class Entity :
-        public base::EntityBase<EntitySnapshot, Entity>,
-        public detail::MaxHistorySize
+        public base::EntityBase<EntitySnapshot, Entity>
+        , public detail::MaxHistorySize
+        , public armem::wm::detail::FindInstanceDataMixin<Entity>
     {
     public:
 
@@ -55,8 +57,9 @@ namespace armarx::armem::server::wm
 
     /// @see base::ProviderSegmentBase
     class ProviderSegment :
-        public base::ProviderSegmentBase<Entity, ProviderSegment>,
-        public detail::MaxHistorySizeParent<ProviderSegment>
+        public base::ProviderSegmentBase<Entity, ProviderSegment>
+        , public detail::MaxHistorySizeParent<ProviderSegment>
+        , public armem::wm::detail::FindInstanceDataMixin<ProviderSegment>
     {
     public:
 
@@ -64,7 +67,14 @@ namespace armarx::armem::server::wm
 
 
         using ProviderSegmentBase::addEntity;
-        EntityT& addEntity(EntityT&& entity);
+
+        template <class ...Args>
+        Entity& addEntity(const std::string& name, Args... args)
+        {
+            Entity& added = ProviderSegmentBase::addEntity(name, args...);
+            added.setMaxHistorySize(this->getMaxHistorySize());
+            return added;
+        }
 
     };
 
@@ -74,6 +84,7 @@ namespace armarx::armem::server::wm
     class CoreSegment :
         public base::CoreSegmentBase<ProviderSegment, CoreSegment>,
         public detail::MaxHistorySizeParent<CoreSegment>
+        , public armem::wm::detail::FindInstanceDataMixin<CoreSegment>
     {
         using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
 
@@ -81,77 +92,28 @@ namespace armarx::armem::server::wm
 
         using Base::CoreSegmentBase;
 
-        // ToDo: Replace by runLocked()
-        std::mutex& mutex() const;
-
-
-        // Non-locking interface
-
-        std::optional<wm::EntitySnapshot> getLatestEntitySnapshot(
-            const MemoryID& entityID) const;
-        std::optional<wm::EntityInstance> getLatestEntityInstance(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-        armarx::aron::datanavigator::DictNavigatorPtr getLatestEntityInstanceData(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-
-
-        template <class AronDtoT>
-        std::optional<AronDtoT> getLatestEntityInstanceDataAs(
-            const MemoryID& entityID, int instanceIndex = 0) const
-        {
-            wm::EntityInstanceDataPtr data = getLatestEntityInstanceData(entityID, instanceIndex);
-            if (data)
-            {
-                AronDtoT aron;
-                aron.fromAron(data);
-                return aron;
-            }
-            else
-            {
-                return std::nullopt;
-            }
-        }
-
-
         /// @see base::CoreSegmentBase::addProviderSegment()
         using CoreSegmentBase::addProviderSegment;
-        ProviderSegment& addProviderSegment(ProviderSegment&& providerSegment);
+        template <class ...Args>
+        ProviderSegment& addProviderSegment(const std::string& name, Args... args)
+        {
+            ProviderSegmentT& added = CoreSegmentBase::addProviderSegment(name, args...);
+            added.setMaxHistorySize(this->getMaxHistorySize());
+            return added;
+        }
 
 
         // Locking interface
 
-        std::optional<wm::EntitySnapshot> getLatestEntitySnapshotLocking(
-            const MemoryID& entityID) const;
-        std::optional<wm::EntityInstance> getLatestEntityInstanceLocking(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-        armarx::aron::datanavigator::DictNavigatorPtr getLatestEntityInstanceDataLocking(
-            const MemoryID& entityID, int instanceIndex = 0) const;
-
-
-        template <class AronDtoT>
-        std::optional<AronDtoT> getLatestEntityInstanceDataLockingAs(
-            const MemoryID& entityID, int instanceIndex = 0) const
+        template <class FunctionT>
+        auto doLocked(FunctionT&& function) const
         {
-            // Keep lock to a minimum.
-            wm::EntityInstanceDataPtr data = nullptr;
-            {
-                std::scoped_lock lock(_mutex);
-                data = getLatestEntityInstanceData(entityID, instanceIndex);
-            }
-            if (data)
-            {
-                AronDtoT aron;
-                aron.fromAron(data);
-                return aron;
-            }
-            else
-            {
-                return std::nullopt;
-            }
+            std::scoped_lock lock(_mutex);
+            return function();
         }
 
 
-    protected:
+    private:
 
         mutable std::mutex _mutex;
 
@@ -162,6 +124,7 @@ namespace armarx::armem::server::wm
     /// @see base::MemoryBase
     class Memory :
         public base::MemoryBase<CoreSegment, Memory>
+        , public armem::wm::detail::FindInstanceDataMixin<Memory>
     {
         using Base = base::MemoryBase<CoreSegment, Memory>;
 
diff --git a/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
index cc34f7e2d7cb73d7a3e3715064508c3b73cab351..9c29804ebdc56444b175b3de0abd115b3a1067c0 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
@@ -27,6 +27,7 @@
 #include <RobotAPI/Test.h>
 #include <RobotAPI/libraries/armem/core/Commit.h>
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/core/operations.h>
 
 #include <iostream>
 #include <set>
@@ -98,7 +99,7 @@ BOOST_AUTO_TEST_CASE(test_forEach)
     BOOST_CHECK_GT(pids.size(), 0);
     BOOST_CHECK_GT(cids.size(), 0);
 
-    BOOST_TEST_MESSAGE("Memory: \n" << memory.dump());
+    BOOST_TEST_MESSAGE("Memory: \n" << armem::print(memory));
 
     memory.forEachInstance([&](const wm::EntityInstance & i) -> bool
     {
diff --git a/source/RobotAPI/libraries/armem/test/ArMemGetFindTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemGetFindTest.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..29c12884d15292706ac2be33410352fe832dbc2a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/test/ArMemGetFindTest.cpp
@@ -0,0 +1,347 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI::ArmarXObjects::armem
+ * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
+ * @date       2020
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE RobotAPI::ArmarXLibraries::armem
+
+#define ARMARX_BOOST_TEST
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/operations.h>
+
+#include <RobotAPI/Test.h>
+
+#include <iostream>
+
+
+namespace armem = armarx::armem;
+namespace wm = armarx::armem::wm;
+namespace aron = armarx::aron;
+
+
+namespace ArMemGetFindTest
+{
+    struct Fixture
+    {
+        wm::EntitySnapshot snapshot;
+        wm::Entity entity;
+        wm::ProviderSegment provSeg;
+        wm::CoreSegment coreSeg;
+        wm::Memory memory;
+
+        armem::MemoryID instanceID;
+        armem::MemoryID snapshotID;
+        armem::MemoryID entityID;
+        armem::MemoryID provSegID;
+        armem::MemoryID coreSegID;
+        armem::MemoryID memoryID;
+
+        Fixture()
+        {
+            {
+                snapshot.time() = armem::Time::microSeconds(1000);
+                snapshot.addInstance();
+            }
+            {
+                entity.name() = "entity";
+                entity.addSnapshot(snapshot);
+            }
+            {
+                provSeg.name() = "provider segment";
+                provSeg.addEntity(entity);
+            }
+            {
+                coreSeg.name() = "core segment";
+                coreSeg.addProviderSegment(provSeg);
+            }
+            {
+                memory.name() = "memory";
+                memory.addCoreSegment(coreSeg);
+            }
+
+            memoryID = memory.id();
+            coreSegID = memoryID.withCoreSegmentName(coreSeg.name());
+            provSegID = coreSegID.withProviderSegmentName(provSeg.name());
+            entityID = provSegID.withEntityName(entity.name());
+            snapshotID = entityID.withTimestamp(snapshot.time());
+            instanceID = snapshotID.withInstanceIndex(0);
+        }
+        ~Fixture()
+        {
+        }
+
+
+        template <class ParentT>
+        void test_get_find_instance_by_id(ParentT&& parent)
+        {
+            _test_get_find_instance_by_id(const_cast<const ParentT&>(parent));
+            _test_get_find_instance_by_id(const_cast<ParentT&>(parent));
+        }
+        template <class ParentT>
+        void _test_get_find_instance_by_id(ParentT&& parent)
+        {
+            BOOST_TEST_CONTEXT("Parent: " << armem::print(parent))
+            {
+                BOOST_CHECK_EQUAL(parent.hasInstance(snapshotID.withInstanceIndex(0)), true);
+                BOOST_CHECK_EQUAL(parent.hasInstance(snapshotID.withInstanceIndex(1)), false);
+
+                BOOST_CHECK_NE(parent.findInstance(snapshotID.withInstanceIndex(0)), nullptr);
+                BOOST_CHECK_EQUAL(parent.findInstance(snapshotID.withInstanceIndex(1)), nullptr);
+
+                BOOST_CHECK_NO_THROW(parent.getInstance(snapshotID.withInstanceIndex(0)));
+                BOOST_CHECK_THROW(parent.getInstance(snapshotID.withInstanceIndex(1)), armem::error::MissingEntry);
+            }
+        }
+
+        template <class ParentT>
+        void test_get_find_snapshot_by_id(ParentT&& parent)
+        {
+            _test_get_find_snapshot_by_id(const_cast<const ParentT&>(parent));
+            _test_get_find_snapshot_by_id(const_cast<ParentT&>(parent));
+        }
+        template <class ParentT>
+        void _test_get_find_snapshot_by_id(ParentT&& parent)
+        {
+            BOOST_TEST_CONTEXT("Parent: " << armem::print(parent))
+            {
+                BOOST_CHECK_EQUAL(parent.hasSnapshot(entityID.withTimestamp(armem::Time::microSeconds(1000))), true);
+                BOOST_CHECK_EQUAL(parent.hasSnapshot(entityID.withTimestamp(armem::Time::microSeconds(2000))), false);
+
+                BOOST_CHECK_NE(parent.findSnapshot(entityID.withTimestamp(armem::Time::microSeconds(1000))), nullptr);
+                BOOST_CHECK_EQUAL(parent.findSnapshot(entityID.withTimestamp(armem::Time::microSeconds(2000))), nullptr);
+
+                BOOST_CHECK_NO_THROW(parent.getSnapshot(entityID.withTimestamp(armem::Time::microSeconds(1000))));
+                BOOST_CHECK_THROW(parent.getSnapshot(entityID.withTimestamp(armem::Time::microSeconds(2000))), armem::error::MissingEntry);
+            }
+        }
+
+
+        template <class ParentT>
+        void test_get_find_entity_by_id(ParentT&& parent)
+        {
+            _test_get_find_entity_by_id(const_cast<const ParentT&>(parent));
+            _test_get_find_entity_by_id(const_cast<ParentT&>(parent));
+        }
+        template <class ParentT>
+        void _test_get_find_entity_by_id(ParentT&& parent)
+        {
+            BOOST_TEST_CONTEXT("Parent: " << armem::print(parent))
+            {
+                BOOST_CHECK_EQUAL(parent.hasEntity(provSegID.withEntityName("entity")), true);
+                BOOST_CHECK_EQUAL(parent.hasEntity(provSegID.withEntityName("other entity")), false);
+
+                BOOST_CHECK_NE(parent.findEntity(provSegID.withEntityName("entity")), nullptr);
+                BOOST_CHECK_EQUAL(parent.findEntity(provSegID.withEntityName("other entity")), nullptr);
+
+                BOOST_CHECK_NO_THROW(parent.getEntity(provSegID.withEntityName("entity")));
+                BOOST_CHECK_THROW(parent.getEntity(provSegID.withEntityName("other entity")), armem::error::MissingEntry);
+            }
+        }
+
+        template <class ParentT>
+        void test_get_find_provider_segment_by_id(ParentT&& parent)
+        {
+            _test_get_find_provider_segment_by_id(const_cast<const ParentT&>(parent));
+            _test_get_find_provider_segment_by_id(const_cast<ParentT&>(parent));
+        }
+        template <class ParentT>
+        void _test_get_find_provider_segment_by_id(ParentT&& parent)
+        {
+            BOOST_TEST_CONTEXT("Parent: " << armem::print(parent))
+            {
+                BOOST_CHECK_EQUAL(parent.hasProviderSegment(provSegID.withProviderSegmentName("provider segment")), true);
+                BOOST_CHECK_EQUAL(parent.hasProviderSegment(provSegID.withProviderSegmentName("other provider segment")), false);
+
+                BOOST_CHECK_NE(parent.findProviderSegment(provSegID.withProviderSegmentName("provider segment")), nullptr);
+                BOOST_CHECK_EQUAL(parent.findProviderSegment(provSegID.withProviderSegmentName("other provider segment")), nullptr);
+
+                BOOST_CHECK_NO_THROW(parent.getProviderSegment(provSegID.withProviderSegmentName("provider segment")));
+                BOOST_CHECK_THROW(parent.getProviderSegment(provSegID.withProviderSegmentName("other provider segment")), armem::error::MissingEntry);
+            }
+        }
+
+        template <class ParentT>
+        void test_get_find_core_segment_by_id(ParentT&& parent)
+        {
+            _test_get_find_core_segment_by_id(const_cast<const ParentT&>(parent));
+            _test_get_find_core_segment_by_id(const_cast<ParentT&>(parent));
+        }
+        template <class ParentT>
+        void _test_get_find_core_segment_by_id(ParentT&& parent)
+        {
+            BOOST_TEST_CONTEXT("Parent: " << armem::print(parent))
+            {
+                BOOST_CHECK_EQUAL(parent.hasCoreSegment(provSegID.withCoreSegmentName("core segment")), true);
+                BOOST_CHECK_EQUAL(parent.hasCoreSegment(provSegID.withCoreSegmentName("other core segment")), false);
+
+                BOOST_CHECK_NE(parent.findCoreSegment(provSegID.withCoreSegmentName("core segment")), nullptr);
+                BOOST_CHECK_EQUAL(parent.findCoreSegment(provSegID.withCoreSegmentName("other core segment")), nullptr);
+
+                BOOST_CHECK_NO_THROW(parent.getCoreSegment(provSegID.withCoreSegmentName("core segment")));
+                BOOST_CHECK_THROW(parent.getCoreSegment(provSegID.withCoreSegmentName("other core segment")), armem::error::MissingEntry);
+            }
+        }
+    };
+}
+
+
+BOOST_FIXTURE_TEST_SUITE(ArMemGetFindTest, Fixture)
+
+
+
+BOOST_AUTO_TEST_CASE(test_snapshot_get_find_instance_by_key)
+{
+    BOOST_CHECK_EQUAL(snapshot.hasInstance(0), true);
+    BOOST_CHECK_EQUAL(snapshot.hasInstance(1), false);
+
+    BOOST_CHECK_NE(snapshot.findInstance(0), nullptr);
+    BOOST_CHECK_EQUAL(snapshot.findInstance(1), nullptr);
+
+    BOOST_CHECK_NO_THROW(snapshot.getInstance(0));
+    BOOST_CHECK_THROW(snapshot.getInstance(1), armem::error::MissingEntry);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_entity_get_find_snapshot_by_key)
+{
+    BOOST_CHECK_EQUAL(entity.hasSnapshot(armem::Time::microSeconds(1000)), true);
+    BOOST_CHECK_EQUAL(entity.hasSnapshot(armem::Time::microSeconds(2000)), false);
+
+    BOOST_CHECK_NE(entity.findSnapshot(armem::Time::microSeconds(1000)), nullptr);
+    BOOST_CHECK_EQUAL(entity.findSnapshot(armem::Time::microSeconds(2000)), nullptr);
+
+    BOOST_CHECK_NO_THROW(entity.getSnapshot(armem::Time::microSeconds(1000)));
+    BOOST_CHECK_THROW(entity.getSnapshot(armem::Time::microSeconds(2000)), armem::error::MissingEntry);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_provider_segment_get_find_entity_by_key)
+{
+    BOOST_CHECK_EQUAL(provSeg.hasEntity("entity"), true);
+    BOOST_CHECK_EQUAL(provSeg.hasEntity("other entity"), false);
+
+    BOOST_CHECK_NE(provSeg.findEntity("entity"), nullptr);
+    BOOST_CHECK_EQUAL(provSeg.findEntity("other entity"), nullptr);
+
+    BOOST_CHECK_NO_THROW(provSeg.getEntity("entity"));
+    BOOST_CHECK_THROW(provSeg.getEntity("other entity"), armem::error::MissingEntry);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_core_segment_get_find_provider_segment_by_key)
+{
+    BOOST_CHECK_EQUAL(coreSeg.hasProviderSegment("provider segment"), true);
+    BOOST_CHECK_EQUAL(coreSeg.hasProviderSegment("other provider segment"), false);
+
+    BOOST_CHECK_NE(coreSeg.findProviderSegment("provider segment"), nullptr);
+    BOOST_CHECK_EQUAL(coreSeg.findProviderSegment("other provider segment"), nullptr);
+
+    BOOST_CHECK_NO_THROW(coreSeg.getProviderSegment("provider segment"));
+    BOOST_CHECK_THROW(coreSeg.getProviderSegment("other provider segment"), armem::error::MissingEntry);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_memory_get_find_core_segment_by_key)
+{
+    BOOST_CHECK_EQUAL(memory.hasCoreSegment("core segment"), true);
+    BOOST_CHECK_EQUAL(memory.hasCoreSegment("other core segment"), false);
+
+    BOOST_CHECK_NE(memory.findCoreSegment("core segment"), nullptr);
+    BOOST_CHECK_EQUAL(memory.findCoreSegment("other core segment"), nullptr);
+
+    BOOST_CHECK_NO_THROW(memory.getCoreSegment("core segment"));
+    BOOST_CHECK_THROW(memory.getCoreSegment("other core segment"), armem::error::MissingEntry);
+}
+
+
+
+BOOST_AUTO_TEST_CASE(test_snapshot_get_find_instance_by_id)
+{
+    test_get_find_instance_by_id(snapshot);
+}
+BOOST_AUTO_TEST_CASE(test_entity_get_find_instance_by_id)
+{
+    test_get_find_instance_by_id(entity);
+}
+BOOST_AUTO_TEST_CASE(test_provider_segment_get_find_instance_by_id)
+{
+    test_get_find_instance_by_id(provSeg);
+}
+BOOST_AUTO_TEST_CASE(test_core_segment_get_find_instance_by_id)
+{
+    test_get_find_instance_by_id(coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_memory_get_find_instance_by_id)
+{
+    test_get_find_instance_by_id(memory);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_entity_get_find_snapshot_by_id)
+{
+    test_get_find_snapshot_by_id(entity);
+}
+BOOST_AUTO_TEST_CASE(test_provider_segment_get_find_snapshot_by_id)
+{
+    test_get_find_snapshot_by_id(provSeg);
+}
+BOOST_AUTO_TEST_CASE(test_core_segment_get_find_snapshot_by_id)
+{
+    test_get_find_snapshot_by_id(coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_memory_get_find_snapshot_by_id)
+{
+    test_get_find_snapshot_by_id(memory);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_provider_segment_get_find_entity_by_id)
+{
+    test_get_find_entity_by_id(provSeg);
+}
+BOOST_AUTO_TEST_CASE(test_core_segment_get_find_entity_by_id)
+{
+    test_get_find_entity_by_id(coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_memory_get_find_entity_by_id)
+{
+    test_get_find_entity_by_id(memory);
+}
+
+
+BOOST_AUTO_TEST_CASE(test_core_segment_get_find_provider_segment_by_id)
+{
+    test_get_find_provider_segment_by_id(coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_memory_get_find_provider_segment_by_id)
+{
+    test_get_find_provider_segment_by_id(memory);
+}
+
+BOOST_AUTO_TEST_CASE(test_memory_get_find_core_segment_by_id)
+{
+    test_get_find_core_segment_by_id(memory);
+}
+
+
+
+BOOST_AUTO_TEST_SUITE_END()
diff --git a/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
index 3ac3d50411854022aa31b781ba011e9ac8d91c75..f0ede7b42a3bdb34d1a103ab43226adae833740a 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
@@ -34,7 +34,6 @@
 
 #include <RobotAPI/libraries/aron/core/Debug.h>
 
-#include "../core/longtermmemory/Memory.h"
 
 //#include "../core/io/diskWriter/NlohmannJSON/NlohmannJSONDiskWriter.h"
 
diff --git a/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
index 376f2ec680f92e64a5c72b496543749a303e8cc1..e9f694a27104c142603752f22f5452c8024663b0 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
@@ -28,9 +28,8 @@
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/diskmemory/Memory.h>
 #include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/operations.h>
 
 #include <iostream>
 #include <SimoxUtility/meta/type_name.h>
@@ -40,6 +39,8 @@
 
 namespace armem = armarx::armem;
 namespace aron = armarx::aron;
+namespace wm = armarx::armem::wm;
+
 
 BOOST_AUTO_TEST_CASE(test_time_to_string)
 {
@@ -80,6 +81,157 @@ BOOST_AUTO_TEST_CASE(test_time_to_string)
 }
 
 
+// Public interface tests
+
+
+namespace ArMemMemoryTest
+{
+    struct APITestFixture
+    {
+        wm::EntityInstance instance { 0 };
+        wm::EntitySnapshot snapshot { armem::Time::microSeconds(1000) };
+        wm::Entity entity { "entity" };
+        wm::ProviderSegment provSeg { "provider" };
+        wm::CoreSegment coreSeg { "core" };
+        wm::Memory memory { "memory" };
+
+
+        void test_add_instance(wm::EntityInstance& added, const wm::EntitySnapshot& parent)
+        {
+            BOOST_TEST_CONTEXT("Added: " << armem::print(added) << "\n Parent: " << armem::print(parent))
+            {
+                const int index = 0;
+                BOOST_CHECK_EQUAL(added.index(), index);
+                BOOST_CHECK_EQUAL(parent.size(), 1);
+                BOOST_CHECK(parent.hasInstance(index));
+                BOOST_CHECK_EQUAL(&parent.getInstance(index), &added);
+            }
+        }
+        void test_add_snapshot(wm::EntitySnapshot& added, const wm::Entity& parent)
+        {
+            BOOST_TEST_CONTEXT("Added: " << armem::print(added) << "\n Parent: " << armem::print(parent))
+            {
+                const armem::Time time = armem::Time::microSeconds(1000);
+                BOOST_CHECK_EQUAL(added.time(), time);
+                BOOST_CHECK_EQUAL(parent.size(), 1);
+                BOOST_CHECK(parent.hasSnapshot(time));
+                BOOST_CHECK_EQUAL(&parent.getSnapshot(time), &added);
+            }
+        }
+        void test_add_entity(wm::Entity& added, const wm::ProviderSegment& parent)
+        {
+            BOOST_TEST_CONTEXT("Added: " << armem::print(added) << "\n Parent: " << armem::print(parent))
+            {
+                const std::string name = "entity";
+                BOOST_CHECK_EQUAL(added.name(), name);
+                BOOST_CHECK_EQUAL(parent.size(), 1);
+                BOOST_CHECK(parent.hasEntity(name));
+                BOOST_CHECK_EQUAL(&parent.getEntity(name), &added);
+            }
+        }
+        void test_add_provider_segment(wm::ProviderSegment& added, const wm::CoreSegment& parent)
+        {
+            BOOST_TEST_CONTEXT("Added: " << armem::print(added) << "\n Parent: " << armem::print(parent))
+            {
+                const std::string name = "provider";
+                BOOST_CHECK_EQUAL(added.name(), name);
+                BOOST_CHECK_EQUAL(parent.size(), 1);
+                BOOST_CHECK(parent.hasProviderSegment(name));
+                BOOST_CHECK_EQUAL(&parent.getProviderSegment(name), &added);
+            }
+        }
+        void test_add_core_segment(wm::CoreSegment& added, const wm::Memory& parent)
+        {
+            BOOST_TEST_CONTEXT("Added: " << armem::print(added) << "\n Parent: " << armem::print(parent))
+            {
+                const std::string name = "core";
+                BOOST_CHECK_EQUAL(added.name(), name);
+                BOOST_CHECK_EQUAL(parent.size(), 1);
+                BOOST_CHECK(parent.hasCoreSegment(name));
+                BOOST_CHECK_EQUAL(&parent.getCoreSegment(name), &added);
+            }
+        }
+    };
+}
+
+
+
+BOOST_FIXTURE_TEST_SUITE(APITest, ArMemMemoryTest::APITestFixture)
+
+
+BOOST_AUTO_TEST_CASE(test_add_instance_no_args)
+{
+    test_add_instance(snapshot.addInstance(), snapshot);
+}
+BOOST_AUTO_TEST_CASE(test_add_instance_copy)
+{
+    test_add_instance(snapshot.addInstance(instance), snapshot);
+}
+BOOST_AUTO_TEST_CASE(test_add_instance_move)
+{
+    test_add_instance(snapshot.addInstance(std::move(instance)), snapshot);
+}
+
+BOOST_AUTO_TEST_CASE(test_add_snapshot_time)
+{
+    test_add_snapshot(entity.addSnapshot(armem::Time::microSeconds(1000)), entity);
+}
+BOOST_AUTO_TEST_CASE(test_add_snapshot_copy)
+{
+    test_add_snapshot(entity.addSnapshot(snapshot), entity);
+}
+BOOST_AUTO_TEST_CASE(test_add_snapshot_move)
+{
+    test_add_snapshot(entity.addSnapshot(std::move(snapshot)), entity);
+}
+
+BOOST_AUTO_TEST_CASE(test_add_entity_name)
+{
+    test_add_entity(provSeg.addEntity("entity"), provSeg);
+}
+BOOST_AUTO_TEST_CASE(test_add_entity_copy)
+{
+    test_add_entity(provSeg.addEntity(entity), provSeg);
+}
+BOOST_AUTO_TEST_CASE(test_add_entity_move)
+{
+    test_add_entity(provSeg.addEntity(std::move(entity)), provSeg);
+}
+
+BOOST_AUTO_TEST_CASE(test_add_provider_segment_name)
+{
+    test_add_provider_segment(coreSeg.addProviderSegment("provider"), coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_add_provider_segment_copy)
+{
+    test_add_provider_segment(coreSeg.addProviderSegment(provSeg), coreSeg);
+}
+BOOST_AUTO_TEST_CASE(test_add_provider_segment_move)
+{
+    test_add_provider_segment(coreSeg.addProviderSegment(std::move(provSeg)), coreSeg);
+}
+
+BOOST_AUTO_TEST_CASE(test_add_core_segment_name)
+{
+    test_add_core_segment(memory.addCoreSegment("core"), memory);
+}
+BOOST_AUTO_TEST_CASE(test_add_core_segment_copy)
+{
+    test_add_core_segment(memory.addCoreSegment(coreSeg), memory);
+}
+BOOST_AUTO_TEST_CASE(test_add_core_segment_move)
+{
+    test_add_core_segment(memory.addCoreSegment(std::move(coreSeg)), memory);
+}
+
+
+BOOST_AUTO_TEST_SUITE_END()
+
+
+
+
+
+// COPY/MOVE CTOR/OP TESTS
 
 
 namespace ArMemMemoryTest
@@ -231,22 +383,22 @@ BOOST_AUTO_TEST_SUITE_END()
 
 BOOST_AUTO_TEST_CASE(test_key_ctors)
 {
-    armem::wm::EntityInstance instance(10);
+    wm::EntityInstance instance(10);
     BOOST_CHECK_EQUAL(instance.index(), 10);
 
-    armem::wm::EntitySnapshot snapshot(armem::Time::milliSeconds(100));
+    wm::EntitySnapshot snapshot(armem::Time::milliSeconds(100));
     BOOST_CHECK_EQUAL(snapshot.time(), armem::Time::milliSeconds(100));
 
-    armem::wm::Entity entity("entity");
+    wm::Entity entity("entity");
     BOOST_CHECK_EQUAL(entity.name(), "entity");
 
-    armem::wm::ProviderSegment provSeg("provSeg");
+    wm::ProviderSegment provSeg("provSeg");
     BOOST_CHECK_EQUAL(provSeg.name(), "provSeg");
 
-    armem::wm::CoreSegment coreSeg("coreSeg");
+    wm::CoreSegment coreSeg("coreSeg");
     BOOST_CHECK_EQUAL(coreSeg.name(), "coreSeg");
 
-    armem::wm::Memory memory("memory");
+    wm::Memory memory("memory");
     BOOST_CHECK_EQUAL(memory.name(), "memory");
 }
 
@@ -278,19 +430,19 @@ void checkMoved_d_ltm(const T& moved)
 }
 
 template <>
-struct CustomChecks<armem::wm::EntityInstance>
+struct CustomChecks<wm::EntityInstance>
 {
-    static void checkEqual(const armem::wm::EntityInstance& lhs, const armem::wm::EntityInstance& rhs)
+    static void checkEqual(const wm::EntityInstance& lhs, const wm::EntityInstance& rhs)
     {
         BOOST_CHECK_EQUAL(lhs.metadata(), rhs.metadata());
         BOOST_CHECK_EQUAL(lhs.data(), rhs.data());
     }
-    static void checkMoved(const armem::wm::EntityInstance& moved)
+    static void checkMoved(const wm::EntityInstance& moved)
     {
         BOOST_CHECK_EQUAL(moved.data(), nullptr);
     }
 };
-template <>
+/*template <>
 struct CustomChecks<armem::d_ltm::EntityInstance>
 {
     static void checkEqual(const armem::d_ltm::EntityInstance& lhs, const armem::d_ltm::EntityInstance& rhs)
@@ -361,7 +513,7 @@ struct CustomChecks<armem::d_ltm::Memory>
     {
         checkMoved_d_ltm(moved);
     }
-};
+};*/
 
 
 struct CopyMoveCtorsOpsTestBase
@@ -495,11 +647,9 @@ struct CopyMoveCtorsOpsTest : public CopyMoveCtorsOpsTestBase
     void reset() override
     {
         in = T {id};
-        if constexpr(std::is_same_v<T, armem::wm::Memory>
-                     || std::is_same_v<T, armem::ltm::Memory>
-                     || std::is_same_v<T, armem::d_ltm::Memory>)
+        if constexpr(std::is_same_v<T, wm::Memory>)
         {
-            in._addMissingCoreSegmentDuringUpdate = true;
+            in.addCoreSegment("C");
         }
         {
             armem::EntityUpdate update;
@@ -596,29 +746,29 @@ struct CopyMoveCtorsOpsTest : public CopyMoveCtorsOpsTestBase
 BOOST_AUTO_TEST_CASE(test_copy_move_ctors_ops)
 {
     {
-        InstanceCopyMoveCtorsOpsTest<armem::wm::EntityInstance>().test();
-        CopyMoveCtorsOpsTest<armem::wm::EntitySnapshot>().test();
-        CopyMoveCtorsOpsTest<armem::wm::Entity>().test();
-        CopyMoveCtorsOpsTest<armem::wm::ProviderSegment>().test();
-        CopyMoveCtorsOpsTest<armem::wm::CoreSegment>().test();
-        CopyMoveCtorsOpsTest<armem::wm::Memory>().test();
+        InstanceCopyMoveCtorsOpsTest<wm::EntityInstance>().test();
+        CopyMoveCtorsOpsTest<wm::EntitySnapshot>().test();
+        CopyMoveCtorsOpsTest<wm::Entity>().test();
+        CopyMoveCtorsOpsTest<wm::ProviderSegment>().test();
+        CopyMoveCtorsOpsTest<wm::CoreSegment>().test();
+        CopyMoveCtorsOpsTest<wm::Memory>().test();
     }
-    {
+    /*{
         InstanceCopyMoveCtorsOpsTest<armem::ltm::EntityInstance>().test();
         CopyMoveCtorsOpsTest<armem::ltm::EntitySnapshot>().test();
         CopyMoveCtorsOpsTest<armem::ltm::Entity>().test();
         CopyMoveCtorsOpsTest<armem::ltm::ProviderSegment>().test();
         CopyMoveCtorsOpsTest<armem::ltm::CoreSegment>().test();
         CopyMoveCtorsOpsTest<armem::ltm::Memory>().test();
-    }
-    {
+    }*/
+    /*{
         InstanceCopyMoveCtorsOpsTest<armem::d_ltm::EntityInstance>().test();
         CopyMoveCtorsOpsTest<armem::d_ltm::EntitySnapshot>().test();
         CopyMoveCtorsOpsTest<armem::d_ltm::Entity>().test();
         CopyMoveCtorsOpsTest<armem::d_ltm::ProviderSegment>().test();
         CopyMoveCtorsOpsTest<armem::d_ltm::CoreSegment>().test();
         CopyMoveCtorsOpsTest<armem::d_ltm::Memory>().test();
-    }
+    }*/
 }
 
 
@@ -627,7 +777,7 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
 {
     armem::EntityUpdate update;
 
-    armem::wm::Memory memory("Memory");
+    wm::Memory memory("Memory");
     BOOST_CHECK_EQUAL(memory.name(), "Memory");
     {
         update.entityID = armem::MemoryID::fromString("OtherMemory/SomeSegment");
@@ -636,7 +786,7 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
         BOOST_CHECK_THROW(memory.update(update), armem::error::MissingEntry);
     }
 
-    armem::wm::CoreSegment& coreSegment = memory.addCoreSegment("ImageRGB");
+    wm::CoreSegment& coreSegment = memory.addCoreSegment("ImageRGB");
     BOOST_CHECK_EQUAL(coreSegment.name(), "ImageRGB");
     BOOST_CHECK(memory.hasCoreSegment(coreSegment.name()));
     {
@@ -647,7 +797,7 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
         //BOOST_CHECK_THROW(coreSegment.update(update), armem::error::MissingEntry);
     }
 
-    armem::wm::ProviderSegment& providerSegment = coreSegment.addProviderSegment("SomeRGBImageProvider");
+    wm::ProviderSegment& providerSegment = coreSegment.addProviderSegment("SomeRGBImageProvider");
     BOOST_CHECK_EQUAL(providerSegment.name(), "SomeRGBImageProvider");
     BOOST_CHECK(coreSegment.hasProviderSegment(providerSegment.name()));
     {
@@ -671,12 +821,12 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
     BOOST_CHECK(providerSegment.hasEntity("image"));
     BOOST_CHECK(!providerSegment.hasEntity("other_image"));
 
-    armem::wm::Entity& entity = providerSegment.getEntity("image");
+    wm::Entity& entity = providerSegment.getEntity("image");
     BOOST_CHECK_EQUAL(entity.name(), "image");
     BOOST_CHECK_EQUAL(entity.size(), 1);
     BOOST_CHECK(entity.hasSnapshot(update.timeCreated));
 
-    armem::wm::EntitySnapshot& entitySnapshot = entity.getSnapshot(update.timeCreated);
+    wm::EntitySnapshot& entitySnapshot = entity.getSnapshot(update.timeCreated);
     BOOST_CHECK_EQUAL(entitySnapshot.size(), update.instancesData.size());
 
 
@@ -753,7 +903,7 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     std::vector<std::string> entityNames = { "A", "B" };
 
     // Fill entities and histories with unlimited size.
-    for (const auto& name : entityNames)
+    for (const std::string& name : entityNames)
     {
         update.entityID.entityName = name;
 
@@ -805,11 +955,12 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     providerSegment.setMaxHistorySize(-1);
 
     entityNames.push_back("C");
-    for (const auto& name : entityNames)
+    for (const std::string& name : entityNames)
     {
         update.entityID.entityName = name;
         update.timeCreated = armem::Time::milliSeconds(5000);
         providerSegment.update(update);
+        BOOST_CHECK_EQUAL(providerSegment.getEntity(name).getMaxHistorySize(), -1);
         BOOST_CHECK_EQUAL(providerSegment.getEntity(name).size(), 3);
     }
 }
diff --git a/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
index 656842b3dcd23d49a84a51a04fc02143c14cada2..13d050572342263d273dc5080f1631cec15faf05 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
@@ -30,6 +30,8 @@
 #include <RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h>
 #include <RobotAPI/libraries/armem/server/query_proc/wm.h>
 
+#include <ArmarXCore/core/exceptions/LocalException.h>
+
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 #include <SimoxUtility/algorithm/string.h>
 
@@ -123,8 +125,9 @@ BOOST_AUTO_TEST_CASE(test_entity_Single_latest)
     {
         BOOST_CHECK_EQUAL(result.name(), entity.name());
         BOOST_CHECK_EQUAL(result.size(), 1);
-        const armem::wm::EntitySnapshot& first = result.getFirstSnapshotAfterOrAt(armem::Time::microSeconds(0));
-        BOOST_CHECK_EQUAL(first.time(), armem::Time::microSeconds(5000));
+        const armem::wm::EntitySnapshot* first = result.findFirstSnapshotAfterOrAt(armem::Time::microSeconds(0));
+        BOOST_REQUIRE_NE(first, nullptr);
+        BOOST_CHECK_EQUAL(first->time(), armem::Time::microSeconds(5000));
     }
 }
 
diff --git a/source/RobotAPI/libraries/armem/test/CMakeLists.txt b/source/RobotAPI/libraries/armem/test/CMakeLists.txt
index b10935f95fedd6a1309248007422c53783d2c9e4..43b75650492c4d69a6fb08d5a550796e5dfd3a3b 100644
--- a/source/RobotAPI/libraries/armem/test/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/test/CMakeLists.txt
@@ -2,10 +2,11 @@
 # Libs required for the tests
 SET(LIBS ${LIBS} ArmarXCore ${LIB_NAME})
 
+armarx_add_test(ArMemForEachTest ArMemForEachTest.cpp "${LIBS}")
+armarx_add_test(ArMemGetFindTest ArMemGetFindTest.cpp "${LIBS}")
 armarx_add_test(ArMemIceConversionsTest ArMemIceConversionsTest.cpp "${LIBS}")
+armarx_add_test(ArMemLTMTest ArMemLTMTest.cpp "${LIBS}")
 armarx_add_test(ArMemMemoryTest ArMemMemoryTest.cpp "${LIBS}")
 armarx_add_test(ArMemMemoryIDTest ArMemMemoryIDTest.cpp "${LIBS}")
-armarx_add_test(ArMemQueryTest ArMemQueryTest.cpp "${LIBS}")
-armarx_add_test(ArMemLTMTest ArMemLTMTest.cpp "${LIBS}")
 armarx_add_test(ArMemQueryBuilderTest ArMemQueryBuilderTest.cpp "${LIBS}")
-armarx_add_test(ArMemForEachTest ArMemForEachTest.cpp "${LIBS}")
+armarx_add_test(ArMemQueryTest ArMemQueryTest.cpp "${LIBS}")
diff --git a/source/RobotAPI/libraries/armem_gui/CMakeLists.txt b/source/RobotAPI/libraries/armem_gui/CMakeLists.txt
index 696c6db777d8512d49168682c8a368243f2b930d..2a781dd3989d5731393e1b5d9304b06f467611a4 100644
--- a/source/RobotAPI/libraries/armem_gui/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_gui/CMakeLists.txt
@@ -18,10 +18,11 @@ set(SOURCES
     gui_utils.cpp
     lifecycle.cpp
 
-    MemoryControlWidget.cpp
     MemoryViewer.cpp
     PeriodicUpdateWidget.cpp
 
+    disk/ControlWidget.cpp
+
     instance/GroupBox.cpp
     instance/ImageView.cpp
     instance/InstanceView.cpp
@@ -53,7 +54,6 @@ set(HEADERS
     gui_utils.h
     lifecycle.h
 
-    MemoryControlWidget.h
     MemoryViewer.h
     PeriodicUpdateWidget.h
     TreeWidgetBuilder.h
@@ -61,6 +61,8 @@ set(HEADERS
     PeriodicUpdateWidget.h
     TreeWidgetBuilder.h
 
+    disk/ControlWidget.h
+
     instance/GroupBox.h
     instance/ImageView.h
     instance/InstanceView.h
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp
deleted file mode 100644
index 38e4d8c88719541e7c4fca92964cfb069c22ba5e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp
+++ /dev/null
@@ -1,87 +0,0 @@
-#include "MemoryControlWidget.h"
-
-#include <QPushButton>
-#include <QLineEdit>
-#include <QTimer>
-#include <QHBoxLayout>
-#include <QFileDialog>
-
-#include <cmath>
-
-
-namespace armarx::armem::gui
-{
-
-    MemoryControlWidget::MemoryControlWidget()
-    {
-        setSizePolicy(QSizePolicy::Policy::Minimum, QSizePolicy::Policy::Fixed);
-
-        auto vlayout = new QVBoxLayout();
-        auto hlayout1 = new QHBoxLayout();
-        auto hlayout2 = new QHBoxLayout();
-
-        hlayout1->setContentsMargins(10, 2, 10, 2);
-        hlayout2->setContentsMargins(10, 2, 10, 2);
-
-        const int margin = 0;
-        vlayout->setContentsMargins(margin, margin, margin, margin);
-
-        _lineEdit = new QLineEdit("/tmp/MemoryExport", this);
-        _lineEdit->setSizePolicy(QSizePolicy::Ignored, QSizePolicy::Preferred);
-        _lineEdit->setMinimumWidth(150);
-
-        _openFileBrowserButton = new QPushButton("Search files", this);
-
-        _storeOnDiskButton = new QPushButton("Store query (Disk)", this);
-        _storeInLTMButton = new QPushButton("Store query (LTM)", this);
-
-        hlayout1->addWidget(_lineEdit);
-        hlayout1->addWidget(_openFileBrowserButton);
-
-        hlayout2->addWidget(_storeOnDiskButton);
-        hlayout2->addWidget(_storeInLTMButton);
-
-        vlayout->addItem(hlayout1);
-        vlayout->addItem(hlayout2);
-
-        this->setLayout(vlayout);
-        // Private connections.
-
-        // Public connections.
-        connect(_openFileBrowserButton, &QPushButton::pressed, this, &This::openFileBrowser);
-        connect(_storeInLTMButton, &QPushButton::pressed, this, &This::storeInLTM);
-        connect(_storeOnDiskButton, &QPushButton::pressed, this, &This::storeOnDisk);
-    }
-
-    void MemoryControlWidget::openFileBrowser()
-    {
-        QFileDialog dialog;
-        dialog.setFileMode(QFileDialog::DirectoryOnly);
-        //dialog.setOption(QFileDialog::DontUseNativeDialog, true);
-        dialog.setOption(QFileDialog::ShowDirsOnly, false);
-        dialog.exec();
-        QString open = dialog.directory().path();
-        _lineEdit->setText(open);
-    }
-
-    QLineEdit* MemoryControlWidget::pathInputBox()
-    {
-        return _lineEdit;
-    }
-
-    QString MemoryControlWidget::getEnteredPath()
-    {
-        return _lineEdit->text();
-    }
-
-    QPushButton* MemoryControlWidget::storeInLTMButton()
-    {
-        return _storeInLTMButton;
-    }
-
-    QPushButton* MemoryControlWidget::storeOnDiskButton()
-    {
-        return _storeOnDiskButton;
-    }
-}
-
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h
deleted file mode 100644
index c6b156db313b01180a7f5884959ffc21b0a73f9d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h
+++ /dev/null
@@ -1,55 +0,0 @@
-#pragma once
-
-#include <QWidget>
-
-class QPushButton;
-class QLineEdit;
-class QFileDialog;
-
-namespace armarx::armem::gui
-{
-
-    class MemoryControlWidget : public QWidget
-    {
-        Q_OBJECT
-        using This = MemoryControlWidget;
-
-    public:
-
-        MemoryControlWidget();
-
-        QLineEdit* pathInputBox();
-        QString getEnteredPath();
-
-        QPushButton* openFileBrowserButton();
-
-        QPushButton* storeInLTMButton();
-        QPushButton* storeOnDiskButton();
-
-    public slots:
-
-        void openFileBrowser();
-
-    signals:
-
-        void storeInLTM();
-        void storeOnDisk();
-
-    private slots:
-
-
-    signals:
-
-
-    private:
-
-        QLineEdit* _lineEdit;
-
-        QPushButton* _openFileBrowserButton;
-
-        QPushButton* _storeInLTMButton;
-        QPushButton* _storeOnDiskButton;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
index 802de477cdd143051b6e45f8f2c4d995ebfa4e29..d52b8c8fd6347867c81a7c4f773fa3aabe8bd548 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
+++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
@@ -3,10 +3,8 @@
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem_gui/gui_utils.h>
 
-#include <RobotAPI/libraries/armem/core/diskmemory/Memory.h>
-
-#include <RobotAPI/libraries/armem/server/query_proc/diskmemory.h>
 #include <RobotAPI/libraries/armem/server/query_proc/wm.h>
+#include <RobotAPI/libraries/armem/server/query_proc/ltm.h>
 
 #include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
 
@@ -18,6 +16,7 @@
 
 #include <QBoxLayout>
 #include <QCheckBox>
+#include <QClipboard>
 #include <QDialog>
 #include <QGroupBox>
 #include <QMenu>
@@ -25,7 +24,6 @@
 #include <QLayout>
 #include <QSettings>
 
-#include <filesystem>
 #include <iomanip>
 
 
@@ -33,9 +31,9 @@ namespace armarx::armem::gui
 {
     MemoryViewer::MemoryViewer(
         QBoxLayout* updateWidgetLayout,
-        QBoxLayout* memoryControlWidgetLayout,
         QGroupBox* memoryGroupBox, QLayout* memoryGroupBoxParentLayout,
         QGroupBox* instanceGroupBox, QLayout* instanceGroupBoxParentLayout,
+        QBoxLayout* diskControlWidgetLayout,
         QLabel* statusLabel
     )
     {
@@ -48,6 +46,10 @@ namespace armarx::armem::gui
         connect(statusLabel, &QLabel::customContextMenuRequested, [statusLabel](const QPoint & pos)
         {
             QMenu menu(statusLabel);
+            menu.addAction("Copy to clipboard", [statusLabel]()
+            {
+                QApplication::clipboard()->setText(statusLabel->text());
+            });
             menu.addAction("Clear status", [statusLabel]()
             {
                 statusLabel->clear();
@@ -61,14 +63,6 @@ namespace armarx::armem::gui
         updateWidget = new armem::gui::PeriodicUpdateWidget(2.0, 60);
         updateWidgetLayout->insertWidget(0, updateWidget);
 
-        // LTM Control
-        if (memoryControlWidgetLayout)
-        {
-            this->memoryControlWidgetLayout = memoryControlWidgetLayout;
-            memoryControlWidget = new armem::gui::MemoryControlWidget();
-            memoryControlWidgetLayout->addWidget(memoryControlWidget);
-        }
-
         // Memory View
         memoryGroup = new armem::gui::MemoryGroupBox();
         armarx::gui::replaceWidget(memoryGroupBox, memoryGroup, memoryGroupBoxParentLayout);
@@ -80,15 +74,25 @@ namespace armarx::armem::gui
         this->instanceGroup->setStatusLabel(statusLabel);
         ARMARX_CHECK_NULL(instanceGroupBox);
 
+        // Disk Control
+        if (diskControlWidgetLayout)
+        {
+            this->diskControlLayout = diskControlWidgetLayout;
+            diskControl = new armem::gui::disk::ControlWidget();
+            diskControlWidgetLayout->addWidget(diskControl);
+        }
+
         // Connections
         //connect(this, &This::connected, this, &This::updateMemory);
 
-        connect(memoryControlWidget, &armem::gui::MemoryControlWidget::storeOnDisk, this, &This::storeOnDisk);
-        connect(memoryControlWidget, &armem::gui::MemoryControlWidget::storeInLTM, this, &This::storeInLTM);
+        connect(diskControl, &armem::gui::disk::ControlWidget::requestedStoreOnDisk, this, &This::storeOnDisk);
+        connect(diskControl, &armem::gui::disk::ControlWidget::requestedLoadFromDisk, this, &This::loadFromDisk);
 
         connect(this, &This::connected, this, &This::updateMemories);
         connect(updateWidget, &armem::gui::PeriodicUpdateWidget::update, this, &This::updateMemories);
 
+        connect(memoryGroup->queryWidget(), &armem::gui::QueryWidget::storeInLTM, this, &This::storeInLTM);
+
         connect(this, &This::memoryDataChanged, this, &This::updateMemoryTree);
         connect(memoryGroup->tree(), &armem::gui::MemoryTreeWidget::selectedItemChanged, this, &This::updateInstanceTree);
 
@@ -97,9 +101,9 @@ namespace armarx::armem::gui
         connect(instanceGroup->view, &armem::gui::InstanceView::memoryIdResolutionRequested, this, &This::resolveMemoryID);
     }
 
-    void MemoryViewer::setLogTag(const std::string& tag)
+    void MemoryViewer::setLogTag(const std::string& _tag)  // Leading _ silences a warning
     {
-        Logging::setTag(tag);
+        Logging::setTag(_tag);
     }
 
     void MemoryViewer::onInit(ManagedIceObject& component)
@@ -168,7 +172,7 @@ namespace armarx::armem::gui
 
     void MemoryViewer::storeInLTM()
     {
-        TIMING_START(MemoryStore);
+        TIMING_START(MemoryStore)
 
         for (auto& [name, reader] : memoryReaders)
         {
@@ -177,45 +181,37 @@ namespace armarx::armem::gui
             reader.readAndStore(input);
         }
 
-        TIMING_END_STREAM(MemoryStore, ARMARX_VERBOSE);
+        TIMING_END_STREAM(MemoryStore, ARMARX_VERBOSE)
     }
 
-    void MemoryViewer::storeOnDisk()
+    void MemoryViewer::storeOnDisk(QString directory)
     {
-        TIMING_START(MemoryExport);
-        QString qs = memoryControlWidget->getEnteredPath();
-        std::string utf8_text = qs.toUtf8().constData();
+        TIMING_START(MemoryExport)
 
-        if (not utf8_text.empty())
-        {
-            ARMARX_IMPORTANT << "Exporting all memories at '" << utf8_text << "'.";
+        std::string status;
+        diskControl->storeOnDisk(directory, memoryData, &status);
 
-            std::filesystem::path p(utf8_text);
-            if (std::filesystem::is_regular_file(p))
-            {
-                ARMARX_WARNING << "Could not export a memory at '" << utf8_text << "'. Skipping export.";
-                return;
-            }
+        statusLabel->setText(QString::fromStdString(status));
+        TIMING_END_STREAM(MemoryExport, ARMARX_VERBOSE)
+    }
 
-            std::filesystem::create_directories(p);
-            for (auto& [name, reader] : memoryReaders)
-            {
-                armem::client::QueryInput input = memoryGroup->queryWidget()->queryInput();
-                armem::client::QueryResult result = reader.query(input);
 
-                armem::d_ltm::Memory dMem(name);
-                dMem.reload(p / name);
-                dMem.append(result.memory);
-            }
-        }
-        else
+    void MemoryViewer::loadFromDisk(QString directory)
+    {
+        std::string status;
+        std::map<std::string, wm::Memory> data =
+            diskControl->loadFromDisk(directory, memoryGroup->queryWidget()->queryInput(), &status);
+
+        for (auto& [name, memory] : data)
         {
-            ARMARX_WARNING << "The path is empty. Could not export the memory in nirvana.";
+            this->memoryData[name] = std::move(memory);
         }
+        statusLabel->setText(QString::fromStdString(status));
 
-        TIMING_END_STREAM(MemoryExport, ARMARX_VERBOSE);
+        emit memoryDataChanged();
     }
 
+
     void MemoryViewer::updateMemories()
     {
         int errorCount = 0;
@@ -223,66 +219,38 @@ namespace armarx::armem::gui
         memoryData.clear();
         memoryReaders = mns.getAllReaders(true);
 
-        std::filesystem::path path(memoryControlWidget->getEnteredPath().toStdString());
-
         armem::client::QueryInput input = memoryGroup->queryWidget()->queryInput();
 
-        // first check if the local file system should be queried
-        if (memoryGroup->queryWidget()->alsoQueryLocalDisk())
+        for (auto& [name, reader] : memoryReaders)
         {
-            if (std::filesystem::is_directory(path))
+            TIMING_START(MemoryQuery)
             {
-                for (const auto& directory : std::filesystem::directory_iterator(path))
+                armem::client::QueryResult result = reader.query(input);
+                if (result.success)
                 {
-                    if (directory.is_directory())
-                    {
-                        std::string k = directory.path().filename();
-                        armem::d_ltm::Memory dMem(k);
-                        dMem.reload(path / k);
-
-                        input.addQueryTargetToAll(armem::query::data::QueryTarget::LTM); // We use LTM as query target for the disk
-
-                        armem::server::query_proc::d_ltm::MemoryQueryProcessor d_ltm_processor;
-                        dMem = d_ltm_processor.process(input.toIce(), dMem);
-
-                        wm::Memory converted = dMem.convert();
-                        memoryData[k] = std::move(converted);
-                    }
+                    memoryData[name] = result.memory;
                 }
-            }
-            else
-            {
-                ARMARX_WARNING << "Could not import a memory from '" << path << "'. Skipping import.";
-            }
-        }
-        else
-        {
-            for (auto& [name, reader] : memoryReaders)
-            {
-                TIMING_START(MemoryQuery);
+                else
                 {
-                    armem::client::QueryResult result = reader.query(input);
-                    if (result.success)
-                    {
-                        memoryData[name] = result.memory;
-                    }
-                    else
-                    {
-                        ARMARX_INFO << "A query for memory '" << name << "' produced an error: " << result.errorMessage;
-                        errorCount++;
-                    }
+                    ARMARX_WARNING << "A query for memory '" << name << "' produced an error: " << result.errorMessage;
+                    errorCount++;
                 }
-                TIMING_END_STREAM(MemoryQuery, ARMARX_VERBOSE);
+            }
+            TIMING_END_STREAM(MemoryQuery, ARMARX_VERBOSE)
 
-                if (debugObserver)
-                {
-                    debugObserver->setDebugDatafield(Logging::tag.tagName, "Memory Query [ms]", new Variant(MemoryQuery.toMilliSecondsDouble()));
-                }
+            if (debugObserver)
+            {
+                debugObserver->setDebugDatafield(Logging::tag.tagName, "Memory Query [ms]", new Variant(MemoryQuery.toMilliSecondsDouble()));
             }
         }
 
         emit memoryDataChanged();
 
+        updateStatusLabel(errorCount);
+    }
+
+    void MemoryViewer::updateStatusLabel(int errorCount)
+    {
         // Code to output status label information
         if (statusLabel and errorCount > 0)
         {
@@ -325,7 +293,7 @@ namespace armarx::armem::gui
                 {
                     try
                     {
-                        snapshot = &data->getEntitySnapshot(id);
+                        snapshot = &data->getSnapshot(id);
                     }
                     catch (const armem::error::ArMemError& e)
                     {
@@ -366,18 +334,17 @@ namespace armarx::armem::gui
         std::optional<wm::EntityInstance> instance;
         try
         {
-            const wm::Memory* data = getSingleMemoryData(id.memoryName);
-            if (data)
+            if (const wm::Memory* data = getSingleMemoryData(id.memoryName))
             {
                 segmentType = data->getProviderSegment(id).aronType();
 
                 if (id.hasInstanceIndex())
                 {
-                    instance = data->getEntityInstance(id);
+                    instance = data->getInstance(id);
                 }
                 else if (id.hasTimestamp())
                 {
-                    instance = data->getEntitySnapshot(id).getInstance(0);
+                    instance = data->getSnapshot(id).getInstance(0);
                 }
                 else
                 {
@@ -385,13 +352,12 @@ namespace armarx::armem::gui
                 }
             }
         }
-        catch (const armem::error::ArMemError& e)
+        catch (const armem::error::ArMemError&)
         {
             // May be handled by remote lookup
-            (void) e;
         }
 
-        if (!instance)
+        if (not instance)
         {
             try
             {
@@ -425,9 +391,9 @@ namespace armarx::armem::gui
 
         // if convMap.empty(), we still need to update to remove existing entries.
 
-        TIMING_START(GuiUpdate);
+        TIMING_START(GuiUpdate)
         memoryGroup->tree()->update(convMap);
-        TIMING_END_STREAM(GuiUpdate, ARMARX_VERBOSE);
+        TIMING_END_STREAM(GuiUpdate, ARMARX_VERBOSE)
 
         if (debugObserver)
         {
@@ -451,7 +417,7 @@ namespace armarx::armem::gui
 
     void MemoryViewer::writeConfigDialog(SimpleConfigDialog* dialog)
     {
-        dialog->addProxyFinder<armarx::armem::mns::MemoryNameSystemInterfacePrx>({CONFIG_KEY_MEMORY, "MemoryNameSystem", "*"});
+        dialog->addProxyFinder<armarx::armem::mns::MemoryNameSystemInterfacePrx>({CONFIG_KEY_MEMORY, "MemoryNameSystem", "MemoryNameSystem"});
         dialog->addProxyFinder<armarx::DebugObserverInterfacePrx>({CONFIG_KEY_DEBUG_OBSERVER, "Debug Observer", "DebugObserver"});
     }
 
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryViewer.h b/source/RobotAPI/libraries/armem_gui/MemoryViewer.h
index 71870bdd565b0b8a585808f5f0e9f0f43c93d315..f2fba34389ee9887d090d72b1ff50768b8d097b5 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.h
+++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.h
@@ -10,11 +10,11 @@
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
 #include <RobotAPI/libraries/armem/client/Reader.h>
+#include <RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.h>
 #include <RobotAPI/libraries/armem_gui/lifecycle.h>
 #include <RobotAPI/libraries/armem_gui/instance/GroupBox.h>
 #include <RobotAPI/libraries/armem_gui/memory/GroupBox.h>
-#include <RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.h>
-#include <RobotAPI/libraries/armem_gui/MemoryControlWidget.h>
+#include <RobotAPI/libraries/armem_gui/disk/ControlWidget.h>
 
 
 class QBoxLayout;
@@ -47,9 +47,9 @@ namespace armarx::armem::gui
 
         MemoryViewer(
             QBoxLayout* updateWidgetLayout,
-            QBoxLayout* ltmControlWidgetLayout,
             QGroupBox* memoryGroupBox, QLayout* memoryGroupBoxParentLayout,
             QGroupBox* instanceGroupBox, QLayout* instanceGroupBoxParentLayout,
+            QBoxLayout* diskControlWidgetLayout,
             QLabel* statusLabel
         );
 
@@ -70,9 +70,12 @@ namespace armarx::armem::gui
 
         void resolveMemoryID(const MemoryID& id);
 
-        // LTMControlWidget
+        // Disk Control
+        void storeOnDisk(QString directory);
+        void loadFromDisk(QString directory);
+
         void storeInLTM();
-        void storeOnDisk();
+
 
 
     signals:
@@ -101,6 +104,7 @@ namespace armarx::armem::gui
         void onDisconnect(ManagedIceObject& component);
 
         const armem::wm::Memory* getSingleMemoryData(const std::string& memoryName);
+        void updateStatusLabel(int errorCount);
 
 
     public:
@@ -114,8 +118,8 @@ namespace armarx::armem::gui
         QLayout* updateWidgetLayout = nullptr;
         armem::gui::PeriodicUpdateWidget* updateWidget = nullptr;
 
-        QLayout* memoryControlWidgetLayout = nullptr;
-        armem::gui::MemoryControlWidget* memoryControlWidget = nullptr;
+        QLayout* diskControlLayout = nullptr;
+        armem::gui::disk::ControlWidget* diskControl = nullptr;
 
         armem::gui::MemoryGroupBox* memoryGroup = nullptr;
 
diff --git a/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e361438099e5e2a34b80d5f64f810a23fb3270d2
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp
@@ -0,0 +1,196 @@
+#include "ControlWidget.h"
+
+#include <RobotAPI/libraries/armem/server/ltm/disk/MemoryManager.h>
+#include <RobotAPI/libraries/armem/server/query_proc/ltm.h>
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <QHBoxLayout>
+#include <QSpacerItem>
+#include <QFileDialog>
+#include <QPushButton>
+
+#include <filesystem>
+
+#include <cmath>
+
+
+namespace armarx::armem::gui::disk
+{
+
+    ControlWidget::ControlWidget()
+    {
+        _latestDirectory = QString::fromStdString("/tmp/MemoryExport");
+
+        _loadFromDiskButton = new QPushButton(" Load from Disk", this);
+        _loadFromDiskButton->setIcon(QIcon(":/icons/document-open.svg"));
+        _storeOnDiskButton = new QPushButton(" Store on Disk", this);
+        _storeOnDiskButton->setIcon(QIcon(":/icons/document-save.svg"));
+
+        // Allow horizontal shrinking of buttons
+        std::vector<QPushButton*> buttons { _storeOnDiskButton, _loadFromDiskButton };
+        for (QPushButton* button : buttons)
+        {
+            button->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::Fixed);
+        }
+
+        this->setSizePolicy(QSizePolicy::Policy::Preferred, QSizePolicy::Policy::Fixed);
+
+        QHBoxLayout* layout = new QHBoxLayout();
+        this->setLayout(layout);
+
+        const int margin = 0;
+        layout->setContentsMargins(margin, margin, margin, margin);
+
+        layout->addWidget(_loadFromDiskButton);
+        layout->addWidget(_storeOnDiskButton);
+
+
+        // Connections
+
+        connect(_loadFromDiskButton, &QPushButton::pressed, [this]()
+        {
+            QString directory = chooseDirectoryDialog();
+            if (directory.size() > 0)
+            {
+                emit requestedLoadFromDisk(directory);
+            }
+        });
+        connect(_storeOnDiskButton, &QPushButton::pressed, [this]()
+        {
+            QString directory = chooseDirectoryDialog();
+            if (directory.size() > 0)
+            {
+                emit requestedStoreOnDisk(directory);
+            }
+        });
+    }
+
+
+    static
+    const std::string&
+    handleSingular(int num, const std::string& singular, const std::string& plural)
+    {
+        return num == 1 ? singular : plural;
+    }
+
+
+    void
+    ControlWidget::storeOnDisk(
+        QString directory,
+        const std::map<std::string, wm::Memory> memoryData,
+        std::string* outStatus)
+    {
+        std::filesystem::path path(directory.toUtf8().constData());
+        ARMARX_CHECK_POSITIVE(path.string().size());  // An empty path indicates an error.
+
+        std::stringstream status;
+        if (std::filesystem::is_regular_file(path))
+        {
+            status << "Could not export memories contents to " << path << ": Cannot overwrite existing file.";
+        }
+        else
+        {
+            int numStored = 0;
+            for (const auto& [name, data] : memoryData)
+            {
+                if (std::filesystem::is_regular_file(path / name))
+                {
+                    status << "Could not export memory '" << name << "' to " << path << ": Cannot overwrite existing file.\n";
+                }
+                else
+                {
+                    std::filesystem::create_directories(path / name);
+
+                    armem::server::ltm::disk::MemoryManager manager;
+                    manager.setName(name);
+                    manager.setBasePath(path / name);
+                    manager.reload();
+                    manager.append(data);
+
+                    numStored++;
+                }
+            }
+            status << "Exported " << numStored << " " << handleSingular(numStored, "memory", "memories") << " to " << path << ".";
+        }
+
+        if (outStatus)
+        {
+            *outStatus = status.str();
+        }
+    }
+
+
+    std::map<std::string, wm::Memory>
+    ControlWidget::loadFromDisk(
+        QString directory,
+        const armem::client::QueryInput& _queryInput,
+        std::string* outStatus)
+    {
+        std::filesystem::path path(directory.toUtf8().constData());
+
+        std::map<std::string, wm::Memory> memoryData;
+        std::stringstream status;
+
+        if (not std::filesystem::is_directory(path))
+        {
+            status << "Could not import a memory from " << path << ". Skipping import.";
+        }
+        else
+        {
+            // We use LTM as query target for the disk
+            armem::client::QueryInput queryInput = _queryInput;
+            queryInput.addQueryTargetToAll(armem::query::data::QueryTarget::LTM);
+            const query::data::Input queryIce = queryInput.toIce();
+
+            int numLoaded = 0;
+            for (const auto& dir : std::filesystem::directory_iterator(path))
+            {
+                if (dir.is_directory())
+                {
+                    const std::string key = dir.path().filename();
+                    armem::server::ltm::disk::MemoryManager manager;
+                    manager.setName(key);
+                    manager.setBasePath(path / key);
+
+                    manager.reload();
+
+                    armem::server::query_proc::ltm::MemoryQueryProcessor ltm_processor;
+                    armem::wm::Memory query_res = ltm_processor.process(queryIce, manager.getCacheAndLutNotConverted());
+
+                    manager.convert(query_res);
+                    memoryData[key] = std::move(query_res);
+
+                    numLoaded++;
+                }
+            }
+            status << "Loaded " << numLoaded << " " << handleSingular(numLoaded, "memory", "memories") << " from " << path << ".";
+        }
+
+        if (outStatus)
+        {
+            *outStatus = status.str();
+        }
+        return memoryData;
+    }
+
+
+    QString ControlWidget::chooseDirectoryDialog()
+    {
+        QFileDialog dialog;
+        dialog.setFileMode(QFileDialog::DirectoryOnly);
+        dialog.setOption(QFileDialog::ShowDirsOnly, false);
+        dialog.setDirectory(_latestDirectory);
+        if (dialog.exec())
+        {
+            _latestDirectory = dialog.directory().path();
+            return _latestDirectory;
+        }
+        else
+        {
+            return QString::fromStdString("");
+        }
+    }
+
+}
+
diff --git a/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.h b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.h
new file mode 100644
index 0000000000000000000000000000000000000000..b14c9b0a0810acbafba74638e6ebd87989e81165
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.h
@@ -0,0 +1,62 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/forward_declarations.h>
+#include <RobotAPI/libraries/armem/client/Query.h>
+
+#include <QWidget>
+#include <QString>
+
+
+class QPushButton;
+
+
+namespace armarx::armem::gui::disk
+{
+
+    class ControlWidget : public QWidget
+    {
+        Q_OBJECT
+        using This = ControlWidget;
+
+    public:
+
+        ControlWidget();
+
+
+        void
+        storeOnDisk(
+            QString directory,
+            const std::map<std::string, wm::Memory> memoryData,
+            std::string* outStatus = nullptr);
+
+        std::map<std::string, wm::Memory>
+        loadFromDisk(
+            QString directory,
+            const armem::client::QueryInput& queryInput,
+            std::string* outStatus = nullptr);
+
+
+    signals:
+
+        void requestedLoadFromDisk(QString directory);
+        void requestedStoreOnDisk(QString directory);
+
+
+    private slots:
+
+        QString chooseDirectoryDialog();
+
+
+    signals:
+
+
+    private:
+
+        QPushButton* _loadFromDiskButton;
+        QPushButton* _storeOnDiskButton;
+
+        QString _latestDirectory;
+
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem_gui/instance/GroupBox.cpp b/source/RobotAPI/libraries/armem_gui/instance/GroupBox.cpp
index ff828d4437f042c7857332ec3957f9b5f55c60a5..6d233680524bef1b515236fb03ec6e7e8e965ec0 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/GroupBox.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/GroupBox.cpp
@@ -15,7 +15,7 @@ namespace armarx::armem::gui::instance
 
         view = new armem::gui::InstanceView();
 
-        useTypeInfoCheckBox = new QCheckBox("Use Type Info", this);
+        useTypeInfoCheckBox = new QCheckBox("Use Type Information", this);
         useTypeInfoCheckBox->setChecked(true);
 
         QHBoxLayout* checkBoxLayout = new QHBoxLayout();
diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
index 2b4ab121dabc7d52188f1d10b8adb501f2c72d32..55370273d39434c43633c3fd2b70f3f3b9c94c75 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
@@ -104,7 +104,7 @@ namespace armarx::armem::gui::instance
         const armem::wm::EntityInstance* instance = nullptr;
         try
         {
-            instance = &memory.getEntityInstance(id);
+            instance = &memory.getInstance(id);
             if (useTypeInfo)
             {
                 aronType = memory.getProviderSegment(id).aronType();
@@ -113,8 +113,7 @@ namespace armarx::armem::gui::instance
         catch (const armem::error::ArMemError& e)
         {
             showErrorMessage(e.what());
-            return;
-        };
+        }
         if (instance)
         {
             update(*instance, aronType);
@@ -175,6 +174,8 @@ namespace armarx::armem::gui::instance
     {
         if (!data)
         {
+            treeItemData->setText(int(Columns::TYPE), QString::fromStdString(""));
+
             armarx::gui::clearItem(treeItemData);
             QTreeWidgetItem* item = new QTreeWidgetItem({"(No data.)"});
             treeItemData->addChild(item);
@@ -189,6 +190,8 @@ namespace armarx::armem::gui::instance
         }
         else
         {
+            treeItemData->setText(int(Columns::TYPE), QString::fromStdString(""));
+
             DataTreeBuilder builder;
             builder.setColumns(int(Columns::KEY), int(Columns::VALUE), int(Columns::TYPE));
             builder.updateTree(treeItemData, data);
diff --git a/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp b/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp
index 0180b51961c795ca4a45fd748078cb5cda1ca663..c548192cb7a98a390f708c8bd7789e51e63089cc 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp
@@ -10,6 +10,28 @@
 const std::string armarx::armem::gui::instance::rawMemoryIDTypeName = armarx::armem::arondto::MemoryID::toAronType()->getName();
 const std::string armarx::armem::gui::instance::sanitizedMemoryIDTypeName = "MemoryID";
 
+
+namespace
+{
+    std::string remove_prefix(const std::string& string, const std::string& prefix)
+    {
+        return simox::alg::starts_with(string, prefix)
+               ? string.substr(prefix.size(), std::string::npos)
+               : string;
+    }
+    std::string remove_wrap(const std::string& string, const std::string& prefix, const std::string& suffix)
+    {
+        if (simox::alg::starts_with(string, prefix) && simox::alg::ends_with(string, suffix))
+        {
+            return string.substr(prefix.size(), string.size() - prefix.size() - suffix.size());
+        }
+        else
+        {
+            return string;
+        }
+    }
+}
+
 std::string armarx::armem::gui::instance::sanitizeTypeName(const std::string& typeName)
 {
     if (typeName == rawMemoryIDTypeName)
@@ -19,15 +41,25 @@ std::string armarx::armem::gui::instance::sanitizeTypeName(const std::string& ty
 
     namespace s = simox::alg;
     std::string n = typeName;
-    n = s::replace_all(n, "Aron", "");
-    n = s::replace_all(n, "Type", "");
-    n = s::replace_all(n, "type::", "");
-    if (s::starts_with(n, "Object<") && s::ends_with(n, ">"))
+    n = s::replace_all(n, "type::Aron", "");
+    n = s::replace_all(n, "data::Aron", "");
+
+    if (false)
     {
-        std::string begin = "Object<";
-        std::string end = ">";
-        n = n.substr(begin.size(), n.size() - begin.size() - end.size());
+        const std::vector<std::string> containers { "Dict", "List", "Object", "Tuple", "Pair", "NDArray" };
+        for (const std::string& s : containers)
+        {
+            n = s::replace_all(n, s + "Type", s);
+        }
     }
+    else
+    {
+        n = s::replace_all(n, "Type", "");
+    }
+
+
+    n = remove_prefix(n, "Aron");
+    n = remove_wrap(n, "Object<", ">");
 
     if (true)
     {
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.cpp b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.cpp
index f837fe2fa6451cf8edd82793f2c6ec773560ce2c..3b624f9404e6eede5d8c6963dc13c885f383782d 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.cpp
@@ -5,6 +5,7 @@
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 #include <RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h>
+#include <RobotAPI/libraries/armem_gui/instance/sanitize_typename.h>
 #include <RobotAPI/libraries/armem_gui/instance/display_visitors/DataDisplayVisitor.h>
 
 
@@ -50,7 +51,7 @@ namespace armarx::armem::gui::instance
         QTreeWidgetItem* item, const std::string& key, aron::datanavigator::Navigator& data)
     {
         const std::string value = armarx::aron::DataDisplayVisitor::getValue(data);
-        setRowTexts(item, key, value, data.getName());
+        setRowTexts(item, key, value, sanitizeTypeName(data.getName()));
     }
 
     DataTreeBuilderBase::DictBuilder DataTreeBuilderBase::getDictBuilder() const
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h
index b225a093d4664d60313b882c1b3de750b48f96e8..d8ce4516b43c7cbccfaff7bfbd5f362d6dbfef0a 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h
@@ -42,6 +42,7 @@ namespace armarx::armem::gui::instance
         void setRowTexts(QTreeWidgetItem* item, const std::string& key, const std::string& value, const std::string& typeName = "") const;
         void setRowTexts(QTreeWidgetItem* item, const std::string& key, aron::datanavigator::Navigator& data);
 
+
     public:
 
         int columnKey = 0;
diff --git a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
index 29c137093ac9c75f0c904c6745c72473c205f1ec..1ff5b509001d5cdb4d095442b4614878396b4157 100644
--- a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
@@ -4,8 +4,6 @@
 
 #include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
 
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
 #include <SimoxUtility/algorithm/string.h>
 
 #include <QHeaderView>
@@ -51,12 +49,12 @@ namespace armarx::armem::gui::memory
 
     void TreeWidget::initBuilders()
     {
-        workingmemoryBuilder.setExpand(true);
-        workingmemoryBuilder.setMakeItemFn([this](const std::string & name, const wm::Memory * memory)
+        memoryBuilder.setExpand(true);
+        memoryBuilder.setMakeItemFn([this](const std::string & name, const wm::Memory * memory)
         {
             return makeItem(name, *memory);
         });
-        workingmemoryBuilder.setUpdateItemFn([this](const std::string&, const wm::Memory * memory, QTreeWidgetItem * memoryItem)
+        memoryBuilder.setUpdateItemFn([this](const std::string&, const wm::Memory * memory, QTreeWidgetItem * memoryItem)
         {
             updateContainerItem(*memory, memoryItem);
             if (memoryItem)
@@ -71,26 +69,26 @@ namespace armarx::armem::gui::memory
             return element.name();
         };
 
-        workingmemoryCoreSegmentBuilder.setExpand(true);
-        workingmemoryCoreSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
-        workingmemoryCoreSegmentBuilder.setMakeItemFn([this](const wm::CoreSegment & coreSeg)
+        coreSegmentBuilder.setExpand(true);
+        coreSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
+        coreSegmentBuilder.setMakeItemFn([this](const wm::CoreSegment & coreSeg)
         {
             return makeItem(coreSeg.name(), coreSeg);
         });
-        workingmemoryCoreSegmentBuilder.setUpdateItemFn([this](const wm::CoreSegment & coreSeg, QTreeWidgetItem * coreSegItem)
+        coreSegmentBuilder.setUpdateItemFn([this](const wm::CoreSegment & coreSeg, QTreeWidgetItem * coreSegItem)
         {
             updateContainerItem(coreSeg, coreSegItem);
             updateChildren(coreSeg, coreSegItem);
             return true;
         });
 
-        workingmemoryProvSegmentBuilder.setExpand(true);
-        workingmemoryProvSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
-        workingmemoryProvSegmentBuilder.setMakeItemFn([this](const wm::ProviderSegment & provSeg)
+        provSegmentBuilder.setExpand(true);
+        provSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
+        provSegmentBuilder.setMakeItemFn([this](const wm::ProviderSegment & provSeg)
         {
             return makeItem(provSeg.name(), provSeg);
         });
-        workingmemoryProvSegmentBuilder.setUpdateItemFn([this](const wm::ProviderSegment & provSeg, QTreeWidgetItem * provSegItem)
+        provSegmentBuilder.setUpdateItemFn([this](const wm::ProviderSegment & provSeg, QTreeWidgetItem * provSegItem)
         {
             updateContainerItem(provSeg, provSegItem);
             updateChildren(provSeg, provSegItem);
@@ -98,46 +96,46 @@ namespace armarx::armem::gui::memory
         });
 
         // entityBuilder.setExpand(true);
-        workingmemoryEntityBuilder.setNameFn(nameFn, int(Columns::KEY));
-        workingmemoryEntityBuilder.setMakeItemFn([this](const wm::Entity & entity)
+        entityBuilder.setNameFn(nameFn, int(Columns::KEY));
+        entityBuilder.setMakeItemFn([this](const wm::Entity & entity)
         {
             return makeItem(entity.name(), entity);
         });
-        workingmemoryEntityBuilder.setUpdateItemFn([this](const wm::Entity & entity, QTreeWidgetItem *  entityItem)
+        entityBuilder.setUpdateItemFn([this](const wm::Entity & entity, QTreeWidgetItem *  entityItem)
         {
             updateContainerItem(entity, entityItem);
             updateChildren(entity, entityItem);
             return true;
         });
 
-        workingmemorySnapshotBuilder.setMakeItemFn([this](const wm::EntitySnapshot & snapshot)
+        snapshotBuilder.setMakeItemFn([this](const wm::EntitySnapshot & snapshot)
         {
             QTreeWidgetItem* item = makeItem(toDateTimeMilliSeconds(snapshot.time()), snapshot);
             item->setData(int(Columns::KEY), Qt::ItemDataRole::UserRole, QVariant(static_cast<qlonglong>(snapshot.time().toMicroSeconds())));
             return item;
         });
-        workingmemorySnapshotBuilder.setCompareFn([](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * item)
+        snapshotBuilder.setCompareFn([](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * item)
         {
             return armarx::detail::compare(static_cast<qlonglong>(snapshot.time().toMicroSeconds()),
                                            item->data(int(Columns::KEY), Qt::ItemDataRole::UserRole).toLongLong());
         });
-        workingmemorySnapshotBuilder.setUpdateItemFn([this](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * snapshotItem)
+        snapshotBuilder.setUpdateItemFn([this](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * snapshotItem)
         {
             updateContainerItem(snapshot, snapshotItem);
             updateChildren(snapshot, snapshotItem);
             return true;
         });
 
-        workingmemoryInstanceBuilder.setMakeItemFn([this](const wm::EntityInstance & instance)
+        instanceBuilder.setMakeItemFn([this](const wm::EntityInstance & instance)
         {
             QTreeWidgetItem* item = makeItem("", instance);
             return item;
         });
-        workingmemoryInstanceBuilder.setCompareFn([](const wm::EntityInstance & lhs, QTreeWidgetItem * rhsItem)
+        instanceBuilder.setCompareFn([](const wm::EntityInstance & lhs, QTreeWidgetItem * rhsItem)
         {
             return armarx::detail::compare(lhs.index(), rhsItem->text(0).toInt());
         });
-        workingmemoryInstanceBuilder.setUpdateItemFn([this](const wm::EntityInstance & instance, QTreeWidgetItem * instanceItem)
+        instanceBuilder.setUpdateItemFn([this](const wm::EntityInstance & instance, QTreeWidgetItem * instanceItem)
         {
             updateItemItem(instance, instanceItem);
             updateChildren(instance, instanceItem);
@@ -237,33 +235,33 @@ namespace armarx::armem::gui::memory
 
     void TreeWidget::updateChildren(const std::map<std::string, const armem::wm::Memory*>& memories, QTreeWidget* tree)
     {
-        workingmemoryBuilder.updateTree(tree, memories);
+        memoryBuilder.updateTree(tree, memories);
     }
 
 
     void TreeWidget::updateChildren(const armem::wm::Memory& memory, QTreeWidgetItem* memoryItem)
     {
-        workingmemoryCoreSegmentBuilder.updateTreeWithIterator(memoryItem, makeIteratorFn(memory));
+        coreSegmentBuilder.updateTreeWithIterator(memoryItem, makeIteratorFn(memory));
     }
 
     void TreeWidget::updateChildren(const armem::wm::CoreSegment& coreSeg, QTreeWidgetItem* coreSegItem)
     {
-        workingmemoryProvSegmentBuilder.updateTreeWithIterator(coreSegItem, makeIteratorFn(coreSeg));
+        provSegmentBuilder.updateTreeWithIterator(coreSegItem, makeIteratorFn(coreSeg));
     }
 
     void TreeWidget::updateChildren(const armem::wm::ProviderSegment& provSeg, QTreeWidgetItem* provSegItem)
     {
-        workingmemoryEntityBuilder.updateTreeWithIterator(provSegItem, makeIteratorFn(provSeg));
+        entityBuilder.updateTreeWithIterator(provSegItem, makeIteratorFn(provSeg));
     }
 
     void TreeWidget::updateChildren(const armem::wm::Entity& entity, QTreeWidgetItem* entityItem)
     {
-        workingmemorySnapshotBuilder.updateTreeWithIterator(entityItem, makeIteratorFn(entity));
+        snapshotBuilder.updateTreeWithIterator(entityItem, makeIteratorFn(entity));
     }
 
     void TreeWidget::updateChildren(const armem::wm::EntitySnapshot& snapshot, QTreeWidgetItem* snapshotItem)
     {
-        workingmemoryInstanceBuilder.updateTreeWithIterator(snapshotItem, makeIteratorFn(snapshot));
+        instanceBuilder.updateTreeWithIterator(snapshotItem, makeIteratorFn(snapshot));
     }
 
     void TreeWidget::updateChildren(const armem::wm::EntityInstance& data, QTreeWidgetItem* dataItem)
@@ -299,16 +297,16 @@ namespace armarx::armem::gui::memory
         (void) level, (void) item;
     }
 
-    template <class... T>
-    void TreeWidget::updateContainerItem(
-        const base::detail::MemoryContainerBase<T...>& container, QTreeWidgetItem* item)
+    template <class ContainerT>
+    void TreeWidget::updateContainerItem(const ContainerT& container, QTreeWidgetItem* item)
     {
         updateItemItem(container, item);
         item->setText(int(Columns::SIZE), QString::number(container.size()));
 
-        if constexpr(std::is_base_of_v<base::detail::AronTyped, base::detail::MemoryContainerBase<T...>>)
+        // Does not work
+        if constexpr(std::is_base_of_v<base::detail::AronTyped, ContainerT>)
         {
-            const base::detail::AronTyped& cast = dynamic_cast<const base::detail::AronTyped&>(container);
+            const base::detail::AronTyped& cast = static_cast<const base::detail::AronTyped&>(container);
             std::string typeName;
             if (cast.aronType())
             {
diff --git a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
index 72987cda1ef736a9f8943161cb8756a6e56b2cdc..75f56c9ace248e58daf3f7ee3ac69baa12b0edfe 100644
--- a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
@@ -5,7 +5,6 @@
 #include <QTreeWidget>
 
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
 
 #include <RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h>
 
@@ -72,18 +71,18 @@ namespace armarx::armem::gui::memory
         QTreeWidgetItem* makeItem(const std::string& key, const std::string& levelName, const MemoryID& id);
 
         void updateItemItem(const armem::base::detail::MemoryItem& level, QTreeWidgetItem* item);
-        template <class... T>
-        void updateContainerItem(const armem::base::detail::MemoryContainerBase<T...>& container, QTreeWidgetItem* item);
+        template <class ContainerT>
+        void updateContainerItem(const ContainerT& container, QTreeWidgetItem* item);
 
 
     private:
 
-        MapTreeWidgetBuilder<std::string, const wm::Memory*> workingmemoryBuilder;
-        TreeWidgetBuilder<wm::CoreSegment> workingmemoryCoreSegmentBuilder;
-        TreeWidgetBuilder<wm::ProviderSegment> workingmemoryProvSegmentBuilder;
-        TreeWidgetBuilder<wm::Entity> workingmemoryEntityBuilder;
-        TreeWidgetBuilder<wm::EntitySnapshot> workingmemorySnapshotBuilder;
-        TreeWidgetBuilder<wm::EntityInstance> workingmemoryInstanceBuilder;
+        MapTreeWidgetBuilder<std::string, const wm::Memory*> memoryBuilder;
+        TreeWidgetBuilder<wm::CoreSegment> coreSegmentBuilder;
+        TreeWidgetBuilder<wm::ProviderSegment> provSegmentBuilder;
+        TreeWidgetBuilder<wm::Entity> entityBuilder;
+        TreeWidgetBuilder<wm::EntitySnapshot> snapshotBuilder;
+        TreeWidgetBuilder<wm::EntityInstance> instanceBuilder;
 
         std::optional<MemoryID> _selectedID;
         /// While this is false, do not handle selection updates.
diff --git a/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.cpp b/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.cpp
index dbb3d3fcabfa2ccf0034d1ba72027664bebe6ebc..f549a9e86046f40feb4087d28acd48726293a5c7 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.cpp
@@ -1,5 +1,8 @@
 #include "QueryWidget.h"
 
+#include <QWidget>
+#include <QTabWidget>
+#include <QPushButton>
 #include <QCheckBox>
 #include <QHBoxLayout>
 #include <QVBoxLayout>
@@ -12,25 +15,35 @@ namespace armarx::armem::gui
 
     QueryWidget::QueryWidget()
     {
-        QVBoxLayout* layout = new QVBoxLayout();
-        setLayout(layout);
+        QHBoxLayout* hlayout1 = new QHBoxLayout();
+        QHBoxLayout* hlayout2 = new QHBoxLayout();
+        QVBoxLayout* vlayout = new QVBoxLayout();
 
         _dataCheckBox = new QCheckBox("Get Data");
         _dataCheckBox->setChecked(true);
 
+        _storeInLTMButton = new QPushButton("Store query result in LTM");
+
         _tabWidget = new QTabWidget();
 
         _snapshotSelectorWidget = new SnapshotSelectorWidget();
         _tabWidget->addTab(_snapshotSelectorWidget, QString("Snapshots"));
 
-        layout->addWidget(_dataCheckBox);
-        layout->addWidget(_tabWidget);
+        hlayout1->addWidget(_dataCheckBox);
+        hlayout1->addWidget(_storeInLTMButton);
+
+        hlayout2->addWidget(_tabWidget);
 
         const int margin = 0;
-        layout->setContentsMargins(margin, margin, margin, margin);
+        vlayout->setContentsMargins(margin, margin, margin, margin);
+
+        vlayout->addLayout(hlayout1);
+        vlayout->addLayout(hlayout2);
 
+        // Public connections.
+        connect(_storeInLTMButton, &QPushButton::pressed, this, &This::storeInLTM);
 
-        // connect to queryChanged
+        setLayout(vlayout);
     }
 
 
@@ -41,11 +54,6 @@ namespace armarx::armem::gui
                : armem::DataMode::NoData;
     }
 
-    bool QueryWidget::alsoQueryLocalDisk() const
-    {
-        return _snapshotSelectorWidget->queryTargetContainsLocalDisk();
-    }
-
     armem::client::QueryInput QueryWidget::queryInput()
     {
         armem::client::query::Builder qb(dataMode());
diff --git a/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.h b/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.h
index d2c3fecd6198ad2ad5c3f37077eb07f4f365dea9..2bc7f223d5db52435b7571970bb4cd398aaeec49 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/QueryWidget.h
@@ -1,13 +1,13 @@
 #pragma once
 
-#include <QWidget>
-#include <QTabWidget>
-
 #include <RobotAPI/libraries/armem/core/DataMode.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 
 #include "SnapshotSelectorWidget.h"
 
+class QWidget;
+class QTabWidget;
+class QPushButton;
 
 namespace armarx::armem::gui
 {
@@ -15,19 +15,21 @@ namespace armarx::armem::gui
     class QueryWidget : public QWidget
     {
         Q_OBJECT
+        using This = QueryWidget;
+
     public:
 
         QueryWidget();
 
         armem::DataMode dataMode() const;
 
-        bool alsoQueryLocalDisk() const;
         armem::client::QueryInput queryInput();
 
 
     public slots:
 
     signals:
+        void storeInLTM();
 
         // ToDo:
         // void queryChanged(armem::query::data::Input query);
@@ -42,6 +44,8 @@ namespace armarx::armem::gui
     private:
 
         QCheckBox* _dataCheckBox;
+        QPushButton* _storeInLTMButton;
+
         QTabWidget* _tabWidget;
 
         SnapshotSelectorWidget* _snapshotSelectorWidget;
diff --git a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
index 9d5cc9ea6064bb6977892623649518791dcaffec..6b38efdddb30e67d1abfb3190d88508dff72258a 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
@@ -29,27 +29,14 @@ namespace armarx::armem::gui
         return targets;
     }
 
-    void SnapshotSelectorWidget::localDiskStateChanged()
+    void SnapshotSelectorWidget::queryTargetStateChanged()
     {
-        if (_LocalDiskMemoryQueryTargetCheckBox->isChecked())
+        if (!_WMQueryTargetCheckBox->isChecked() && !_LTMQueryTargetCheckBox->isChecked())
         {
-            _WMQueryTargetCheckBox->setChecked(false);
-            _LTMQueryTargetCheckBox->setChecked(false);
-            _WMQueryTargetCheckBox->setEnabled(false);
-            _LTMQueryTargetCheckBox->setEnabled(false);
-        }
-        else
-        {
-            _WMQueryTargetCheckBox->setEnabled(true);
-            _LTMQueryTargetCheckBox->setEnabled(true);
+            _WMQueryTargetCheckBox->setChecked(true);
         }
     }
 
-    bool SnapshotSelectorWidget::queryTargetContainsLocalDisk() const
-    {
-        return _LocalDiskMemoryQueryTargetCheckBox->isChecked();
-    }
-
     SnapshotSelectorWidget::SnapshotSelectorWidget()
     {
         _pageLayout = new QVBoxLayout();
@@ -72,13 +59,12 @@ namespace armarx::armem::gui
             auto queryTargetLayout = new QHBoxLayout();
             _WMQueryTargetCheckBox = new QCheckBox("WM");
             _LTMQueryTargetCheckBox = new QCheckBox("LTM");
-            _LocalDiskMemoryQueryTargetCheckBox = new QCheckBox("Local Disk");
 
-            connect(_LocalDiskMemoryQueryTargetCheckBox, &QCheckBox::stateChanged, this, &This::localDiskStateChanged);
+            connect(_WMQueryTargetCheckBox, &QCheckBox::stateChanged, this, &This::queryTargetStateChanged);
+            connect(_LTMQueryTargetCheckBox, &QCheckBox::stateChanged, this, &This::queryTargetStateChanged);
 
             queryTargetLayout->addWidget(_WMQueryTargetCheckBox);
             queryTargetLayout->addWidget(_LTMQueryTargetCheckBox);
-            queryTargetLayout->addWidget(_LocalDiskMemoryQueryTargetCheckBox);
 
             _WMQueryTargetCheckBox->setChecked(true);
 
diff --git a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h
index a0b69eb1b6f362e64880ab400c0bea29bcdc73fc..e7ec233c896133beb1b675baf37e2d0e2f53489c 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h
@@ -37,7 +37,6 @@ namespace armarx::armem::gui
         armem::DataMode dataMode() const;
         client::query::SnapshotSelector selector();
         query::data::QueryTargets queryTargets() const;
-        bool queryTargetContainsLocalDisk() const;
 
 
     public slots:
@@ -51,7 +50,7 @@ namespace armarx::armem::gui
 
         void hideAllForms();
         void showSelectedFormForQuery(QString selected);
-        void localDiskStateChanged();
+        void queryTargetStateChanged();
 
     signals:
         void queryOutdated();
@@ -67,7 +66,6 @@ namespace armarx::armem::gui
         QComboBox* _queryComboBox;
         QCheckBox* _WMQueryTargetCheckBox;
         QCheckBox* _LTMQueryTargetCheckBox;
-        QCheckBox* _LocalDiskMemoryQueryTargetCheckBox;
         /// The forms for the different query types. Hidden when not selected.
         std::map<QString, SnapshotForm*> _queryForms;
 
diff --git a/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp b/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp
index 303a319bcd30566b8000e1d10cc6ab3ef812093d..f7bb3e3e9a4cdc560838c0a3d25c0d7074a96503 100644
--- a/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp
+++ b/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp
@@ -30,27 +30,101 @@
 #include <iostream>
 
 #include <RobotAPI/libraries/armem_gui/instance/sanitize_typename.h>
+#include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h>
 #include <RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h>
 
-using namespace armarx::armem::gui::instance;
+namespace dn = armarx::aron::datanavigator;
+namespace tn = armarx::aron::typenavigator;
 
 
-BOOST_AUTO_TEST_CASE(test_sanitizeTypeName)
+namespace ArMemGuiTest
 {
-    using namespace armarx::aron::typenavigator;
+    struct Fixture
     {
-        DictNavigator dict;
-        dict.setAcceptedType(std::make_shared<FloatNavigator>());
-        BOOST_CHECK_EQUAL(sanitizeTypeName(dict.getName()), "Dict<Float>");
+    };
+
+    void test_sanitize(const std::string& in, const std::string& expected)
+    {
+        const std::string out = armarx::armem::gui::instance::sanitizeTypeName(in);
+        BOOST_TEST_CONTEXT("in = '" << in << "'")
+        {
+            BOOST_CHECK_EQUAL(out, expected);
+        }
     }
+}
+
+
+
+BOOST_FIXTURE_TEST_SUITE(ArMemGuiTest, ArMemGuiTest::Fixture)
+
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_int)
+{
+    test_sanitize(tn::IntNavigator().getName(), "Int");
+    test_sanitize(dn::IntNavigator().getName(), "Int");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_float)
+{
+    test_sanitize(tn::FloatNavigator().getName(), "Float");
+    test_sanitize(dn::FloatNavigator().getName(), "Float");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_dict)
+{
+    tn::DictNavigator dict;
+    dict.setAcceptedType(std::make_shared<tn::FloatNavigator>());
+    test_sanitize(dict.getName(), "Dict<Float>");
+
+    test_sanitize(dn::DictNavigator().getName(), "Dict");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_list)
+{
+    tn::ListNavigator list;
+    list.setAcceptedType(std::make_shared<tn::LongNavigator>());
+    test_sanitize(list.getName(), "List<Long>");
+
+    test_sanitize(dn::ListNavigator().getName(), "List");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_object)
+{
+    tn::ObjectNavigator obj;
+    obj.setObjectName("namespace::MyObjectName");
+    test_sanitize(obj.getName(), "MyObjectName    (namespace)");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_tuple)
+{
+    tn::TupleNavigator type;
+    type.addAcceptedType(std::make_shared<tn::IntNavigator>());
+    type.addAcceptedType(std::make_shared<tn::FloatNavigator>());
+    test_sanitize(type.getName(), "Tuple<Int, Float>");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_pair)
+{
+    tn::PairNavigator type;
+    type.setFirstAcceptedType(std::make_shared<tn::IntNavigator>());
+    type.setSecondAcceptedType(std::make_shared<tn::FloatNavigator>());
+    test_sanitize(type.getName(), "Pair<Int, Float>");
+}
+
+BOOST_AUTO_TEST_CASE(test_sanitizeTypeName_ndarry)
+{
     {
-        ListNavigator list;
-        list.setAcceptedType(std::make_shared<LongNavigator>());
-        BOOST_CHECK_EQUAL(sanitizeTypeName(list.getName()), "List<Long>");
+        tn::NDArrayNavigator type;
+        type.setDimensions({ 3, 2, 1});
+        type.setTypename("float");
+        test_sanitize(type.getName(), "NDArray");
     }
     {
-        ObjectNavigator obj;
-        obj.setObjectName("namespace::MyObjectName");
-        BOOST_CHECK_EQUAL(sanitizeTypeName(obj.getName()), "MyObjectName    (namespace)");
+        dn::NDArrayNavigator data;
+        data.setDimensions({ 3, 2, 1});
+        test_sanitize(data.getName(), "NDArray<3, 2, 1, >");
     }
 }
+
+
+BOOST_AUTO_TEST_SUITE_END()
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
index 237bc31cc8827f0fb9f80284bf0c639c23d093ec..d1cb1e0082d6ef95491530518e7f52839601d771 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
@@ -1,25 +1,20 @@
 #include "Writer.h"
 
-#include <mutex>
-#include <optional>
-
-#include <IceUtil/Time.h>
-
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 
-#include "ArmarXCore/core/exceptions/LocalException.h"
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
-#include "RobotAPI/libraries/ArmarXObjects/ObjectID.h"
-#include "RobotAPI/libraries/ArmarXObjects/ObjectInfo.h"
+#include <RobotAPI/libraries/ArmarXObjects/ObjectID.h>
+#include <RobotAPI/libraries/ArmarXObjects/ObjectInfo.h>
 #include <RobotAPI/libraries/ArmarXObjects/aron/ObjectID.aron.generated.h>
 #include <RobotAPI/libraries/armem/client/query.h>
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
 #include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/operations.h>
 #include <RobotAPI/libraries/armem_objects/aron/ObjectClass.aron.generated.h>
 #include <RobotAPI/libraries/armem_objects/aron/ObjectInstance.aron.generated.h>
-#include <RobotAPI/libraries/armem_objects/aron_conversions.h>
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot/aron/RobotDescription.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot/aron_conversions.h>
@@ -27,6 +22,7 @@
 
 #include "utils.h"
 
+
 namespace armarx::armem::articulated_object
 {
     Writer::Writer(armem::client::MemoryNameSystem& memoryNameSystem) :
@@ -86,7 +82,6 @@ namespace armarx::armem::articulated_object
 
     void Writer::updateKnownObject(const armem::MemoryID& snapshotId)
     {
-
         arondto::RobotDescription aronArticulatedObjectDescription;
         // aronArticulatedObjectDescription.fromAron(snapshotId.ent);
 
@@ -269,59 +264,41 @@ namespace armarx::armem::articulated_object
                 .getCoreSegment(properties.coreClassSegmentName)
                 .getProviderSegment(properties.providerName); // TODO(fabian.reister): all
         // clang-format on
-        const auto entities = simox::alg::get_values(providerSegment.entities());
 
-        if (entities.empty())
+        if (const armem::wm::EntityInstance* instance = findFirstInstance(providerSegment))
         {
-            ARMARX_WARNING << "No entity found";
-            return std::nullopt;
+            return convertRobotDescription(*instance);
         }
-
-        const auto entitySnapshots = simox::alg::get_values(entities.front().history());
-
-        if (entitySnapshots.empty())
+        else
         {
             ARMARX_WARNING << "No entity snapshots found";
             return std::nullopt;
         }
-
-        // TODO(fabian.reister): check if 0 available
-        const armem::wm::EntityInstance& instance = entitySnapshots.front().getInstance(0);
-
-        return convertRobotDescription(instance);
     }
 
     std::unordered_map<std::string, armem::MemoryID>
     Writer::getRobotDescriptions(const armarx::armem::wm::Memory& memory) const
     {
-        std::unordered_map<std::string, armem::MemoryID> descriptions;
-
         const armem::wm::CoreSegment& coreSegment =
             memory.getCoreSegment(properties.coreClassSegmentName);
 
-        for (const auto& [providerName, providerSegment] : coreSegment.providerSegments())
+        std::unordered_map<std::string, armem::MemoryID> descriptions;
+        coreSegment.forEachEntity([&descriptions](const wm::Entity & entity)
         {
-            for (const auto& [name, entity] : providerSegment.entities())
+            if (entity.empty())
             {
-                if (entity.empty())
-                {
-                    ARMARX_WARNING << "No entity found";
-                    continue;
-                }
-
-                const auto entitySnapshots          = simox::alg::get_values(entity.history());
-                const armem::wm::EntitySnapshot& sn = entitySnapshots.front();
-                const armem::wm::EntityInstance& instance = sn.getInstance(0);
-
-                const auto robotDescription = convertRobotDescription(instance);
-
-                if (robotDescription)
-                {
-                    const armem::MemoryID snapshotID(sn.id());
-                    descriptions.insert({robotDescription->name, snapshotID});
-                }
+                ARMARX_WARNING << "No entity found";
+                return true;
             }
-        }
+
+            const armem::wm::EntitySnapshot& sn = entity.getFirstSnapshot();
+            if (const auto robotDescription = convertRobotDescription(sn.getInstance(0)))
+            {
+                const armem::MemoryID snapshotID(sn.id());
+                descriptions.insert({robotDescription->name, snapshotID});
+            }
+            return true;
+        });
 
         return descriptions;
     }
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.h b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.h
index 95495220780d95278685c8c349462708aa822a3e..3e827d66a496ddf8df4448788f39ca1c36722290 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.h
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.h
@@ -22,8 +22,9 @@
 #pragma once
 
 #include <mutex>
+#include <optional>
 
-#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+#include <ArmarXCore/core/application/properties/forward_declarations.h>
 
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
 #include <RobotAPI/libraries/armem/client/Reader.h>
@@ -39,7 +40,7 @@ namespace armarx::armem::articulated_object
         virtual public WriterInterface
     {
     public:
-        Writer(armem::client::MemoryNameSystem& memoryNameSystem);
+        Writer(armem::client::MemoryNameSystem& memoryNameSystemopti);
         virtual ~Writer() = default;
 
         void registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def);
diff --git a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
index 2ddcc827d80c0700f59cb5f9ee8638322f4e5633..2c60cb9bd35ab7b3010e5b5f5fb0e719d0817f98 100644
--- a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
@@ -54,30 +54,31 @@ namespace armarx::armem::server::obj::attachments
     Segment::getAttachments(const armem::Time& timestamp) const
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
-        std::scoped_lock(coreSegment->mutex());
-
-        std::vector<armarx::armem::attachment::ObjectAttachment> attachments;
-        coreSegment->forEachEntity([this, &attachments](const wm::Entity & entity)
+        return coreSegment->doLocked([this]()
         {
-            const wm::EntityInstance& entityInstance = entity.getLatestSnapshot().getInstance(0);
-
-            const auto aronAttachment = tryCast<armarx::armem::arondto::attachment::ObjectAttachment>(entityInstance);
-            if (not aronAttachment)
+            std::vector<armarx::armem::attachment::ObjectAttachment> attachments;
+            coreSegment->forEachEntity([this, &attachments](const wm::Entity & entity)
             {
-                ARMARX_WARNING << "Could not convert entity instance to 'ObjectAttachment'";
-                return true;
-            }
+                const wm::EntityInstance& entityInstance = entity.getLatestSnapshot().getInstance(0);
 
-            ARMARX_DEBUG << "Key is " << armem::MemoryID(entity.id());
+                const auto aronAttachment = tryCast<armarx::armem::arondto::attachment::ObjectAttachment>(entityInstance);
+                if (not aronAttachment)
+                {
+                    ARMARX_WARNING << "Could not convert entity instance to 'ObjectAttachment'";
+                    return true;
+                }
 
-            armarx::armem::attachment::ObjectAttachment attachment;
-            fromAron(*aronAttachment, attachment);
+                ARMARX_DEBUG << "Key is " << armem::MemoryID(entity.id());
 
-            attachments.push_back(attachment);
-            return true;
-        });
+                armarx::armem::attachment::ObjectAttachment attachment;
+                fromAron(*aronAttachment, attachment);
 
-        return attachments;
+                attachments.push_back(attachment);
+                return true;
+            });
+
+            return attachments;
+        });
     }
 
 }  // namespace armarx::armem::server::obj::attachments
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
index 1e9957aff7b0d093d3bd1d6e16f289d6a2a04afd..cb0088285ca161ddc9283f3a024b65a86809fb1b 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
@@ -32,7 +32,7 @@ namespace armarx::armem::server::obj::clazz
         viz::Layer layer = arviz.layer(properties.layerName);
         if (properties.show)
         {
-            const wm::Entity* entity = classCoreSegment.findEntity(MemoryID().withEntityName(properties.entityName));
+            const wm::Entity* entity = classCoreSegment.findEntity(properties.entityName);
             if (entity)
             {
                 ARMARX_INFO << "Drawing floor class '" << properties.entityName << "'.";
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
index cd10a49c91957e5fa86094597c7903f76fb04c13..8b1ae942a95b73119eea072b7f33a539a05fbbdf 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
@@ -124,8 +124,10 @@ namespace armarx::armem::server::obj::clazz
         {
             try
             {
-                std::optional<arondto::ObjectClass> aron =
-                    coreSegment->getLatestEntityInstanceDataLockingAs<arondto::ObjectClass>(entityID, 0);
+                std::optional<arondto::ObjectClass> aron = coreSegment->doLocked([this, &entityID]()
+                {
+                    return coreSegment->findLatestInstanceDataAs<arondto::ObjectClass>(entityID, 0);
+                });
                 if (not aron.has_value())
                 {
                     return;
@@ -269,12 +271,14 @@ namespace armarx::armem::server::obj::clazz
         }
         if (infiniteHistory.hasValueChanged() || maxHistorySize.hasValueChanged())
         {
-            std::scoped_lock lock(segment.mutex());
-            segment.properties.maxHistorySize = infiniteHistory.getValue() ? -1 : maxHistorySize.getValue();
-            if (segment.coreSegment)
+            segment.doLocked([this, &segment]()
             {
-                segment.coreSegment->setMaxHistorySize(long(segment.properties.maxHistorySize));
-            }
+                segment.properties.maxHistorySize = infiniteHistory.getValue() ? -1 : maxHistorySize.getValue();
+                if (segment.coreSegment)
+                {
+                    segment.coreSegment->setMaxHistorySize(long(segment.properties.maxHistorySize));
+                }
+            });
         }
     }
 
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
index d6d224fe0580e4aa73656515a671ba5753e33326..9668e307ba7c7ff3ed1143087bf4aee1adf2608c 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
@@ -1039,28 +1039,29 @@ namespace armarx::armem::server::obj::instance
         if (storeButton.wasClicked())
         {
             armem::obj::SceneSnapshot scene;
+            segment.doLocked([&scene, &segment]()
             {
-                std::scoped_lock lock(segment.mutex());
                 scene = segment.getSceneSnapshot();
-            }
+            });
             segment.storeScene(storeLoadLine.getValue(), scene);
         }
 
         if (infiniteHistory.hasValueChanged() || maxHistorySize.hasValueChanged()
             || discardSnapshotsWhileAttached.hasValueChanged())
         {
-            std::scoped_lock lock(segment.mutex());
-
-            if (infiniteHistory.hasValueChanged() || maxHistorySize.hasValueChanged())
+            segment.doLocked([this, &segment]()
             {
-                segment.properties.maxHistorySize = infiniteHistory.getValue() ? -1 : maxHistorySize.getValue();
-                if (segment.coreSegment)
+                if (infiniteHistory.hasValueChanged() || maxHistorySize.hasValueChanged())
                 {
-                    segment.coreSegment->setMaxHistorySize(long(segment.properties.maxHistorySize));
+                    segment.properties.maxHistorySize = infiniteHistory.getValue() ? -1 : maxHistorySize.getValue();
+                    if (segment.coreSegment)
+                    {
+                        segment.coreSegment->setMaxHistorySize(long(segment.properties.maxHistorySize));
+                    }
                 }
-            }
 
-            segment.p.discardSnapshotsWhileAttached = discardSnapshotsWhileAttached.getValue();
+                segment.p.discardSnapshotsWhileAttached = discardSnapshotsWhileAttached.getValue();
+            });
         }
     }
 
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/SegmentAdapter.cpp b/source/RobotAPI/libraries/armem_objects/server/instance/SegmentAdapter.cpp
index 7cd8b1202ac34600f8bfc6ecc912037b49d8bee6..a9f2aaf31acec502463676cff6e0fc692d736911 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/SegmentAdapter.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/SegmentAdapter.cpp
@@ -123,8 +123,8 @@ namespace armarx::armem::server::obj::instance
                            << "with invalid provider proxy.\nIgnoring provider '" << providerName << "'.";
             return;
         }
+        segment.doLocked([this, &providerName, &info]()
         {
-            std::scoped_lock lock(segment.mutex());
             std::stringstream ss;
             for (const auto& id : info.supportedObjects)
             {
@@ -133,7 +133,7 @@ namespace armarx::armem::server::obj::instance
             ARMARX_VERBOSE << "Provider '" << providerName << "' available.\n"
                            << "Supported objects: \n" << ss.str();
             segment.providers[providerName] = info;
-        }
+        });
     }
 
 
@@ -164,8 +164,8 @@ namespace armarx::armem::server::obj::instance
             return;
         }
 
+        segment.doLocked([&]()
         {
-            std::scoped_lock lock(segment.mutex());
             RemoteRobot::synchronizeLocalClone(segment.robot, segment.robotStateComponent);
 
             if (segment.robot->hasRobotNode(calibration.robotNode))
@@ -200,7 +200,7 @@ namespace armarx::armem::server::obj::instance
                     { "t MemorySetObjectPoses [ms]", new Variant(tCommitObjectPoses.toMilliSecondsDouble()) },
                 });
             }
-        }
+        });
     }
 
 
@@ -218,12 +218,12 @@ namespace armarx::armem::server::obj::instance
     {
         TIMING_START(tGetObjectPoses);
 
-        TIMING_START(tGetObjectPosesLock);
-        std::scoped_lock lock(segment.mutex());
-        TIMING_END_STREAM(tGetObjectPosesLock, ARMARX_VERBOSE);
-
         const IceUtil::Time now = TimeUtil::GetTime();
-        const objpose::data::ObjectPoseSeq result = objpose::toIce(simox::alg::get_values(segment.getObjectPoses(now)));
+        const objpose::ObjectPoseSeq objectPoses = segment.doLocked([this, &now]()
+        {
+            return simox::alg::get_values(segment.getObjectPoses(now));
+        });
+        const objpose::data::ObjectPoseSeq result = objpose::toIce(objectPoses);
 
         TIMING_END_STREAM(tGetObjectPoses, ARMARX_VERBOSE);
 
@@ -232,7 +232,6 @@ namespace armarx::armem::server::obj::instance
             debugObserver->setDebugChannel(getName(),
             {
                 { "t GetObjectPoses() [ms]", new Variant(tGetObjectPoses.toMilliSecondsDouble()) },
-                { "t GetObjectPoses() lock [ms]", new Variant(tGetObjectPosesLock.toMilliSecondsDouble()) }
             });
         }
 
@@ -243,12 +242,12 @@ namespace armarx::armem::server::obj::instance
     {
         TIMING_START(GetObjectPoses);
 
-        TIMING_START(GetObjectPosesLock);
-        std::scoped_lock lock(segment.mutex());
-        TIMING_END_STREAM(GetObjectPosesLock, ARMARX_VERBOSE);
-
         const IceUtil::Time now = TimeUtil::GetTime();
-        const objpose::data::ObjectPoseSeq result = objpose::toIce(simox::alg::get_values(segment.getObjectPosesByProvider(providerName, now)));
+        const objpose::ObjectPoseSeq objectPoses = segment.doLocked([this, &now, &providerName]()
+        {
+            return simox::alg::get_values(segment.getObjectPosesByProvider(providerName, now));
+        });
+        const objpose::data::ObjectPoseSeq result = objpose::toIce(objectPoses);
 
         TIMING_END_STREAM(GetObjectPoses, ARMARX_VERBOSE);
 
@@ -257,7 +256,6 @@ namespace armarx::armem::server::obj::instance
             debugObserver->setDebugChannel(getName(),
             {
                 { "t GetObjectPosesByProvider() [ms]", new Variant(GetObjectPoses.toMilliSecondsDouble()) },
-                { "t GetObjectPosesByProvider() lock [ms]", new Variant(GetObjectPosesLock.toMilliSecondsDouble()) }
             });
         }
 
@@ -296,26 +294,28 @@ namespace armarx::armem::server::obj::instance
         }
         else
         {
-            std::scoped_lock lock(segment.mutex());
-            for (const auto& objectID : input.request.objectIDs)
+            segment.doLocked([&]()
             {
-                bool found = true;
-                for (const auto& [providerName, info] : segment.providers)
+                for (const auto& objectID : input.request.objectIDs)
                 {
-                    // ToDo: optimize look up.
-                    if (std::find(info.supportedObjects.begin(), info.supportedObjects.end(), objectID) != info.supportedObjects.end())
+                    bool found = true;
+                    for (const auto& [providerName, info] : segment.providers)
                     {
-                        providerRequests[providerName].objectIDs.push_back(objectID);
-                        updateProxy(providerName);
-                        break;
+                        // ToDo: optimize look up.
+                        if (std::find(info.supportedObjects.begin(), info.supportedObjects.end(), objectID) != info.supportedObjects.end())
+                        {
+                            providerRequests[providerName].objectIDs.push_back(objectID);
+                            updateProxy(providerName);
+                            break;
+                        }
+                    }
+                    if (!found)
+                    {
+                        ARMARX_ERROR << "Did not find a provider for " << objectID << ".";
+                        output.results[objectID].providerName = "";
                     }
                 }
-                if (!found)
-                {
-                    ARMARX_ERROR << "Did not find a provider for " << objectID << ".";
-                    output.results[objectID].providerName = "";
-                }
-            }
+            });
         }
 
         for (const auto& [providerName, request] : providerRequests)
@@ -343,69 +343,84 @@ namespace armarx::armem::server::obj::instance
 
     objpose::ProviderInfoMap SegmentAdapter::getAvailableProvidersInfo(const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.providers;
+        return segment.doLocked([this]()
+        {
+            return segment.providers;
+        });
     }
 
 
     Ice::StringSeq SegmentAdapter::getAvailableProviderNames(const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return simox::alg::get_keys(segment.providers);
+        return segment.doLocked([this]()
+        {
+            return simox::alg::get_keys(segment.providers);
+        });
     }
 
 
     objpose::ProviderInfo SegmentAdapter::getProviderInfo(const std::string& providerName, const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.getProviderInfo(providerName);
+        return segment.doLocked([this, &providerName]()
+        {
+            return segment.getProviderInfo(providerName);
+        });
     }
 
 
     bool SegmentAdapter::hasProvider(const std::string& providerName, const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.providers.count(providerName) > 0;
+        return segment.doLocked([this, &providerName]()
+        {
+            return segment.providers.count(providerName) > 0;
+        });
     }
 
 
     objpose::AttachObjectToRobotNodeOutput SegmentAdapter::attachObjectToRobotNode(
         const objpose::AttachObjectToRobotNodeInput& input, const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.attachObjectToRobotNode(input);
+        return segment.doLocked([this, &input]()
+        {
+            return segment.attachObjectToRobotNode(input);
+        });
     }
 
 
     objpose::DetachObjectFromRobotNodeOutput SegmentAdapter::detachObjectFromRobotNode(
         const objpose::DetachObjectFromRobotNodeInput& input, const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.detachObjectFromRobotNode(input);
+        return segment.doLocked([this, &input]()
+        {
+            return segment.detachObjectFromRobotNode(input);
+        });
     }
 
 
     objpose::DetachAllObjectsFromRobotNodesOutput SegmentAdapter::detachAllObjectsFromRobotNodes(
         const objpose::DetachAllObjectsFromRobotNodesInput& input, const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-        return segment.detachAllObjectsFromRobotNodes(input);
+        return segment.doLocked([this, &input]()
+        {
+            return segment.detachAllObjectsFromRobotNodes(input);
+        });
     }
 
 
     objpose::AgentFramesSeq SegmentAdapter::getAttachableFrames(const Ice::Current&)
     {
-        std::scoped_lock lock(segment.mutex());
-
-        objpose::AgentFramesSeq output;
-        std::vector<VirtualRobot::RobotPtr> agents = { segment.robot };
-        for (VirtualRobot::RobotPtr agent : agents)
+        return segment.doLocked([this]()
         {
-            objpose::AgentFrames& frames = output.emplace_back();
-            frames.agent = agent->getName();
-            frames.frames = agent->getRobotNodeNames();
-        }
-        return output;
+            objpose::AgentFramesSeq output;
+            std::vector<VirtualRobot::RobotPtr> agents = { segment.robot };
+            for (VirtualRobot::RobotPtr agent : agents)
+            {
+                objpose::AgentFrames& frames = output.emplace_back();
+                frames.agent = agent->getName();
+                frames.frames = agent->getRobotNodeNames();
+            }
+            return output;
+        });
     }
 
 
@@ -433,9 +448,8 @@ namespace armarx::armem::server::obj::instance
 
                     objpose::ObjectPoseMap objectPoses;
                     visu.minConfidence = -1;
+                    return segment.doLocked([this, &objectPoses, &objectFinder]()
                     {
-                        std::scoped_lock lock(segment.mutex());
-
                         const IceUtil::Time now = TimeUtil::GetTime();
 
                         // Also include decayed objects in result
@@ -452,7 +466,7 @@ namespace armarx::armem::server::obj::instance
                         {
                             visu.minConfidence = segment.decay.removeObjectsBelowConfidence;
                         }
-                    }
+                    });
 
                     const std::vector<viz::Layer> layers = visu.visualizeCommit(objectPoses, objectFinder);
                     arviz.commit(layers);
@@ -514,8 +528,10 @@ namespace armarx::armem::server::obj::instance
         }
         this->segment.update(adapter.segment);
         {
-            std::scoped_lock lock(adapter.segment.mutex());
-            this->decay.update(adapter.segment.decay);
+            adapter.segment.doLocked([this, &adapter]()
+            {
+                this->decay.update(adapter.segment.decay);
+            });
         }
         {
             std::scoped_lock lock(adapter.robotHeadMutex);
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp
index 32da2d6450e67eb228e7d8099123842a4b8f84d9..d46c7dfa1cc72847b27a820ecd4281ec1cb649e6 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp
@@ -20,8 +20,6 @@
  */
 
 #include "TransformReader.h"
-#include "RobotAPI/libraries/armem/core/Time.h"
-#include "RobotAPI/libraries/armem_robot_state/common/localization/types.h"
 
 #include <algorithm>
 #include <iterator>
@@ -45,20 +43,23 @@
 #include <ArmarXCore/core/time/CycleUtil.h>
 
 // this package
+#include <RobotAPI/libraries/core/FramedPose.h>
+
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #include <RobotAPI/libraries/aron/core/navigator/type/NavigatorFactory.h>
-#include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/libraries/armem_robot_state/aron_conversions.h>
 #include <RobotAPI/libraries/armem_robot_state/aron/Transform.aron.generated.h>
-
+#include <RobotAPI/libraries/armem_robot_state/common/localization/types.h>
 #include <RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.h>
 
+
 namespace armarx::armem::client::robot_state::localization
 {
 
@@ -135,11 +136,11 @@ namespace armarx::armem::client::robot_state::localization
     TransformResult TransformReader::lookupTransform(const TransformQuery& query) const
     {
         const auto& timestamp = query.header.timestamp;
-
-        const auto durationEpsilon = IceUtil::Time::milliSeconds(-1);
-
         ARMARX_DEBUG << "Looking up transform at timestamp " << timestamp;
 
+        const IceUtil::Time durationEpsilon = IceUtil::Time::milliSeconds(-1);
+        (void) durationEpsilon;
+
         // Query all entities from provider.
         armem::client::query::Builder qb;
 
@@ -152,18 +153,20 @@ namespace armarx::armem::client::robot_state::localization
         // clang-format on
 
         const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
-
         ARMARX_DEBUG << "Lookup result in reader: " << qResult;
 
         if (not qResult.success)
         {
-            return {.transform =
+            return
+            {
+                .transform =
                 {
                     .header = query.header,
                 },
                 .status       = TransformResult::Status::ErrorFrameNotAvailable,
                 .errorMessage = "Error in tf lookup '" + query.header.parentFrame + " -> " +
-                query.header.frame + "' : " + qResult.errorMessage};
+                query.header.frame + "' : " + qResult.errorMessage
+            };
         }
 
         const auto& localizationCoreSegment = qResult.memory.getCoreSegment(properties.localizationSegment);
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp b/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
index 8fd1077e58c9c13ca6eeb3b429aacf569c837950..9925ab30ff83b84d1e8927c51c16fddc6536b185 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
@@ -98,8 +98,10 @@ namespace armarx::armem::server::robot_state::description
 
     Segment::RobotDescriptionMap Segment::getRobotDescriptionsLocking(const armem::Time& timestamp) const
     {
-        std::scoped_lock lock(mutex());
-        return getRobotDescriptions(timestamp);
+        return doLocked([this, &timestamp]()
+        {
+            return getRobotDescriptions(timestamp);
+        });
     }
 
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
index 4eb19d15583fd12493d5dd2a6312c6154931e15f..4d2fa4b85d69a1bb5aef0871af5e455490447ea2 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
@@ -55,8 +55,10 @@ namespace armarx::armem::server::robot_state::localization
     Segment::RobotFramePoseMap
     Segment::getRobotFramePosesLocking(const armem::Time& timestamp) const
     {
-        std::scoped_lock lock(mutex());
-        return getRobotFramePoses(timestamp);
+        return this->doLocked([this, &timestamp]()
+        {
+            return getRobotFramePoses(timestamp);
+        });
     }
 
 
@@ -99,8 +101,10 @@ namespace armarx::armem::server::robot_state::localization
     Segment::RobotPoseMap
     Segment::getRobotGlobalPosesLocking(const armem::Time& timestamp) const
     {
-        std::scoped_lock lock(mutex());
-        return getRobotGlobalPoses(timestamp);
+        return this->doLocked([this, &timestamp]()
+        {
+            return getRobotGlobalPoses(timestamp);
+        });
     }
 
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp b/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp
index a63610cf6f7727feaebf60ca2139ab09c0d6e6af..8a88e6fae3a9df8980e1bb5bd54451e2457c342b 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp
@@ -59,14 +59,10 @@ namespace armarx::armem::server::robot_state::proprioception
         const armem::Time& timestamp,
         DebugObserverHelper* debugObserver) const
     {
-        TIMING_START(tRobotJointPositionsLock);
-        std::scoped_lock lock(mutex());
-        TIMING_END_STREAM(tRobotJointPositionsLock, ARMARX_DEBUG);
-        if (debugObserver)
+        return doLocked([this, &timestamp, &debugObserver]()
         {
-            debugObserver->setDebugObserverDatafield(dp + "t 0 Lock Core Segment (ms)", tRobotJointPositionsLock.toMilliSecondsDouble());
-        }
-        return getRobotJointPositions(timestamp, debugObserver);
+            return getRobotJointPositions(timestamp, debugObserver);
+        });
     }
 
 
diff --git a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
index 5f8db702e460cbb2e729862458314920823be780..e93d191b2f99b0eccb973a925a77ebdf674ffaee 100644
--- a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
@@ -3,6 +3,7 @@ add_subdirectory(ivt)
 add_subdirectory(pcl)
 add_subdirectory(eigen)
 add_subdirectory(opencv)
+add_subdirectory(json)
 
 
 add_library(AronConverter INTERFACE)
@@ -13,7 +14,8 @@ target_link_libraries(AronConverter
         RobotAPI::aron::converter::ivt    
         RobotAPI::aron::converter::pcl    
         RobotAPI::aron::converter::eigen    
-        RobotAPI::aron::converter::opencv    
+        RobotAPI::aron::converter::opencv
+        RobotAPI::aron::converter::json
 )
 
 add_library(aron::converter ALIAS AronConverter)
diff --git a/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..8f5c8006f3b16d7343a2f74b1c6b6562de426165
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt
@@ -0,0 +1,24 @@
+set(LIB_NAME aronjsonconverter)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+find_package(IVT COMPONENTS ivt ivtopencv QUIET)
+armarx_build_if(IVT_FOUND "IVT not available")
+
+set(LIBS
+    aron
+)
+
+set(LIB_FILES
+    NLohmannJSONConverter.cpp
+)
+
+set(LIB_HEADERS
+    NLohmannJSONConverter.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+
+add_library(RobotAPI::aron::converter::json ALIAS aronjsonconverter)
diff --git a/source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
similarity index 50%
rename from source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp
rename to source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
index fd67c5f822cbfa3783bf1fc23b3de24f06a27f88..3eb6f82327e13ed89629e5de76a41909a9f0f9e2 100644
--- a/source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp
+++ b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
@@ -1,4 +1,4 @@
-#include "json_conversions.h"
+#include "NLohmannJSONConverter.h"
 
 #include <RobotAPI/libraries/aron/core/Debug.h>
 #include <RobotAPI/libraries/aron/core/io/dataIO/visitor/Visitor.h>
@@ -7,17 +7,32 @@
 #include <RobotAPI/libraries/aron/core/io/dataIO/writer/nlohmannJSON/NlohmannJSONWriter.h>
 
 
-namespace armarx::armem
+namespace armarx::aron::converter
 {
-    void from_aron(const aron::datanavigator::DictNavigatorPtr& aron, nlohmann::json& j)
+    nlohmann::json AronNlohmannJSONConverter::ConvertToNlohmannJSON(const datanavigator::DictNavigatorPtr& aron)
+    {
+        nlohmann::json j;
+        ConvertToNlohmannJSON(aron, j);
+        return j;
+    }
+
+    void AronNlohmannJSONConverter::ConvertToNlohmannJSON(const aron::datanavigator::DictNavigatorPtr& aron, nlohmann::json& j)
     {
         aron::dataIO::writer::NlohmannJSONWriter dataWriter;
         aron::dataIO::Visitor::VisitAndSetup(dataWriter, aron);
         j = dataWriter.getResult();
     }
 
-    void to_aron(aron::datanavigator::DictNavigatorPtr& a, const nlohmann::json& e,
-                 const aron::typenavigator::NavigatorPtr& expectedStructure)
+
+
+    datanavigator::DictNavigatorPtr AronNlohmannJSONConverter::ConvertFromNlohmannJSON(const nlohmann::json& j)
+    {
+        auto aron = std::make_shared<aron::datanavigator::DictNavigator>();
+        ConvertFromNlohmannJSON(aron, j);
+        return aron;
+    }
+
+    void AronNlohmannJSONConverter::ConvertFromNlohmannJSON(aron::datanavigator::DictNavigatorPtr& a, const nlohmann::json& e, const aron::typenavigator::NavigatorPtr& expectedStructure)
     {
         aron::dataIO::reader::NlohmannJSONReader dataReader(e);
         aron::dataIO::writer::NavigatorWriter navWriter;
diff --git a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..2e1a89c63511d9806951887a7461fa09dcb17da4
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h
@@ -0,0 +1,29 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+#include <string>
+#include <numeric>
+
+// Memory
+#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
+
+// JSON
+#include <SimoxUtility/json/json.hpp>
+
+namespace armarx::aron::converter
+{
+    class AronNlohmannJSONConverter
+    {
+
+    public:
+        AronNlohmannJSONConverter() = delete;
+
+        static nlohmann::json ConvertToNlohmannJSON(const datanavigator::DictNavigatorPtr&);
+        static void ConvertToNlohmannJSON(const datanavigator::DictNavigatorPtr&, nlohmann::json&);
+
+        static datanavigator::DictNavigatorPtr ConvertFromNlohmannJSON(const nlohmann::json&);
+        static void ConvertFromNlohmannJSON(datanavigator::DictNavigatorPtr&, const nlohmann::json&, const aron::typenavigator::NavigatorPtr& = nullptr);
+    };
+}