diff --git a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp
index 487c9c6fc4c732fc1d4fe2f126724cb74c8dd810..72e5b8f33073f716e9d3a299ea26dda288dc6066 100644
--- a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp
+++ b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp
@@ -42,7 +42,7 @@
 #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/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #include <RobotAPI/libraries/armem_objects/types.h>
 
diff --git a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h
index f85a804e97337e1193ca1f38048beb103e65ce59..b4cab3fc71e6d6b1dd92e3128fd3a90a8c191109 100644
--- a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h
+++ b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h
@@ -14,7 +14,7 @@
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 #include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/libraries/armem/client/ComponentPlugin.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.h>
 #include <RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.h>
 
diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
index 8ae42e00bd5385886696dd6ead35feb927665947..036d27d2bf49f7d5ac9f84e940bf7e1e88b033b1 100644
--- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
+++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
@@ -34,7 +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/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 #include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h>
 
@@ -260,37 +260,24 @@ namespace armarx
 
         if (qResult.success)
         {
-            armem::wm::Memory& memory = qResult.memory;
-
-            ARMARX_CHECK_EQUAL(memory.coreSegments().size(), 1);
-            armem::wm::CoreSegment& coreSeg = memory.coreSegments().begin()->second;
+            ARMARX_IMPORTANT << "Getting entity via ID";
 
-            ARMARX_CHECK_EQUAL(coreSeg.providerSegments().size(), 1);
-            armem::wm::ProviderSegment& provSeg = coreSeg.providerSegments().begin()->second;
+            armem::wm::Memory& memory = qResult.memory;
+            ARMARX_CHECK_GREATER_EQUAL(memory.size(), 1);
 
-            ARMARX_CHECK_EQUAL(provSeg.entities().size(), 1);
-            armem::wm::Entity& entity = provSeg.entities().begin()->second;
+            const armem::wm::Entity* entity = memory.findEntity(entityID);
+            ARMARX_CHECK_NOT_NULL(entity);
+            ARMARX_CHECK_GREATER_EQUAL(entity->size(), 1);
 
-            ARMARX_CHECK_GREATER_EQUAL(entity.history().size(), 1);
-            armem::wm::EntitySnapshot& snapshot = entity.history().begin()->second;
+            const armem::wm::EntitySnapshot& snapshot = entity->getLatestSnapshot();
+            ARMARX_CHECK_GREATER_EQUAL(snapshot.size(), 1);
 
             ARMARX_INFO << "Result: "
-                        << "\n- memory:       \t" << memory.name()
-                        << "\n- core segment: \t" << coreSeg.name()
-                        << "\n- prov segment: \t" << provSeg.name()
-                        << "\n- entity:       \t" << entity.name()
+                        << "\n- entity:       \t" << entity->name()
                         << "\n- snapshot:     \t" << snapshot.time()
                         << "\n- #instances:   \t" << snapshot.size()
                         ;
 
-            ARMARX_IMPORTANT << "Getting entity via ID";
-            const armem::wm::Entity& e = memory.getEntity(entityID);
-            ARMARX_INFO << "Result: "
-                        << "\n- entity:       \t" << e.name()
-                        << "\n- snapshot:     \t" << e.getLatestSnapshot().time()
-                        << "\n- #instances:   \t" << e.getLatestSnapshot().size()
-                        ;
-
             // Show memory contents in remote gui.
             tab.queryResult = std::move(memory);
             tab.rebuild = true;
diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h
index 5680e316a6228021932afea5d73abd02fdcda6d8..ca28ab86bc1e755c49b93649fd77b26aac0a4250 100644
--- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h
+++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h
@@ -34,7 +34,7 @@
 #include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 #include <RobotAPI/libraries/armem/client/ComponentPlugin.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 namespace armarx
diff --git a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp
index 6650e573785cce732f0f2bbe7c128aa34fc58626..8ab75efc78ddad8492598356df374266947fe515 100644
--- a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp
+++ b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp
@@ -23,7 +23,7 @@
 
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 
diff --git a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h
index 4e1d01f5564e96c7e46ad2db33081835873dd7a6..33770ad5425f8824fca2f40ae45323861f29cc91 100644
--- a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h
+++ b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h
@@ -33,7 +33,7 @@
 #include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 #include <RobotAPI/libraries/armem/client/ComponentPlugin.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h>
 
diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/test/ExampleMemoryTest.cpp b/source/RobotAPI/components/armem/server/ExampleMemory/test/ExampleMemoryTest.cpp
index c5ba35a13aa4ec127f64d0992021d29262d54407..56c9d08f49759de2f75c8085551ea63fb9263935 100644
--- a/source/RobotAPI/components/armem/server/ExampleMemory/test/ExampleMemoryTest.cpp
+++ b/source/RobotAPI/components/armem/server/ExampleMemory/test/ExampleMemoryTest.cpp
@@ -41,7 +41,7 @@ BOOST_AUTO_TEST_CASE(test_ExampleData_type)
 {
     armarx::aron::typenavigator::ObjectNavigatorPtr type = ExampleData::toAronType();
 
-    BOOST_CHECK_EQUAL(type->childrenSize(), 15);
+    BOOST_CHECK_EQUAL(type->childrenSize(), 16);
 
     armem::wm::Memory memory;
     armem::wm::CoreSegment& core = memory.addCoreSegment("ExampleData", type);
diff --git a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp
index c0a9fd2f33211d9a130f236b9350836b75b51466..6c86b6afa76fe043b4dea16affb609f7db049caf 100644
--- a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp
+++ b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp
@@ -29,7 +29,8 @@
 #include <ArmarXCore/core/logging/Logging.h>
 
 #include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 
 #include <RobotAPI/libraries/armem_skills/aron_conversions.h>
@@ -70,7 +71,7 @@ namespace armarx
         workingMemory.name() = p.memoryName;
 
         {
-            armarx::armem::wm::CoreSegment& c = workingMemory.addCoreSegment(p.statechartCoreSegmentName, armarx::armem::arondto::Statechart::Transition::toAronType());
+            armarx::armem::server::wm::CoreSegment& c = workingMemory.addCoreSegment(p.statechartCoreSegmentName, armarx::armem::arondto::Statechart::Transition::toAronType());
             c.addProviderSegment("Transitions", armarx::armem::arondto::Statechart::Transition::toAronType());
         }
     }
diff --git a/source/RobotAPI/gui-plugins/ObjectPoseGui/ObjectPoseGuiWidgetController.cpp b/source/RobotAPI/gui-plugins/ObjectPoseGui/ObjectPoseGuiWidgetController.cpp
index dffe7711debc728d596f5ecd7cd851df2527e120..adb7c77bd1e04491b7e16ecb1599119df0ee2ce6 100644
--- a/source/RobotAPI/gui-plugins/ObjectPoseGui/ObjectPoseGuiWidgetController.cpp
+++ b/source/RobotAPI/gui-plugins/ObjectPoseGui/ObjectPoseGuiWidgetController.cpp
@@ -201,7 +201,7 @@ namespace armarx
         {
             bool expand = item->childCount() == 0;
 
-            TreeWidgetBuilder builder(objectPoses);
+            TreeWidgetBuilder<objpose::ObjectPose> builder;
             builder.setNameFn([](const objpose::ObjectPose & pose)
             {
                 return pose.objectID.str();
@@ -245,7 +245,7 @@ namespace armarx
 
                 return true;
             });
-            builder.updateTree(item, objectPoses);
+            builder.updateTreeWithContainer(item, objectPoses);
 
             if (expand)
             {
@@ -299,7 +299,7 @@ namespace armarx
         {
             (void) dataset;
 
-            TreeWidgetBuilder builder(datasetData);
+            TreeWidgetBuilder<std::pair<std::string, std::string>> builder;
             builder.setCompareFn([](const std::pair<std::string, std::string>& lhs, QTreeWidgetItem * item)
             {
                 auto rhs = std::make_pair(item->text(0).toStdString(), item->text(1).toStdString());
@@ -324,7 +324,7 @@ namespace armarx
                 }
                 return true;
             });
-            builder.updateTree(datasetItem, datasetData);
+            builder.updateTreeWithContainer(datasetItem, datasetData);
 
             return true;
         });
diff --git a/source/RobotAPI/interface/armem/query.ice b/source/RobotAPI/interface/armem/query.ice
index 2a1586fece346e89cbe491cd21c026ddab603e0e..936294507f0b05627051fa6974309faa1db4d758 100644
--- a/source/RobotAPI/interface/armem/query.ice
+++ b/source/RobotAPI/interface/armem/query.ice
@@ -14,8 +14,7 @@ module armarx
                 enum QueryTarget
                 {
                     WM,
-                    LTM,
-                    Disk
+                    LTM
                 };
                 sequence<QueryTarget> QueryTargets;
 
diff --git a/source/RobotAPI/interface/objectpose/ObjectPoseStorageInterface.ice b/source/RobotAPI/interface/objectpose/ObjectPoseStorageInterface.ice
index 3097f6c7596fd3fdf82aedd9d974712081cf503c..1dfe8b9f299d24684a0acdd3d6f53ed61063d397 100644
--- a/source/RobotAPI/interface/objectpose/ObjectPoseStorageInterface.ice
+++ b/source/RobotAPI/interface/objectpose/ObjectPoseStorageInterface.ice
@@ -81,7 +81,7 @@ module armarx
         };
         struct AttachObjectToRobotNodeOutput
         {
-            bool success;
+            bool success = false;
             data::ObjectAttachmentInfo attachment;
         };
 
@@ -99,7 +99,7 @@ module armarx
         struct DetachObjectFromRobotNodeOutput
         {
             /// Whether the object was attached before.
-            bool wasAttached;
+            bool wasAttached = false;
         };
 
         struct DetachAllObjectsFromRobotNodesInput
@@ -113,7 +113,7 @@ module armarx
         struct DetachAllObjectsFromRobotNodesOutput
         {
             /// Number of objects that have been detached.
-            int numDetached;
+            int numDetached = 0;
         };
 
         struct AgentFrames
diff --git a/source/RobotAPI/libraries/armem/CMakeLists.txt b/source/RobotAPI/libraries/armem/CMakeLists.txt
index ef5f227686bf252f3f7941fd3f0d96aed72442d1..457c62565e215c4d76a686cc73647aeb71397190 100644
--- a/source/RobotAPI/libraries/armem/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/CMakeLists.txt
@@ -25,38 +25,34 @@ set(LIB_FILES
     core/Commit.cpp
     core/MemoryID.cpp
     core/MemoryID_operators.cpp
+    core/operations.cpp
     core/SuccessHeader.cpp
     core/Time.cpp
-    core/ice_conversions.cpp
     core/aron_conversions.cpp
+    core/ice_conversions.cpp
     core/json_conversions.cpp
 
     core/base/detail/MemoryItem.cpp
-    core/base/detail/MaxHistorySize.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/negative_index_semantics.cpp
 
-    core/base/CoreSegmentBase.cpp
+    # core/base/CoreSegmentBase.cpp
     core/base/EntityBase.cpp
     core/base/EntityInstanceBase.cpp
     core/base/EntitySnapshotBase.cpp
-    core/base/MemoryBase.cpp
-    core/base/ProviderSegmentBase.cpp
-
-    core/workingmemory/ice_conversions.cpp
-    core/workingmemory/detail/CopyWithoutData.cpp
-    core/workingmemory/CoreSegment.cpp
-    core/workingmemory/Entity.cpp
-    core/workingmemory/EntityInstance.cpp
-    core/workingmemory/EntitySnapshot.cpp
-    core/workingmemory/Memory.cpp
-    core/workingmemory/ProviderSegment.cpp
-    core/workingmemory/ice_conversions.cpp
-    core/workingmemory/json_conversions.cpp
-    core/workingmemory/entityInstance_conversions.cpp
-    core/workingmemory/visitor/Visitor.cpp
-    core/workingmemory/visitor/FunctionalVisitor.cpp
+    # core/base/MemoryBase.cpp
+    # core/base/ProviderSegmentBase.cpp
+    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/visitor/Visitor.cpp
+    core/wm/visitor/FunctionalVisitor.cpp
 
     core/longtermmemory/CoreSegment.cpp
     core/longtermmemory/Entity.cpp
@@ -98,6 +94,10 @@ set(LIB_FILES
     server/MemoryRemoteGui.cpp
     server/RemoteGuiAronDataVisitor.cpp
 
+    server/wm/memory_definitions.cpp
+    server/wm/ice_conversions.cpp
+    server/wm/detail/MaxHistorySize.cpp
+
     server/segment/Segment.cpp
     server/segment/SpecializedSegment.cpp
 
@@ -107,23 +107,9 @@ set(LIB_FILES
     server/query_proc/base/CoreSegmentQueryProcessorBase.cpp
     server/query_proc/base/MemoryQueryProcessorBase.cpp
 
-    server/query_proc/workingmemory/BaseQueryProcessor.cpp
-    server/query_proc/workingmemory/EntityQueryProcessor.cpp
-    server/query_proc/workingmemory/ProviderSegmentQueryProcessor.cpp
-    server/query_proc/workingmemory/CoreSegmentQueryProcessor.cpp
-    server/query_proc/workingmemory/MemoryQueryProcessor.cpp
-
-    server/query_proc/longtermmemory/BaseQueryProcessor.cpp
-    server/query_proc/longtermmemory/EntityQueryProcessor.cpp
-    server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.cpp
-    server/query_proc/longtermmemory/CoreSegmentQueryProcessor.cpp
-    server/query_proc/longtermmemory/MemoryQueryProcessor.cpp
-
-    server/query_proc/diskmemory/BaseQueryProcessor.cpp
-    server/query_proc/diskmemory/EntityQueryProcessor.cpp
-    server/query_proc/diskmemory/ProviderSegmentQueryProcessor.cpp
-    server/query_proc/diskmemory/CoreSegmentQueryProcessor.cpp
-    server/query_proc/diskmemory/MemoryQueryProcessor.cpp
+    server/query_proc/diskmemory.cpp
+    server/query_proc/ltm.cpp
+    server/query_proc/wm.cpp
 
     mns/MemoryNameSystem.cpp
     mns/ComponentPlugin.cpp
@@ -133,10 +119,13 @@ set(LIB_FILES
 
 set(LIB_HEADERS
     core.h
+    core/forward_declarations.h
+
     core/Commit.h
     core/DataMode.h
     core/MemoryID.h
     core/MemoryID_operators.h
+    core/operations.h
     core/SuccessHeader.h
     core/Time.h
     core/aron_conversions.h
@@ -150,10 +139,11 @@ set(LIB_HEADERS
     core/error/mns.h
 
     core/base/detail/MemoryItem.h
-    core/base/detail/MaxHistorySize.h
     core/base/detail/MemoryContainerBase.h
     core/base/detail/EntityContainerBase.h
     core/base/detail/AronTyped.h
+    core/base/detail/iteration_mixins.h
+    core/base/detail/negative_index_semantics.h
 
     core/base/CoreSegmentBase.h
     core/base/EntityBase.h
@@ -161,20 +151,15 @@ set(LIB_HEADERS
     core/base/EntitySnapshotBase.h
     core/base/MemoryBase.h
     core/base/ProviderSegmentBase.h
+    core/base/ice_conversions.h
 
-    core/workingmemory/detail/CopyWithoutData.h
-    core/workingmemory/CoreSegment.h
-    core/workingmemory/Entity.h
-    core/workingmemory/EntityInstance.h
-    core/workingmemory/EntitySnapshot.h
-    core/workingmemory/Memory.h
-    core/workingmemory/ProviderSegment.h
-    core/workingmemory/ice_conversions.h
-    core/workingmemory/json_conversions.h
-    core/workingmemory/entityInstance_conversions.h
-    core/workingmemory/visitor.h
-    core/workingmemory/visitor/Visitor.h
-    core/workingmemory/visitor/FunctionalVisitor.h
+    core/wm.h
+    core/wm/memory_definitions.h
+    core/wm/aron_conversions.h
+    core/wm/ice_conversions.h
+    core/wm/json_conversions.h
+    core/wm/visitor/Visitor.h
+    core/wm/visitor/FunctionalVisitor.h
 
     core/longtermmemory/CoreSegment.h
     core/longtermmemory/Entity.h
@@ -217,45 +202,38 @@ set(LIB_HEADERS
     client/util/SimpleWriterBase.h
 
     server.h
+    server/forward_declarations.h
+
     server/ComponentPlugin.h
     server/MemoryToIceAdapter.h
     server/MemoryRemoteGui.h
     server/RemoteGuiAronDataVisitor.h
 
+    server/wm/memory_definitions.h
+    server/wm/ice_conversions.h
+    server/wm/detail/MaxHistorySize.h
+
     server/segment/Segment.h
     server/segment/SpecializedSegment.h
 
     server/query_proc.h
+
+    server/query_proc/base.h
     server/query_proc/base/BaseQueryProcessorBase.h
     server/query_proc/base/EntityQueryProcessorBase.h
     server/query_proc/base/ProviderSegmentQueryProcessorBase.h
     server/query_proc/base/CoreSegmentQueryProcessorBase.h
     server/query_proc/base/MemoryQueryProcessorBase.h
 
-    server/query_proc/workingmemory/BaseQueryProcessor.h
-    server/query_proc/workingmemory/EntityQueryProcessor.h
-    server/query_proc/workingmemory/ProviderSegmentQueryProcessor.h
-    server/query_proc/workingmemory/CoreSegmentQueryProcessor.h
-    server/query_proc/workingmemory/MemoryQueryProcessor.h
-
-    server/query_proc/longtermmemory/BaseQueryProcessor.h
-    server/query_proc/longtermmemory/EntityQueryProcessor.h
-    server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.h
-    server/query_proc/longtermmemory/CoreSegmentQueryProcessor.h
-    server/query_proc/longtermmemory/MemoryQueryProcessor.h
-
-    server/query_proc/diskmemory/BaseQueryProcessor.h
-    server/query_proc/diskmemory/EntityQueryProcessor.h
-    server/query_proc/diskmemory/ProviderSegmentQueryProcessor.h
-    server/query_proc/diskmemory/CoreSegmentQueryProcessor.h
-    server/query_proc/diskmemory/MemoryQueryProcessor.h
+    server/query_proc/diskmemory.h
+    server/query_proc/ltm.h
+    server/query_proc/wm.h
 
     mns.h
     mns/MemoryNameSystem.h
     mns/ComponentPlugin.h
 
     util/util.h
-
 )
 
 armarx_add_library(
diff --git a/source/RobotAPI/libraries/armem/client/Query.cpp b/source/RobotAPI/libraries/armem/client/Query.cpp
index 1777839f24e6f2522e7f0efb9670f79ff463231b..52000cf3d25f118ea80cf7dfc7c5ea5830cb36f8 100644
--- a/source/RobotAPI/libraries/armem/client/Query.cpp
+++ b/source/RobotAPI/libraries/armem/client/Query.cpp
@@ -1,6 +1,6 @@
 #include "Query.h"
 
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 namespace armarx::armem::client
 {
diff --git a/source/RobotAPI/libraries/armem/client/Query.h b/source/RobotAPI/libraries/armem/client/Query.h
index c6bb445bfe8ee9a3547ae621aa8c16ec8e0e2be9..56b9caa79b06bf598836a8cb4df5ab492177604a 100644
--- a/source/RobotAPI/libraries/armem/client/Query.h
+++ b/source/RobotAPI/libraries/armem/client/Query.h
@@ -3,10 +3,10 @@
 // RobotAPI
 #include <RobotAPI/interface/armem/query.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/core/SuccessHeader.h>
 #include <RobotAPI/libraries/armem/core/DataMode.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 namespace armarx::armem::client::query
diff --git a/source/RobotAPI/libraries/armem/client/Reader.cpp b/source/RobotAPI/libraries/armem/client/Reader.cpp
index a589512f13bcdaaa2536f597a54474eb72f96574..1f0e2ee51717e011de75f9fad4dd9c2c598ada88 100644
--- a/source/RobotAPI/libraries/armem/client/Reader.cpp
+++ b/source/RobotAPI/libraries/armem/client/Reader.cpp
@@ -6,9 +6,8 @@
 
 #include <RobotAPI/libraries/armem/core/MemoryID_operators.h>
 #include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.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>
 
 #include "query/Builder.h"
@@ -162,30 +161,25 @@ namespace armarx::armem::client
     }
 
 
-    struct FindLatestSnapshotVisitor : public wm::Visitor
-    {
-        std::optional<wm::EntitySnapshot> latest = std::nullopt;
-
-        bool visitEnter(const wm::EntitySnapshot& snapshot) override;
-    };
-    bool FindLatestSnapshotVisitor::visitEnter(const wm::EntitySnapshot& snapshot)
-    {
-        if (not latest.has_value() or snapshot.time() < latest->time())
-        {
-            latest = snapshot;
-        }
-        return true;
-    }
-
-
     std::optional<wm::EntitySnapshot> Reader::getLatestSnapshotIn(const MemoryID& id, DataMode dataMode) const
     {
         client::QueryResult result = getLatestSnapshotsIn(id, dataMode);
         if (result.success)
         {
-            FindLatestSnapshotVisitor visitor;
-            visitor.applyTo(result.memory);
-            return visitor.latest;
+            std::optional<wm::EntitySnapshot> latest = std::nullopt;
+            result.memory.forEachEntity([&latest](const wm::Entity & entity)
+            {
+                if (not entity.empty())
+                {
+                    const wm::EntitySnapshot& snapshot = entity.getLatestSnapshot();
+                    if (not latest.has_value() or latest->time() < snapshot.time())
+                    {
+                        latest = snapshot;
+                    }
+                }
+                return true;
+            });
+            return latest;
         }
         else
         {
diff --git a/source/RobotAPI/libraries/armem/client/Reader.h b/source/RobotAPI/libraries/armem/client/Reader.h
index 1d69491d2cf33e7bdf460634ef69bc26db4bb52b..e9ee1b69afef7d2befdaaf0169b0117a13edbad5 100644
--- a/source/RobotAPI/libraries/armem/client/Reader.h
+++ b/source/RobotAPI/libraries/armem/client/Reader.h
@@ -8,8 +8,7 @@
 // RobotAPI
 #include <RobotAPI/interface/armem/server/ReadingMemoryInterface.h>
 #include <RobotAPI/interface/armem/server/StoringMemoryInterface.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.h>
-// #include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include "Query.h"
 
diff --git a/source/RobotAPI/libraries/armem/client/Writer.h b/source/RobotAPI/libraries/armem/client/Writer.h
index dd953fa368d9a46363677d3bc39bc71f8da2a9ce..92c7ce04a3d1ec9317f33404bafef2ac58c8c3cd 100644
--- a/source/RobotAPI/libraries/armem/client/Writer.h
+++ b/source/RobotAPI/libraries/armem/client/Writer.h
@@ -2,7 +2,7 @@
 
 #include <RobotAPI/interface/armem/server/WritingMemoryInterface.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 
 namespace armarx::armem::client
diff --git a/source/RobotAPI/libraries/armem/client/query/selectors.cpp b/source/RobotAPI/libraries/armem/client/query/selectors.cpp
index 98e79d06ab3642b25bee40e89daf728ab3dfee2b..ecd3f8c5f4a1b3ed0a7dde04c8dc1ac8a06b5265 100644
--- a/source/RobotAPI/libraries/armem/client/query/selectors.cpp
+++ b/source/RobotAPI/libraries/armem/client/query/selectors.cpp
@@ -1,7 +1,7 @@
 #include "selectors.h"
 #include "RobotAPI/libraries/armem/core/ice_conversions.h"
 
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 
 namespace dq = ::armarx::armem::query::data;
diff --git a/source/RobotAPI/libraries/armem/core.h b/source/RobotAPI/libraries/armem/core.h
index c8ddee31ce054decbc8fdc33edf7959502601da7..11abe789b8cd0aef6ab2d9017c96cb1237cc5040 100644
--- a/source/RobotAPI/libraries/armem/core.h
+++ b/source/RobotAPI/libraries/armem/core.h
@@ -6,13 +6,7 @@
 #include "core/MemoryID.h"
 #include "core/Time.h"
 
-#include "core/workingmemory/Memory.h"
-#include "core/workingmemory/CoreSegment.h"
-#include "core/workingmemory/ProviderSegment.h"
-#include "core/workingmemory/Entity.h"
-#include "core/workingmemory/EntitySnapshot.h"
-#include "core/workingmemory/EntityInstance.h"
-#include "core/workingmemory/ice_conversions.h"
+#include "core/wm.h"
 
 
 namespace armarx::armem
diff --git a/source/RobotAPI/libraries/armem/core/Commit.cpp b/source/RobotAPI/libraries/armem/core/Commit.cpp
index fed7ed660b450bb0865a018f9c8d7119dd96a7b4..fed012450b059f50159c659217694c160e8f636a 100644
--- a/source/RobotAPI/libraries/armem/core/Commit.cpp
+++ b/source/RobotAPI/libraries/armem/core/Commit.cpp
@@ -1,9 +1,11 @@
 #include "Commit.h"
 
-#include <SimoxUtility/algorithm/apply.hpp>
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <SimoxUtility/algorithm/apply.hpp>
+
 
 namespace armarx::armem
 {
diff --git a/source/RobotAPI/libraries/armem/core/Commit.h b/source/RobotAPI/libraries/armem/core/Commit.h
index fc69a4b53dcaecc52d703aa42c00405f4162825f..685886a7f27b5d43b78cd0195693e32c3a58fffa 100644
--- a/source/RobotAPI/libraries/armem/core/Commit.h
+++ b/source/RobotAPI/libraries/armem/core/Commit.h
@@ -1,11 +1,12 @@
 #pragma once
 
-#include <vector>
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
 
-#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
 
-#include "../core/MemoryID.h"
-#include "../core/Time.h"
+#include <memory>
+#include <vector>
 
 
 namespace armarx::armem
diff --git a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
index 5e22ba7036a7d0b94a4a329e3d73e591b29a9543..0de79cccd0af6a85dd396b8891e91c572ee24fb2 100644
--- a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
@@ -6,7 +6,7 @@
 #include "ProviderSegmentBase.h"
 #include "detail/AronTyped.h"
 #include "detail/EntityContainerBase.h"
-#include "detail/MaxHistorySize.h"
+#include "detail/iteration_mixins.h"
 
 
 namespace armarx::armem::base
@@ -18,8 +18,10 @@ namespace armarx::armem::base
     template <class _ProviderSegmentT, class _Derived>
     class CoreSegmentBase :
         public detail::EntityContainerBase<_ProviderSegmentT, typename _ProviderSegmentT::EntityT, _Derived>,
-        public detail::MaxHistorySize,
-        public detail::AronTyped
+        public detail::AronTyped,
+        public detail::ForEachEntityInstanceMixin<_Derived>,
+        public detail::ForEachEntitySnapshotMixin<_Derived>,
+        public detail::ForEachEntityMixin<_Derived>
     {
         using Base = detail::EntityContainerBase<_ProviderSegmentT, typename _ProviderSegmentT::EntityT, _Derived>;
 
@@ -50,20 +52,21 @@ namespace armarx::armem::base
             {}
         };
 
+
     public:
 
         CoreSegmentBase()
         {
         }
-        CoreSegmentBase(const std::string& name, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
-            CoreSegmentBase(MemoryID().withCoreSegmentName(name), aronType)
+        explicit CoreSegmentBase(const std::string& name, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+            CoreSegmentBase(name, MemoryID(), aronType)
         {
         }
-        CoreSegmentBase(const std::string& name, const MemoryID& parentID, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
-            CoreSegmentBase(parentID.withProviderSegmentName(name), aronType)
+        explicit CoreSegmentBase(const std::string& name, const MemoryID& parentID, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+            CoreSegmentBase(parentID.withCoreSegmentName(name), aronType)
         {
         }
-        CoreSegmentBase(const MemoryID& id, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+        explicit CoreSegmentBase(const MemoryID& id, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
             Base(id),
             AronTyped(aronType)
         {
@@ -75,6 +78,8 @@ namespace armarx::armem::base
         CoreSegmentBase& operator=(CoreSegmentBase&& other) = default;
 
 
+        // READ ACCESS
+
         inline const std::string& name() const
         {
             return this->id().coreSegmentName;
@@ -85,19 +90,14 @@ namespace armarx::armem::base
         }
 
 
-        inline const auto& providerSegments() const
-        {
-            return this->_container;
-        }
-        inline auto& providerSegments()
+        bool hasProviderSegment(const std::string& name) const
         {
-            return this->_container;
+            return this->_container.count(name) > 0;
         }
 
-
-        bool hasProviderSegment(const std::string& name) const
+        std::vector<std::string> getProviderSegmentNames() const
         {
-            return this->_container.count(name) > 0;
+            return simox::alg::get_keys(this->_container);
         }
 
         ProviderSegmentT& getProviderSegment(const std::string& name)
@@ -119,13 +119,13 @@ namespace armarx::armem::base
         }
 
         using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const override
+        const EntityT& getEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.coreSegmentName, this->getKeyString());
             return getProviderSegment(id.providerSegmentName).getEntity(id);
         }
 
-        const EntityT* findEntity(const MemoryID& id) const override
+        const EntityT* findEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.coreSegmentName, this->getKeyString());
             if (id.hasProviderSegmentName())
@@ -145,12 +145,51 @@ namespace armarx::armem::base
             }
         }
 
+
+        // ITERATION
+
+        /**
+         * @param func Function like: bool process(ProviderSegmentT& provSeg)
+         */
+        template <class ProviderSegmentFunctionT>
+        bool forEachProviderSegment(ProviderSegmentFunctionT&& func)
+        {
+            return this->forEachChild(func);
+        }
+        /**
+         * @param func Function like: bool process(const ProviderSegmentT& provSeg)
+         */
+        template <class ProviderSegmentFunctionT>
+        bool forEachProviderSegment(ProviderSegmentFunctionT&& func) const
+        {
+            return this->forEachChild(func);
+        }
+
+        // forEachEntity() is provided by ForEachEntityMixin.
+        // forEachSnapshot() is provided by ForEachEntitySnapshotMixin.
+        // forEachInstance() is provided by ForEachEntityInstanceMixin.
+
+
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline const auto& providerSegments() const
+        {
+            return this->_container;
+        }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline auto& providerSegments()
+        {
+            return this->_container;
+        }
+
+
+        // MODIFICATION
+
         /**
          * @brief Updates an entity's history.
          *
          * Missing entity entries are added before updating.
          */
-        virtual UpdateResult update(const EntityUpdate& update)
+        UpdateResult update(const EntityUpdate& update)
         {
             this->_checkContainerName(update.entityID.coreSegmentName, this->name());
 
@@ -185,7 +224,7 @@ namespace armarx::armem::base
                 }
                 else
                 {
-                    throw error::MissingEntry::create<EntitySnapshotT>(providerSegmentName, *this);
+                    throw error::MissingEntry::create<ProviderSegmentT>(providerSegmentName, *this);
                 }
             }
             else
@@ -197,21 +236,18 @@ namespace armarx::armem::base
 
         void append(const _Derived& m)
         {
-            ARMARX_INFO << "CoreSegment: Merge name '" << m.name() << "' into '" << name() << "'";
+            // ARMARX_INFO << "CoreSegment: Merge name '" << m.name() << "' into '" << name() << "'";
 
-            for (const auto& [k, s] : m.container())
+            m.forEachProviderSegment([this](const ProviderSegmentT & provSeg)
             {
-                if (const auto& it = this->_container.find(k); it != this->_container.end())
+                auto it = this->_container.find(provSeg.name());
+                if (it == this->_container.end())
                 {
-                    // segment already exists
-                    it->second.append(s);
+                    it = this->_container.emplace(provSeg.name(), this->id().withProviderSegmentName(provSeg.name())).first;
                 }
-                else
-                {
-                    auto wms = this->_container.emplace(k, this->id().withProviderSegmentName(k));
-                    wms.first->second.append(s);
-                }
-            }
+                it->second.append(provSeg);
+                return true;
+            });
         }
 
         /**
@@ -223,7 +259,7 @@ 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, type));
+            return addProviderSegment(ProviderSegmentT(name, this->id(), type));
         }
 
         /// Copy and insert a provider segment.
@@ -238,31 +274,18 @@ namespace armarx::armem::base
             if (hasProviderSegment(providerSegment.name()))
             {
                 throw armem::error::ContainerEntryAlreadyExists(
-                    providerSegment.getLevelName(), providerSegment.name(), getLevelName(), this->getKeyString());
+                    ProviderSegmentT::getLevelName(), providerSegment.name(), getLevelName(), this->getKeyString());
             }
 
             auto it = this->_container.emplace(providerSegment.name(), std::move(providerSegment)).first;
             it->second.id().setCoreSegmentID(this->id());
-            it->second.setMaxHistorySize(_maxHistorySize);
             return it->second;
         }
 
 
-        /**
-         * @brief Sets the maximum history size of entities in this segment.
-         * This affects all current entities as well as new ones.
-         * @see Entity::setMaxHistorySize()
-         */
-        void setMaxHistorySize(long maxSize) override
-        {
-            MaxHistorySize::setMaxHistorySize(maxSize);
-            for (auto& [name, seg] : this->_container)
-            {
-                seg.setMaxHistorySize(maxSize);
-            }
-        }
+        // MISC
 
-        virtual bool equalsDeep(const CoreSegmentBase& other) const
+        bool equalsDeep(const DerivedT& other) const
         {
             //std::cout << "CoreSegment::equalsDeep" << std::endl;
             if (this->size() != other.size())
@@ -283,33 +306,17 @@ namespace armarx::armem::base
             return true;
         }
 
-        std::string getLevelName() const override
+        static std::string getLevelName()
         {
             return "core segment";
         }
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return this->name();
         }
 
 
-    protected:
-
-        virtual void _copySelf(DerivedT& other) const override
-        {
-            Base::_copySelf(other);
-            other.aronType() = _aronType;
-            other._addMissingProviderSegmentDuringUpdate = _addMissingProviderSegmentDuringUpdate;
-        }
-        virtual void _copySelfEmpty(DerivedT& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.aronType() = _aronType;
-            other._addMissingProviderSegmentDuringUpdate = _addMissingProviderSegmentDuringUpdate;
-        }
-
-
     private:
 
         bool _addMissingProviderSegmentDuringUpdate = true;
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityBase.cpp b/source/RobotAPI/libraries/armem/core/base/EntityBase.cpp
index 0d2c67b63d566f7170bd9b31cfaf18785b85f87b..d3038a357bdad823f04e8d154a569a7eebaf90d5 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityBase.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/EntityBase.cpp
@@ -1 +1,2 @@
 #include "EntityBase.h"
+
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityBase.h b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
index 0775a71f977fde16966550f0506e9fd0f591e9a5..05cbf780d1e95611d629d320581122b59c5f358c 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
@@ -5,14 +5,13 @@
 
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "../../core/Time.h"
-#include "../../core/MemoryID.h"
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
 
 #include "EntitySnapshotBase.h"
-#include "detail/MaxHistorySize.h"
 #include "detail/MemoryContainerBase.h"
+#include "detail/iteration_mixins.h"
+#include "detail/negative_index_semantics.h"
 
 
 namespace armarx::armem::base
@@ -40,7 +39,7 @@ namespace armarx::armem::base
     template <class _EntitySnapshotT, class _Derived>
     class EntityBase :
         public detail::MemoryContainerBase<std::map<Time, _EntitySnapshotT>, _Derived>,
-        public detail::MaxHistorySize
+        public detail::ForEachEntityInstanceMixin<_Derived>
     {
         using Base = detail::MemoryContainerBase<std::map<Time, _EntitySnapshotT>, _Derived>;
 
@@ -66,11 +65,11 @@ namespace armarx::armem::base
         EntityBase()
         {
         }
-        EntityBase(const std::string& name, const MemoryID& parentID = {}) :
+        explicit EntityBase(const std::string& name, const MemoryID& parentID = {}) :
             EntityBase(parentID.withEntityName(name))
         {
         }
-        EntityBase(const MemoryID& id) :
+        explicit EntityBase(const MemoryID& id) :
             Base(id)
         {
         }
@@ -82,27 +81,7 @@ namespace armarx::armem::base
         EntityBase& operator=(EntityBase&& other) = default;
 
 
-        virtual bool equalsDeep(const EntityBase& other) const
-        {
-            //std::cout << "Entity::equalsDeep" << std::endl;
-            if (this->size() != other.size())
-            {
-                return false;
-            }
-            for (const auto& [key, snapshot] : this->_container)
-            {
-                if (not other.hasSnapshot(key))
-                {
-                    return false;
-                }
-                if (not snapshot.equalsDeep(other.getSnapshot(key)))
-                {
-                    return false;
-                }
-            }
-            return true;
-        }
-
+        // READING
 
         inline const std::string& name() const
         {
@@ -113,26 +92,14 @@ namespace armarx::armem::base
             return const_cast<std::string&>(const_cast<const EntityBase*>(this)->name());
         }
 
-
-        inline const ContainerT& history() const
-        {
-            return this->_container;
-        }
-        inline ContainerT& history()
-        {
-            return const_cast<ContainerT&>(const_cast<const EntityBase*>(this)->history());
-        }
-
-
         /**
          * @brief Indicates whether a history entry for the given time exists.
          */
-        virtual bool hasSnapshot(const Time& time)
+        bool hasSnapshot(const Time& time)
         {
             return const_cast<const EntityBase*>(this)->hasSnapshot(time);
         }
-
-        virtual bool hasSnapshot(const Time& time) const
+        bool hasSnapshot(const Time& time) const
         {
             return this->_container.count(time) > 0;
         }
@@ -154,12 +121,7 @@ namespace armarx::armem::base
         /**
          * @brief Get all timestamps in the history.
          */
-        virtual std::vector<Time> getTimestamps()
-        {
-            return const_cast<const EntityBase*>(this)->getTimestamps();
-        }
-
-        virtual std::vector<Time> getTimestamps() const
+        std::vector<Time> getTimestamps() const
         {
             return simox::alg::get_keys(this->_container);
         }
@@ -172,12 +134,12 @@ namespace armarx::armem::base
          *
          * @throws `armem::error::MissingEntry` If there is no such entry.
          */
-        virtual EntitySnapshotT& getSnapshot(const Time& time)
+        EntitySnapshotT& getSnapshot(const Time& time)
         {
             return const_cast<EntitySnapshotT&>(const_cast<const EntityBase*>(this)->getSnapshot(time));
         }
 
-        virtual 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())
@@ -210,149 +172,233 @@ namespace armarx::armem::base
         {
             return const_cast<EntitySnapshotT&>(const_cast<const EntityBase*>(this)->getLatestSnapshot());
         }
-
         const EntitySnapshotT& getLatestSnapshot() const
         {
             return getLatestItem().second;
         }
 
         /**
-         * @brief Return the lastest snapshot before or at time.
+         * @brief Return the snapshot with the most recent timestamp.
+         * @return The latest snapshot.
+         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
+         */
+        EntitySnapshotT& getFirstSnapshot()
+        {
+            return const_cast<EntitySnapshotT&>(const_cast<const EntityBase*>(this)->getFirstSnapshot());
+        }
+        const EntitySnapshotT& getFirstSnapshot() const
+        {
+            return getFirstItem().second;
+        }
+
+
+        /**
+         * @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
          */
-        virtual const EntitySnapshotT& getLatestSnapshotBeforeOrAt(const Time& time) const
+        const EntitySnapshotT& getLatestSnapshotBefore(const Time& time) const
         {
-            // first element equal or greater
-            typename ContainerT::const_iterator refIt = this->_container.upper_bound(time);
+            if (this->empty())
+            {
+                throw error::EntityHistoryEmpty(this->name());
+            }
 
-            if (refIt == this->_container.begin())
+            // We want the rightmost element < time
+            // lower_bound() gives us the the leftmost >= time, which is probably the right neighbour
+            typename ContainerT::const_iterator greaterEq = this->_container.lower_bound(time);
+            // Special cases:
+            // refIt = begin() => no element < time
+            if (greaterEq == this->_container.begin())
             {
-                if (refIt->first == time)
-                {
-                    return refIt->second;
-                }
                 throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
             }
 
-            // last element less than
-            typename ContainerT::const_iterator refItPrev = std::prev(refIt);
+            // end(): No element >= time, we can still have one < time (rbegin()) => std::prev(end())
+            // empty has been checked above
 
-            // ... or we return the element before if possible
-            if (refItPrev != this->_container.begin())
-            {
-                return refItPrev->second;
-            }
+            // std::prev of end() is ok
+            typename ContainerT::const_iterator less = std::prev(greaterEq);
 
-            throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+            // we return the element before if possible
+            return less->second;
         }
 
         /**
-         * @brief Return the lastest snapshot before time.
+         * @brief Return the lastest 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
          */
-        virtual const EntitySnapshotT& getLatestSnapshotBefore(const Time& time) const
+        const EntitySnapshotT& getLatestSnapshotBeforeOrAt(const Time& time) const
+        {
+            return getLatestSnapshotBefore(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
+         */
+        const EntitySnapshotT& getFirstSnapshotAfterOrAt(const Time& time) const
         {
-            // first element equal or greater
-            typename ContainerT::const_iterator refIt = this->_container.upper_bound(time);
+            // We want the leftmost element >= time.
+            // That's lower bound.
+            typename ContainerT::const_iterator greaterEq = this->_container.lower_bound(time);
 
-            if (refIt == this->_container.begin())
+            if (greaterEq == this->_container.end())
             {
                 throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
             }
+            return greaterEq->second;
+        }
 
-            // last element less than
-            typename ContainerT::const_iterator refItPrev = std::prev(refIt);
+        /**
+         * @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
+         */
+        const EntitySnapshotT& getFirstSnapshotAfter(const Time& time) const
+        {
+            return getFirstSnapshotAfter(time - Time::microSeconds(1));
+        }
 
-            // we return the element before if possible
-            if (refItPrev != this->_container.begin())
-            {
-                return refItPrev->second;
-            }
 
-            throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+        // ITERATION
+
+        /**
+         * @param func Function like: bool process(EntitySnapshotT& snapshot)
+         */
+        template <class SnapshotFunctionT>
+        bool forEachSnapshot(SnapshotFunctionT&& func)
+        {
+            return this->forEachChild(func);
         }
+        /**
+         * @param func Function like void process(const EntitySnapshotT& snapshot)
+         */
+        template <class SnapshotFunctionT>
+        bool forEachSnapshot(SnapshotFunctionT&& func) const
+        {
+            return this->forEachChild(func);
+        }
+        // forEachInstance() is provided by ForEachEntityInstanceMixin.
+
 
         /**
-         * @brief Return all snapshots before or at time.
+         * @brief Return all snapshots before (excluding) time.
          * @param time The time.
          * @return The latest snapshots.
-         * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
-         * @throw `armem::error::MissingEntry` If no such snapshots
          */
-        virtual const std::vector<std::reference_wrapper<const EntitySnapshotT>> getSnapshotsBefore(const Time& time) const
+        template <class FunctionT>
+        void forEachSnapshotBefore(const Time& time, FunctionT&& func) const
         {
-            std::vector<std::reference_wrapper<const EntitySnapshotT>> ret;
-            const EntitySnapshotT& latest = getLatestSnapshotBefore(time);
-
             for (const auto& [timestamp, snapshot] : this->_container)
             {
-                ret.emplace_back(snapshot);
-                if (timestamp == latest.id().timestamp)
+                if (timestamp >= time)
+                {
+                    break;
+                }
+                if (not call(func, snapshot))
                 {
                     break;
                 }
             }
-            return ret;
         }
 
         /**
-         * @brief Return first snapshot after or at time.
+         * @brief Return all snapshots before 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 latest snapshots.
          */
-        virtual const EntitySnapshotT& getFirstSnapshotAfterOrAt(const Time& time) const
+        template <class FunctionT>
+        void forEachSnapshotBeforeOrAt(const Time& time, FunctionT&& func) const
         {
-            // first element equal or greater
-            typename ContainerT::const_iterator refIt = this->_container.upper_bound(time);
-
-            if (refIt == this->_container.end())
-            {
-                throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
-            }
-            return refIt->second;
+            getSnapshotsBefore(time + Time::microSeconds(1), func);
         }
 
+
         /**
-         * @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
+         * @brief Return all snapshots between, including, min and max.
+         * @param min The lowest time to include.
+         * @param min The highest time to include.
+         * @return The snapshots in [min, max].
          */
-        virtual const EntitySnapshotT& getFirstSnapshotAfter(const Time& time) const
+        template <class FunctionT>
+        void forEachSnapshotInTimeRange(const Time& min, const Time& max, FunctionT&& func) const
         {
-            // first element equal or greater
-            typename ContainerT::const_iterator refIt = this->_container.upper_bound(time);
+            // Returns an iterator pointing to the first element that is not less than (i.e. greater or equal to) key.
+            auto begin = min.toMicroSeconds() > 0 ? this->_container.lower_bound(min) : this->_container.begin();
+            // Returns an iterator pointing to the first element that is *greater than* key.
+            auto end = max.toMicroSeconds() > 0 ? this->_container.upper_bound(max) : this->_container.end();
 
-            if (refIt == this->_container.end())
+            for (auto it = begin; it != end && it != this->_container.end(); ++it)
             {
-                throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+                if (not call(func, it->second))
+                {
+                    break;
+                }
             }
+        }
 
-            if (refIt->first > time)
+        /**
+         * @brief Return all snapshots from first to last index.
+         *
+         * Negative index are counted from the end, e.g.
+         * last == -1 results in getting all queries until the end.
+         *
+         * @param first The first index to include.
+         * @param first The last index to include.
+         * @return The snapshots in [first, last].
+         */
+        template <class FunctionT>
+        void forEachSnapshotInIndexRange(long first, long last, FunctionT&& func) const
+        {
+            if (this->empty())
             {
-                return refIt->second;
+                return;
             }
 
-            // first element greater than
-            typename ContainerT::const_iterator refItNext = std::next(refIt);
+            const size_t first_ = detail::negativeIndexSemantics(first, this->size());
+            const size_t last_ = detail::negativeIndexSemantics(last, this->size());
 
-            if (refItNext != this->_container.end())
+            if (first_ <= last_)
             {
-                return refItNext->second;
+                auto it = this->_container.begin();
+                std::advance(it, first_);
+
+                size_t num = last_ - first_ + 1;  // +1 to make last inclusive
+                for (size_t i = 0; i < num; ++i, ++it)
+                {
+                    if (not call(func, it->second))
+                    {
+                        break;
+                    }
+                }
             }
+        }
+
 
-            throw error::MissingEntry::create<EntitySnapshotT>(toDateTimeMilliSeconds(time), *this);
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline const ContainerT& history() const
+        {
+            return this->_container;
         }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline ContainerT& history()
+        {
+            return const_cast<ContainerT&>(const_cast<const EntityBase*>(this)->history());
+        }
+
 
+        // MODIFICATION
 
         /**
          * @brief Add the given update to this entity's history.
@@ -371,7 +417,7 @@ namespace armarx::armem::base
             {
                 // Insert into history.
                 snapshot = &addSnapshot(update.timeCreated);
-                ret.removedSnapshots = truncate();
+                // ret.removedSnapshots = this->truncate();
                 ret.entityUpdateType = UpdateType::InsertedNew;
             }
             else
@@ -380,30 +426,30 @@ namespace armarx::armem::base
                 ret.entityUpdateType = UpdateType::UpdatedExisting;
             }
             // Update entry.
-            snapshot->update(update, this->id());
+            snapshot->update(update);
             ret.id = snapshot->id();
 
             return ret;
         }
 
+
         void append(const DerivedT& m)
         {
-            ARMARX_INFO << "Entity: Merge name '" << m.name() << "' into '" << name() << "'";
+            // ARMARX_INFO << "Entity: Merge name '" << m.name() << "' into '" << name() << "'";
 
-            for (const auto& [k, s] : m.container())
+            m.forEachSnapshot([this](const EntitySnapshotT & snapshot)
             {
-                if (const auto& it = this->_container.find(k); it != this->_container.end())
-                {
-                    // segment already exists
-                    // We assume that a snapshot does not change, so ignore
-                }
-                else
+                auto it = this->_container.find(snapshot.time());
+                if (it == this->_container.end())
                 {
-                    auto snapshot = s.copy();
-                    snapshot.id() = this->id().withTimestamp(k); // update id (e.g. memory name) if necessary
-                    this->_container.insert(std::make_pair(k, std::move(snapshot)));
+                    EntitySnapshotT copy { snapshot };
+                    copy.id() = this->id().withTimestamp(snapshot.time()); // update id (e.g. memory name) if necessary
+                    this->_container.emplace(snapshot.time(), copy);
                 }
-            }
+                // else: segment already exists
+                // We assume that a snapshot does not change, so ignore
+                return true;
+            });
         }
 
         /**
@@ -425,26 +471,39 @@ namespace armarx::armem::base
 
         EntitySnapshotT& addSnapshot(const Time& timestamp)
         {
-            return addSnapshot(EntitySnapshotT(timestamp));
+            return addSnapshot(EntitySnapshotT(timestamp, this->id()));
         }
 
 
-        /**
-         * @brief Sets the maximum history size.
-         *
-         * The current history is truncated if necessary.
-         */
-        void setMaxHistorySize(long maxSize) override
+
+        // MISC
+
+        bool equalsDeep(const DerivedT& other) const
         {
-            MaxHistorySize::setMaxHistorySize(maxSize);
-            truncate();
+            //std::cout << "Entity::equalsDeep" << std::endl;
+            if (this->size() != other.size())
+            {
+                return false;
+            }
+            for (const auto& [key, snapshot] : this->_container)
+            {
+                if (not other.hasSnapshot(key))
+                {
+                    return false;
+                }
+                if (not snapshot.equalsDeep(other.getSnapshot(key)))
+                {
+                    return false;
+                }
+            }
+            return true;
         }
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return this->id().entityName;
         }
-        std::string getLevelName() const override
+        static std::string getLevelName()
         {
             return "entity";
         }
@@ -452,28 +511,11 @@ namespace armarx::armem::base
 
     protected:
 
-        /// If maximum size is set, ensure `history`'s is not higher.
-        std::vector<EntitySnapshotT> truncate()
-        {
-            std::vector<EntitySnapshotT> removedElements;
-            if (_maxHistorySize >= 0)
-            {
-                while (this->_container.size() > size_t(_maxHistorySize))
-                {
-                    removedElements.push_back(std::move(this->_container.begin()->second));
-                    this->_container.erase(this->_container.begin());
-                }
-                ARMARX_CHECK_LESS_EQUAL(this->_container.size(), _maxHistorySize);
-            }
-            return removedElements;
-        }
-
         /**
          * @brief Return the snapshot with the most recent timestamp.
          * @return The latest snapshot.
          * @throw `armem::error::EntityHistoryEmpty` If the history is empty.
          */
-        virtual
         const typename ContainerT::value_type&
         getLatestItem() const
         {
@@ -484,6 +526,22 @@ namespace armarx::armem::base
             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.cpp b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
index a6cfc7103728d5a81fecefe4ade6c96efef2814e..1cc2e9544d00ce96d65658acaf853c670418bdce 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
@@ -1 +1,25 @@
 #include "EntityInstanceBase.h"
+
+
+namespace armarx::armem::base
+{
+    bool EntityInstanceMetadata::operator==(const EntityInstanceMetadata& other) const
+    {
+        return timeCreated == other.timeCreated
+               && timeSent == other.timeSent
+               && timeArrived == other.timeArrived
+               && std::abs(confidence - other.confidence) < 1e-6f;
+    }
+}
+
+
+std::ostream& armarx::armem::base::operator<<(std::ostream& os, const EntityInstanceMetadata& d)
+{
+    os << "EntityInstanceMetadata: "
+       << "\n- t_create =   \t" << armem::toStringMicroSeconds(d.timeCreated) << " us"
+       << "\n- t_sent =     \t" << armem::toStringMicroSeconds(d.timeSent) << " us"
+       << "\n- t_arrived =  \t" << armem::toStringMicroSeconds(d.timeArrived) << " us"
+       << "\n- confidence = \t" << d.confidence << " us"
+       ;
+    return os;
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
index 8dd474c667687e6235a96a191e577163ca194cba..fcb1869f791d9094fd793ff3af721e5fb942f111 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
@@ -1,17 +1,53 @@
 #pragma once
 
-#include "../../core/Time.h"
+#include <RobotAPI/libraries/armem/core/Commit.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
 
-#include "../Commit.h"
 #include "detail/MemoryItem.h"
 
 
 namespace armarx::armem::base
 {
+
+    /**
+     * @brief Default data of an entity instance (empty).
+     */
+    struct NoData
+    {
+    };
+
+
+    /**
+     * @brief Metadata of an entity instance.
+     */
+    struct EntityInstanceMetadata
+    {
+        /// Time when this value was created.
+        Time timeCreated;
+        /// Time when this value was sent to the memory.
+        Time timeSent;
+        /// Time when this value has arrived at the memory.
+        Time timeArrived;
+
+        /// An optional confidence, may be used for things like decay.
+        float confidence = 1.0;
+
+
+        bool operator==(const EntityInstanceMetadata& other) const;
+        inline bool operator!=(const EntityInstanceMetadata& other) const
+        {
+            return !(*this == other);
+        }
+    };
+
+    std::ostream& operator<<(std::ostream& os, const EntityInstanceMetadata& rhs);
+
+
+
     /**
      * @brief Data of a single entity instance.
      */
-    template <class _DerivedT>
+    template <class _DataT = NoData, class _MetadataT = EntityInstanceMetadata>
     class EntityInstanceBase :
         public detail::MemoryItem
     {
@@ -19,19 +55,18 @@ namespace armarx::armem::base
 
     public:
 
-        using DerivedT = _DerivedT;
+        using MetadataT = _MetadataT;
+        using DataT = _DataT;
 
 
-    public:
-
         EntityInstanceBase()
         {
         }
-        EntityInstanceBase(int index, const MemoryID& parentID = {}) :
+        explicit EntityInstanceBase(int index, const MemoryID& parentID = {}) :
             EntityInstanceBase(parentID.withInstanceIndex(index))
         {
         }
-        EntityInstanceBase(const MemoryID& id) :
+        explicit EntityInstanceBase(const MemoryID& id) :
             Base(id)
         {
         }
@@ -46,40 +81,47 @@ namespace armarx::armem::base
             return id().instanceIndex;
         }
 
-        /**
-         * @brief Fill `*this` with the update's values.
-         * @param update The update.
-         * @param index The instances index.
-         */
-        virtual void update(const EntityUpdate& update, int index) = 0;
 
-        virtual bool equalsDeep(const DerivedT& other) const = 0;
+        EntityInstanceMetadata& metadata()
+        {
+            return _metadata;
+        }
+        const EntityInstanceMetadata& metadata() const
+        {
+            return _metadata;
+        }
 
-        virtual DerivedT copy() const
+        const DataT& data() const
         {
-            DerivedT d;
-            this->_copySelf(d);
-            return d;
+            return _data;
         }
 
+        DataT& data()
+        {
+            return _data;
+        }
 
-        std::string getLevelName() const override
+
+        static std::string getLevelName()
         {
             return "entity instance";
         }
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return std::to_string(index());
         }
 
 
+
     protected:
 
-        virtual void _copySelf(DerivedT& other) const
-        {
-            Base::_copySelf(other);
-        }
+        /// The metadata.
+        MetadataT _metadata;
+
+        /// The data. May be nullptr.
+        DataT _data;
+
 
     };
 
diff --git a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.cpp b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.cpp
index 5f7899f50d954f16b2d9c0a9569519529895eb20..72b4c48877c78dce70737fa58c58cd1b82b2d2e5 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.cpp
@@ -1 +1,11 @@
 #include "EntitySnapshotBase.h"
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+
+void armarx::armem::base::detail::throwIfNotEqual(const Time& ownTime, const Time& updateTime)
+{
+    ARMARX_CHECK_EQUAL(ownTime, updateTime)
+            << "Cannot update a snapshot to an update with another timestamp. \n"
+            << "Note: A snapshot's timestamp must not be changed after construction.";
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
index cf68286be26368cb4821fecbbe241e3ef33e0fbe..36d7274acedb92271587e3ba941345254033d840 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
@@ -1,6 +1,5 @@
 #pragma once
 
-#include <memory>
 #include <vector>
 
 #include "../MemoryID.h"
@@ -8,8 +7,13 @@
 
 #include "EntityInstanceBase.h"
 #include "detail/MemoryContainerBase.h"
+#include "detail/iteration_mixins.h"
 
 
+namespace armarx::armem::base::detail
+{
+    void throwIfNotEqual(const Time& ownTime, const Time& updateTime);
+}
 namespace armarx::armem::base
 {
     /**
@@ -34,11 +38,11 @@ namespace armarx::armem::base
         EntitySnapshotBase()
         {
         }
-        EntitySnapshotBase(Time time, const MemoryID& parentID = {}) :
+        explicit EntitySnapshotBase(Time time, const MemoryID& parentID = {}) :
             EntitySnapshotBase(parentID.withTimestamp(time))
         {
         }
-        EntitySnapshotBase(const MemoryID& id) :
+        explicit EntitySnapshotBase(const MemoryID& id) :
             Base(id)
         {
         }
@@ -49,24 +53,7 @@ namespace armarx::armem::base
         EntitySnapshotBase& operator=(EntitySnapshotBase&& other) = default;
 
 
-        bool equalsDeep(const EntitySnapshotBase& other) const
-        {
-            //std::cout << "EntitySnapshot::equalsDeep" << std::endl;
-            if (this->size() != other.size())
-            {
-                return false;
-            }
-            int i = 0;
-            for (const auto& instance : this->_container)
-            {
-                if (not instance.equalsDeep(other.getInstance(i)))
-                {
-                    return false;
-                }
-                i++;
-            }
-            return true;
-        }
+        // READING
 
         inline Time& time()
         {
@@ -78,34 +65,6 @@ namespace armarx::armem::base
             return this->id().timestamp;
         }
 
-
-        inline const std::vector<EntityInstanceT>& instances() const
-        {
-            return this->_container;
-        }
-        inline std::vector<EntityInstanceT>& instances()
-        {
-            return const_cast<std::vector<EntityInstanceT>&>(const_cast<const EntitySnapshotBase*>(this)->instances());
-        }
-
-
-        void update(const EntityUpdate& update, std::optional<MemoryID> parentID = std::nullopt)
-        {
-            if (parentID)
-            {
-                this->id() = *parentID;
-            }
-            time() = update.timeCreated;
-
-            this->_container.clear();
-            for (int i = 0; i < int(update.instancesData.size()); ++i)
-            {
-                EntityInstanceT& data = this->_container.emplace_back(i, this->id());
-                data.update(update, i);
-            }
-        }
-
-
         bool hasInstance(int index) const
         {
             size_t si = size_t(index);
@@ -122,7 +81,6 @@ namespace armarx::armem::base
         {
             return const_cast<EntityInstanceT&>(const_cast<const EntitySnapshotBase*>(this)->getInstance(index));
         }
-
         const EntityInstanceT& getInstance(int index) const
         {
             if (hasInstance(index))
@@ -135,6 +93,23 @@ namespace armarx::armem::base
             }
         }
 
+        EntityInstanceT* findInstance(int index)
+        {
+            return const_cast<EntityInstanceT*>(const_cast<const EntitySnapshotBase*>(this)->findInstance(index));
+        }
+        const EntityInstanceT* findInstance(int index) const
+        {
+            if (hasInstance(index))
+            {
+                return &this->_container[static_cast<size_t>(index)];
+            }
+            else
+            {
+                return nullptr;
+            }
+        }
+
+
         /**
          * @brief Get the given instance.
          * @param index The instance's index.
@@ -157,6 +132,51 @@ namespace armarx::armem::base
         }
 
 
+        // ITERATION
+
+        /**
+         * @param func Function like void process(EntityInstanceT& instance)>
+         */
+        template <class InstanceFunctionT>
+        bool forEachInstance(InstanceFunctionT&& func)
+        {
+            return this->forEachChild(func);
+        }
+        /**
+         * @param func Function like void process (const EntityInstanceT& instance)
+         */
+        template <class InstanceFunctionT>
+        bool forEachInstance(InstanceFunctionT&& func) const
+        {
+            return this->forEachChild(func);
+        }
+
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline const std::vector<EntityInstanceT>& instances() const
+        {
+            return this->_container;
+        }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline std::vector<EntityInstanceT>& instances()
+        {
+            return const_cast<std::vector<EntityInstanceT>&>(const_cast<const EntitySnapshotBase*>(this)->instances());
+        }
+
+
+        // MODIFICATION
+
+        void update(const EntityUpdate& update)
+        {
+            detail::throwIfNotEqual(time(), update.timeCreated);
+
+            this->_container.clear();
+            for (int index = 0; index < int(update.instancesData.size()); ++index)
+            {
+                EntityInstanceT& data = this->_container.emplace_back(index, this->id());
+                data.update(update);
+            }
+        }
+
         /**
          * @brief Add a single instance with data.
          * @param instance The instance.
@@ -181,27 +201,49 @@ namespace armarx::armem::base
                                              "Cannot add an EntityInstance because its index is too big.");
             }
 
-            int new_index = this->_container.size();
-            auto& it = this->_container.emplace_back(std::move(instance));
-            it.index() = new_index;
-            return it;
+            int index = static_cast<int>(this->_container.size());
+            EntityInstanceT& added = this->_container.emplace_back(std::move(instance));
+            added.id() = this->id().withInstanceIndex(index);
+            return added;
         }
 
         EntityInstanceT& addInstance()
         {
-            int new_index = this->_container.size();
-            auto& it = this->_container.emplace_back(EntityInstanceT());;
-            it.index() = new_index;
-            it.id() = this->id().withInstanceIndex(new_index);
-            return it;
+            int index = static_cast<int>(this->size());
+            EntityInstanceT& added = this->_container.emplace_back(EntityInstanceT());
+            added.id() = this->id().withInstanceIndex(index);
+            return added;
         }
 
-        std::string getKeyString() const override
+
+        // MISC
+
+        bool equalsDeep(const DerivedT& other) const
+        {
+            //std::cout << "EntitySnapshot::equalsDeep" << std::endl;
+            if (this->size() != other.size())
+            {
+                return false;
+            }
+            int i = 0;
+            for (const auto& instance : this->_container)
+            {
+                if (not instance.equalsDeep(other.getInstance(i)))
+                {
+                    return false;
+                }
+                i++;
+            }
+            return true;
+        }
+
+
+        std::string getKeyString() const
         {
             return toDateTimeMilliSeconds(this->time());
         }
 
-        std::string getLevelName() const override
+        static std::string getLevelName()
         {
             return "entity snapshot";
         }
diff --git a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
index 1bc42b0cc579dbf8abe4f2831608166451ff8fbb..80b57801d0031c3b66a7e6b72573290ed8c05a5a 100644
--- a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
@@ -7,6 +7,7 @@
 
 #include "CoreSegmentBase.h"
 #include "detail/EntityContainerBase.h"
+#include "detail/iteration_mixins.h"
 
 
 namespace armarx::armem::base
@@ -17,7 +18,11 @@ namespace armarx::armem::base
      */
     template <class _CoreSegmentT, class _Derived>
     class MemoryBase :
-        public detail::EntityContainerBase<_CoreSegmentT, typename _CoreSegmentT::ProviderSegmentT::EntityT, _Derived>
+        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>
     {
         using Base = detail::EntityContainerBase<_CoreSegmentT, typename _CoreSegmentT::ProviderSegmentT::EntityT, _Derived>;
 
@@ -57,11 +62,11 @@ namespace armarx::armem::base
         MemoryBase()
         {
         }
-        MemoryBase(const std::string& name) :
+        explicit MemoryBase(const std::string& name) :
             MemoryBase(MemoryID().withMemoryName(name))
         {
         }
-        MemoryBase(const MemoryID& id) :
+        explicit MemoryBase(const MemoryID& id) :
             Base(id)
         {
         }
@@ -72,6 +77,8 @@ namespace armarx::armem::base
         MemoryBase& operator=(MemoryBase&& other) = default;
 
 
+        // READ ACCESS
+
         inline const std::string& name() const
         {
             return this->id().memoryName;
@@ -82,19 +89,14 @@ namespace armarx::armem::base
         }
 
 
-        inline auto& coreSegments() const
-        {
-            return this->_container;
-        }
-        inline auto& coreSegments()
+        bool hasCoreSegment(const std::string& name) const
         {
-            return this->_container;
+            return this->_container.count(name) > 0;
         }
 
-
-        bool hasCoreSegment(const std::string& name) const
+        std::vector<std::string> getCoreSegmentNames() const
         {
-            return this->_container.count(name) > 0;
+            return simox::alg::get_keys(this->_container);
         }
 
         CoreSegmentT& getCoreSegment(const std::string& name)
@@ -141,13 +143,13 @@ namespace armarx::armem::base
 
 
         using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const override
+        const EntityT& getEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.memoryName, this->name());
             return getCoreSegment(id.coreSegmentName).getEntity(id);
         }
 
-        const EntityT* findEntity(const MemoryID& id) const override
+        const EntityT* findEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.memoryName, this->name());
             if (id.hasCoreSegmentName())
@@ -167,32 +169,66 @@ namespace armarx::armem::base
             }
         }
 
+
+        // ITERATION
+
+        /**
+         * @param func Function like: bool process(CoreSegmentT& coreSeg)
+         */
+        template <class CoreSegmentFunctionT>
+        bool forEachCoreSegment(CoreSegmentFunctionT&& func)
+        {
+            return this->forEachChild(func);
+        }
+        /**
+         * @param func Function like: bool process(const CoreSegmentT& coreSeg)
+         */
+        template <class CoreSegmentFunctionT>
+        bool forEachCoreSegment(CoreSegmentFunctionT&& func) const
+        {
+            return this->forEachChild(func);
+        }
+
+        // forEachProviderSegment() is provided by ForEachProviderSegmentMixin.
+        // forEachEntity() is provided by ForEachEntityMixin.
+        // forEachSnapshot() is provided by ForEachEntitySnapshotMixin.
+        // forEachInstance() is provided by ForEachEntityInstanceMixin.
+
+
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline auto& coreSegments() const
+        {
+            return this->_container;
+        }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline auto& coreSegments()
+        {
+            return this->_container;
+        }
+
+
+        // MODIFICATION
+
         /**
          * @brief Add an empty core segment with the given name.
          * @param name The core segment name.
          * @param coreSegmentType The core segment type (optional).
          * @return The added core segment.
          */
-        CoreSegmentT& addCoreSegment(const std::string& name, aron::typenavigator::ObjectNavigatorPtr coreSegmentType = nullptr)
+        CoreSegmentT& addCoreSegment(
+            const std::string& name, aron::typenavigator::ObjectNavigatorPtr coreSegmentType = nullptr)
         {
-            return addCoreSegment(CoreSegmentT(name, coreSegmentType));
+            return _addCoreSegment(name, name, this->id(), coreSegmentType);
         }
         /// Copy and insert a core segment.
         CoreSegmentT& addCoreSegment(const CoreSegmentT& coreSegment)
         {
-            return addCoreSegment(CoreSegmentT(coreSegment));
+            return _addCoreSegment(coreSegment.name(), CoreSegmentT(coreSegment));
         }
         /// Move and insert a core segment.
         CoreSegmentT& addCoreSegment(CoreSegmentT&& coreSegment)
         {
-            if (this->_container.count(coreSegment.name()) > 0)
-            {
-                throw armem::error::ContainerEntryAlreadyExists(coreSegment.getLevelName(), coreSegment.name(),
-                        this->getLevelName(), this->name());
-            }
-            auto it = this->_container.emplace(coreSegment.name(), std::move(coreSegment)).first;
-            it->second.id().setMemoryID(this->id());
-            return it->second;
+            return _addCoreSegment(coreSegment.name(), coreSegment);
         }
 
         /**
@@ -223,10 +259,10 @@ namespace armarx::armem::base
          * @param commit The commit.
          * @return The resulting memory IDs.
          */
-        virtual std::vector<UpdateResult> update(const Commit& commit)
+        std::vector<UpdateResult> update(const Commit& commit)
         {
             std::vector<UpdateResult> results;
-            for (const auto& update : commit.updates)
+            for (const EntityUpdate& update : commit.updates)
             {
                 results.push_back(this->update(update));
             }
@@ -238,7 +274,7 @@ namespace armarx::armem::base
          * @param update The update.
          * @return The resulting entity snapshot's ID.
          */
-        virtual UpdateResult update(const EntityUpdate& update)
+        UpdateResult update(const EntityUpdate& update)
         {
             this->_checkContainerName(update.entityID.memoryName, this->name());
 
@@ -272,7 +308,7 @@ namespace armarx::armem::base
                 }
                 else
                 {
-                    throw error::MissingEntry::create<EntitySnapshotT>(coreSegmentName, *this);
+                    throw error::MissingEntry::create<CoreSegmentT>(coreSegmentName, *this);
                 }
             }
             else
@@ -290,22 +326,19 @@ namespace armarx::armem::base
         {
             ARMARX_INFO << "Memory: Merge name '" << m.name() << "' into '" << name() << "'";
 
-            for (const auto& [k, s] : m.container())
+            m.forEachCoreSegment([this](const CoreSegmentT & coreSeg)
             {
-                if (const auto& it = this->_container.find(k); it != this->_container.end())
-                {
-                    // segment already exists
-                    it->second.append(s);
-                }
-                else
+                auto it = this->_container.find(coreSeg.name());
+                if (it == this->_container.end())
                 {
-                    auto wms = this->_container.emplace(k, this->id().withCoreSegmentName(k));
-                    wms.first->second.append(s);
+                    it = this->_container.emplace(coreSeg.name(), this->id().withCoreSegmentName(coreSeg.name())).first;
                 }
-            }
+                it->second.append(coreSeg);
+                return true;
+            });
         }
 
-        virtual bool equalsDeep(const MemoryBase& other) const
+        bool equalsDeep(const MemoryBase& other) const
         {
             //std::cout << "Memory::equalsDeep" << std::endl;
             if (this->size() != other.size())
@@ -326,12 +359,12 @@ namespace armarx::armem::base
             return true;
         }
 
-        std::string getLevelName() const override
+        static std::string getLevelName()
         {
             return "memory";
         }
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return this->name();
         }
@@ -339,37 +372,55 @@ namespace armarx::armem::base
         std::string dump() const
         {
             std::stringstream ss;
-            ss << "Memory: " << this->name() << "\n";
-            for (const auto& [ckey, cseg] : this->container())
+            ss << "Memory '" << this->name() << "': \n";
+            forEachCoreSegment([&ss](const CoreSegmentT & cseg)
             {
-                ss << " |- Found core seg: " << ckey << "\n";
-                for (const auto& [pkey, pseg] : cseg.container())
+                ss << "+- Core segment '" << cseg.name() << "' (" << cseg.size() << "): \n";
+                cseg.forEachProviderSegment([&ss](const ProviderSegmentT & pseg)
                 {
-                    ss << " |   |- Found prov seg: " << pkey << "\n";
-                    for (const auto& [ekey, eseg] : pseg.container())
+                    ss << "|  +- Provider segment '" << pseg.name() << "' (" << pseg.size() << "): \n";
+                    pseg.forEachEntity([&ss](const EntityT & entity)
                     {
-                        ss << " |   |   |- Found entity: " << ekey << "\n";
-                    }
-                }
-            }
+                        ss << "|  |  +- Entity '" << entity.name() << "' (" << entity.size() << "): \n";
+                        return true;
+                    });
+                    return true;
+                });
+                return true;
+            });
             return ss.str();
         }
 
-    protected:
 
-        virtual void _copySelf(DerivedT& other) const override
-        {
-            Base::_copySelf(other);
-            other._addMissingCoreSegmentDuringUpdate = _addMissingCoreSegmentDuringUpdate;
-        }
-        virtual void _copySelfEmpty(DerivedT& other) const override
+    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)
         {
-            Base::_copySelfEmpty(other);
-            other._addMissingCoreSegmentDuringUpdate = _addMissingCoreSegmentDuringUpdate;
+            auto [it, existed] = this->_container.try_emplace(name, args...);
+            if (existed)
+            {
+                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;
+            }
         }
 
+
     public:
 
         bool _addMissingCoreSegmentDuringUpdate = false;
+
     };
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h b/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
index 57ff3210244fa516551f4906a2ea07c2cc81f09d..e5163241738a0e8dbba5edbd35f8e5a568060746 100644
--- a/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h
@@ -6,7 +6,7 @@
 #include "EntityBase.h"
 #include "detail/AronTyped.h"
 #include "detail/EntityContainerBase.h"
-#include "detail/MaxHistorySize.h"
+#include "detail/iteration_mixins.h"
 
 
 namespace armarx::armem::base
@@ -18,8 +18,9 @@ namespace armarx::armem::base
     template <class _EntityT, class _Derived>
     class ProviderSegmentBase :
         public detail::EntityContainerBase<_EntityT, _EntityT, _Derived>,
-        public detail::MaxHistorySize,
-        public detail::AronTyped
+        public detail::AronTyped,
+        public detail::ForEachEntityInstanceMixin<_Derived>,
+        public detail::ForEachEntitySnapshotMixin<_Derived>
     {
         using Base = detail::EntityContainerBase<_EntityT, _EntityT, _Derived>;
 
@@ -53,15 +54,15 @@ namespace armarx::armem::base
         {
         }
 
-        ProviderSegmentBase(const std::string& name, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
-            ProviderSegmentBase(MemoryID().withProviderSegmentName(name), aronType)
+        explicit ProviderSegmentBase(const std::string& name, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+            ProviderSegmentBase(name, MemoryID(), aronType)
         {
         }
-        ProviderSegmentBase(const std::string& name, const MemoryID parentID, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+        explicit ProviderSegmentBase(const std::string& name, const MemoryID parentID, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
             ProviderSegmentBase(parentID.withProviderSegmentName(name), aronType)
         {
         }
-        ProviderSegmentBase(const MemoryID id, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
+        explicit ProviderSegmentBase(const MemoryID id, aron::typenavigator::ObjectNavigatorPtr aronType = nullptr) :
             Base(id),
             AronTyped(aronType)
         {
@@ -73,6 +74,8 @@ namespace armarx::armem::base
         ProviderSegmentBase& operator=(ProviderSegmentBase&& other) = default;
 
 
+        // READ ACCESS
+
         inline const std::string& name() const
         {
             return this->id().providerSegmentName;
@@ -83,23 +86,18 @@ namespace armarx::armem::base
         }
 
 
-        inline const auto& entities() const
-        {
-            return this->_container;
-        }
-        inline auto& entities()
+        bool hasEntity(const std::string& name) const
         {
-            return this->_container;
+            return this->_container.count(name) > 0;
         }
 
-
-        bool hasEntity(const std::string& name) const
+        std::vector<std::string> getEntityNames() const
         {
-            return this->_container.count(name) > 0;
+            return simox::alg::get_keys(this->_container);
         }
 
         using Base::getEntity;
-        const EntityT& getEntity(const MemoryID& id) const override
+        const EntityT& getEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.providerSegmentName, this->getKeyString());
             return getEntity(id.entityName);
@@ -123,7 +121,7 @@ namespace armarx::armem::base
             }
         }
 
-        const EntityT* findEntity(const MemoryID& id) const override
+        const EntityT* findEntity(const MemoryID& id) const
         {
             this->_checkContainerName(id.providerSegmentName, this->getKeyString());
             auto it = this->_container.find(id.entityName);
@@ -137,6 +135,46 @@ namespace armarx::armem::base
             }
         }
 
+
+        // ITERATION
+
+        // All functors are taken as universal reference (F&&).
+
+        /**
+         * @param func Function like: bool process(EntityT& entity)
+         */
+        template <class EntityFunctionT>
+        bool forEachEntity(EntityFunctionT&& func)
+        {
+            return this->forEachChild(func);
+        }
+        /**
+         * @param func Function like: bool process(const EntityT& entity)
+         */
+        template <class EntityFunctionT>
+        bool forEachEntity(EntityFunctionT&& func) const
+        {
+            return this->forEachChild(func);
+        }
+
+        // forEachSnapshot() is provided by ForEachEntitySnapshotMixin.
+        // forEachInstance() is provided by ForEachEntityInstanceMixin.
+
+
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline const ContainerT& entities() const
+        {
+            return this->_container;
+        }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
+        inline ContainerT& entities()
+        {
+            return this->_container;
+        }
+
+
+        // MODIFICATION
+
         /**
          * @brief Updates an entity's history.
          *
@@ -154,7 +192,6 @@ namespace armarx::armem::base
             {
                 // Add entity entry.
                 entity = &addEntity(update.entityID.entityName);
-                entity->setMaxHistorySize(_maxHistorySize);
                 updateType = UpdateType::InsertedNew;
             }
             else
@@ -170,27 +207,24 @@ namespace armarx::armem::base
 
         void append(const _Derived& m)
         {
-            ARMARX_INFO << "ProviderSegment: Merge name '" << m.name() << "' into '" << name() << "'";
+            // ARMARX_INFO << "ProviderSegment: Merge name '" << m.name() << "' into '" << name() << "'";
 
-            for (const auto& [k, s] : m.container())
+            m.forEachEntity([this](const EntityT & entity)
             {
-                if (const auto& it = this->_container.find(k); it != this->_container.end())
+                auto it = this->_container.find(entity.name());
+                if (it == this->_container.end())
                 {
-                    // segment already exists
-                    it->second.append(s);
+                    it = this->_container.emplace(entity.name(), this->id().withEntityName(entity.name())).first;
                 }
-                else
-                {
-                    auto wms = this->_container.emplace(k, this->id().withEntityName(k));
-                    wms.first->second.append(s);
-                }
-            }
+                it->second.append(entity);
+                return true;
+            });
         }
 
         /// Add an empty entity with the given name.
         EntityT& addEntity(const std::string& name)
         {
-            return addEntity(EntityT(name));
+            return addEntity(EntityT(name, this->id()));
         }
         /// Copy and insert an entity.
         EntityT& addEntity(const EntityT& entity)
@@ -206,22 +240,9 @@ namespace armarx::armem::base
         }
 
 
-        /**
-         * @brief Sets the maximum history size of container in this segment.
-         * This affects all current container as well as new ones.
-         * @see Entity::setMaxHistorySize()
-         */
-        void setMaxHistorySize(long maxSize) override
-        {
-            MaxHistorySize::setMaxHistorySize(maxSize);
-            for (auto& [name, entity] : this->_container)
-            {
-                entity.setMaxHistorySize(maxSize);
-            }
-        }
+        // MISC
 
-
-        virtual bool equalsDeep(const ProviderSegmentBase& other) const
+        bool equalsDeep(const DerivedT& other) const
         {
             //std::cout << "ProviderSegment::equalsDeep" << std::endl;
             if (this->size() != other.size())
@@ -243,30 +264,17 @@ namespace armarx::armem::base
             return true;
         }
 
-        std::string getLevelName() const override
+
+        static std::string getLevelName()
         {
             return "provider segment";
         }
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return this->name();
         }
 
-
-    protected:
-
-        virtual void _copySelf(DerivedT& other) const override
-        {
-            Base::_copySelf(other);
-            other.aronType() = _aronType;
-        }
-        virtual void _copySelfEmpty(DerivedT& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.aronType() = _aronType;
-        }
-
     };
 
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.cpp b/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.cpp
index ec7ca0402ad128dc6d342aa28279929c376df557..48147758528cb5ac46baa8a952272ee831ed1e01 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.cpp
@@ -1,5 +1,8 @@
 #include "AronTyped.h"
 
+#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
+
+
 namespace armarx::armem::base::detail
 {
 
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.h b/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.h
index fb0ad088fb4fb27ca39cf09f034ea7eb3b202cfe..16233556c83f8febb732824a7001c9b2e8d1e2ac 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/AronTyped.h
@@ -1,6 +1,6 @@
 #pragma once
 
-#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
 
 namespace armarx::armem::base::detail
@@ -13,7 +13,7 @@ namespace armarx::armem::base::detail
     {
     public:
 
-        AronTyped(aron::typenavigator::ObjectNavigatorPtr aronType = nullptr);
+        explicit AronTyped(aron::typenavigator::ObjectNavigatorPtr aronType = nullptr);
 
 
         bool hasAronType() const;
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h b/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h
index 95993d560c6435fd147ddfc7a2a7aa9267d94855..53cddfff656cdf0fb000323afc4aefcc18c2f50f 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/EntityContainerBase.h
@@ -1,12 +1,12 @@
 #pragma once
 
-#include "../../Commit.h"
-#include "../../error/ArMemError.h"
+#include <RobotAPI/libraries/armem/core/Commit.h>
+#include <RobotAPI/libraries/armem/core/error/ArMemError.h>
 
 #include "MemoryContainerBase.h"
 
-#include "../EntityBase.h"
-#include "../EntitySnapshotBase.h"
+#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
+#include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
 
 
 namespace armarx::armem::base::detail
@@ -34,8 +34,9 @@ namespace armarx::armem::base::detail
 
     public:
 
-        using Base::MemoryContainerBase;
-        using Base::operator=;
+        // `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.
@@ -43,11 +44,11 @@ namespace armarx::armem::base::detail
          * @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)->getEntity(id));
+            return const_cast<EntityT&>(const_cast<const EntityContainerBase*>(this)->_derived().getEntity(id));
         }
-        virtual const EntityT& getEntity(const MemoryID& id) const = 0;
 
         /**
          * @brief Find an entity.
@@ -61,7 +62,11 @@ namespace armarx::armem::base::detail
          * @param id The entities ID.
          * @return A pointer to the first matching entity or `nullptr` if none was found.
          */
-        virtual const EntityT* findEntity(const MemoryID& id) const = 0;
+        // const EntityT* findEntity(const MemoryID& id) const;
+        EntityT* findEntity(const MemoryID& id)
+        {
+            return const_cast<EntityT*>(const_cast<const EntityContainerBase*>(this)->_derived().findEntity(id));
+        }
 
 
         /**
@@ -75,12 +80,12 @@ namespace armarx::armem::base::detail
          */
         EntitySnapshotT& getEntitySnapshot(const MemoryID& id)
         {
-            return const_cast<EntitySnapshotT&>(const_cast<const EntityContainerBase*>(this)->getEntitySnapshot(id));
+            return const_cast<EntitySnapshotT&>(const_cast<const EntityContainerBase*>(this)->_derived().getEntitySnapshot(id));
         }
 
         const EntitySnapshotT& getEntitySnapshot(const MemoryID& id) const
         {
-            const EntityT& entity = getEntity(id);
+            const EntityT& entity = _derived().getEntity(id);
 
             if (id.hasTimestamp())
             {
@@ -101,6 +106,19 @@ namespace armarx::armem::base::detail
         {
             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/MaxHistorySize.h b/source/RobotAPI/libraries/armem/core/base/detail/MaxHistorySize.h
deleted file mode 100644
index 1fc07ed85e54716d24d2447fa17cb95b291f2766..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/base/detail/MaxHistorySize.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-
-
-namespace armarx::armem::base::detail
-{
-    // TODO: Replace by ConstrainedHistorySize (not only max entries, e.g. delete oldest / delete least accessed / ...)
-    class MaxHistorySize
-    {
-    public:
-
-        virtual ~MaxHistorySize();
-
-        /**
-         * @brief Sets the maximum history size of entities in this segment.
-         * This affects all current entities as well as new ones.
-         * @see Entity::setMaxHistorySize()
-         */
-        virtual void setMaxHistorySize(long maxSize);
-        virtual long getMaxHistorySize() const;
-
-
-    protected:
-
-        /**
-         * @brief Maximum size of entity histories.
-         *
-         * If negative, the size of `history` is not limited.
-         *
-         * @see Entity::maxHstorySize
-         */
-        long _maxHistorySize = -1;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h b/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
index 518e3f877f38ea364657c0a5448d48bc6cf36fbf..4d7cbec1877176f511e854eeefa60a9d6159aded 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/MemoryContainerBase.h
@@ -3,6 +3,7 @@
 #include <RobotAPI/libraries/armem/core/error/ArMemError.h>
 
 #include "MemoryItem.h"
+#include "iteration_mixins.h"
 
 
 namespace armarx::armem::base::detail
@@ -18,16 +19,16 @@ namespace armarx::armem::base::detail
         using Base = MemoryItem;
 
     public:
+
         using DerivedT = _DerivedT;
         using ContainerT = _ContainerT;
 
 
     public:
 
-
         MemoryContainerBase()
         {}
-        MemoryContainerBase(const MemoryID& id) :
+        explicit MemoryContainerBase(const MemoryID& id) :
             MemoryItem(id)
         {
         }
@@ -48,32 +49,56 @@ namespace armarx::armem::base::detail
         {
             return _container.size();
         }
-        bool hasData() const
-        {
-            return size() > 0;
-        }
         void clear()
         {
             return _container.clear();
         }
 
+
+        // ITERATION
+
+        /**
+         * @param func Function like: bool process(ChildT& provSeg)
+         */
+        template <class ChildFunctionT>
+        bool forEachChild(ChildFunctionT&& func)
+        {
+            return base::detail::forEachChild(this->_container, func);
+        }
+        /**
+         * @param func Function like: bool process(const ChildT& provSeg)
+         */
+        template <class ChildFunctionT>
+        bool forEachChild(ChildFunctionT&& func) const
+        {
+            return base::detail::forEachChild(this->_container, func);
+        }
+
+
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         typename ContainerT::const_iterator begin() const
         {
             return _container.begin();
         }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         typename ContainerT::iterator begin()
         {
             return _container.begin();
         }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         typename ContainerT::const_iterator end() const
         {
             return _container.end();
         }
+        [[deprecated("Direct container access is deprecated. Use forEach*() instead.")]]
         typename ContainerT::iterator end()
         {
             return _container.end();
         }
 
+
+    protected:
+
         const ContainerT& container() const
         {
             return _container;
@@ -83,24 +108,6 @@ namespace armarx::armem::base::detail
             return _container;
         }
 
-        // Copying
-        DerivedT copy() const
-        {
-            DerivedT d;
-            this->_copySelf(d);
-            return d;
-        }
-
-        /// Make a copy not containing any elements.
-        DerivedT copyEmpty() const
-        {
-            DerivedT d;
-            this->_copySelfEmpty(d);
-            return std::move(d);
-        }
-
-
-    protected:
 
         /**
          * @throw `armem::error::ContainerNameMismatch` if `gottenName` does not match `actualName`.
@@ -110,21 +117,11 @@ namespace armarx::armem::base::detail
         {
             if (!((emptyOk && gottenName.empty()) || gottenName == actualName))
             {
-                throw armem::error::ContainerNameMismatch(gottenName, this->getLevelName(), actualName);
+                throw armem::error::ContainerNameMismatch(
+                    gottenName, DerivedT::getLevelName(), actualName);
             }
         }
 
-        virtual void _copySelf(DerivedT& other) const
-        {
-            Base::_copySelf(other);
-            other.container() = _container;
-        }
-
-        virtual void _copySelfEmpty(DerivedT& other) const
-        {
-            Base::_copySelf(other);
-        }
-
 
     protected:
 
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.cpp b/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.cpp
index a6a9f73e17443091503c09472bc3cee7259644ac..8f4a1920f0a1fcd669b9c3fc2193a617b4dba205 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.cpp
@@ -8,33 +8,15 @@ namespace armarx::armem::base::detail
     {
     }
 
+
     MemoryItem::MemoryItem(const MemoryID& id) :
         _id(id)
     {
     }
 
-    /*
-    MemoryItem::MemoryItem(const MemoryItem& other) :
-        _id(other.id())
-    {}
-    */
-
 
     MemoryItem::~MemoryItem()
     {
     }
 
-    /*
-    MemoryItem& MemoryItem::operator=(const MemoryItem& other)
-    {
-        other._copySelf(*this);
-        return *this;
-    }
-    */
-
-    void MemoryItem::_copySelf(MemoryItem& other) const
-    {
-        other.id() = id();
-    }
-
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.h b/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.h
index 45226e6327520b7bbddc198364c16c2b8229352c..6aea07121aa201fcbbf0f0b18f46ccc3ab4e2aac 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/MemoryItem.h
@@ -2,7 +2,7 @@
 
 #include <string>
 
-#include "../../MemoryID.h"
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
 
 
 namespace armarx::armem::base::detail
@@ -16,18 +16,13 @@ namespace armarx::armem::base::detail
     public:
 
         MemoryItem();
-        MemoryItem(const MemoryID& id);
+        explicit MemoryItem(const MemoryID& id);
 
         MemoryItem(const MemoryItem& other) = default;
         MemoryItem(MemoryItem&& other) = default;
         MemoryItem& operator=(const MemoryItem& other) = default;
         MemoryItem& operator=(MemoryItem&& other) = default;
 
-        virtual ~MemoryItem();
-
-
-        //MemoryItem& operator=(const MemoryItem& other);
-
 
         inline MemoryID& id()
         {
@@ -39,19 +34,11 @@ namespace armarx::armem::base::detail
         }
 
 
-        // Introspection
-
-        /// Get a string version of `*this`' key.
-        virtual std::string getKeyString() const = 0;
-
-        /// Get a readable name of this level for messages, errors etc.
-        virtual std::string getLevelName() const = 0;
-
-
     protected:
 
-        /// Copy `*this` to `other`.
-        virtual void _copySelf(MemoryItem& other) const;
+        // Protected so we get a compile error if someone tries to destruct a MemoryItem
+        // instead of a derived type.
+        ~MemoryItem();
 
 
     protected:
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.cpp b/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..459cd4d5c7bd694bcb289496352d7e2cad4966cd
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.cpp
@@ -0,0 +1,7 @@
+#include "iteration_mixins.h"
+
+
+namespace armarx::armem::base::detail
+{
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.h b/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.h
new file mode 100644
index 0000000000000000000000000000000000000000..c923a857e1d016b06b313f7e860ab57ec438a9d4
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/iteration_mixins.h
@@ -0,0 +1,214 @@
+#pragma once
+
+#include <type_traits>
+
+
+namespace armarx::armem::base::detail
+{
+
+    // Helper functions to implement the forEach*() method at the current level.
+
+    // Handle functions with different return type.
+    template <class FunctionT, class ChildT>
+    bool call(FunctionT&& func, ChildT&& child)
+    {
+        if constexpr(std::is_same_v<decltype(func(child)), bool>)
+        {
+            if (!func(child))
+            {
+                return false;
+            }
+            return true;
+        }
+        else
+        {
+            func(child);
+            return true;
+        }
+    }
+
+
+    // Single-valued containers.
+    template <class ContainerT, class FunctionT>
+    bool forEachChildSingle(ContainerT& container, FunctionT&& func)
+    {
+        for (auto& child : container)
+        {
+            if (not call(func, child))
+            {
+                return false;
+            }
+        }
+        return true;
+    }
+
+
+    // Pair-valued containers.
+    template <class ContainerT, class FunctionT>
+    bool forEachChildPair(ContainerT& container, FunctionT&& func)
+    {
+        for (auto& [_, child] : container)
+        {
+            if (not call(func, child))
+            {
+                return false;
+            }
+        }
+        return true;
+    }
+
+
+    // see: https://en.cppreference.com/w/cpp/types/void_t
+
+    // primary template handles types that have no nested ::type member:
+    template< class, class = void >
+    struct has_mapped_type : std::false_type { };
+
+    // specialization recognizes types that do have a nested ::type member:
+    template< class T >
+    struct has_mapped_type<T, std::void_t<typename T::mapped_type>> : std::true_type { };
+
+
+    template <class ContainerT, class FunctionT>
+    bool forEachChild(ContainerT& container, FunctionT&& func)
+    {
+        if constexpr(has_mapped_type<ContainerT>::value)
+        {
+            return forEachChildPair(container, func);
+        }
+        else
+        {
+            return forEachChildSingle(container, func);
+        }
+    }
+
+
+    // We use auto instead of, e.g. DerivedT::EntitySnapshotT,
+    // as we cannot use the typedef before DerivedT was completely defined.
+
+    template <class DerivedT>
+    struct ForEachEntityInstanceMixin
+    {
+        // not: using EntitySnapshotT = typename DerivedT::EntitySnapshotT;
+
+        /**
+         * @param func Function like: bool process(EntityInstanceT& instance)>
+         */
+        template <class InstanceFunctionT>
+        bool forEachInstance(InstanceFunctionT&& func)
+        {
+            return static_cast<DerivedT*>(this)->forEachSnapshot(
+                       [&func](auto & snapshot) -> bool
+            {
+                return snapshot.forEachInstance(func);
+            });
+        }
+
+        /**
+         * @param func Function like: bool process(const EntityInstanceT& instance)
+         */
+        template <class InstanceFunctionT>
+        bool forEachInstance(InstanceFunctionT&& func) const
+        {
+            return static_cast<const DerivedT*>(this)->forEachSnapshot(
+                       [&func](const auto & snapshot) -> bool
+            {
+                return snapshot.forEachInstance(func);
+            });
+        }
+    };
+
+
+    template <class DerivedT>
+    struct ForEachEntitySnapshotMixin
+    {
+        /**
+         * @param func Function like: bool process(EntitySnapshotT& snapshot)>
+         */
+        template <class SnapshotFunctionT>
+        bool forEachSnapshot(SnapshotFunctionT&& func)
+        {
+            return static_cast<DerivedT*>(this)->forEachEntity(
+                       [&func](auto & entity) -> bool
+            {
+                return entity.forEachSnapshot(func);
+            });
+        }
+
+        /**
+         * @param func Function like: bool process(const EntitySnapshotT& snapshot)
+         */
+        template <class SnapshotFunctionT>
+        bool forEachSnapshot(SnapshotFunctionT&& func) const
+        {
+            return static_cast<const DerivedT*>(this)->forEachEntity(
+                       [&func](const auto & entity) -> bool
+            {
+                return entity.forEachSnapshot(func);
+            });
+        }
+    };
+
+
+    template <class DerivedT>
+    struct ForEachEntityMixin
+    {
+        /**
+         * @param func Function like: bool process(EntityT& entity)>
+         */
+        template <class FunctionT>
+        bool forEachEntity(FunctionT&& func)
+        {
+            return static_cast<DerivedT*>(this)->forEachProviderSegment(
+                       [&func](auto & providerSegment) -> bool
+            {
+                return providerSegment.forEachEntity(func);
+            });
+        }
+
+        /**
+         * @param func Function like: bool process(const EntityT& entity)
+         */
+        template <class FunctionT>
+        bool forEachEntity(FunctionT&& func) const
+        {
+            return static_cast<const DerivedT*>(this)->forEachProviderSegment(
+                       [&func](const auto & providerSegment) -> bool
+            {
+                return providerSegment.forEachEntity(func);
+            });
+        }
+    };
+
+
+    template <class DerivedT>
+    struct ForEachProviderSegmentMixin
+    {
+        /**
+         * @param func Function like: bool process(ProviderSegmentT& providerSegment)>
+         */
+        template <class FunctionT>
+        bool forEachProviderSegment(FunctionT&& func)
+        {
+            return static_cast<DerivedT*>(this)->forEachCoreSegment(
+                       [&func](auto & coreSegment) -> bool
+            {
+                return coreSegment.forEachProviderSegment(func);
+            });
+        }
+
+        /**
+         * @param func Function like: bool process(const ProviderSegmentT& providerSegment)
+         */
+        template <class FunctionT>
+        bool forEachProviderSegment(FunctionT&& func) const
+        {
+            return static_cast<const DerivedT*>(this)->forEachCoreSegment(
+                       [&func](const auto & coreSegment) -> bool
+            {
+                return coreSegment.forEachProviderSegment(func);
+            });
+        }
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.cpp b/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a1875ff53545a3d2574cf9764a14d321946e5514
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.cpp
@@ -0,0 +1,17 @@
+#include "negative_index_semantics.h"
+
+#include <algorithm>
+
+
+size_t armarx::armem::base::detail::negativeIndexSemantics(long index, size_t size)
+{
+    const size_t max = size > 0 ? size - 1 : 0;
+    if (index >= 0)
+    {
+        return std::clamp<size_t>(static_cast<size_t>(index), 0, max);
+    }
+    else
+    {
+        return static_cast<size_t>(std::clamp<long>(static_cast<long>(size) + index, 0, static_cast<long>(max)));
+    }
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h b/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h
new file mode 100644
index 0000000000000000000000000000000000000000..4efe169276c83ff12c13400e6de162a8b4db5d8d
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h
@@ -0,0 +1,11 @@
+#pragma once
+
+#include <stddef.h>
+
+
+namespace armarx::armem::base::detail
+{
+
+    size_t negativeIndexSemantics(long index, size_t size);
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..48c084154c41b26b174504d2565fe57d3a49d55a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
@@ -0,0 +1,78 @@
+#include "ice_conversions.h"
+
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
+
+#include <RobotAPI/libraries/armem/core/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/ice_conversions_templates.h>
+
+
+namespace armarx::armem::base
+{
+
+    void detail::toIceItem(data::detail::MemoryItem& ice, const armem::base::detail::MemoryItem& item)
+    {
+        toIce(ice.id, item.id());
+    }
+    void detail::fromIceItem(const data::detail::MemoryItem& ice, armem::base::detail::MemoryItem& item)
+    {
+        fromIce(ice.id, item.id());
+    }
+
+
+    void detail::toIce(aron::data::AronDictPtr& ice, const aron::datanavigator::DictNavigatorPtr& data)
+    {
+        ice = data ? data->toAronDictPtr() : nullptr;
+    }
+    void detail::fromIce(const aron::data::AronDictPtr& ice, aron::datanavigator::DictNavigatorPtr& data)
+    {
+        if (ice)
+        {
+            data = aron::datanavigator::DictNavigator::FromAronDictPtr(ice);
+        }
+        else
+        {
+            data = nullptr;
+        };
+    }
+
+    void detail::toIce(aron::type::AronTypePtr& ice, const aron::typenavigator::ObjectNavigatorPtr& bo)
+    {
+        ice = bo ? bo->toAronPtr() : nullptr;
+    }
+    void detail::fromIce(const aron::type::AronTypePtr& ice, aron::typenavigator::ObjectNavigatorPtr& bo)
+    {
+        bo = ice
+             ? aron::typenavigator::ObjectNavigator::DynamicCastAndCheck(aron::typenavigator::Navigator::FromAronType(ice))
+             : nullptr;
+    }
+
+}
+namespace armarx::armem
+{
+    void base::toIce(data::EntityInstanceMetadata& ice, const EntityInstanceMetadata& metadata)
+    {
+        ice.confidence = metadata.confidence;
+        toIce(ice.timeArrivedMicroSeconds, metadata.timeArrived);
+        toIce(ice.timeCreatedMicroSeconds, metadata.timeCreated);
+        toIce(ice.timeSentMicroSeconds, metadata.timeSent);
+    }
+    void base::fromIce(const data::EntityInstanceMetadata& ice, EntityInstanceMetadata& metadata)
+    {
+        metadata.confidence = ice.confidence;
+        fromIce(ice.timeArrivedMicroSeconds, metadata.timeArrived);
+        fromIce(ice.timeCreatedMicroSeconds, metadata.timeCreated);
+        fromIce(ice.timeSentMicroSeconds, metadata.timeSent);
+    }
+
+
+    void base::toIce(data::EntityInstanceMetadataPtr& ice, const EntityInstanceMetadata& metadata)
+    {
+        armem::toIce<data::EntityInstanceMetadata>(ice, metadata);
+    }
+    void base::fromIce(const data::EntityInstanceMetadataPtr& ice, EntityInstanceMetadata& metadata)
+    {
+        armem::fromIce<data::EntityInstanceMetadata>(ice, metadata);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/ice_conversions.h b/source/RobotAPI/libraries/armem/core/base/ice_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..646754cc4cbfc3d61c0ce0b1e19c333ee2d7f92b
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/base/ice_conversions.h
@@ -0,0 +1,195 @@
+#pragma once
+
+#include "EntityInstanceBase.h"
+#include "EntitySnapshotBase.h"
+#include "EntityBase.h"
+#include "ProviderSegmentBase.h"
+#include "CoreSegmentBase.h"
+#include "MemoryBase.h"
+
+#include <RobotAPI/libraries/armem/core/ice_conversions_templates.h>
+#include <RobotAPI/libraries/armem/core/ice_conversions.h>
+
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
+
+#include <RobotAPI/interface/armem/memory.h>
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+
+namespace armarx::armem::base::detail
+{
+    void toIceItem(data::detail::MemoryItem& ice, const MemoryItem& item);
+    void fromIceItem(const data::detail::MemoryItem& ice, MemoryItem& item);
+
+    void toIce(aron::data::AronDictPtr& ice, const aron::datanavigator::DictNavigatorPtr& bo);
+    void fromIce(const aron::data::AronDictPtr& ice, aron::datanavigator::DictNavigatorPtr& bo);
+
+    void toIce(aron::type::AronTypePtr& ice, const aron::typenavigator::ObjectNavigatorPtr& bo);
+    void fromIce(const aron::type::AronTypePtr& ice, aron::typenavigator::ObjectNavigatorPtr& bo);
+}
+namespace armarx::armem::base
+{
+    void toIce(data::EntityInstanceMetadata& ice, const EntityInstanceMetadata& metadata);
+    void fromIce(const data::EntityInstanceMetadata& ice, EntityInstanceMetadata& metadata);
+
+    void toIce(data::EntityInstanceMetadataPtr& ice, const EntityInstanceMetadata& metadata);
+    void fromIce(const data::EntityInstanceMetadataPtr& ice, EntityInstanceMetadata& metadata);
+
+
+    template <class ...Args>
+    void toIce(data::EntityInstance& ice, const EntityInstanceBase<Args...>& data)
+    {
+        detail::toIceItem(ice, data);
+
+        // detail::toIce(std::ref(ice.data).get(), data.data());
+        detail::toIce(ice.data, data.data());
+        toIce(ice.metadata, data.metadata());
+    }
+    template <class ...Args>
+    void fromIce(const data::EntityInstance& ice, EntityInstanceBase<Args...>& data)
+    {
+        detail::fromIceItem(ice, data);
+
+        detail::fromIce(ice.data, data.data());
+        fromIce(ice.metadata, data.metadata());
+    }
+
+    template <class ...Args>
+    void toIce(data::EntitySnapshot& ice, const EntitySnapshotBase<Args...>& snapshot)
+    {
+        detail::toIceItem(ice, snapshot);
+
+        ice.instances.clear();
+        snapshot.forEachInstance([&ice](const auto & instance)
+        {
+            armem::toIce(ice.instances.emplace_back(), instance);
+        });
+    }
+    template <class ...Args>
+    void fromIce(const data::EntitySnapshot& ice, EntitySnapshotBase<Args...>& snapshot)
+    {
+        detail::fromIceItem(ice, snapshot);
+
+        snapshot.clear();
+        for (const data::EntityInstancePtr& iceInstance : ice.instances)
+        {
+            snapshot.addInstance(armem::fromIce<typename EntitySnapshotBase<Args...>::EntityInstanceT>(iceInstance));
+        }
+    }
+
+    template <class ...Args>
+    void toIce(data::Entity& ice, const EntityBase<Args...>& entity)
+    {
+        detail::toIceItem(ice, entity);
+
+        ice.history.clear();
+        entity.forEachSnapshot([&ice](const auto & snapshot)
+        {
+            armem::toIce(ice.history[armem::toIce<long>(snapshot.time())], snapshot);
+        });
+    }
+    template <class ...Args>
+    void fromIce(const data::Entity& ice, EntityBase<Args...>& entity)
+    {
+        detail::fromIceItem(ice, entity);
+
+        entity.clear();
+        for (const auto& [key, snapshot] : ice.history)
+        {
+            entity.addSnapshot(armem::fromIce<typename EntityBase<Args...>::EntitySnapshotT>(snapshot));
+        }
+    }
+
+
+    template <class ...Args>
+    void toIce(data::ProviderSegment& ice, const ProviderSegmentBase<Args...>& providerSegment)
+    {
+        detail::toIceItem(ice, providerSegment);
+
+        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)
+        {
+            armem::toIce(ice.entities[entity.name()], entity);
+        });
+    }
+    template <class ...Args>
+    void fromIce(const data::ProviderSegment& ice, ProviderSegmentBase<Args...>& providerSegment)
+    {
+        detail::fromIceItem(ice, providerSegment);
+
+        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)
+        {
+            providerSegment.addEntity(
+                armem::fromIce<typename ProviderSegmentBase<Args...>::EntityT>(entity));
+        }
+    }
+
+    template <class ...Args>
+    void toIce(data::CoreSegment& ice, const CoreSegmentBase<Args...>& coreSegment)
+    {
+        detail::toIceItem(ice, coreSegment);
+
+        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>
+    void fromIce(const data::CoreSegment& ice, CoreSegmentBase<Args...>& coreSegment)
+    {
+        detail::fromIceItem(ice, coreSegment);
+
+        detail::fromIce(ice.aronType, coreSegment.aronType());
+        ARMARX_CHECK(!coreSegment.aronType() || ice.aronType);
+
+        // fromIce(ice.providerSegments, coreSegment.providerSegments());
+        coreSegment.clear();
+        for (const auto& [key, providerSegment] : ice.providerSegments)
+        {
+            coreSegment.addProviderSegment(
+                armem::fromIce<typename CoreSegmentBase<Args...>::ProviderSegmentT>(providerSegment));
+        }
+    }
+
+    template <class ...Args>
+    void toIce(data::Memory& ice, const MemoryBase<Args...>& memory)
+    {
+        base::detail::toIceItem(ice, memory);
+
+        ice.coreSegments.clear();
+        memory.forEachCoreSegment([&ice](const auto & coreSegment)
+        {
+            armem::toIce(ice.coreSegments[coreSegment.name()], coreSegment);
+            return true;
+        });
+    }
+    template <class ...Args>
+    void fromIce(const data::Memory& ice, MemoryBase<Args...>& memory)
+    {
+        base::detail::fromIceItem(ice, memory);
+
+        memory.clear();
+        for (const auto& [key, coreSegment] : ice.coreSegments)
+        {
+            // We can avoid using CoreSegment's copy constructor this way:
+            armem::fromIce(coreSegment, memory.addCoreSegment(coreSegment->id.coreSegmentName));
+        }
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp
index b166468d81929da12c8204a6e2df9ab90b994528..204aa8f86e20d99df852abbdc79be3d1a07ef39f 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.cpp
@@ -78,9 +78,9 @@ namespace armarx::armem::d_ltm
         std::filesystem::create_directories(_fullPath());
         TypeIO::writeAronType(_aronType, _fullPath());
 
-        for (const auto& [k, s] : m)
+        m.forEachProviderSegment([this](const wm::ProviderSegment & s)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            if (auto it = _container.find(s.name()); it != _container.end())
             {
                 it->second.append(s);
             }
@@ -88,18 +88,19 @@ namespace armarx::armem::d_ltm
             {
                 try
                 {
-                    std::filesystem::create_directory(_fullPath() / k);
+                    std::filesystem::create_directory(_fullPath() / s.name());
                 }
                 catch (...)
                 {
                     ARMARX_WARNING << GetHandledExceptionString();
-                    return;
+                    return false;
                 }
 
-                auto wms = _container.emplace(k, id().withProviderSegmentName(k));
+                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
index 76bb297e76d268ce8517449686ffae1cdb3ed2cd..2d8bd8f29e7027ea63b797d0a19f4b96e116898e 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/CoreSegment.h
@@ -2,8 +2,8 @@
 
 #include <filesystem>
 
-#include "../base/CoreSegmentBase.h"
-#include "../workingmemory/CoreSegment.h"
+#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include "ProviderSegment.h"
 
@@ -22,7 +22,6 @@ namespace armarx::armem::d_ltm
     public:
 
         using Base::CoreSegmentBase;
-        using Base::operator=;
 
 
         // Conversion
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp
index 5d784a097de4ef68ec2df0bdc1adce94fa737809..d4d0ac233f1fac1e910869f56cc12541928798ce 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/Entity.cpp
@@ -1,5 +1,8 @@
 #include "Entity.h"
 
+#include <ArmarXCore/core/logging/Logging.h>
+
+
 namespace armarx::armem::d_ltm
 {
     std::filesystem::path Entity::_fullPath() const
@@ -63,20 +66,21 @@ namespace armarx::armem::d_ltm
     void Entity::append(const wm::Entity& m)
     {
         std::filesystem::create_directories(_fullPath());
-        for (const auto& [k, s] : m.container())
+        m.forEachSnapshot([this](const wm::EntitySnapshot & s)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            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(k.toMicroSeconds()));
-                auto wms = _container.emplace(std::make_pair(k, id().withTimestamp(k)));
+                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
index 35022275570c93378cbe0c767aad1776da594838..63011ceff58a0ec7ff4b77bf2afeaa0252bbcec0 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Entity.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/Entity.h
@@ -2,8 +2,8 @@
 
 #include <filesystem>
 
-#include "../base/EntityBase.h"
-#include "../workingmemory/Entity.h"
+#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include "EntitySnapshot.h"
 
@@ -38,7 +38,6 @@ namespace armarx::armem::d_ltm
     public:
 
         using Base::EntityBase;
-        using Base::operator=;
 
 
         // Conversion
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp
index dd0458b83bbb8ed461ddeab50af42181fda843e4..56786756655453bb97952a206ff642b9f65174cb 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.cpp
@@ -1,22 +1,22 @@
 #include "EntityInstance.h"
 
-#include <iostream>
-#include <fstream>
+#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 "../../core/error.h"
-#include "ArmarXCore/core/exceptions/LocalException.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
 {
 
-    EntityInstance::EntityInstance(const EntityInstance& other) :
-        Base(other),
-        path(other.path)
-    {
-    }
-
     bool EntityInstance::equalsDeep(const EntityInstance& other) const
     {
         return id() == other.id();
@@ -24,25 +24,11 @@ namespace armarx::armem::d_ltm
 
 
 
-    void EntityInstance::update(const EntityUpdate& update, int index)
-    {
-        ARMARX_CHECK_FITS_SIZE(index, update.instancesData.size());
-
-        this->index() = index;
-    }
-
-    EntityInstance EntityInstance::copy() const
+    void EntityInstance::update(const EntityUpdate& update)
     {
-        EntityInstance d;
-        this->_copySelf(d);
-        return d;
+        ARMARX_CHECK_FITS_SIZE(this->index(), update.instancesData.size());
     }
 
-    void EntityInstance::_copySelf(EntityInstance& other) const
-    {
-        EntityInstanceBase<EntityInstance>::_copySelf(other);
-        other.path = path;
-    }
 
     std::filesystem::path EntityInstance::_fullPath() const
     {
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h
index 89b96c011fcccb6bfc5471850185b0cea49f77b0..c56a944f264c08e1f26b35df1ecb622dff92c0e6 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/EntityInstance.h
@@ -2,11 +2,10 @@
 
 #include <filesystem>
 
-#include "../base/EntityInstanceBase.h"
-#include "../workingmemory/EntityInstance.h"
+#include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-#include "../workingmemory/entityInstance_conversions.h"
-#include "../workingmemory/json_conversions.h"
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
 
 namespace armarx::armem::d_ltm
@@ -15,30 +14,24 @@ namespace armarx::armem::d_ltm
      * @brief Data of a single entity instance.
      */
     class EntityInstance :
-        public base::EntityInstanceBase<EntityInstance>
+        public base::EntityInstanceBase<base::NoData, base::NoData>
     {
-        using Base = base::EntityInstanceBase<EntityInstance>;
+        using Base = base::EntityInstanceBase<base::NoData, base::NoData>;
 
     public:
 
         using Base::EntityInstanceBase;
 
-        EntityInstance(const EntityInstance& other);
-        EntityInstance(EntityInstance&& other) = default;
-        EntityInstance& operator=(const EntityInstance& other) = default;
-        EntityInstance& operator=(EntityInstance&& other) = default;
-
 
         /**
          * @brief Fill `*this` with the update's values.
          * @param update The update.
          * @param index The instances index.
          */
-        virtual void update(const EntityUpdate& update, int index) override;
+        void update(const EntityUpdate& update);
 
-        virtual bool equalsDeep(const EntityInstance& other) const override;
+        bool equalsDeep(const EntityInstance& other) const;
 
-        virtual EntityInstance copy() const override;
 
         // Conversion
         wm::EntityInstance convert(const aron::typenavigator::NavigatorPtr& expectedStructure) const;
@@ -47,8 +40,6 @@ namespace armarx::armem::d_ltm
         void reload(const std::shared_ptr<std::filesystem::path>&);
         void setTo(const wm::EntityInstance&);
 
-    protected:
-        virtual void _copySelf(EntityInstance& other) const override;
 
     private:
         std::filesystem::path _fullPath() const;
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp
index ab5b56d2274f78c350818693c269af18f0a4a979..9354ab7d52e0dcbd058aec022892132b753b51ab 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.cpp
@@ -83,7 +83,7 @@ namespace armarx::armem::d_ltm
         _container.clear();
 
         int i = 0;
-        for (const auto& s : m.instances())
+        m.forEachInstance([this, &i](wm::EntityInstance & s)
         {
             try
             {
@@ -92,12 +92,14 @@ namespace armarx::armem::d_ltm
             catch (...)
             {
                 ARMARX_WARNING << GetHandledExceptionString();
-                continue;;
+                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
index 545a8c0d64641c65e7faf7aa26dea77ee9865e0c..9587e3be44435814d4709979a1fb394c67b953c7 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/EntitySnapshot.h
@@ -2,11 +2,13 @@
 
 #include <filesystem>
 
-#include "../base/EntitySnapshotBase.h"
-#include "../workingmemory/EntitySnapshot.h"
+#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
 {
@@ -22,7 +24,6 @@ namespace armarx::armem::d_ltm
     public:
 
         using Base::EntitySnapshotBase;
-        using Base::operator=;
 
 
         // Conversion
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp
index 0fb6fba92b2ebc116787bffba2d7ed5bc743227b..3fc60e0496aa21c441cf5e8a60443e43ef741a46 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/Memory.cpp
@@ -65,9 +65,9 @@ namespace armarx::armem::d_ltm
     void Memory::append(const wm::Memory& m)
     {
         std::filesystem::create_directories(_fullPath());
-        for (const auto& [k, s] : m.container())
+        m.forEachCoreSegment([this](const wm::CoreSegment & s) -> bool
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            if (auto it = _container.find(s.name()); it != _container.end())
             {
                 it->second.append(s);
             }
@@ -75,18 +75,20 @@ namespace armarx::armem::d_ltm
             {
                 try
                 {
-                    std::filesystem::create_directory(_fullPath() / k);
+                    std::filesystem::create_directory(_fullPath() / s.name());
                 }
                 catch (...)
                 {
                     ARMARX_WARNING << GetHandledExceptionString();
-                    return;
+                    return false;
                 }
 
-                auto wms = _container.emplace(k, id().withCoreSegmentName(k));
+                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
index 7f7872f7a638cc31122f09b00a95755ede4d9606..aaa1e460a5bff94195ae6da7662a7e53b33861e4 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/Memory.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/Memory.h
@@ -2,8 +2,8 @@
 
 #include <filesystem>
 
-#include "../base/MemoryBase.h"
-#include "../workingmemory/Memory.h"
+#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include "CoreSegment.h"
 
@@ -22,7 +22,6 @@ namespace armarx::armem::d_ltm
     public:
 
         using Base::MemoryBase;
-        using Base::operator=;
 
 
         // Conversion
diff --git a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp
index 620e819f6b1fc05d4aeadc285edb087f5ea0e119..08ed0c2b07edc156764f02dc88c5f76160f9d355 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.cpp
@@ -95,9 +95,9 @@ namespace armarx::armem::d_ltm
 
         TypeIO::writeAronType(_aronType, _fullPath());
 
-        for (const auto& [k, s] : m.container())
+        m.forEachEntity([this](const wm::Entity & s)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            if (auto it = _container.find(s.name()); it != _container.end())
             {
                 it->second.append(s);
             }
@@ -106,18 +106,20 @@ namespace armarx::armem::d_ltm
 
                 try
                 {
-                    std::filesystem::create_directory(_fullPath() / k);
+                    std::filesystem::create_directory(_fullPath() / s.name());
                 }
                 catch (...)
                 {
                     ARMARX_WARNING << GetHandledExceptionString();
-                    return;
+                    return false;
                 }
 
-                auto wms = _container.emplace(k, id().withEntityName(k));
+                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
index 8ad96ea0630af0d5aba8b7270fe229c235c2a010..0e866b08cc5c50f623fd9b5676136834078c953a 100644
--- a/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.h
+++ b/source/RobotAPI/libraries/armem/core/diskmemory/ProviderSegment.h
@@ -2,8 +2,8 @@
 
 #include <filesystem>
 
-#include "../base/ProviderSegmentBase.h"
-#include "../workingmemory/ProviderSegment.h"
+#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 #include "Entity.h"
 
@@ -22,7 +22,6 @@ namespace armarx::armem::d_ltm
     public:
 
         using Base::ProviderSegmentBase;
-        using Base::operator=;
 
 
         // Conversion
diff --git a/source/RobotAPI/libraries/armem/core/error/ArMemError.h b/source/RobotAPI/libraries/armem/core/error/ArMemError.h
index e6843d13be5bc07e71d90b00cf6a911ca717e524..219d489fad038da1098d724bddd9e2bc74b0a5d7 100644
--- a/source/RobotAPI/libraries/armem/core/error/ArMemError.h
+++ b/source/RobotAPI/libraries/armem/core/error/ArMemError.h
@@ -84,8 +84,8 @@ namespace armarx::armem::error
         template <class MissingT, class ContainerT>
         static MissingEntry create(const std::string& missingKey, const ContainerT& container)
         {
-            return MissingEntry(MissingT().getLevelName(), missingKey,
-                                container.getLevelName(), container.getKeyString(), container.size());
+            return MissingEntry(MissingT::getLevelName(), missingKey,
+                                ContainerT::getLevelName(), container.getKeyString(), container.size());
         }
 
 
diff --git a/source/RobotAPI/libraries/armem/core/forward_declarations.h b/source/RobotAPI/libraries/armem/core/forward_declarations.h
new file mode 100644
index 0000000000000000000000000000000000000000..761a8513111d55de8b81ade1af62a60ee18f1f3c
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/forward_declarations.h
@@ -0,0 +1,52 @@
+#pragma once
+
+
+namespace armarx::armem
+{
+    // class Time;  // Cannot be forward declared (it's a typedef)
+
+    class MemoryID;
+    class Commit;
+    class EntityUpdate;
+    class CommitResult;
+    class EntityUpdateResult;
+}
+
+namespace armarx::armem::base
+{
+    struct NoData;
+    struct EntityInstanceMetadata;
+
+    template <class _DataT, class _MetadataT>
+    class EntityInstanceBase;
+    template <class _EntityInstanceT, class _Derived>
+    class EntitySnapshotBase;
+    template <class _EntitySnapshotT, class _Derived>
+    class EntityBase;
+    template <class _EntityT, class _Derived>
+    class ProviderSegmentBase;
+    template <class _ProviderSegmentT, class _Derived>
+    class CoreSegmentBase;
+    template <class _CoreSegmentT, class _Derived>
+    class MemoryBase;
+}
+
+namespace armarx::armem::wm
+{
+    class EntityInstance;
+    class EntitySnapshot;
+    class Entity;
+    class ProviderSegment;
+    class CoreSegment;
+    class Memory;
+}
+
+namespace armarx::armem::server::wm
+{
+    using EntityInstance = armem::wm::EntityInstance;
+    using EntitySnapshot = armem::wm::EntitySnapshot;
+    class Entity;
+    class ProviderSegment;
+    class CoreSegment;
+    class Memory;
+}
diff --git a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
index d79acf1da2b86f94414205131173797e0354bc24..cca45a3b2cf04f26ec76d158e9cf1e711bbfecb2 100644
--- a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
@@ -1,20 +1,20 @@
 #include "ice_conversions.h"
 
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
 
-namespace armarx
+
+void IceUtil::toIce(long& ice, const IceUtil::Time& time)
 {
+    ice = time.toMicroSeconds();
+}
 
-    /*
-        void armem::fromIce(long ice, Time& time)
-        {
-            time = Time::microSeconds(ice);
-        }
+void IceUtil::fromIce(const long& ice, IceUtil::Time& time)
+{
+    time = Time::microSeconds(ice);
+}
 
-        void armem::toIce(long& ice, const Time& time)
-        {
-            ice = time.toMicroSeconds();
-        }
-    */
+namespace armarx
+{
 
     void armem::toIce(data::MemoryID& ice, const MemoryID& id)
     {
@@ -144,14 +144,5 @@ namespace armarx
         update.timeArrived = timeArrived;
     }
 
-
-    void armem::detail::toIceItem(data::detail::MemoryItem& ice, const armem::base::detail::MemoryItem& item)
-    {
-        toIce(ice.id, item.id());
-    }
-
-    void armem::detail::fromIceItem(const data::detail::MemoryItem& ice, armem::base::detail::MemoryItem& item)
-    {
-        fromIce(ice.id, item.id());
-    }
 }
+
diff --git a/source/RobotAPI/libraries/armem/core/ice_conversions.h b/source/RobotAPI/libraries/armem/core/ice_conversions.h
index 874684cac2a6a52b8742c36dcc2bdea8346e1586..e8f104fe04ebcb721b0ffbf4b70b18ada0af234c 100644
--- a/source/RobotAPI/libraries/armem/core/ice_conversions.h
+++ b/source/RobotAPI/libraries/armem/core/ice_conversions.h
@@ -6,29 +6,21 @@
 #include "ice_conversions_templates.h"
 
 #include "Commit.h"
-#include "base/detail/MemoryItem.h"
+#include "MemoryID.h"
+#include "Time.h"
 
 
 namespace IceUtil
 {
     // Define in original namespace to allow ADL.
-    inline void toIce(long& ice, const Time& time)
-    {
-        ice = time.toMicroSeconds();
-    }
-    inline void fromIce(const long& ice, Time& time)
-    {
-        time = Time::microSeconds(ice);
-    }
+    void toIce(long& ice, const Time& time);
+    void fromIce(const long& ice, Time& time);
 }
 
 
 namespace armarx::armem
 {
 
-    // void fromIce(long ice, Time& time);
-    // void toIce(long& ice, const Time& time);
-
     void fromIce(const data::MemoryID& ice, MemoryID& id);
     void toIce(data::MemoryID& ice, const MemoryID& id);
 
@@ -51,12 +43,5 @@ namespace armarx::armem
     void fromIce(const data::Commit& ice, Commit& commit, Time timeArrived);
     void fromIce(const data::EntityUpdate& ice, EntityUpdate& update, Time timeArrived);
 
-
-    namespace detail
-    {
-        void toIceItem(data::detail::MemoryItem& ice, const armem::base::detail::MemoryItem& item);
-        void fromIceItem(const data::detail::MemoryItem& ice, armem::base::detail::MemoryItem& item);
-    }
-
 }
 
diff --git a/source/RobotAPI/libraries/armem/core/ice_conversions_templates.h b/source/RobotAPI/libraries/armem/core/ice_conversions_templates.h
index e0c71faac37cd899d85d174c33196499a29df770..8060e22a0782e23c6bb989fe900fcce99c7ff7c6 100644
--- a/source/RobotAPI/libraries/armem/core/ice_conversions_templates.h
+++ b/source/RobotAPI/libraries/armem/core/ice_conversions_templates.h
@@ -1,9 +1,12 @@
 #pragma once
 
-#include <memory>
-
 #include "Commit.h"
 
+#include <Ice/Handle.h>
+
+#include <map>
+#include <memory>
+#include <vector>
 
 
 namespace armarx::armem
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp
index d47dc46cb63c5266edc8b9e8457c1fb4b75a4527..1fc021d65fe460b4b91331196446ef8661337aa6 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.cpp
@@ -1,8 +1,10 @@
 #include "CoreSegment.h"
 
+#include "error.h"
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include "error.h"
+#include <SimoxUtility/json/json.hpp>
 
 
 namespace armarx::armem::ltm
@@ -33,7 +35,7 @@ namespace armarx::armem::ltm
             nlohmann::json json = nlohmann::json::parse(bsoncxx::to_json(doc));
             ARMARX_INFO << "CoreSegment: Found foreign key: " << json.at("foreign_key");
 
-            MemoryID i((std::string) 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);
@@ -41,7 +43,7 @@ namespace armarx::armem::ltm
 
             std::string k = i.providerSegmentName;
 
-            if (const auto& it = _container.find(k); it != _container.end())
+            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?");
             }
@@ -62,24 +64,23 @@ namespace armarx::armem::ltm
         mongocxx::database db = client[dbsettings.database];
         mongocxx::collection coll = db[id().str()];
 
-        for (const auto& [k, s] : m.container())
+        m.forEachProviderSegment([this, &coll](const wm::ProviderSegment & provSeg)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
-            {
-                it->second.append(s);
-            }
-            else
+            auto it = _container.find(provSeg.name());
+            if (it == _container.end())
             {
-                auto builder = bsoncxx::builder::stream::document{};
+                bsoncxx::builder::stream::document builder;
                 bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << s.id().withProviderSegmentName(k).str()
+                                                       << "foreign_key" << provSeg.id().str()
                                                        << bsoncxx::builder::stream::finalize;
                 coll.insert_one(foreign_key.view());
 
-                auto wms = _container.emplace(k, id().withProviderSegmentName(k));
-                wms.first->second.dbsettings = dbsettings;
-                wms.first->second.append(s);
+                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
index 3a7225058a265949de50e98a63d1d3c6ce5bf371..32f05ef2f773388b6006c573b7017064193d80c3 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/CoreSegment.h
@@ -1,10 +1,10 @@
 #pragma once
 
-#include "../base/CoreSegmentBase.h"
-
 #include "ProviderSegment.h"
+#include "mongodb/MongoDBConnectionManager.h"
 
-#include "../workingmemory/CoreSegment.h"
+#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 namespace armarx::armem::ltm
@@ -21,7 +21,6 @@ namespace armarx::armem::ltm
     public:
 
         using Base::CoreSegmentBase;
-        using Base::operator=;
 
 
         // Conversion
@@ -31,21 +30,10 @@ namespace armarx::armem::ltm
         void reload();
         void append(const wm::CoreSegment&);
 
-    protected:
-        virtual void _copySelf(CoreSegment& other) const override
-        {
-            Base::_copySelf(other);
-            other.dbsettings = dbsettings;
-        }
-
-        virtual void _copySelfEmpty(CoreSegment& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.dbsettings = dbsettings;
-        }
-
     public:
+
         MongoDBConnectionManager::MongoDBSettings dbsettings;
+
     };
 
 }
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp
index bccb79c9d1d162a6c67a4f80c57b58b04425863e..6604c26e935cb4619fc7439d8e9a1f318a14ff63 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.cpp
@@ -1,5 +1,9 @@
 #include "Entity.h"
 
+#include <ArmarXCore/core/logging/Logging.h>
+
+#include <SimoxUtility/json/json.hpp>
+
 
 namespace armarx::armem::ltm
 {
@@ -26,17 +30,12 @@ namespace armarx::armem::ltm
         int i = 0;
         for (auto doc : cursor)
         {
-            if (i > MAX_HISTORY_SIZE)
-            {
-                // TODO: Add logic for most queried data?
-                break;
-            }
             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 (const auto& it = _container.find(k); it != _container.end())
+            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?");
             }
@@ -58,21 +57,22 @@ namespace armarx::armem::ltm
         mongocxx::database db = client[dbsettings.database];
         mongocxx::collection coll = db[id().str()];
 
-        for (const auto& [k, s] : m.container())
+        m.forEachSnapshot([this](const wm::EntitySnapshot & snapshot)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            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(k, id().withTimestamp(k)));
+                auto wms = _container.emplace(std::make_pair(snapshot.time(), id().withTimestamp(snapshot.time())));
                 wms.first->second.dbsettings = dbsettings;
-                wms.first->second.setTo(s, k);
+                wms.first->second.setTo(snapshot, snapshot.time());
                 //truncateHistoryToSize();
             }
-        }
+            return true;
+        });
     }
 
     bool Entity::hasSnapshot(const Time& time) const
@@ -87,21 +87,22 @@ namespace armarx::armem::ltm
         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);
+        bsoncxx::stdx::optional<bsoncxx::document::value> maybe_result =
+            coll.find_one(document{} << "timestamp" << time.toMicroSeconds() << finalize);
         if (!maybe_result)
         {
             return false;
         }
 
-        auto json = nlohmann::json::parse(bsoncxx::to_json(*maybe_result));
-        auto id = MemoryID::fromString(json["id"].get<std::string>());
-        auto instances = json["instances"];
+        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 (unsigned int i = 0; i < instances.size(); ++i)
+        for (size_t i = 0; i < instances.size(); ++i)
         {
-            EntityInstance instance(id.withInstanceIndex(i));
+            EntityInstance instance(id.withInstanceIndex(static_cast<int>(i)));
             snapshot.addInstance(instance);
         }
 
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h
index 20377befd61f741a642e139aafe1de3c2cc7f24b..99bc3a736f0abe803ec101a81f4b1ac75b87d92e 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/Entity.h
@@ -1,10 +1,10 @@
 #pragma once
 
-#include "../base/EntityBase.h"
-
 #include "EntitySnapshot.h"
+#include "mongodb/MongoDBConnectionManager.h"
 
-#include "../workingmemory/Entity.h"
+#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 namespace armarx::armem::ltm
@@ -36,13 +36,7 @@ namespace armarx::armem::ltm
     public:
 
         using Base::EntityBase;
-        using Base::operator=;
 
-        Entity()
-        {
-            // the history of snapshots is just a cache of frequently used elements
-            setMaxHistorySize(MAX_HISTORY_SIZE);
-        }
 
         // Conversion
         wm::Entity convert() const;
@@ -51,33 +45,19 @@ namespace armarx::armem::ltm
         void reload();
         void append(const wm::Entity&);
 
-        // virtual overrides for LTM lookups
-        virtual bool hasSnapshot(const Time& time) const override;
-        virtual std::vector<Time> getTimestamps() const override;
-        virtual const EntitySnapshot& getSnapshot(const Time& time) const override;
-
-    protected:
-        virtual void _copySelf(Entity& other) const override
-        {
-            Base::_copySelf(other);
-            other.dbsettings = dbsettings;
-        }
+        // overrides for LTM lookups
+        bool hasSnapshot(const Time& time) const;
+        std::vector<Time> getTimestamps() const;
+        const EntitySnapshot& getSnapshot(const Time& time) const;
 
-        virtual void _copySelfEmpty(Entity& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.dbsettings = dbsettings;
-        }
 
     protected:
-        // virtual overrides for LTM storage
-        virtual const ContainerT::value_type& getLatestItem() const override;
+        // overrides for LTM storage
+        const ContainerT::value_type& getLatestItem() const;
 
     public:
         MongoDBConnectionManager::MongoDBSettings dbsettings;
 
-    private:
-        const static constexpr int MAX_HISTORY_SIZE = 200;
     };
 
 }
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp
index 5e44714904efe74f920b891b665e13497b749508..63fe18145c561e9efda0ba2a14cb07175b029d1c 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.cpp
@@ -1,30 +1,19 @@
 #include "EntityInstance.h"
 
-#include "../../core/error.h"
-
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+
 namespace armarx::armem::ltm
 {
 
-    bool EntityInstanceMetadata::operator==(const EntityInstanceMetadata& other) const
-    {
-        return timeCreated == other.timeCreated
-               && timeSent == other.timeSent
-               && timeArrived == other.timeArrived
-               && std::abs(confidence - other.confidence) < 1e-6f;
-    }
-
     bool EntityInstance::equalsDeep(const EntityInstance& other) const
     {
         return id() == other.id() && _metadata == other.metadata();
     }
 
-    void EntityInstance::update(const EntityUpdate& update, int index)
+    void EntityInstance::update(const EntityUpdate& update)
     {
-        ARMARX_CHECK_FITS_SIZE(index, update.instancesData.size());
-
-        this->index() = index;
+        ARMARX_CHECK_FITS_SIZE(this->index(), update.instancesData.size());
 
         this->_metadata.confidence = update.confidence;
         this->_metadata.timeCreated = update.timeCreated;
@@ -32,16 +21,4 @@ namespace armarx::armem::ltm
         this->_metadata.timeArrived = update.timeArrived;
     }
 
-    EntityInstance EntityInstance::copy() const
-    {
-        EntityInstance d;
-        this->_copySelf(d);
-        return d;
-    }
-
-    void EntityInstance::_copySelf(EntityInstance& other) const
-    {
-        Base::_copySelf(other);
-        other._metadata = _metadata;
-    }
 }
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h
index e95ae277e83b2a927172ad1e663c42a700fef849..6046f6ac50902d6f7f770361915dbd30d5a15ec1 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/EntityInstance.h
@@ -1,84 +1,35 @@
 #pragma once
 
-#include "../base/EntityInstanceBase.h"
+#include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
 
-#include "../workingmemory/EntityInstance.h"
-#include "mongodb/MongoDBConnectionManager.h"
-
-#include "../workingmemory/entityInstance_conversions.h"
-#include "../workingmemory/json_conversions.h"
 
 namespace armarx::armem::ltm
 {
 
-    /**
-     * @brief Metadata of an entity instance.
-     */
-    struct EntityInstanceMetadata
-    {
-        /// Time when this value was created.
-        Time timeCreated;
-        /// Time when this value was sent to the memory.
-        Time timeSent;
-        /// Time when this value has arrived at the memory.
-        Time timeArrived;
+    using EntityInstanceMetadata = base::EntityInstanceMetadata;
 
-        /// An optional confidence, may be used for things like decay.
-        float confidence = 1.0;
-
-
-        bool operator==(const EntityInstanceMetadata& other) const;
-        inline bool operator!=(const EntityInstanceMetadata& other) const
-        {
-            return !(*this == other);
-        }
-    };
 
     /**
      * @brief Data of a single entity instance.
      */
     class EntityInstance :
-        public base::EntityInstanceBase<EntityInstance>
+        public base::EntityInstanceBase<base::NoData, EntityInstanceMetadata>
     {
-        using Base = base::EntityInstanceBase<EntityInstance>;
+        using Base = base::EntityInstanceBase<base::NoData, EntityInstanceMetadata>;
 
     public:
 
         using Base::EntityInstanceBase;
 
-        EntityInstance(const EntityInstance& other) = default;
-        EntityInstance(EntityInstance&& other) = default;
-        EntityInstance& operator=(const EntityInstance& other) = default;
-        EntityInstance& operator=(EntityInstance&& other) = default;
-
-
-        EntityInstanceMetadata& metadata()
-        {
-            return _metadata;
-        }
-        inline const EntityInstanceMetadata& metadata() const
-        {
-            return _metadata;
-        }
-
 
         /**
          * @brief Fill `*this` with the update's values.
          * @param update The update.
          * @param index The instances index.
          */
-        virtual void update(const EntityUpdate& update, int index) override;
-
-        virtual bool equalsDeep(const EntityInstance& other) const override;
-
-        virtual EntityInstance copy() const override;
-
-    protected:
-        virtual void _copySelf(EntityInstance& other) const override;
+        void update(const EntityUpdate& update);
 
+        bool equalsDeep(const EntityInstance& other) const;
 
-    private:
-        /// The metadata.
-        EntityInstanceMetadata _metadata;
     };
 }
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp
index aae8a6d3258c94a27e9f931838a44c8d1b6426aa..8cbe688125a7571a3e8f0a19031b25722bb79bbf 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.cpp
@@ -2,8 +2,11 @@
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include "../workingmemory/entityInstance_conversions.h"
-#include "../workingmemory/json_conversions.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"
 
@@ -18,7 +21,6 @@ namespace armarx::armem::ltm
         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());
@@ -85,18 +87,20 @@ namespace armarx::armem::ltm
         auto array_builder = bsoncxx::builder::basic::array{};
 
         int i = 0;
-        for (const auto& s : m.container())
+        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, s);
+            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;
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h
index 02361d2e708365303fbce81f56eaa9b49fb07a61..3029f8a7ca0278b9a505ee2fa5a744cfab327359 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/EntitySnapshot.h
@@ -1,10 +1,12 @@
 #pragma once
 
-#include "../base/EntitySnapshotBase.h"
-
 #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 "../workingmemory/EntitySnapshot.h"
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
 
 namespace armarx::armem::ltm
@@ -21,7 +23,6 @@ namespace armarx::armem::ltm
     public:
 
         using Base::EntitySnapshotBase;
-        using Base::operator=;
 
 
         // Conversion
@@ -31,20 +32,10 @@ namespace armarx::armem::ltm
         void reload();
         void setTo(const wm::EntitySnapshot&, const armem::Time& t);
 
-    protected:
-        virtual void _copySelf(EntitySnapshot& other) const override
-        {
-            Base::_copySelf(other);
-            other.dbsettings = dbsettings;
-        }
-
-        virtual void _copySelfEmpty(EntitySnapshot& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.dbsettings = dbsettings;
-        }
 
     public:
+
         MongoDBConnectionManager::MongoDBSettings dbsettings;
+
     };
 }
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp
index 2080879c55f1dd94e5aeeb2f6d78f72ada5c4aaf..ab4cb5d13ec0a30c0e8dc04125b61bd4b031df99 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.cpp
@@ -1,11 +1,13 @@
 #include "Memory.h"
 
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.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
 {
@@ -13,7 +15,6 @@ namespace armarx::armem::ltm
     Memory::Memory(const Memory& other) :
         Base(other),
         dbsettings(other.dbsettings),
-        alwaysTransferSettings(other.alwaysTransferSettings),
         periodicTransferSettings(other.periodicTransferSettings),
         onFullTransferSettings(other.onFullTransferSettings),
         mongoDBMutex()
@@ -23,9 +24,8 @@ namespace armarx::armem::ltm
 
 
     Memory::Memory(Memory&& other) :
-        Base(other),
+        Base(std::move(other)),
         dbsettings(other.dbsettings),
-        alwaysTransferSettings(other.alwaysTransferSettings),
         periodicTransferSettings(other.periodicTransferSettings),
         onFullTransferSettings(other.onFullTransferSettings),
         reloaded(other.reloaded)
@@ -37,8 +37,8 @@ namespace armarx::armem::ltm
     Memory& Memory::operator=(const Memory& other)
     {
         Base::operator=(other);
+
         dbsettings = other.dbsettings;
-        alwaysTransferSettings = other.alwaysTransferSettings;
         periodicTransferSettings = other.periodicTransferSettings;
         onFullTransferSettings = other.onFullTransferSettings;
 
@@ -49,9 +49,9 @@ namespace armarx::armem::ltm
 
     Memory& Memory::operator=(Memory&& other)
     {
-        Base::operator=(other);
+        Base::operator=(std::move(other));
+
         dbsettings = std::move(other.dbsettings);
-        alwaysTransferSettings = std::move(other.alwaysTransferSettings);
         periodicTransferSettings = std::move(other.periodicTransferSettings);
         onFullTransferSettings = std::move(other.onFullTransferSettings);
         reloaded = other.reloaded;
@@ -69,7 +69,7 @@ namespace armarx::armem::ltm
             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"
-                           << "mongod --port " << dbsettings.port << " --dbpath \"/tmp/\""
+                           << "armarx memory start"
                            << "\n\n";
             return false;
         }
@@ -83,17 +83,17 @@ namespace armarx::armem::ltm
         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(alwaysTransferSettings.enabled, prefix + "ltm.30_enableAlwaysTransfer", "Enable transfer whenever new data is committed (This disables the other transfer modes!).");
-        defs->optional(periodicTransferSettings.enabled, prefix + "ltm.31_enablePeriodicTransfer", "Enable transfer based on periodic interval.");
-        defs->optional(onFullTransferSettings.enabled, prefix + "ltm.32_enableOnFullTransfer", "Enable transfer whenever the wm is full (see maxHistorySize).");
+        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())
         {
-            wm::Memory m(id());
             return m;
         }
 
@@ -101,7 +101,6 @@ namespace armarx::armem::ltm
 
         TIMING_START(LTM_Convert);
 
-        wm::Memory m(id());
         for (const auto& [_, s] : _container)
         {
             m.addCoreSegment(s.convert());
@@ -160,7 +159,7 @@ namespace armarx::armem::ltm
 
             std::string k = i.coreSegmentName;
 
-            if (const auto& it = _container.find(k); it != _container.end())
+            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?");
             }
@@ -198,9 +197,9 @@ namespace armarx::armem::ltm
         mongocxx::database db = client[dbsettings.database];
         mongocxx::collection coll = db[id().str()];
 
-        for (const auto& [k, s] : m.container())
+        m.forEachCoreSegment([this, &coll](const wm::CoreSegment & s)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            if (auto it = _container.find(s.name()); it != _container.end())
             {
                 // TODO check if foreign key exists
                 it->second.append(s);
@@ -209,15 +208,17 @@ namespace armarx::armem::ltm
             {
                 auto builder = bsoncxx::builder::stream::document{};
                 bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << s.id().withCoreSegmentName(k).str()
+                                                       << "foreign_key" << s.id().withCoreSegmentName(s.name()).str()
                                                        << bsoncxx::builder::stream::finalize;
                 coll.insert_one(foreign_key.view());
 
-                auto wms = _container.emplace(k, id().withCoreSegmentName(k));
+                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);
     }
@@ -230,7 +231,6 @@ namespace armarx::armem::ltm
             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
index b24f4a7a662e2b5980d3dec00ecbb39b2c972673..41e82bce38b50f9e122e34056c2b5fd74cec4bac 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/Memory.h
@@ -1,17 +1,15 @@
 #pragma once
 
-// BaseClass
-#include "../base/MemoryBase.h"
-
-// CoreSegment
 #include "CoreSegment.h"
+#include "mongodb/MongoDBConnectionManager.h"
+
+#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-// WM
-#include "../workingmemory/Memory.h"
+#include <ArmarXCore/core/application/properties/forward_declarations.h>
+
+#include <mutex>
 
-// Properties
-#include <ArmarXCore/core/application/properties/PluginAll.h>
-#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
 
 namespace armarx::armem::ltm
 {
@@ -25,19 +23,11 @@ namespace armarx::armem::ltm
 
     public:
 
-        using Base::MemoryBase;
-        using Base::operator=;
-
         struct TransferSettings
         {
             bool enabled = false;
         };
 
-        struct AlwaysTransferSettings : public TransferSettings
-        {
-
-        };
-
         struct PeriodicTransferSettings : public TransferSettings
         {
             bool deleteFromWMOnTransfer = false;
@@ -53,9 +43,14 @@ namespace armarx::armem::ltm
             };
 
             Mode mode;
+            int batch_size = 20;
         };
 
 
+    public:
+
+        using Base::MemoryBase;
+
         Memory(const Memory& other);
         Memory(Memory&& other);
         Memory& operator=(const Memory& other);
@@ -71,18 +66,6 @@ namespace armarx::armem::ltm
         void reload();
         void append(const wm::Memory&);
 
-    protected:
-        virtual void _copySelf(Memory& other) const override
-        {
-            Base::_copySelf(other);
-            other.dbsettings = dbsettings;
-        }
-
-        virtual void _copySelfEmpty(Memory& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.dbsettings = dbsettings;
-        }
 
     private:
         bool checkConnection() const;
@@ -92,7 +75,6 @@ namespace armarx::armem::ltm
     public:
         MongoDBConnectionManager::MongoDBSettings dbsettings;
 
-        AlwaysTransferSettings alwaysTransferSettings;
         PeriodicTransferSettings periodicTransferSettings;
         OnFullTransferSettings onFullTransferSettings;
 
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp
index 5fcf4a1351e34f257e773c2ac32e9d4eb64c5401..8126867e4db4be01c91dfb582b67c94303751927 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.cpp
@@ -1,8 +1,10 @@
 #include "ProviderSegment.h"
 
+#include "error.h"
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include "error.h"
+#include <SimoxUtility/json/json.hpp>
 
 
 namespace armarx::armem::ltm
@@ -39,7 +41,7 @@ namespace armarx::armem::ltm
 
             std::string k = i.entityName;
 
-            if (const auto& it = _container.find(k); it != _container.end())
+            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?");
             }
@@ -60,9 +62,9 @@ namespace armarx::armem::ltm
         mongocxx::database db = client[dbsettings.database];
         mongocxx::collection coll = db[id().str()];
 
-        for (const auto& [k, s] : m.container())
+        m.forEachEntity([this, &coll](const wm::Entity & s)
         {
-            if (const auto& it = _container.find(k); it != _container.end())
+            if (auto it = _container.find(s.name()); it != _container.end())
             {
                 it->second.append(s);
             }
@@ -70,14 +72,16 @@ namespace armarx::armem::ltm
             {
                 auto builder = bsoncxx::builder::stream::document{};
                 bsoncxx::document::value foreign_key = builder
-                                                       << "foreign_key" << s.id().withEntityName(k).str()
+                                                       << "foreign_key" << s.id().withEntityName(s.name()).str()
                                                        << bsoncxx::builder::stream::finalize;
                 coll.insert_one(foreign_key.view());
 
-                auto wms = _container.emplace(k, id().withEntityName(k));
+                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
index bb49f232e9fe231e1cd500e3f9739ddaa0d7d83f..bf1d5e3a9f4cbd816e087957d0bb3d6351b0b6cd 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.h
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/ProviderSegment.h
@@ -1,10 +1,10 @@
 #pragma once
 
-#include "../base/ProviderSegmentBase.h"
-
 #include "Entity.h"
+#include "mongodb/MongoDBConnectionManager.h"
 
-#include "../workingmemory/ProviderSegment.h"
+#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 namespace armarx::armem::ltm
@@ -21,7 +21,6 @@ namespace armarx::armem::ltm
     public:
 
         using Base::ProviderSegmentBase;
-        using Base::operator=;
 
 
         // Conversion
@@ -31,19 +30,6 @@ namespace armarx::armem::ltm
         void reload();
         void append(const wm::ProviderSegment&);
 
-    protected:
-        virtual void _copySelf(ProviderSegment& other) const override
-        {
-            Base::_copySelf(other);
-            other.dbsettings = dbsettings;
-        }
-
-        virtual void _copySelfEmpty(ProviderSegment& other) const override
-        {
-            Base::_copySelfEmpty(other);
-            other.dbsettings = dbsettings;
-        }
-
     public:
         MongoDBConnectionManager::MongoDBSettings dbsettings;
     };
diff --git a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp b/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
index 6ad44836900e04765790a9a3c2a19881e1288656..fd2bbbb6ccb8aee93c4d343b818dc55872f7838a 100644
--- a/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
+++ b/source/RobotAPI/libraries/armem/core/longtermmemory/mongodb/MongoDBConnectionManager.cpp
@@ -20,7 +20,7 @@ namespace armarx::armem::ltm
         initialize_if();
 
         const auto uri_str = settings.uri();
-        const auto& it = Connections.find(uri_str);
+        auto it = Connections.find(uri_str);
         if (it == Connections.end())
         {
             mongocxx::uri uri(uri_str);
@@ -43,7 +43,7 @@ namespace armarx::armem::ltm
             if (!force)
             {
                 const auto uri_str = settings.uri();
-                const auto& it = Connections.find(uri_str);
+                auto it = Connections.find(uri_str);
                 if (it != Connections.end())
                 {
                     auto admin = it->second["admin"];
@@ -70,7 +70,7 @@ namespace armarx::armem::ltm
         initialize_if();
 
         const auto uri_str = settings.uri();
-        const auto& it = Connections.find(uri_str);
+        auto it = Connections.find(uri_str);
         return it != Connections.end();
     }
 }
diff --git a/source/RobotAPI/libraries/armem/core/operations.cpp b/source/RobotAPI/libraries/armem/core/operations.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b9ebedd316a41494d93bf99b1700fd83c475ba71
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/operations.cpp
@@ -0,0 +1,32 @@
+#include "operations.h"
+
+
+namespace armarx
+{
+
+    std::vector<aron::datanavigator::DictNavigatorPtr>
+    armem::getAronData(const wm::EntitySnapshot& snapshot)
+    {
+        std::vector<aron::datanavigator::DictNavigatorPtr> result;
+        snapshot.forEachChild([&result](const wm::EntityInstance & instance)
+        {
+            result.push_back(instance.data());
+            return true;
+        });
+        return result;
+    }
+
+
+    armem::EntityUpdate armem::toEntityUpdate(const wm::EntitySnapshot& snapshot)
+    {
+        EntityUpdate up;
+        up.entityID = snapshot.id().getEntityID();
+        up.timeCreated = snapshot.time();
+        up.instancesData = getAronData(snapshot);
+        return up;
+    }
+
+}
+
+
+
diff --git a/source/RobotAPI/libraries/armem/core/operations.h b/source/RobotAPI/libraries/armem/core/operations.h
new file mode 100644
index 0000000000000000000000000000000000000000..3b0182e324f32b832c97aaafa04ada90e604c9fa
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/operations.h
@@ -0,0 +1,34 @@
+#pragma once
+
+#include "wm/memory_definitions.h"
+
+
+/*
+ * Functions performing some "advanced" operations on the memory
+ * data structure, which are using their public API but should not
+ * be part of it.
+ */
+
+namespace armarx::armem
+{
+
+    std::vector<aron::datanavigator::DictNavigatorPtr>
+    getAronData(const wm::EntitySnapshot& snapshot);
+
+    EntityUpdate toEntityUpdate(const wm::EntitySnapshot& snapshot);
+
+
+    template <class ContainerT>
+    Commit toCommit(const ContainerT& container)
+    {
+        Commit commit;
+        container.forEachSnapshot([&commit](const wm::EntitySnapshot & snapshot)
+        {
+            commit.add(toEntityUpdate(snapshot));
+            return true;
+        });
+        return commit;
+    }
+
+}
+
diff --git a/source/RobotAPI/libraries/armem/core/wm.h b/source/RobotAPI/libraries/armem/core/wm.h
new file mode 100644
index 0000000000000000000000000000000000000000..83776ed701261bde89ed1fe2fd1e4ff479f06f44
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm.h
@@ -0,0 +1,10 @@
+#pragma once
+
+#include "wm/memory_definitions.h"
+
+
+namespace armarx::armem::wm
+{
+
+}
+
diff --git a/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a4a5faa1404129feed5f2573c706c22900c108df
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
@@ -0,0 +1,69 @@
+#include "aron_conversions.h"
+
+#include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h>
+
+
+namespace armarx::armem
+{
+
+    constexpr const char* DATA_WRAPPER_DATA_FIELD            = "__ARON_DATA";
+    constexpr const char* DATA_WRAPPER_TIME_STORED_FIELD     = "__WRITER_METADATA__TIME_STORED";
+    constexpr const char* DATA_WRAPPER_TIME_CREATED_FIELD    = "__ENTITY_METADATA__TIME_CREATED";
+    constexpr const char* DATA_WRAPPER_TIME_SENT_FIELD       = "__ENTITY_METADATA__TIME_SENT";
+    constexpr const char* DATA_WRAPPER_TIME_ARRIVED_FIELD    = "__ENTITY_METADATA__TIME_ARRIVED";
+    constexpr const char* DATA_WRAPPER_CONFIDENCE_FIELD      = "__ENTITY_METADATA__CONFIDENCE";
+
+}
+
+
+void armarx::armem::from_aron(const aron::datanavigator::DictNavigatorPtr& dataWrapped, wm::EntityInstance& e)
+{
+    wm::EntityInstanceMetadata& metadata = e.metadata();
+
+    if (dataWrapped->hasElement(DATA_WRAPPER_DATA_FIELD))
+    {
+        e.data() = aron::datanavigator::DictNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_DATA_FIELD));
+    }
+
+    auto timeCreated = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_CREATED_FIELD));
+    metadata.timeCreated = Time::microSeconds(timeCreated->toAronLongPtr()->value);
+
+    auto timeSent = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_SENT_FIELD));
+    metadata.timeSent = Time::microSeconds(timeSent->toAronLongPtr()->value);
+
+    auto timeArrived = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_ARRIVED_FIELD));
+    metadata.timeArrived = Time::microSeconds(timeArrived->toAronLongPtr()->value);
+
+    auto confidence = aron::datanavigator::DoubleNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_CONFIDENCE_FIELD));
+    metadata.confidence = static_cast<float>(confidence->toAronDoublePtr()->value);
+}
+
+
+void armarx::armem::to_aron(aron::datanavigator::DictNavigatorPtr& a, const wm::EntityInstance& e)
+{
+    if (e.data())
+    {
+        a->addElement(DATA_WRAPPER_DATA_FIELD, e.data());
+    }
+
+    auto timeWrapped = std::make_shared<aron::datanavigator::LongNavigator>();
+    timeWrapped->setValue(Time::now().toMicroSeconds());
+    a->addElement(DATA_WRAPPER_TIME_STORED_FIELD, timeWrapped);
+
+    const wm::EntityInstanceMetadata& metadata = e.metadata();
+    auto timeCreated = std::make_shared<aron::datanavigator::LongNavigator>();
+    timeCreated->setValue(metadata.timeCreated.toMicroSeconds());
+    a->addElement(DATA_WRAPPER_TIME_CREATED_FIELD, timeCreated);
+
+    auto timeSent = std::make_shared<aron::datanavigator::LongNavigator>();
+    timeSent->setValue(metadata.timeSent.toMicroSeconds());
+    a->addElement(DATA_WRAPPER_TIME_SENT_FIELD, timeSent);
+
+    auto timeArrived = std::make_shared<aron::datanavigator::LongNavigator>();
+    timeArrived->setValue(metadata.timeArrived.toMicroSeconds());
+    a->addElement(DATA_WRAPPER_TIME_ARRIVED_FIELD, timeArrived);
+
+    auto confidence = std::make_shared<aron::datanavigator::DoubleNavigator>();
+    confidence->setValue(static_cast<double>(metadata.confidence));
+    a->addElement(DATA_WRAPPER_CONFIDENCE_FIELD, confidence);
+}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.h b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.h
similarity index 59%
rename from source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.h
rename to source/RobotAPI/libraries/armem/core/wm/aron_conversions.h
index f3b25566f110dca844e24dcac4c997f724c74548..f6b43dc8bd468008b9fe8ee470564f5de89e16cb 100644
--- a/source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.h
+++ b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.h
@@ -1,6 +1,9 @@
 #pragma once
 
-#include "Memory.h"
+#include <RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h>
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
 
 namespace armarx::armem
 {
diff --git a/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..70a905a931fd331a6ecdfbc2c278924b0da9144a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.cpp
@@ -0,0 +1,64 @@
+#include "ice_conversions.h"
+
+#include <RobotAPI/libraries/armem/core/base/ice_conversions.h>
+
+
+namespace armarx::armem
+{
+
+    void wm::toIce(data::EntityInstance& ice, const EntityInstance& data)
+    {
+        base::toIce(ice, data);
+    }
+    void wm::fromIce(const data::EntityInstance& ice, EntityInstance& data)
+    {
+        base::fromIce(ice, data);
+    }
+
+
+    void wm::toIce(data::EntitySnapshot& ice, const EntitySnapshot& snapshot)
+    {
+        base::toIce(ice, snapshot);
+    }
+    void wm::fromIce(const data::EntitySnapshot& ice, EntitySnapshot& snapshot)
+    {
+        base::fromIce(ice, snapshot);
+    }
+
+    void wm::toIce(data::Entity& ice, const Entity& entity)
+    {
+        base::toIce(ice, entity);
+    }
+    void wm::fromIce(const data::Entity& ice, Entity& entity)
+    {
+        base::fromIce(ice, entity);
+    }
+
+    void wm::toIce(data::ProviderSegment& ice, const ProviderSegment& providerSegment)
+    {
+        base::toIce(ice, providerSegment);
+    }
+    void wm::fromIce(const data::ProviderSegment& ice, ProviderSegment& providerSegment)
+    {
+        base::fromIce(ice, providerSegment);
+    }
+
+    void wm::toIce(data::CoreSegment& ice, const CoreSegment& coreSegment)
+    {
+        base::toIce(ice, coreSegment);
+    }
+    void wm::fromIce(const data::CoreSegment& ice, CoreSegment& coreSegment)
+    {
+        base::fromIce(ice, coreSegment);
+    }
+
+    void wm::toIce(data::Memory& ice, const Memory& memory)
+    {
+        base::toIce(ice, memory);
+    }
+    void wm::fromIce(const data::Memory& ice, Memory& memory)
+    {
+        base::fromIce(ice, memory);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/wm/ice_conversions.h b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..4a58f16aaa6eef4c6f6685a86ed66298c1407454
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/ice_conversions.h
@@ -0,0 +1,34 @@
+#pragma once
+
+#include <RobotAPI/interface/armem/commit.h>
+#include <RobotAPI/interface/armem/memory.h>
+
+#include "memory_definitions.h"
+
+
+namespace armarx::armem::wm
+{
+
+    void toIce(data::EntityInstance& ice, const EntityInstance& data);
+    void fromIce(const data::EntityInstance& ice, EntityInstance& data);
+
+
+    void toIce(data::EntitySnapshot& ice, const EntitySnapshot& snapshot);
+    void fromIce(const data::EntitySnapshot& ice, EntitySnapshot& snapshot);
+
+    void toIce(data::Entity& ice, const Entity& entity);
+    void fromIce(const data::Entity& ice, Entity& entity);
+
+
+    void toIce(data::ProviderSegment& ice, const ProviderSegment& providerSegment);
+    void fromIce(const data::ProviderSegment& ice, ProviderSegment& providerSegment);
+
+    void toIce(data::CoreSegment& ice, const CoreSegment& coreSegment);
+    void fromIce(const data::CoreSegment& ice, CoreSegment& coreSegment);
+
+    void toIce(data::Memory& ice, const Memory& memory);
+    void fromIce(const data::Memory& ice, Memory& memory);
+}
+
+// Must be included after the prototypes. Otherwise the compiler cannot find the correct methods in ice_coversion_templates.h
+#include <RobotAPI/libraries/armem/core/ice_conversions.h>
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp
similarity index 64%
rename from source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.cpp
rename to source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp
index e7499d8b42edf895bbbdb2f0d06a1fe3ed2ee823..fd67c5f822cbfa3783bf1fc23b3de24f06a27f88 100644
--- a/source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/json_conversions.cpp
@@ -1,10 +1,14 @@
 #include "json_conversions.h"
 
 #include <RobotAPI/libraries/aron/core/Debug.h>
+#include <RobotAPI/libraries/aron/core/io/dataIO/visitor/Visitor.h>
+#include <RobotAPI/libraries/aron/core/io/dataIO/converter/Converter.h>
+#include <RobotAPI/libraries/aron/core/io/dataIO/reader/nlohmannJSON/NlohmannJSONReader.h>
+#include <RobotAPI/libraries/aron/core/io/dataIO/writer/nlohmannJSON/NlohmannJSONWriter.h>
+
 
 namespace armarx::armem
 {
-
     void from_aron(const aron::datanavigator::DictNavigatorPtr& aron, nlohmann::json& j)
     {
         aron::dataIO::writer::NlohmannJSONWriter dataWriter;
@@ -12,7 +16,8 @@ namespace armarx::armem
         j = dataWriter.getResult();
     }
 
-    void to_aron(aron::datanavigator::DictNavigatorPtr& a, const nlohmann::json& e, const aron::typenavigator::NavigatorPtr& expectedStructure)
+    void to_aron(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/armem/core/wm/json_conversions.h b/source/RobotAPI/libraries/armem/core/wm/json_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..4ce93812b606688e642eecc0b7856210adce1a90
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/json_conversions.h
@@ -0,0 +1,14 @@
+#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
new file mode 100644
index 0000000000000000000000000000000000000000..c9516fc3b74ce05797d7d8c39b12f83b0bdf740d
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
@@ -0,0 +1,92 @@
+#include "memory_definitions.h"
+
+#include "error.h"
+
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <map>
+#include <vector>
+
+
+namespace armarx::armem::wm
+{
+
+    bool EntityInstance::equalsDeep(const EntityInstance& other) const
+    {
+        if (_data and other.data())
+        {
+            return id() == other.id()
+                   && _metadata == other.metadata()
+                   && *_data == *other.data();
+        }
+        if (_data or other.data())
+        {
+            return false;
+        }
+        return id() == other.id() && _metadata == other.metadata();
+    }
+
+
+    void EntityInstance::update(const EntityUpdate& update)
+    {
+        ARMARX_CHECK_FITS_SIZE(this->index(), update.instancesData.size());
+
+        this->data() = update.instancesData.at(size_t(this->index()));
+
+        this->_metadata.confidence = update.confidence;
+
+        this->_metadata.timeCreated = update.timeCreated;
+        this->_metadata.timeSent = update.timeSent;
+        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
new file mode 100644
index 0000000000000000000000000000000000000000..679153b47809682fec38adb5baea609dd99c5c28
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.h
@@ -0,0 +1,135 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/base/EntityInstanceBase.h>
+#include <RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h>
+#include <RobotAPI/libraries/armem/core/base/EntityBase.h>
+#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
+
+#include <optional>
+
+
+namespace armarx::armem::wm
+{
+
+    using EntityInstanceMetadata = base::EntityInstanceMetadata;
+    using EntityInstanceData = armarx::aron::datanavigator::DictNavigator;
+    using EntityInstanceDataPtr = armarx::aron::datanavigator::DictNavigatorPtr;
+
+
+    /// @see base::EntityInstanceBase
+    class EntityInstance :
+        public base::EntityInstanceBase<EntityInstanceDataPtr, EntityInstanceMetadata>
+    {
+        using Base = base::EntityInstanceBase<EntityInstanceDataPtr, 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;
+
+    };
+
+
+
+    /// @see base::EntitySnapshotBase
+    class EntitySnapshot :
+        public base::EntitySnapshotBase<EntityInstance, EntitySnapshot>
+    {
+    public:
+
+        using base::EntitySnapshotBase<EntityInstance, EntitySnapshot>::EntitySnapshotBase;
+
+    };
+
+
+    /// @see base::EntityBase
+    class Entity :
+        public base::EntityBase<EntitySnapshot, Entity>
+    {
+    public:
+
+        using base::EntityBase<EntitySnapshot, Entity>::EntityBase;
+
+    };
+
+
+
+    /// @see base::ProviderSegmentBase
+    class ProviderSegment :
+        public base::ProviderSegmentBase<Entity, ProviderSegment>
+    {
+    public:
+
+        using base::ProviderSegmentBase<Entity, ProviderSegment>::ProviderSegmentBase;
+
+    };
+
+
+
+    /// @see base::CoreSegmentBase
+    class CoreSegment :
+        public base::CoreSegmentBase<ProviderSegment, CoreSegment>
+    {
+        using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
+
+    public:
+
+        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;
+            }
+        }
+
+    };
+
+
+
+    /// @see base::MemoryBase
+    class Memory :
+        public base::MemoryBase<CoreSegment, Memory>
+    {
+        using Base = base::MemoryBase<CoreSegment, Memory>;
+
+    public:
+
+        using Base::MemoryBase;
+
+    };
+
+}
+
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/FunctionalVisitor.cpp b/source/RobotAPI/libraries/armem/core/wm/visitor/FunctionalVisitor.cpp
similarity index 82%
rename from source/RobotAPI/libraries/armem/core/workingmemory/visitor/FunctionalVisitor.cpp
rename to source/RobotAPI/libraries/armem/core/wm/visitor/FunctionalVisitor.cpp
index 53016fc6c83d9ef6e24a2e75942a12bced7d0eaa..f72b37c1a7ab68320c8ff2ec8c071dd741e61f22 100644
--- a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/FunctionalVisitor.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/visitor/FunctionalVisitor.cpp
@@ -2,7 +2,7 @@
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 
 
@@ -18,6 +18,4 @@ namespace armarx::armem::wm
     {
     }
 
-
-
 }
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/FunctionalVisitor.h b/source/RobotAPI/libraries/armem/core/wm/visitor/FunctionalVisitor.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/core/workingmemory/visitor/FunctionalVisitor.h
rename to source/RobotAPI/libraries/armem/core/wm/visitor/FunctionalVisitor.h
diff --git a/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp b/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..1140bc11be0a43e41e2e5c690ae8a73132440a6b
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.cpp
@@ -0,0 +1,141 @@
+#include "Visitor.h"
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+
+
+namespace armarx::armem::wm
+{
+
+    Visitor::Visitor()
+    {
+    }
+
+    Visitor::~Visitor()
+    {
+    }
+
+    bool Visitor::applyTo(Memory& memory)
+    {
+        visitEnter(memory);
+        bool cont = memory.forEachCoreSegment([this](CoreSegment & coreSeg)
+        {
+            return applyTo(coreSeg);
+        });
+        visitExit(memory);
+        return cont;
+    }
+
+    bool Visitor::applyTo(CoreSegment& coreSegment)
+    {
+        visitEnter(coreSegment);
+        bool cont = coreSegment.forEachProviderSegment([this](ProviderSegment & provSeg)
+        {
+            return applyTo(provSeg);
+        });
+        visitExit(coreSegment);
+        return cont;
+    }
+
+    bool Visitor::applyTo(ProviderSegment& providerSegment)
+    {
+        visitEnter(providerSegment);
+        bool cont = providerSegment.forEachEntity([this](Entity & entity)
+        {
+            return applyTo(entity);
+        });
+        visitExit(providerSegment);
+        return cont;
+    }
+
+    bool Visitor::applyTo(Entity& entity)
+    {
+        visitEnter(entity);
+        bool cont = entity.forEachSnapshot([this](EntitySnapshot & snapshot)
+        {
+            return applyTo(snapshot);
+        });
+        visitExit(entity);
+        return cont;
+    }
+
+    bool Visitor::applyTo(EntitySnapshot& snapshot)
+    {
+        visitEnter(snapshot);
+        bool cont = snapshot.forEachInstance([this](EntityInstance & instance)
+        {
+            return applyTo(instance);
+        });
+        visitExit(snapshot);
+        return cont;
+    }
+
+    bool Visitor::applyTo(EntityInstance& instance)
+    {
+        return visit(instance);
+    }
+
+
+    bool Visitor::applyTo(const Memory& memory)
+    {
+        visitEnter(memory);
+        bool cont = memory.forEachCoreSegment([this](const CoreSegment & coreSeg)
+        {
+            return applyTo(coreSeg);
+        });
+        visitExit(memory);
+        return cont;
+    }
+
+    bool Visitor::applyTo(const CoreSegment& coreSegment)
+    {
+        visitEnter(coreSegment);
+        bool cont = coreSegment.forEachProviderSegment([this](const ProviderSegment & provSeg)
+        {
+            return applyTo(provSeg);
+        });
+        visitExit(coreSegment);
+        return cont;
+    }
+
+    bool Visitor::applyTo(const ProviderSegment& providerSegment)
+    {
+        visitEnter(providerSegment);
+        bool cont = providerSegment.forEachEntity([this](const Entity & entity)
+        {
+            return applyTo(entity);
+        });
+        visitExit(providerSegment);
+        return cont;
+    }
+
+    bool Visitor::applyTo(const Entity& entity)
+    {
+        visitEnter(entity);
+        bool cont = entity.forEachSnapshot([this](const EntitySnapshot & snapshot)
+        {
+            return applyTo(snapshot);
+        });
+        visitExit(entity);
+        return cont;
+    }
+
+    bool Visitor::applyTo(const EntitySnapshot& snapshot)
+    {
+        visitEnter(snapshot);
+        bool cont = snapshot.forEachInstance([this](const EntityInstance & instance)
+        {
+            return applyTo(instance);
+        });
+        visitExit(snapshot);
+        return cont;
+    }
+
+    bool Visitor::applyTo(const EntityInstance& instance)
+    {
+        return visit(instance);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/Visitor.h b/source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/core/workingmemory/visitor/Visitor.h
rename to source/RobotAPI/libraries/armem/core/wm/visitor/Visitor.h
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.cpp
deleted file mode 100644
index 601f079350de8536aff130943d539eafee4e43b3..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.cpp
+++ /dev/null
@@ -1,136 +0,0 @@
-#include "CoreSegment.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "error.h"
-
-
-namespace armarx::armem::wm
-{
-
-    CoreSegment::CoreSegment(const CoreSegment& other) :
-        CoreSegment::Base(other),
-        _mutex()
-    {
-        // Do not copy _mutex.
-    }
-
-
-    CoreSegment::CoreSegment(CoreSegment&& other) : CoreSegment::Base(other)
-    {
-        // Do not move _mutex.
-    }
-
-
-    CoreSegment& CoreSegment::operator=(const CoreSegment& other)
-    {
-        Base::operator=(other);
-        // Don't copy _mutex.
-        return *this;
-    }
-
-
-    CoreSegment& CoreSegment::operator=(CoreSegment&& other)
-    {
-        Base::operator=(other);
-        // Don't move _mutex.
-        return *this;
-    }
-
-
-    Commit CoreSegment::toCommit() const
-    {
-        Commit c;
-        for (const auto& [k, s] : _container)
-        {
-            c.append(s.toCommit());
-        }
-        return c;
-    }
-
-
-    void CoreSegment::_copySelfWithoutData(CoreSegment& other) const
-    {
-        other.id() = _id;
-        other.setMaxHistorySize(_maxHistorySize);
-        for (const auto& [k, s] : _container)
-        {
-            other.addProviderSegment(s.copyWithoutData());
-        }
-    }
-
-
-    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;
-        }
-    }
-
-
-    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);
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h b/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h
deleted file mode 100644
index 86b9b439e72d4d686b2c52fe5fd39f0a9b6aaf1c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h
+++ /dev/null
@@ -1,111 +0,0 @@
-#pragma once
-
-#include <mutex>
-#include <optional>
-
-#include "../base/CoreSegmentBase.h"
-
-#include "ProviderSegment.h"
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-
-    /**
-     * @brief Data of a core segment containing multiple provider segments.
-     */
-    class CoreSegment :
-        public base::CoreSegmentBase<ProviderSegment, CoreSegment>,
-        public detail::CopyWithoutData<CoreSegment>
-    {
-        using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
-
-    public:
-
-        using Base::CoreSegmentBase;
-
-        CoreSegment(const CoreSegment& other);
-        CoreSegment(CoreSegment&& other);
-        CoreSegment& operator=(const CoreSegment& other);
-        CoreSegment& operator=(CoreSegment&& other);
-
-        /**
-         * @brief Convert the content of this segmnet into a commit
-         * @return The resulting commit
-         */
-        Commit toCommit() const;
-
-        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;
-            }
-        }
-
-
-        // 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
-        {
-            // 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;
-            }
-        }
-
-
-    protected:
-
-        virtual void _copySelfWithoutData(CoreSegment& other) const override;
-
-        mutable std::mutex _mutex;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/Entity.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/Entity.cpp
deleted file mode 100644
index e704e96d5454d27bfb095120c1901e000611122a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/Entity.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-#include "Entity.h"
-
-namespace armarx::armem::wm
-{
-
-    Commit Entity::toCommit() const
-    {
-        Commit c;
-        for (const auto& [k, s] : _container)
-        {
-            EntityUpdate& up = c.add();
-            up.entityID = id();
-            up.timeCreated = k;
-            up.instancesData = s.getAronData();
-        }
-        return c;
-    }
-
-    void Entity::_copySelfWithoutData(Entity& other) const
-    {
-        other.id() = _id;
-        other.setMaxHistorySize(_maxHistorySize);
-        for (const auto& [k, s] : _container)
-        {
-            other.addSnapshot(s.copyWithoutData());
-        }
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/Entity.h b/source/RobotAPI/libraries/armem/core/workingmemory/Entity.h
deleted file mode 100644
index a6a7621e21272db6447e9e09b695900eefd263c1..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/Entity.h
+++ /dev/null
@@ -1,57 +0,0 @@
-#pragma once
-
-#include "../base/EntityBase.h"
-
-#include "EntitySnapshot.h"
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-    /**
-     * @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>,
-        public detail::CopyWithoutData<Entity>
-    {
-        using Base = base::EntityBase<EntitySnapshot, Entity>;
-
-    public:
-
-        using Base::EntityBase;
-
-        Entity(const Entity& other) = default;
-        Entity(Entity&& other) = default;
-        Entity& operator=(const Entity& other) = default;
-        Entity& operator=(Entity&& other) = default;
-
-        /**
-         * @brief Convert the content of this segmnet into a commit
-         * @return The resulting commit
-         */
-        Commit toCommit() const;
-
-    protected:
-
-        virtual void _copySelfWithoutData(Entity& other) const override;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.cpp
deleted file mode 100644
index 6149449c77533abd656a460097969f0066d8d88f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.cpp
+++ /dev/null
@@ -1,77 +0,0 @@
-#include "EntityInstance.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-
-std::ostream& armarx::armem::wm::operator<<(std::ostream& os, const EntityInstanceMetadata& d)
-{
-    os << "EntityInstanceMetadata: "
-       << "\n- t_create =   \t" << armem::toStringMicroSeconds(d.timeCreated) << " us"
-       << "\n- t_sent =     \t" << armem::toStringMicroSeconds(d.timeSent) << " us"
-       << "\n- t_arrived =  \t" << armem::toStringMicroSeconds(d.timeArrived) << " us"
-       << "\n- confidence = \t" << d.confidence << " us"
-       ;
-    return os;
-}
-
-namespace armarx::armem::wm
-{
-
-    bool EntityInstanceMetadata::operator==(const EntityInstanceMetadata& other) const
-    {
-        return timeCreated == other.timeCreated
-               && timeSent == other.timeSent
-               && timeArrived == other.timeArrived
-               && std::abs(confidence - other.confidence) < 1e-6f;
-    }
-
-
-    bool EntityInstance::equalsDeep(const EntityInstance& other) const
-    {
-        if (_data and other.data())
-        {
-            return id() == other.id()
-                   && _metadata == other.metadata()
-                   && *_data == *other.data();
-        }
-        if (_data or other.data())
-        {
-            return false;
-        }
-        return id() == other.id() && _metadata == other.metadata();
-    }
-
-    void EntityInstance::update(const EntityUpdate& update, int index)
-    {
-        ARMARX_CHECK_FITS_SIZE(index, update.instancesData.size());
-
-        this->index() = index;
-        setData(update.instancesData.at(size_t(index)));
-
-        this->_metadata.confidence = update.confidence;
-
-        this->_metadata.timeCreated = update.timeCreated;
-        this->_metadata.timeSent = update.timeSent;
-        this->_metadata.timeArrived = update.timeArrived;
-    }
-
-    EntityInstance EntityInstance::copy() const
-    {
-        EntityInstance d;
-        this->_copySelf(d);
-        return d;
-    }
-
-    void EntityInstance::_copySelf(EntityInstance& other) const
-    {
-        Base::_copySelf(other);
-        other._metadata = _metadata;
-        other._data = _data;
-    }
-
-    void EntityInstance::_copySelfWithoutData(EntityInstance& other) const
-    {
-        Base::_copySelf(other);
-        other._metadata = _metadata;
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h b/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h
deleted file mode 100644
index d3dc888d0304276bc6aaf1c677e8b33f4a1cae1a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h
+++ /dev/null
@@ -1,107 +0,0 @@
-#pragma once
-
-#include "../base/EntityInstanceBase.h"
-
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-
-    using EntityInstanceData = armarx::aron::datanavigator::DictNavigator;
-    using EntityInstanceDataPtr = armarx::aron::datanavigator::DictNavigatorPtr;
-
-
-    /**
-     * @brief Metadata of an entity instance.
-     */
-    struct EntityInstanceMetadata
-    {
-        /// Time when this value was created.
-        Time timeCreated;
-        /// Time when this value was sent to the memory.
-        Time timeSent;
-        /// Time when this value has arrived at the memory.
-        Time timeArrived;
-
-        /// An optional confidence, may be used for things like decay.
-        float confidence = 1.0;
-
-
-        bool operator==(const EntityInstanceMetadata& other) const;
-        inline bool operator!=(const EntityInstanceMetadata& other) const
-        {
-            return !(*this == other);
-        }
-    };
-
-    std::ostream& operator<<(std::ostream& os, const EntityInstanceMetadata& rhs);
-
-
-    /**
-     * @brief Data of a single entity instance.
-     */
-    class EntityInstance :
-        public base::EntityInstanceBase<EntityInstance>,
-        public detail::CopyWithoutData<EntityInstance>
-    {
-        using Base = base::EntityInstanceBase<EntityInstance>;
-
-    public:
-
-        using Base::EntityInstanceBase;
-
-        EntityInstance(const EntityInstance& other) = default;
-        EntityInstance(EntityInstance&& other) = default;
-        EntityInstance& operator=(const EntityInstance& other) = default;
-        EntityInstance& operator=(EntityInstance&& other) = default;
-
-
-        EntityInstanceMetadata& metadata()
-        {
-            return _metadata;
-        }
-        inline const EntityInstanceMetadata& metadata() const
-        {
-            return _metadata;
-        }
-
-        inline EntityInstanceDataPtr data() const
-        {
-            return _data;
-        }
-
-        void setData(const aron::datanavigator::DictNavigatorPtr& data)
-        {
-            this->_data = data;
-        }
-
-
-        /**
-         * @brief Fill `*this` with the update's values.
-         * @param update The update.
-         * @param index The instances index.
-         */
-        virtual void update(const EntityUpdate& update, int index) override;
-
-        virtual bool equalsDeep(const EntityInstance& other) const override;
-
-        virtual EntityInstance copy() const override;
-
-
-    protected:
-
-        virtual void _copySelf(EntityInstance& other) const override;
-        virtual void _copySelfWithoutData(EntityInstance& other) const override;
-
-
-    private:
-
-        /// The metadata.
-        EntityInstanceMetadata _metadata;
-
-        /// The data. May be nullptr.
-        EntityInstanceDataPtr _data;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.cpp
deleted file mode 100644
index 76d5400131a7ec6a57478f13afb0dfc38a4da174..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-#include "EntitySnapshot.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "error.h"
-
-
-namespace armarx::armem::wm
-{
-    std::vector<aron::datanavigator::DictNavigatorPtr> EntitySnapshot::getAronData() const
-    {
-        std::vector<aron::datanavigator::DictNavigatorPtr> ret;
-        for (const auto& aron : _container)
-        {
-            ret.push_back(aron.data());
-        }
-        return ret;
-    }
-
-    void EntitySnapshot::_copySelfWithoutData(EntitySnapshot& other) const
-    {
-        other.id() = _id;
-        for (const auto& s : _container)
-        {
-            other.addInstance(s.copyWithoutData());
-        }
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.h b/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.h
deleted file mode 100644
index 3eedb48d0b4aaa5191541d8ca1586ffc59ab5998..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/EntitySnapshot.h
+++ /dev/null
@@ -1,33 +0,0 @@
-#pragma once
-
-#include "../base/EntitySnapshotBase.h"
-
-#include "EntityInstance.h"
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-
-    /**
-     * @brief Data of an entity at one point in time.
-     */
-    class EntitySnapshot :
-        public base::EntitySnapshotBase<EntityInstance, EntitySnapshot>,
-        public detail::CopyWithoutData<EntitySnapshot>
-    {
-        using Base = base::EntitySnapshotBase<EntityInstance, EntitySnapshot>;
-
-    public:
-
-        using Base::EntitySnapshotBase;
-        using Base::operator=;
-
-        std::vector<aron::datanavigator::DictNavigatorPtr> getAronData() const;
-
-    protected:
-
-        virtual void _copySelfWithoutData(EntitySnapshot& other) const override;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/Memory.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/Memory.cpp
deleted file mode 100644
index 70fd41e7c451175d5964a81d48f4e8270c2e611c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/Memory.cpp
+++ /dev/null
@@ -1,95 +0,0 @@
-#include "Memory.h"
-
-#include <map>
-#include <vector>
-
-
-namespace armarx::armem::wm
-{
-
-    // TODO: add core segment if param is set
-    std::vector<Memory::Base::UpdateResult>
-    Memory::updateLocking(const Commit& commit)
-    {
-        // Group updates by core segment, then update each core segment in a batch to only lock it once.
-        std::map<std::string, std::vector<const EntityUpdate*>> updatesPerCoreSegment;
-        for (const EntityUpdate& update : commit.updates)
-        {
-            updatesPerCoreSegment[update.entityID.coreSegmentName].push_back(&update);
-        }
-
-        std::vector<Memory::Base::UpdateResult> result;
-        // To throw an exception after the commit if a core segment is missing and the memory should not create new ones
-        std::vector<std::string> missingCoreSegmentNames;
-        for (const auto& [coreSegmentName, updates] : updatesPerCoreSegment)
-        {
-            auto it = this->_container.find(coreSegmentName);
-            if (it != this->_container.end())
-            {
-                CoreSegment& coreSegment = it->second;
-
-                // Lock the core segment for the whole batch.
-                std::scoped_lock lock(coreSegment.mutex());
-
-                for (const EntityUpdate* update : updates)
-                {
-                    auto r = coreSegment.update(*update);
-                    Base::UpdateResult ret { r };
-                    ret.memoryUpdateType = UpdateType::UpdatedExisting;
-                    result.push_back(ret);
-                }
-            }
-            else
-            {
-                // Perform the other updates first, then throw afterwards.
-                missingCoreSegmentNames.push_back(coreSegmentName);
-            }
-        }
-        // Throw an exception if something went wrong.
-        if (not missingCoreSegmentNames.empty())
-        {
-            // Just throw an exception for the first entry. We can extend this exception in the future.
-            throw armem::error::MissingEntry::create<CoreSegment>(missingCoreSegmentNames.front(), *this);
-        }
-        return result;
-    }
-
-
-    // TODO: Add core segment if param is set
-    Memory::Base::UpdateResult
-    Memory::updateLocking(const EntityUpdate& update)
-    {
-        this->_checkContainerName(update.entityID.memoryName, this->name());
-
-        CoreSegment& segment = getCoreSegment(update.entityID.coreSegmentName);
-        Base::UpdateResult result;
-        {
-            std::scoped_lock lock(segment.mutex());
-            result = segment.update(update);
-        }
-        result.memoryUpdateType = UpdateType::UpdatedExisting;
-        return result;
-    }
-
-
-    Commit Memory::toCommit() const
-    {
-        Commit c;
-        for (const auto& [k, s] : _container)
-        {
-            c.append(s.toCommit());
-        }
-        return c;
-    }
-
-
-    void Memory::_copySelfWithoutData(Memory& other) const
-    {
-        other.id() = _id;
-        for (const auto& [k, s] : _container)
-        {
-            other.addCoreSegment(s.copyWithoutData());
-        }
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/Memory.h b/source/RobotAPI/libraries/armem/core/workingmemory/Memory.h
deleted file mode 100644
index d52bce5ca30d2a464881e73f4cd4994a29429751..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/Memory.h
+++ /dev/null
@@ -1,56 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
-
-#include "CoreSegment.h"
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-
-    /**
-     * @brief Data of a memory consisting of multiple core segments.
-     */
-    class Memory :
-        public base::MemoryBase<CoreSegment, Memory>,
-        public detail::CopyWithoutData<Memory>
-    {
-        using Base = base::MemoryBase<CoreSegment, Memory>;
-
-    public:
-
-        using Base::MemoryBase;
-
-        Memory(const Memory& other) = default;
-        Memory(Memory&& other) = default;
-        Memory& operator=(const Memory& other) = default;
-        Memory& operator=(Memory&& other) = default;
-
-        /**
-         * @brief Perform the commit, locking the core segments.
-         *
-         * Groups the commits by core segment, and updates each core segment
-         * in a batch, locking the core segment.
-         */
-        std::vector<Base::UpdateResult> updateLocking(const Commit& commit);
-
-        /**
-         * @brief Update the memory, locking the updated core segment.
-         */
-        Base::UpdateResult updateLocking(const EntityUpdate& update);
-
-
-        /**
-         * @brief Convert the content of this memory into a commit
-         * @return The resulting commit
-         */
-        Commit toCommit() const;
-
-
-    protected:
-
-        virtual void _copySelfWithoutData(Memory& other) const override;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.cpp
deleted file mode 100644
index bd03cf21cd8b616a3afcc4d531377288e55c5f2f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.cpp
+++ /dev/null
@@ -1,31 +0,0 @@
-#include "ProviderSegment.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include "error.h"
-
-
-namespace armarx::armem::wm
-{
-
-    Commit ProviderSegment::toCommit() const
-    {
-        Commit c;
-        for (const auto& [k, s] : _container)
-        {
-            c.append(s.toCommit());
-        }
-        return c;
-    }
-
-    void ProviderSegment::_copySelfWithoutData(ProviderSegment& other) const
-    {
-        other.id() = _id;
-        other.setMaxHistorySize(_maxHistorySize);
-        for (const auto& [k, s] : _container)
-        {
-            other.addEntity(s.copyWithoutData());
-        }
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h b/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h
deleted file mode 100644
index 7d1e9db335ee39433351a8e15113059836bf825d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h
+++ /dev/null
@@ -1,44 +0,0 @@
-#pragma once
-
-#include "../base/ProviderSegmentBase.h"
-
-#include "Entity.h"
-#include "detail/CopyWithoutData.h"
-
-
-namespace armarx::armem::wm
-{
-
-    /**
-     * @brief Data of a provider segment containing multiple entities.
-     */
-    class ProviderSegment :
-        public base::ProviderSegmentBase<Entity, ProviderSegment>,
-        public detail::CopyWithoutData<ProviderSegment>
-
-    {
-        using Base = base::ProviderSegmentBase<Entity, ProviderSegment>;
-
-    public:
-
-        using Base::ProviderSegmentBase;
-
-        ProviderSegment(const ProviderSegment& other) = default;
-        ProviderSegment(ProviderSegment&& other) = default;
-        ProviderSegment& operator=(const ProviderSegment& other) = default;
-        ProviderSegment& operator=(ProviderSegment&& other) = default;
-
-        /**
-         * @brief Convert the content of this segmnet into a commit
-         * @return The resulting commit
-         */
-        Commit toCommit() const;
-
-
-    protected:
-
-        virtual void _copySelfWithoutData(ProviderSegment& other) const override;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.cpp
deleted file mode 100644
index 70441033dd0fcb24a502bcd4e552764c7c2f5d3c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "CopyWithoutData.h"
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.h b/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.h
deleted file mode 100644
index caabd1e6002c803aa6a1015afd7ce660abd2482f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/detail/CopyWithoutData.h
+++ /dev/null
@@ -1,30 +0,0 @@
-#pragma once
-
-
-namespace armarx::armem::wm::detail
-{
-
-    /**
-     * @class Allows copying `*this` without data in the leaf
-     * data structures.
-     */
-    template <class DerivedT>
-    class CopyWithoutData
-    {
-    public:
-
-        /// Get a copy of `this` without data.
-        virtual DerivedT copyWithoutData() const
-        {
-            DerivedT t;
-            _copySelfWithoutData(t);
-            return t;
-        }
-
-
-    protected:
-
-        virtual void _copySelfWithoutData(DerivedT& other) const = 0;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.cpp
deleted file mode 100644
index 31538f8d8e2f1eeaf932ed16e50b7040520f0a99..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/entityInstance_conversions.cpp
+++ /dev/null
@@ -1,64 +0,0 @@
-#include "json_conversions.h"
-
-namespace armarx::armem
-{
-
-    constexpr const char* DATA_WRAPPER_DATA_FIELD            = "__ARON_DATA";
-    constexpr const char* DATA_WRAPPER_TIME_STORED_FIELD     = "__WRITER_METADATA__TIME_STORED";
-    constexpr const char* DATA_WRAPPER_TIME_CREATED_FIELD    = "__ENTITY_METADATA__TIME_CREATED";
-    constexpr const char* DATA_WRAPPER_TIME_SENT_FIELD       = "__ENTITY_METADATA__TIME_SENT";
-    constexpr const char* DATA_WRAPPER_TIME_ARRIVED_FIELD    = "__ENTITY_METADATA__TIME_ARRIVED";
-    constexpr const char* DATA_WRAPPER_CONFIDENCE_FIELD      = "__ENTITY_METADATA__CONFIDENCE";
-
-    void from_aron(const aron::datanavigator::DictNavigatorPtr& dataWrapped, wm::EntityInstance& e)
-    {
-        wm::EntityInstanceMetadata& metadata = e.metadata();
-
-        if (dataWrapped->hasElement(DATA_WRAPPER_DATA_FIELD))
-        {
-            aron::datanavigator::DictNavigatorPtr data = aron::datanavigator::DictNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_DATA_FIELD));
-            e.setData(data);
-        }
-
-        auto timeCreated = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_CREATED_FIELD));
-        metadata.timeCreated = Time::microSeconds(timeCreated->toAronLongPtr()->value);
-
-        auto timeSent = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_SENT_FIELD));
-        metadata.timeSent = Time::microSeconds(timeSent->toAronLongPtr()->value);
-
-        auto timeArrived = aron::datanavigator::LongNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_TIME_ARRIVED_FIELD));
-        metadata.timeArrived = Time::microSeconds(timeArrived->toAronLongPtr()->value);
-
-        auto confidence = aron::datanavigator::DoubleNavigator::DynamicCastAndCheck(dataWrapped->getElement(DATA_WRAPPER_CONFIDENCE_FIELD));
-        metadata.confidence = static_cast<float>(confidence->toAronDoublePtr()->value);
-    }
-
-    void to_aron(aron::datanavigator::DictNavigatorPtr& a, const wm::EntityInstance& e)
-    {
-        if (e.data())
-        {
-            a->addElement(DATA_WRAPPER_DATA_FIELD, e.data());
-        }
-
-        auto timeWrapped = std::make_shared<aron::datanavigator::LongNavigator>();
-        timeWrapped->setValue(Time::now().toMicroSeconds());
-        a->addElement(DATA_WRAPPER_TIME_STORED_FIELD, timeWrapped);
-
-        const wm::EntityInstanceMetadata& metadata = e.metadata();
-        auto timeCreated = std::make_shared<aron::datanavigator::LongNavigator>();
-        timeCreated->setValue(metadata.timeCreated.toMicroSeconds());
-        a->addElement(DATA_WRAPPER_TIME_CREATED_FIELD, timeCreated);
-
-        auto timeSent = std::make_shared<aron::datanavigator::LongNavigator>();
-        timeSent->setValue(metadata.timeSent.toMicroSeconds());
-        a->addElement(DATA_WRAPPER_TIME_SENT_FIELD, timeSent);
-
-        auto timeArrived = std::make_shared<aron::datanavigator::LongNavigator>();
-        timeArrived->setValue(metadata.timeArrived.toMicroSeconds());
-        a->addElement(DATA_WRAPPER_TIME_ARRIVED_FIELD, timeArrived);
-
-        auto confidence = std::make_shared<aron::datanavigator::DoubleNavigator>();
-        confidence->setValue(static_cast<double>(metadata.confidence));
-        a->addElement(DATA_WRAPPER_CONFIDENCE_FIELD, confidence);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.cpp
deleted file mode 100644
index bfc049995a6553e53a78be00294cb9c162e80a0d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.cpp
+++ /dev/null
@@ -1,128 +0,0 @@
-#include "ice_conversions.h"
-
-namespace armarx::armem
-{
-    void toIce(armarx::armem::data::EntityInstanceMetadata& ice, const armarx::armem::wm::EntityInstanceMetadata& metadata)
-    {
-        ice.confidence = metadata.confidence;
-        toIce(ice.timeArrivedMicroSeconds, metadata.timeArrived);
-        toIce(ice.timeCreatedMicroSeconds, metadata.timeCreated);
-        toIce(ice.timeSentMicroSeconds, metadata.timeSent);
-    }
-    void fromIce(const armarx::armem::data::EntityInstanceMetadata& ice, armarx::armem::wm::EntityInstanceMetadata& metadata)
-    {
-        metadata.confidence = ice.confidence;
-        fromIce(ice.timeArrivedMicroSeconds, metadata.timeArrived);
-        fromIce(ice.timeCreatedMicroSeconds, metadata.timeCreated);
-        fromIce(ice.timeSentMicroSeconds, metadata.timeSent);
-    }
-
-    void toIce(data::EntityInstance& ice, const wm::EntityInstance& data)
-    {
-        detail::toIceItem(ice, data);
-
-        if (data.data())
-        {
-            ice.data = data.data()->toAronDictPtr();
-        }
-        toIce(ice.metadata, data.metadata());
-    }
-    void fromIce(const data::EntityInstance& ice, wm::EntityInstance& data)
-    {
-        detail::fromIceItem(ice, data);
-
-        if (ice.data)
-        {
-            data.setData(aron::datanavigator::DictNavigator::FromAronDictPtr(ice.data));
-        }
-        fromIce(ice.metadata, data.metadata());
-    }
-
-
-    void toIce(data::EntitySnapshot& ice, const wm::EntitySnapshot& snapshot)
-    {
-        detail::toIceItem(ice, snapshot);
-
-        toIce(ice.instances, snapshot.instances());
-    }
-    void fromIce(const data::EntitySnapshot& ice, wm::EntitySnapshot& snapshot)
-    {
-        detail::fromIceItem(ice, snapshot);
-
-        fromIce(ice.instances, snapshot.instances());
-    }
-
-    void toIce(data::Entity& ice, const wm::Entity& entity)
-    {
-        detail::toIceItem(ice, entity);
-
-        toIce(ice.history, entity.history());
-    }
-    void fromIce(const data::Entity& ice, wm::Entity& entity)
-    {
-        detail::fromIceItem(ice, entity);
-
-        fromIce(ice.history, entity.history());
-    }
-
-
-    void toIce(data::ProviderSegment& ice, const wm::ProviderSegment& providerSegment)
-    {
-        detail::toIceItem(ice, providerSegment);
-
-        if (providerSegment.hasAronType())
-        {
-            ice.aronType = providerSegment.aronType()->toAronPtr();
-        }
-        ARMARX_CHECK(!providerSegment.aronType() || ice.aronType);
-        toIce(ice.entities, providerSegment.entities());
-    }
-    void fromIce(const data::ProviderSegment& ice, wm::ProviderSegment& providerSegment)
-    {
-        detail::fromIceItem(ice, providerSegment);
-
-        if (ice.aronType)
-        {
-            providerSegment.aronType() = aron::typenavigator::ObjectNavigator::DynamicCastAndCheck(aron::typenavigator::Navigator::FromAronType(ice.aronType));
-        }
-        ARMARX_CHECK(!providerSegment.aronType() || ice.aronType);
-        fromIce(ice.entities, providerSegment.entities());
-    }
-
-    void toIce(data::CoreSegment& ice, const wm::CoreSegment& coreSegment)
-    {
-        detail::toIceItem(ice, coreSegment);
-
-        if (coreSegment.hasAronType())
-        {
-            ice.aronType = coreSegment.aronType()->toAronPtr();
-        }
-        ARMARX_CHECK(!coreSegment.aronType() || ice.aronType);
-        toIce(ice.providerSegments, coreSegment.providerSegments());
-    }
-    void fromIce(const data::CoreSegment& ice, wm::CoreSegment& coreSegment)
-    {
-        detail::fromIceItem(ice, coreSegment);
-
-        if (ice.aronType)
-        {
-            coreSegment.aronType() = aron::typenavigator::ObjectNavigator::DynamicCastAndCheck(aron::typenavigator::Navigator::FromAronType(ice.aronType));
-        }
-        ARMARX_CHECK(!coreSegment.aronType() || ice.aronType);
-        fromIce(ice.providerSegments, coreSegment.providerSegments());
-    }
-
-    void toIce(data::Memory& ice, const wm::Memory& memory)
-    {
-        detail::toIceItem(ice, memory);
-
-        toIce(ice.coreSegments, memory.coreSegments());
-    }
-    void fromIce(const data::Memory& ice, wm::Memory& memory)
-    {
-        detail::fromIceItem(ice, memory);
-
-        fromIce(ice.coreSegments, memory.coreSegments());
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h b/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h
deleted file mode 100644
index 4d14e6b0d04e9086e701cc38a159e516e533d95c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h
+++ /dev/null
@@ -1,36 +0,0 @@
-#pragma once
-
-#include <RobotAPI/interface/armem/commit.h>
-#include <RobotAPI/interface/armem/memory.h>
-
-#include "Memory.h"
-
-
-namespace armarx::armem
-{
-    void toIce(data::EntityInstanceMetadata& ice, const wm::EntityInstanceMetadata& metadata);
-    void fromIce(const data::EntityInstanceMetadata& ice, wm::EntityInstanceMetadata& metadata);
-
-    void toIce(data::EntityInstance& ice, const wm::EntityInstance& data);
-    void fromIce(const data::EntityInstance& ice, wm::EntityInstance& data);
-
-
-    void toIce(data::EntitySnapshot& ice, const wm::EntitySnapshot& snapshot);
-    void fromIce(const data::EntitySnapshot& ice, wm::EntitySnapshot& snapshot);
-
-    void toIce(data::Entity& ice, const wm::Entity& entity);
-    void fromIce(const data::Entity& ice, wm::Entity& entity);
-
-
-    void toIce(data::ProviderSegment& ice, const wm::ProviderSegment& providerSegment);
-    void fromIce(const data::ProviderSegment& ice, wm::ProviderSegment& providerSegment);
-
-    void toIce(data::CoreSegment& ice, const wm::CoreSegment& coreSegment);
-    void fromIce(const data::CoreSegment& ice, wm::CoreSegment& coreSegment);
-
-    void toIce(data::Memory& ice, const wm::Memory& memory);
-    void fromIce(const data::Memory& ice, wm::Memory& memory);
-}
-
-// Must be included after the prototypes. Otherwise the compiler cannot find the correct methods in ice_coversion_templates.h
-#include "../ice_conversions.h"
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.h b/source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.h
deleted file mode 100644
index d132d88f7d7fb694be8b3dc086c87dcafa276e6a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/json_conversions.h
+++ /dev/null
@@ -1,15 +0,0 @@
-#pragma once
-
-#include "Memory.h"
-
-#include <RobotAPI/libraries/aron/core/io/dataIO/converter/Converter.h>
-#include <RobotAPI/libraries/aron/core/io/dataIO/visitor/Visitor.h>
-#include <RobotAPI/libraries/aron/core/io/dataIO/reader/nlohmannJSON/NlohmannJSONReader.h>
-#include <RobotAPI/libraries/aron/core/io/dataIO/writer/nlohmannJSON/NlohmannJSONWriter.h>
-
-
-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/workingmemory/visitor.h b/source/RobotAPI/libraries/armem/core/workingmemory/visitor.h
deleted file mode 100644
index 815ee1b34908dc5916e7d909e709bc735409f63c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/visitor.h
+++ /dev/null
@@ -1,4 +0,0 @@
-#pragma once
-
-#include "visitor/FunctionalVisitor.h"
-#include "visitor/Visitor.h"
diff --git a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/Visitor.cpp b/source/RobotAPI/libraries/armem/core/workingmemory/visitor/Visitor.cpp
deleted file mode 100644
index ede63a494a7aff26c54ba1d7149200c91be7d987..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/core/workingmemory/visitor/Visitor.cpp
+++ /dev/null
@@ -1,191 +0,0 @@
-#include "Visitor.h"
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/error.h>
-
-
-namespace armarx::armem::wm
-{
-
-    Visitor::Visitor()
-    {
-    }
-
-    Visitor::~Visitor()
-    {
-    }
-
-    bool Visitor::applyTo(Memory& memory)
-    {
-        bool cont = true;
-        visitEnter(memory);
-        for (auto& [_, coreSeg] : memory)
-        {
-            if (!applyTo(coreSeg))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(memory);
-        return cont;
-    }
-
-    bool Visitor::applyTo(CoreSegment& coreSegment)
-    {
-        bool cont = true;
-        visitEnter(coreSegment);
-        for (auto& [_, provSeg] : coreSegment)
-        {
-            if (!applyTo(provSeg))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(coreSegment);
-        return cont;
-    }
-
-    bool Visitor::applyTo(ProviderSegment& providerSegment)
-    {
-        bool cont = true;
-        visitEnter(providerSegment);
-        for (auto& [_, entity] : providerSegment)
-        {
-            if (!applyTo(entity))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(providerSegment);
-        return cont;
-    }
-
-    bool Visitor::applyTo(Entity& entity)
-    {
-        bool cont = true;
-        visitEnter(entity);
-        for (auto& [_, snapshot] : entity)
-        {
-            if (!applyTo(snapshot))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(entity);
-        return cont;
-    }
-
-    bool Visitor::applyTo(EntitySnapshot& snapshot)
-    {
-        bool cont = true;
-        visitEnter(snapshot);
-        for (auto& instance : snapshot)
-        {
-            if (!applyTo(instance))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(snapshot);
-        return cont;
-    }
-
-    bool Visitor::applyTo(EntityInstance& instance)
-    {
-        return visit(instance);
-    }
-
-
-    bool Visitor::applyTo(const Memory& memory)
-    {
-        bool cont = true;
-        visitEnter(memory);
-        for (const auto& [_, coreSeg] : memory)
-        {
-            if (!applyTo(coreSeg))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(memory);
-        return cont;
-    }
-
-    bool Visitor::applyTo(const CoreSegment& coreSegment)
-    {
-        bool cont = true;
-        visitEnter(coreSegment);
-        for (const auto& [_, provSeg] : coreSegment)
-        {
-            if (!applyTo(provSeg))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(coreSegment);
-        return cont;
-    }
-
-    bool Visitor::applyTo(const ProviderSegment& providerSegment)
-    {
-        bool cont = true;
-        visitEnter(providerSegment);
-        for (const auto& [_, entity] : providerSegment)
-        {
-            if (!applyTo(entity))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(providerSegment);
-        return cont;
-    }
-
-    bool Visitor::applyTo(const Entity& entity)
-    {
-        bool cont = true;
-        visitEnter(entity);
-        for (const auto& [_, snapshot] : entity)
-        {
-            if (!applyTo(snapshot))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(entity);
-        return cont;
-    }
-
-    bool Visitor::applyTo(const EntitySnapshot& snapshot)
-    {
-        bool cont = true;
-        visitEnter(snapshot);
-        for (const auto& instance : snapshot)
-        {
-            if (!applyTo(instance))
-            {
-                cont = false;
-                break;
-            }
-        }
-        visitExit(snapshot);
-        return cont;
-    }
-
-    bool Visitor::applyTo(const EntityInstance& instance)
-    {
-        return visit(instance);
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp b/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
index 8c814a160b49b0367cece67d407b986ac4d372e5..ae847a803dc64e68b53c432b222cb6ddbe2fcd86 100644
--- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp
@@ -1,13 +1,11 @@
 #include "ComponentPlugin.h"
 
-#include <ArmarXCore/core/Component.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include "MemoryToIceAdapter.h"
 
 #include <RobotAPI/libraries/armem/core/error.h>
 
-#include "MemoryToIceAdapter.h"
-
-//#include <RobotAPI/libraries/armem/core/io/diskWriter/NlohmannJSON/NlohmannJSONDiskWriter.h>
+#include <ArmarXCore/core/Component.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 
 namespace armarx::armem::server::plugins
diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h b/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
index 06ba31f7a128549f51be85de300a92bdd310cf95..0b2b872c1ff4686eecefd8ae8508bcfc45600d5f 100644
--- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
+++ b/source/RobotAPI/libraries/armem/server/ComponentPlugin.h
@@ -8,7 +8,7 @@
 #include <RobotAPI/interface/armem/client/MemoryListenerInterface.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
 #include <RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h>
 
@@ -98,7 +98,7 @@ namespace armarx::armem::server
     public:
 
         /// The actual memory.
-        wm::Memory workingMemory;
+        server::wm::Memory workingMemory;
         // [[deprecated ("The global working memory mutex is deprecated. Use the core segment mutexes instead.")]]
         // std::mutex workingMemoryMutex;
 
diff --git a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
index 9347cb7e9234723d33407693cb68ec1f5ea8448d..6664288a0fa5f86da4df906819cba3be385cbcb9 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.cpp
@@ -1,106 +1,96 @@
 #include "MemoryRemoteGui.h"
 
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include "RemoteGuiAronDataVisitor.h"
 
 #include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h>
 #include <RobotAPI/libraries/aron/core/navigator/visitors/DataVisitor.h>
 
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
 #include <SimoxUtility/meta/type_name.h>
 
-#include "RemoteGuiAronDataVisitor.h"
+#include <mutex>
 
 
 namespace armarx::armem::server
 {
 
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::Memory& memory) const
+    template <class ...Args>
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::MemoryBase<Args...>& memory) const
     {
         GroupBox group;
-        group.setLabel(makeGroupLabel("Memory", memory.name(), memory.coreSegments().size()));
+        group.setLabel(makeGroupLabel("Memory", memory.name(), memory.size()));
 
-        if (memory.coreSegments().empty())
+        if (memory.empty())
         {
             group.addChild(Label(makeNoItemsMessage("core segments")));
         }
-        for (const auto& [name, coreSegment] : memory.coreSegments())
+        memory.forEachCoreSegment([this, &group](const auto & coreSegment)
         {
-            group.addChild(makeGroupBox(coreSegment));
-        }
-
+            group.addChild(this->makeGroupBox(coreSegment));
+        });
         return group;
     }
 
-
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::CoreSegment& coreSegment) const
+    template <class ...Args>
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::CoreSegmentBase<Args...>& coreSegment) const
     {
-        std::scoped_lock lock(coreSegment.mutex());
-
         GroupBox group;
-        group.setLabel(makeGroupLabel("Core Segment", coreSegment.name(), coreSegment.providerSegments().size()));
+        group.setLabel(makeGroupLabel("Core Segment", coreSegment.name(), coreSegment.size()));
 
-        if (coreSegment.providerSegments().empty())
+        if (coreSegment.empty())
         {
             group.addChild(Label(makeNoItemsMessage("provider segments")));
         }
-        for (const auto& [name, providerSegment] : coreSegment.providerSegments())
+        coreSegment.forEachProviderSegment([this, &group](const auto & providerSegment)
         {
-            group.addChild(makeGroupBox(providerSegment));
-        }
-
+            group.addChild(this->makeGroupBox(providerSegment));
+        });
         return group;
     }
 
-
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::ProviderSegment& providerSegment) const
+    template <class ...Args>
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::ProviderSegmentBase<Args...>& providerSegment) const
     {
         GroupBox group;
-        group.setLabel(makeGroupLabel("Provider Segment", providerSegment.name(), providerSegment.entities().size()));
+        group.setLabel(makeGroupLabel("Provider Segment", providerSegment.name(), providerSegment.size()));
 
-        if (providerSegment.entities().empty())
+        if (providerSegment.empty())
         {
             group.addChild(Label(makeNoItemsMessage("entities")));
         }
-        for (const auto& [name, entity] : providerSegment.entities())
+        providerSegment.forEachEntity([this, &group](const auto & entity)
         {
-            group.addChild(makeGroupBox(entity));
-        }
-
+            group.addChild(this->makeGroupBox(entity));
+        });
         return group;
     }
 
-
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::Entity& entity) const
+    template <class ...Args>
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::_makeGroupBox(const armem::base::EntityBase<Args...>& entity) const
     {
         GroupBox group;
-        group.setLabel(makeGroupLabel("Entity", entity.name(), entity.history().size()));
+        group.setLabel(makeGroupLabel("Entity", entity.name(), entity.size()));
 
-        if (entity.history().empty())
+        if (entity.empty())
         {
             group.addChild(Label(makeNoItemsMessage("snapshots")));
         }
-        if (int(entity.history().size()) <= maxHistorySize)
+
+        auto addChild = [this, &group](const armem::wm::EntitySnapshot & snapshot)
         {
-            for (const auto& [time, snapshot] : entity.history())
-            {
-                group.addChild(makeGroupBox(snapshot));
-            }
+            group.addChild(makeGroupBox(snapshot));
+        };
+
+        if (int(entity.size()) <= maxHistorySize)
+        {
+            entity.forEachSnapshot(addChild);
         }
         else
         {
-            int margin = 2;
-            auto it = entity.history().begin();
-            auto rit = entity.history().end();
-            --rit;
-            for (int i = 0; i < margin; ++i, ++it)
-            {
-                group.addChild(makeGroupBox(it->second));
-                --rit;
-            }
-            group.addChild(Label("..."));
-            for (; rit != entity.history().end(); ++rit)
-            {
-                group.addChild(makeGroupBox(rit->second));
-            }
+            const int margin = 2;
+            entity.forEachSnapshotInIndexRange(0, margin, addChild);
+            entity.forEachSnapshotInIndexRange(-margin, -1, addChild);
         }
         group.setCollapsed(true);
 
@@ -108,27 +98,76 @@ namespace armarx::armem::server
     }
 
 
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::EntitySnapshot& snapshot) const
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::server::wm::Memory& memory) const
+    {
+        return this->_makeGroupBox(memory);
+    }
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::Memory& memory) const
+    {
+        return this->_makeGroupBox(memory);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::server::wm::CoreSegment& coreSegment) const
+    {
+        std::scoped_lock lock(coreSegment.mutex());
+        return this->_makeGroupBox(coreSegment);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::CoreSegment& coreSegment) const
+    {
+        return this->_makeGroupBox(coreSegment);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::server::wm::ProviderSegment& providerSegment) const
+    {
+        return this->_makeGroupBox(providerSegment);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::ProviderSegment& providerSegment) const
+    {
+        return this->_makeGroupBox(providerSegment);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::Entity& entity) const
+    {
+        return this->_makeGroupBox(entity);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::server::wm::Entity& entity) const
+    {
+        return this->_makeGroupBox(entity);
+    }
+
+
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::EntitySnapshot& snapshot) const
     {
         GroupBox group;
         group.setLabel(makeGroupLabel("t", armem::toDateTimeMilliSeconds(snapshot.time()),
-                                      snapshot.instances().size(), " = ", ""));
+                                      snapshot.size(), " = ", ""));
 
-        if (snapshot.instances().empty())
+        if (snapshot.empty())
         {
             group.addChild(Label(makeNoItemsMessage("instances")));
         }
-        for (const wm::EntityInstance& instance : snapshot.instances())
+        snapshot.forEachInstance([this, &group](const armem::wm::EntityInstance & instance)
         {
             group.addChild(makeGroupBox(instance));
-        }
+            return true;
+        });
         group.setCollapsed(true);
 
         return group;
     }
 
 
-    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const wm::EntityInstance& instance) const
+    MemoryRemoteGui::GroupBox MemoryRemoteGui::makeGroupBox(const armem::wm::EntityInstance& instance) const
     {
         GroupBox group;
 
diff --git a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.h b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.h
index f4a7fad95f1efa38d8ad7044d661e77fef60be31..c6aef5c51546ac203c50d38f80696b89f3b6f3b9 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.h
+++ b/source/RobotAPI/libraries/armem/server/MemoryRemoteGui.h
@@ -2,7 +2,7 @@
 
 #include <ArmarXGui/libraries/RemoteGui/Client/Widgets.h>
 
-#include "../core/workingmemory/Memory.h"
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 
 namespace armarx::armem::server
@@ -17,12 +17,18 @@ namespace armarx::armem::server
         using GroupBox = armarx::RemoteGui::Client::GroupBox;
         using Label = armarx::RemoteGui::Client::Label;
 
-        GroupBox makeGroupBox(const wm::Memory& memory) const;
-        GroupBox makeGroupBox(const wm::CoreSegment& coreSegment) const;
-        GroupBox makeGroupBox(const wm::ProviderSegment& providerSegment) const;
-        GroupBox makeGroupBox(const wm::Entity& entity) const;
-        GroupBox makeGroupBox(const wm::EntitySnapshot& entitySnapshot) const;
-        GroupBox makeGroupBox(const wm::EntityInstance& instance) const;
+
+        GroupBox makeGroupBox(const armem::wm::Memory& memory) const;
+        GroupBox makeGroupBox(const armem::wm::CoreSegment& coreSegment) const;
+        GroupBox makeGroupBox(const armem::wm::ProviderSegment& providerSegment) const;
+        GroupBox makeGroupBox(const armem::wm::Entity& entity) const;
+        GroupBox makeGroupBox(const armem::wm::EntitySnapshot& entitySnapshot) const;
+        GroupBox makeGroupBox(const armem::wm::EntityInstance& instance) const;
+
+        GroupBox makeGroupBox(const armem::server::wm::Memory& memory) const;
+        GroupBox makeGroupBox(const armem::server::wm::CoreSegment& coreSegment) const;
+        GroupBox makeGroupBox(const armem::server::wm::ProviderSegment& providerSegment) const;
+        GroupBox makeGroupBox(const armem::server::wm::Entity& entity) const;
 
 
         std::string makeGroupLabel(const std::string& term, const std::string& name, size_t size,
@@ -33,6 +39,17 @@ namespace armarx::armem::server
 
         int maxHistorySize = 10;
 
+    private:
+
+        template <class ...Args>
+        MemoryRemoteGui::GroupBox _makeGroupBox(const armem::base::MemoryBase<Args...>& memory) const;
+        template <class ...Args>
+        MemoryRemoteGui::GroupBox _makeGroupBox(const armem::base::CoreSegmentBase<Args...>& coreSegment) const;
+        template <class ...Args>
+        MemoryRemoteGui::GroupBox _makeGroupBox(const armem::base::ProviderSegmentBase<Args...>& providerSegment) const;
+        template <class ...Args>
+        MemoryRemoteGui::GroupBox _makeGroupBox(const armem::base::EntityBase<Args...>& entity) const;
+
     };
 
 
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
index 354eec9cea9d1d1e37f4dc4ea790b47ba1749755..52fb496592390a1f7df893d0709c73937da55ae5 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
@@ -1,12 +1,17 @@
 #include "MemoryToIceAdapter.h"
 
-#include "ArmarXCore/core/logging/Logging.h"
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include "query_proc/wm.h"
+#include "query_proc/ltm.h"
+
+#include <RobotAPI/libraries/armem/server/wm/ice_conversions.h>
+
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
-#include "../error.h"
-#include "../core/workingmemory/ice_conversions.h"
-#include "query_proc/workingmemory/MemoryQueryProcessor.h"
-#include "query_proc/longtermmemory/MemoryQueryProcessor.h"
+#include <RobotAPI/libraries/aron/core/Exception.h>
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 
 namespace armarx::armem::server
@@ -33,7 +38,7 @@ namespace armarx::armem::server
 
         data::AddSegmentResult output;
 
-        armem::wm::CoreSegment* coreSegment = nullptr;
+        server::wm::CoreSegment* coreSegment = nullptr;
         try
         {
             coreSegment = &workingMemory->getCoreSegment(input.coreSegmentName);
@@ -65,7 +70,7 @@ namespace armarx::armem::server
                 // This is ok.
                 if (input.clearWhenExists)
                 {
-                    wm::ProviderSegment& provider = coreSegment->getProviderSegment(input.providerSegmentName);
+                    server::wm::ProviderSegment& provider = coreSegment->getProviderSegment(input.providerSegmentName);
                     provider.clear();
                 }
             }
@@ -176,17 +181,7 @@ namespace armarx::armem::server
                 // TODO: Move outside of loop?
                 if (longtermMemory)
                 {
-                    if (longtermMemory->alwaysTransferSettings.enabled)
-                    {
-                        wm::Memory tmp(longtermMemory->name());
-                        tmp._addMissingCoreSegmentDuringUpdate = true;
-                        tmp.update(update);
-                        longtermMemory->append(tmp);
-                    }
-                    else
-                    {
-                        // TODO: see below
-                    }
+
                 }
 
                 // TODO: Consollidate to ltm if onFilledTransfer is enabled (fabian.peller)
@@ -234,15 +229,15 @@ namespace armarx::armem::server
         ARMARX_CHECK_NOT_NULL(workingMemory);
 
         // Core segment processors will aquire the core segment locks.
-        armem::wm::query_proc::MemoryQueryProcessor wmProcessor(
+        query_proc::wm_server::MemoryQueryProcessor wmServerProcessor(
             input.withData ? armem::DataMode::WithData : armem::DataMode::NoData);
-        wm::Memory wmResult = wmProcessor.process(input, *workingMemory);
+        armem::wm::Memory wmResult = wmServerProcessor.process(input.memoryQueries, *workingMemory);
 
-        armem::ltm::query_proc::MemoryQueryProcessor ltmProcessor;
+        query_proc::ltm::MemoryQueryProcessor ltmProcessor;
         ltm::Memory ltmResult = ltmProcessor.process(input, *longtermMemory);
 
         armem::query::data::Result result;
-        if (ltmResult.hasData())
+        if (not ltmResult.empty())
         {
             ARMARX_INFO << "The LTM returned data after query";
 
@@ -251,14 +246,14 @@ namespace armarx::armem::server
             // 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.
-            wm::Memory ltmConverted = ltmResult.convert();
-            if (!ltmConverted.hasData())
+            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.";
             }
 
             wmResult.append(ltmConverted);
-            if (!wmResult.hasData())
+            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.";
             }
@@ -267,8 +262,10 @@ namespace armarx::armem::server
             auto queryInput = armem::client::QueryInput::fromIce(input);
             queryInput.replaceQueryTarget(query::data::QueryTarget::LTM, query::data::QueryTarget::WM);
 
-            wm::Memory merged_result = wmProcessor.process(queryInput.toIce(), wmResult);
-            if (!merged_result.hasData())
+            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())
             {
                 ARMARX_ERROR << "A merged and postprocessed Memory has no data although at least the LTM result contains data. This indicates that something is wrong.";
             }
@@ -276,7 +273,7 @@ namespace armarx::armem::server
             result.memory = toIce<data::MemoryPtr>(merged_result);
 
             // also move results of ltm to wm
-            //this->commit(ltm_converted.toCommit());
+            //this->commit(toCommit(ltm_converted));
 
             // mark removed entries of wm in viewer
             // TODO
@@ -333,7 +330,7 @@ namespace armarx::armem::server
 
         if (queryResult.success)
         {
-            wm::Memory m;
+            armem::wm::Memory m;
             fromIce(queryResult.memory, m);
             longtermMemory->append(m);
         }
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
index f4b4b4c94eac3a51cb8c90e2fcabfc09288e3ead..6aa68b5714ad369e3b2bbad08d7c1ca06ab04bb8 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
@@ -3,15 +3,15 @@
 #include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/interface/armem/client/MemoryListenerInterface.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
 #include <RobotAPI/libraries/armem/client/Query.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 
 namespace armarx::armem::server
 {
 
-
     /**
      * @brief Helps connecting a Memory server to the Ice interface.
      *
@@ -23,7 +23,8 @@ namespace armarx::armem::server
     public:
 
         /// Construct an MemoryToIceAdapter from an existing Memory.
-        MemoryToIceAdapter(wm::Memory* workingMemory = nullptr, ltm::Memory* longtermMemory = nullptr);
+        MemoryToIceAdapter(server::wm::Memory* workingMemory = nullptr,
+                           ltm::Memory* longtermMemory = nullptr);
 
         void setMemoryListener(client::MemoryListenerInterfacePrx memoryListenerTopic);
 
@@ -54,7 +55,7 @@ namespace armarx::armem::server
 
     public:
 
-        wm::Memory* workingMemory;
+        server::wm::Memory* workingMemory;
         ltm::Memory* longtermMemory;
 
         client::MemoryListenerInterfacePrx memoryListenerTopic;
diff --git a/source/RobotAPI/libraries/armem/server/forward_declarations.h b/source/RobotAPI/libraries/armem/server/forward_declarations.h
new file mode 100644
index 0000000000000000000000000000000000000000..6872e2584352195ca8e587043e275acfbffb3739
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/forward_declarations.h
@@ -0,0 +1,18 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/forward_declarations.h>
+
+
+namespace armarx::armem::server
+{
+    class MemoryToIceAdapter;
+}
+namespace armarx::armem::server::wm
+{
+    using EntityInstance = armem::wm::EntityInstance;
+    using EntitySnapshot = armem::wm::EntitySnapshot;
+    class Entity;
+    class ProviderSegment;
+    class CoreSegment;
+    class Memory;
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base.h b/source/RobotAPI/libraries/armem/server/query_proc/base.h
new file mode 100644
index 0000000000000000000000000000000000000000..1d826798cecac7371882ce0783ddc05414a4f237
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base.h
@@ -0,0 +1,12 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h>
+#include <RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h>
+#include <RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h>
+#include <RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h>
+
+
+namespace armarx::armem::server::query_proc::base
+{
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.cpp b/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.cpp
index 34e2abd99c889d65723065c8b4726b2ea0aa9bd1..a3dfb4eb4102e21ee0cc97d7a9919b55c7c83f35 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.cpp
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.cpp
@@ -1,2 +1,21 @@
 #include "BaseQueryProcessorBase.h"
 
+#include <ArmarXCore/core/logging/Logging.h>
+
+
+namespace armarx::armem::server::query_proc::base
+{
+
+    std::set<query::data::QueryTarget>
+    detail::getTargets(const std::vector<query::data::QueryTarget>& _targets)
+    {
+        std::set<query::data::QueryTarget> targets(_targets.begin(), _targets.end());
+        if (targets.empty())
+        {
+            ARMARX_DEBUG << "Query has no targets - using WM as default.";
+            targets.insert(query::data::QueryTarget::WM);
+        }
+        return targets;
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.h
index 2af92450309d640122bffc9066c1a1df7bdfff49..73c662e04ebd734cbe79c3b19f676f684223a88c 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.h
@@ -1,88 +1,91 @@
 #pragma once
 
-#include <ArmarXCore/core/logging/Logging.h>
 #include <RobotAPI/interface/armem/query.h>
 
+#include <Ice/Handle.h>
 
-namespace armarx::armem::base::query_proc
+#include <set>
+#include <vector>
+
+
+namespace armarx::armem::server::query_proc::base::detail
 {
+    // If empty, e.g. when receiving queries from python, we use WM as default.
+    // We do it here as (Sl)ice does not support default values for vectors.
+    std::set<query::data::QueryTarget> getTargets(const std::vector<query::data::QueryTarget>& _targets);
+}
+namespace armarx::armem::server::query_proc::base
+{
+
+    using QueryTarget = query::data::QueryTarget;
+
 
     /**
      * @brief Base class for memory query processors.
      */
-    template <class DataT, class QueryT>
+    template <QueryTarget queryTarget, class DataT, class ResultT, class QueryT>
     class BaseQueryProcessorBase
     {
     public:
+
         using QueryPtrT = ::IceInternal::Handle<QueryT>;
         using QuerySeqT = std::vector<QueryPtrT>;
 
+
     public:
 
         virtual ~BaseQueryProcessorBase() = default;
 
 
-        DataT process(const QueryT& query, const DataT& data) const
+        ResultT process(const QueryT& query, const DataT& data) const
         {
-            DataT result = data.copyEmpty();
-            if (getTargets(query.targets).count(getTargetType()))
+            ResultT result { data.id() };
+            if (detail::getTargets(query.targets).count(queryTarget))
             {
                 this->process(result, query, data);
             }
             return result;
         }
 
-        DataT process(const QueryPtrT& query, const DataT& data) const
+        ResultT process(const QueryPtrT& query, const DataT& data) const
         {
             return this->process(*query, *data);
         }
 
-        DataT process(const QuerySeqT& queries, const DataT& data) const
+        ResultT process(const QuerySeqT& queries, const DataT& data) const
         {
-            DataT result = data.copyEmpty();
+            ResultT result { data.id() };
             this->process(result, queries, data);
             return result;
         }
 
-        void process(DataT& result, const QuerySeqT& queries, const DataT& data) const
+        void process(ResultT& result, const QuerySeqT& queries, const DataT& data) const
         {
             if (queries.empty())
             {
-                ARMARX_DEBUG << "There are no queries to process.";
                 return;
             }
 
             for (const auto& query : queries)
             {
-                if (getTargets(query->targets).count(getTargetType()))
+                if (detail::getTargets(query->targets).count(queryTarget))
                 {
                     this->process(result, *query, data);
                 }
             }
         }
 
-        virtual void process(DataT& result, const QueryT& query, const DataT& data) const = 0;
-
 
-    protected:
+        /**
+         * @brief Process the query and populate `result`.
+         *
+         * @param result The result container.
+         * @param query The query.
+         * @param data The source container.
+         */
+        virtual void process(ResultT& result, const QueryT& query, const DataT& data) const = 0;
 
-        virtual query::data::QueryTarget getTargetType() const = 0;
-
-
-    private:
+    };
 
-        /// If empty, e.g. when receiving queries from python, we use WM as default.
-        /// We do it here as (Sl)ice does not support default values for vectors.
-        static std::set<query::data::QueryTarget> getTargets(const std::vector<query::data::QueryTarget>& _targets)
-        {
-            std::set<query::data::QueryTarget> targets(_targets.begin(), _targets.end());
-            if (targets.empty())
-            {
-                ARMARX_DEBUG << "Query has no targets - using WM as default.";
-                targets.insert(query::data::QueryTarget::WM);
-            }
-            return targets;
-        }
 
-    };
 }
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 9d7b2518227e4ddf0c5d759963af193656e39894..3050e6e4e91a90bfbfa97feff7f3afc6cb804f41 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h
@@ -9,31 +9,46 @@
 #include <RobotAPI/libraries/armem/core/error.h>
 
 #include "BaseQueryProcessorBase.h"
-#include "ProviderSegmentQueryProcessorBase.h"
 
 
-namespace armarx::armem::base::query_proc
+namespace armarx::armem::server::query_proc::base
 {
 
     /**
      * @brief Handles memory queries.
      */
-    template <class _CoreSegmentT>
+    template <QueryTarget queryTarget, class _CoreSegmentT, class _ResultCoreSegmentT, class _ChildProcessorT>
     class CoreSegmentQueryProcessorBase :
-        virtual public BaseQueryProcessorBase<_CoreSegmentT, armem::query::data::CoreSegmentQuery>
+        public BaseQueryProcessorBase<queryTarget, _CoreSegmentT, _ResultCoreSegmentT, armem::query::data::CoreSegmentQuery>
     {
-        using Base = BaseQueryProcessorBase<_CoreSegmentT, armem::query::data::CoreSegmentQuery>;
+        using Base = BaseQueryProcessorBase<queryTarget, _CoreSegmentT, _ResultCoreSegmentT, armem::query::data::CoreSegmentQuery>;
 
     public:
+
         using CoreSegmentT = _CoreSegmentT;
-        using ProviderSegmentT = typename _CoreSegmentT::ProviderSegmentT;
-        using EntityT = typename ProviderSegmentT::EntityT;
-        using EntitySnapshotT = typename EntityT::EntitySnapshotT;
+        using ProviderSegmentT = typename CoreSegmentT::ProviderSegmentT;
+
+        using ResultCoreSegmentT = _ResultCoreSegmentT;
+        using ResultProviderSegmentT = typename ResultCoreSegmentT::ProviderSegmentT;
+
+        using ChildProcessorT = _ChildProcessorT;
+
+
+    public:
+
+        CoreSegmentQueryProcessorBase()
+        {
+        }
+        CoreSegmentQueryProcessorBase(ChildProcessorT&& childProcessor) :
+            childProcessor(childProcessor)
+        {
+        }
+
 
         using Base::process;
-        virtual void process(_CoreSegmentT& result,
+        virtual void process(ResultCoreSegmentT& result,
                              const armem::query::data::CoreSegmentQuery& query,
-                             const _CoreSegmentT& coreSegment) const override
+                             const CoreSegmentT& coreSegment) const override
         {
             if (auto q = dynamic_cast<const armem::query::data::core::All*>(&query))
             {
@@ -53,24 +68,24 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_CoreSegmentT& result,
+        void process(ResultCoreSegmentT& result,
                      const armem::query::data::core::All& query,
-                     const _CoreSegmentT& coreSegment) const
+                     const CoreSegmentT& coreSegment) const
         {
-            for (const auto& [name, providerSegment] : coreSegment.providerSegments())
+            coreSegment.forEachProviderSegment([this, &query, &result](const ProviderSegmentT & providerSegment)
             {
-                result.addProviderSegment(providerSegmentProcessorProcess(query.providerSegmentQueries, providerSegment));
-            }
+                childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
+            });
         }
 
-        void process(_CoreSegmentT& result,
+        void process(ResultCoreSegmentT& result,
                      const armem::query::data::core::Single& query,
-                     const _CoreSegmentT& coreSegment) const
+                     const CoreSegmentT& coreSegment) const
         {
             try
             {
                 const ProviderSegmentT& providerSegment = coreSegment.getProviderSegment(query.providerSegmentName);
-                result.addProviderSegment(providerSegmentProcessorProcess(query.providerSegmentQueries, providerSegment));
+                childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
             }
             catch (const error::MissingEntry&)
             {
@@ -78,21 +93,25 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_CoreSegmentT& result,
+        void process(ResultCoreSegmentT& result,
                      const armem::query::data::core::Regex& query,
-                     const _CoreSegmentT& coreSegment) const
+                     const CoreSegmentT& coreSegment) const
         {
             std::regex regex(query.providerSegmentNameRegex);
-            for (const auto& [name, providerSegment] : coreSegment.providerSegments())
+            coreSegment.forEachProviderSegment(
+                [this, &result, &query, &regex](const ProviderSegmentT & providerSegment)
             {
                 if (std::regex_search(providerSegment.name(), regex))
                 {
-                    result.addProviderSegment(providerSegmentProcessorProcess(query.providerSegmentQueries, providerSegment));
+                    childProcessor.process(result.addProviderSegment(providerSegment.name()), query.providerSegmentQueries, providerSegment);
                 }
-            }
+            });
         }
 
+
     protected:
-        virtual ProviderSegmentT providerSegmentProcessorProcess(const armem::query::data::ProviderSegmentQuerySeq& a, const ProviderSegmentT& o) const = 0;
+
+        ChildProcessorT childProcessor;
+
     };
 }
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 40113207f194c76301fbe8768a6d42c22f8b01db..0c4a842fa2772ae18b475b9e28ad3b13077bb49d 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h
@@ -1,41 +1,42 @@
 #pragma once
 
-#include <cstdint>
-#include <iterator>
+#include "BaseQueryProcessorBase.h"
+
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/ice_conversions.h>
 
 #include <RobotAPI/interface/armem/query.h>
 
-#include <ArmarXCore/core/exceptions/LocalException.h>
-#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
-#include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/ice_conversions.h>
-
-#include "BaseQueryProcessorBase.h"
-#include "RobotAPI/libraries/armem/core/Time.h"
+#include <cstdint>
+#include <iterator>
 
 
-namespace armarx::armem::base::query_proc
+namespace armarx::armem::server::query_proc::base
 {
 
-    /**
-     * @brief Handles memory queries.
-     */
-    template <class _EntityT>
+    template <QueryTarget queryTarget, class _EntityT, class _ResultEntityT>
     class EntityQueryProcessorBase :
-        virtual public BaseQueryProcessorBase<_EntityT, armem::query::data::EntityQuery>
+        public BaseQueryProcessorBase<queryTarget, _EntityT, _ResultEntityT, armem::query::data::EntityQuery>
     {
-        using Base = BaseQueryProcessorBase<_EntityT, armem::query::data::EntityQuery>;
+        using Base = BaseQueryProcessorBase<queryTarget, _EntityT, _ResultEntityT, armem::query::data::EntityQuery>;
 
     public:
+
         using EntityT = _EntityT;
         using EntitySnapshotT = typename EntityT::EntitySnapshotT;
 
+        using ResultEntityT = _ResultEntityT;
+        using ResultSnapshotT = typename ResultEntityT::EntitySnapshotT;
+
+
         using Base::process;
-        void process(_EntityT& result,
-                     const armem::query::data::EntityQuery& query,
-                     const _EntityT& entity) const override
+        virtual void process(ResultEntityT& result,
+                             const armem::query::data::EntityQuery& query,
+                             const EntityT& entity) const override
         {
             if (auto q = dynamic_cast<const armem::query::data::entity::All*>(&query))
             {
@@ -71,22 +72,24 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::All& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
             (void) query;
             // Copy this entitiy and its contents.
 
-            for (const auto& [time, snapshot] : entity)
+            entity.forEachSnapshot([this, &result](const EntitySnapshotT & snapshot)
             {
                 addResultSnapshot(result, snapshot);
-            }
+            });
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::Single& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
             if (query.timestamp < 0)
             {
@@ -131,9 +134,10 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::TimeRange& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
             if (query.minTimestamp <= query.maxTimestamp || query.minTimestamp < 0 || query.maxTimestamp < 0)
             {
@@ -143,54 +147,39 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::IndexRange& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
-            if (entity.empty())
-            {
-                return;
-            }
-
-            size_t first = negativeIndexSemantics(query.first, entity.history().size());
-            size_t last = negativeIndexSemantics(query.last, entity.history().size());
-
-            if (first <= last)
+            entity.forEachSnapshotInIndexRange(
+                query.first, query.last,
+                [this, &result](const EntitySnapshotT & snapshot)
             {
-                auto it = entity.begin();
-                std::advance(it, first);
-
-                size_t num = last - first + 1;  // +1 to make last inclusive
-                for (size_t i = 0; i < num; ++i, ++it)
-                {
-                    addResultSnapshot(result, it);
-                }
-            }
+                addResultSnapshot(result, snapshot);
+            });
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const Time& min,
                      const Time& max,
-                     const _EntityT& entity,
+                     const EntityT& entity,
                      const armem::query::data::EntityQuery& query) const
         {
             (void) query;
-
-            // Returns an iterator pointing to the first element that is not less than (i.e. greater or equal to) key.
-            auto begin = min.toMicroSeconds() > 0 ? entity.history().lower_bound(min) : entity.history().begin();
-            // Returns an iterator pointing to the first element that is *greater than* key.
-            auto end = max.toMicroSeconds() > 0 ? entity.history().upper_bound(max) : entity.history().end();
-
-            for (auto it = begin; it != end && it != entity.history().end(); ++it)
+            entity.forEachSnapshotInTimeRange(
+                min, max,
+                [this, &result](const EntitySnapshotT & snapshot)
             {
-                addResultSnapshot(result, it);
-            }
+                addResultSnapshot(result, snapshot);
+            });
         }
 
 
-        void process(_EntityT& result,
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::BeforeOrAtTime& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
             const auto referenceTimestamp = fromIce<Time>(query.timestamp);
             ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp is negative!";
@@ -207,39 +196,40 @@ namespace armarx::armem::base::query_proc
         }
 
 
-        void process(_EntityT& result,
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::BeforeTime& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
-            const auto referenceTimestamp = fromIce<Time>(query.timestamp);
-            ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp is negative!";
+            const armem::Time referenceTimestamp = fromIce<Time>(query.timestamp);
+            ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp must be non-negative.";
 
-            const auto maxEntries = fromIce<std::int64_t>(query.maxEntries);
-
-            try
+            std::vector<const EntitySnapshotT*> befores;
+            entity.forEachSnapshotBefore(referenceTimestamp, [&befores](const EntitySnapshotT & s)
             {
-                const auto before = entity.getSnapshotsBefore(referenceTimestamp);
+                befores.push_back(&s);
+            });
 
-                int i = 0;
-                for (const auto& snapshot : before)
-                {
-                    if (maxEntries >= 0 && i >= maxEntries)
-                    {
-                        break;
-                    }
-                    addResultSnapshot(result, snapshot);
-                    ++i;
-                }
+            size_t num = 0;
+            if (query.maxEntries < 0)
+            {
+                num = befores.size();
             }
-            catch (const  error::MissingEntry&)
+            else
             {
-                // Leave empty.
+                num = std::min(befores.size(), static_cast<size_t>(query.maxEntries));
+            }
+
+            for (size_t r = 0; r < num; ++r)
+            {
+                size_t i = befores.size() - 1 - r;
+                addResultSnapshot(result, *befores[i]);
             }
         }
 
-        void process(_EntityT& result,
+
+        void process(ResultEntityT& result,
                      const armem::query::data::entity::TimeApprox& query,
-                     const _EntityT& entity) const
+                     const EntityT& entity) const
         {
             const auto referenceTimestamp = fromIce<Time>(query.timestamp);
             ARMARX_CHECK(referenceTimestamp.toMicroSeconds() >= 0) << "Reference timestamp is negative!";
@@ -285,26 +275,16 @@ namespace armarx::armem::base::query_proc
             }
             catch (const armem::error::MissingEntry&)
             {
-
             }
         }
 
-        static size_t negativeIndexSemantics(long index, size_t size)
-        {
-            const size_t max = size > 0 ? size - 1 : 0;
-            if (index >= 0)
-            {
-                return std::clamp<size_t>(static_cast<size_t>(index), 0, max);
-            }
-            else
-            {
-                return static_cast<size_t>(std::clamp<long>(static_cast<long>(size) + index, 0, static_cast<long>(max)));
-            }
-        }
 
     protected:
-        virtual void addResultSnapshot(_EntityT& result, typename _EntityT::ContainerT::const_iterator it) const = 0;
-        virtual void addResultSnapshot(_EntityT& result, const typename _EntityT::EntitySnapshotT& snapshot) const = 0;
+
+        void addResultSnapshot(ResultEntityT& result, const EntitySnapshotT& snapshot) const
+        {
+            result.addSnapshot(snapshot);
+        }
 
     };
 }
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 55c5e51126b49775db7317d6401aa695c4b5581c..df71683c29f2cb17db976e8be971725934b03348 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h
@@ -1,47 +1,56 @@
 #pragma once
 
-#include <regex>
-
-#include <RobotAPI/interface/armem/query.h>
-
 #include "BaseQueryProcessorBase.h"
-#include "CoreSegmentQueryProcessorBase.h"
 
+#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 <RobotAPI/libraries/armem/core/error.h>
+#include <regex>
 
 
-namespace armarx::armem::base::query_proc
+namespace armarx::armem::server::query_proc::base
 {
-    /**
-     * @brief Handles memory queries.
-     */
-    template <class _MemoryT>
+
+    template <QueryTarget queryTarget, class _MemoryT, class _ResultMemoryT, class _ChildProcessorT>
     class MemoryQueryProcessorBase :
-        virtual public BaseQueryProcessorBase<_MemoryT, armem::query::data::MemoryQuery>
+        public BaseQueryProcessorBase<queryTarget, _MemoryT, _ResultMemoryT, armem::query::data::MemoryQuery>
     {
-        using Base = BaseQueryProcessorBase<_MemoryT, armem::query::data::MemoryQuery>;
+        using Base = BaseQueryProcessorBase<queryTarget, _MemoryT, _ResultMemoryT, armem::query::data::MemoryQuery>;
 
     public:
+
         using MemoryT = _MemoryT;
         using CoreSegmentT = typename MemoryT::CoreSegmentT;
-        using ProviderSegmentT = typename CoreSegmentT::ProviderSegmentT;
-        using EntityT = typename ProviderSegmentT::EntityT;
-        using EntitySnapshotT = typename EntityT::EntitySnapshotT;
+
+        using ResultMemoryT = _ResultMemoryT;
+        using ResultCoreSegmentT = typename ResultMemoryT::CoreSegmentT;
+
+        using ChildProcessorT = _ChildProcessorT;
+
+
+    public:
+
+        MemoryQueryProcessorBase()
+        {
+        }
+        MemoryQueryProcessorBase(ChildProcessorT&& childProcessor) :
+            childProcessor(childProcessor)
+        {
+        }
 
 
         using Base::process;
-        _MemoryT process(const armem::query::data::Input& input, const _MemoryT& memory) const
+        ResultMemoryT process(const armem::query::data::Input& input, const MemoryT& memory) const
         {
             return this->process(input.memoryQueries, memory);
         }
 
-        void process(_MemoryT& result,
-                     const armem::query::data::MemoryQuery& query,
-                     const _MemoryT& memory) const override
+        virtual void process(ResultMemoryT& result,
+                             const armem::query::data::MemoryQuery& query,
+                             const MemoryT& memory) const override
         {
             if (auto q = dynamic_cast<const armem::query::data::memory::All*>(&query))
             {
@@ -57,49 +66,52 @@ namespace armarx::armem::base::query_proc
             }
             else
             {
-                throw armem::error::UnknownQueryType("memory segment", query);
+                throw armem::error::UnknownQueryType(MemoryT::getLevelName(), query);
             }
         }
 
-        void process(_MemoryT& result,
+        void process(ResultMemoryT& result,
                      const armem::query::data::memory::All& query,
-                     const _MemoryT& memory) const
+                     const MemoryT& memory) const
         {
-            for (const auto& [name, coreSegment] : memory.coreSegments())
+            memory.forEachCoreSegment([this, &result, &query](const CoreSegmentT & coreSegment)
             {
-                result.addCoreSegment(coreSegmentProcessorProcess(query.coreSegmentQueries, coreSegment));
-            }
+                childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
+            });
         }
 
-        void process(_MemoryT& result,
+        void process(ResultMemoryT& result,
                      const armem::query::data::memory::Single& query,
-                     const _MemoryT& memory) const
+                     const MemoryT& memory) const
         {
             try
             {
                 const CoreSegmentT& coreSegment = memory.getCoreSegment(query.coreSegmentName);
-                result.addCoreSegment(coreSegmentProcessorProcess(query.coreSegmentQueries, coreSegment));
+                childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
             }
             catch (const error::MissingEntry&)
             {
             }
         }
 
-        void process(_MemoryT& result,
+        void process(ResultMemoryT& result,
                      const armem::query::data::memory::Regex& query,
-                     const _MemoryT& memory) const
+                     const MemoryT& memory) const
         {
-            std::regex regex(query.coreSegmentNameRegex);
-            for (const auto& [name, coreSegment] : memory.coreSegments())
+            const std::regex regex(query.coreSegmentNameRegex);
+            memory.forEachCoreSegment([this, &result, &query, &regex](const CoreSegmentT & coreSegment)
             {
                 if (std::regex_search(coreSegment.name(), regex))
                 {
-                    result.addCoreSegment(coreSegmentProcessorProcess(query.coreSegmentQueries, coreSegment));
+                    childProcessor.process(result.addCoreSegment(coreSegment.name()), query.coreSegmentQueries, coreSegment);
                 }
-            }
+            });
         }
 
+
     protected:
-        virtual CoreSegmentT coreSegmentProcessorProcess(const armem::query::data::CoreSegmentQuerySeq& a, const CoreSegmentT& o) const = 0;
+
+        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 b3b7da7ffa9cc1d06aeadabef58c5aebba3974de..5102a12829c106e58159e7dcc35a7df0890f93d5 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h
@@ -1,39 +1,50 @@
 #pragma once
 
-#include <RobotAPI/interface/armem/query.h>
-
 #include "BaseQueryProcessorBase.h"
-#include "EntityQueryProcessorBase.h"
 
-#include <regex>
+#include <RobotAPI/libraries/armem/core/error.h>
 
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <RobotAPI/interface/armem/query.h>
 
-#include <RobotAPI/libraries/armem/core/error.h>
+#include <regex>
 
 
-namespace armarx::armem::base::query_proc
+namespace armarx::armem::server::query_proc::base
 {
 
-    /**
-     * @brief Handles memory queries.
-     */
-    template <class _ProviderSegmentT>
+    template <QueryTarget queryTarget, class _ProviderSegmentT, class _ResultProviderSegmentT, class _ChildProcessorT>
     class ProviderSegmentQueryProcessorBase :
-        virtual public BaseQueryProcessorBase<_ProviderSegmentT, armem::query::data::ProviderSegmentQuery>
+        public BaseQueryProcessorBase<queryTarget, _ProviderSegmentT, _ResultProviderSegmentT, armem::query::data::ProviderSegmentQuery>
     {
-        using Base = BaseQueryProcessorBase<_ProviderSegmentT, armem::query::data::ProviderSegmentQuery>;
+        using Base = BaseQueryProcessorBase<queryTarget, _ProviderSegmentT, _ResultProviderSegmentT, armem::query::data::ProviderSegmentQuery>;
+
 
     public:
+
         using ProviderSegmentT = _ProviderSegmentT;
         using EntityT = typename ProviderSegmentT::EntityT;
-        using EntitySnapshotT = typename EntityT::EntitySnapshotT;
+
+        using ResultProviderSegmentT = _ResultProviderSegmentT;
+        using ResultEntityT = typename ResultProviderSegmentT::EntityT;
+
+        using ChildProcessorT = _ChildProcessorT;
+
+
+    public:
+
+        ProviderSegmentQueryProcessorBase()
+        {
+        }
+        ProviderSegmentQueryProcessorBase(ChildProcessorT&& childProcessor) :
+            childProcessor(childProcessor)
+        {
+        }
+
 
         using Base::process;
-        void process(_ProviderSegmentT& result,
-                     const armem::query::data::ProviderSegmentQuery& query,
-                     const _ProviderSegmentT& providerSegment) const override
+        virtual void process(ResultProviderSegmentT& result,
+                             const armem::query::data::ProviderSegmentQuery& query,
+                             const ProviderSegmentT& providerSegment) const override
         {
             if (auto q = dynamic_cast<const armem::query::data::provider::All*>(&query))
             {
@@ -49,28 +60,28 @@ namespace armarx::armem::base::query_proc
             }
             else
             {
-                throw armem::error::UnknownQueryType("provider segment", query);
+                throw armem::error::UnknownQueryType(ProviderSegmentT::getLevelName(), query);
             }
         }
 
-        void process(_ProviderSegmentT& result,
+        void process(ResultProviderSegmentT& result,
                      const armem::query::data::provider::All& query,
-                     const _ProviderSegmentT& providerSegment) const
+                     const ProviderSegmentT& providerSegment) const
         {
-            for (const auto& [name, entity] : providerSegment.entities())
+            providerSegment.forEachEntity([this, &result, &query](const EntityT & entity)
             {
-                result.addEntity(entityProcessorProcess(query.entityQueries, entity));
-            }
+                childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
+            });
         }
 
-        void process(_ProviderSegmentT& result,
+        void process(ResultProviderSegmentT& result,
                      const armem::query::data::provider::Single& query,
-                     const _ProviderSegmentT& providerSegment) const
+                     const ProviderSegmentT& providerSegment) const
         {
             try
             {
                 const EntityT& entity = providerSegment.getEntity(query.entityName);
-                result.addEntity(entityProcessorProcess(query.entityQueries, entity));
+                childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
             }
             catch (const error::MissingEntry&)
             {
@@ -78,21 +89,25 @@ namespace armarx::armem::base::query_proc
             }
         }
 
-        void process(_ProviderSegmentT& result,
+        void process(ResultProviderSegmentT& result,
                      const armem::query::data::provider::Regex& query,
-                     const _ProviderSegmentT& providerSegment) const
+                     const ProviderSegmentT& providerSegment) const
         {
-            std::regex regex(query.entityNameRegex);
-            for (const auto& [name, entity] : providerSegment.entities())
+            const std::regex regex(query.entityNameRegex);
+            providerSegment.forEachEntity([this, &result, &query, &regex](const EntityT & entity)
             {
                 if (std::regex_search(entity.name(), regex))
                 {
-                    result.addEntity(entityProcessorProcess(query.entityQueries, entity));
+                    childProcessor.process(result.addEntity(entity.name()), query.entityQueries, entity);
                 }
-            }
+                return true;
+            });
         }
 
+
     protected:
-        virtual EntityT entityProcessorProcess(const armem::query::data::EntityQuerySeq& a, const EntityT& o) const = 0;
+
+        ChildProcessorT childProcessor;
+
     };
 }
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a695cf43d51dcbbc2329fa1c48fbe8e63565c24f
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.cpp
@@ -0,0 +1,7 @@
+#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
new file mode 100644
index 0000000000000000000000000000000000000000..0f2ffe791d192b9bc2b5f2a2be311735808427a4
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory.h
@@ -0,0 +1,32 @@
+#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/diskmemory/BaseQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/BaseQueryProcessor.cpp
deleted file mode 100644
index 68821bcd95cdf2aaccf7126d4055495d39d0393d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/BaseQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "BaseQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/BaseQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/BaseQueryProcessor.h
deleted file mode 100644
index 469b5f907d01bbff757b1bea14ff8e80e5769315..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/BaseQueryProcessor.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include <RobotAPI/interface/armem/query.h>
-#include <RobotAPI/libraries/armem/core/DataMode.h>
-
-#include "../base/BaseQueryProcessorBase.h"
-
-
-namespace armarx::armem::d_ltm::query_proc
-{
-    /**
-     * @brief Base class for memory query processors.
-     */
-    template <class DataT, class QueryT>
-    class BaseQueryProcessor :
-        virtual public base::query_proc::BaseQueryProcessorBase<DataT, QueryT>
-    {
-        using Base = base::query_proc::BaseQueryProcessorBase<DataT, QueryT>;
-
-    public:
-        BaseQueryProcessor()
-        {}
-
-    protected:
-
-        query::data::QueryTarget getTargetType() const override
-        {
-            return query::data::QueryTarget::Disk;
-        }
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.cpp
deleted file mode 100644
index afbe35ad15eea0342b0b0d4df0200aaf0d32aa2a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "CoreSegmentQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.h
deleted file mode 100644
index 5c043a2d1dbe2218078591adc3fc0ebac0bfe932..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/CoreSegmentQueryProcessor.h
+++ /dev/null
@@ -1,36 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/CoreSegmentQueryProcessorBase.h"
-
-#include "../../../core/diskmemory/CoreSegment.h"
-
-#include "ProviderSegmentQueryProcessor.h"
-
-
-namespace armarx::armem::d_ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class CoreSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<d_ltm::CoreSegment, armem::query::data::CoreSegmentQuery>,
-        virtual public base::query_proc::CoreSegmentQueryProcessorBase<d_ltm::CoreSegment>
-    {
-        using Base = BaseQueryProcessor<d_ltm::CoreSegment, armem::query::data::CoreSegmentQuery>;
-
-    public:
-        CoreSegmentQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual ProviderSegmentT providerSegmentProcessorProcess(const armem::query::data::ProviderSegmentQuerySeq& q, const ProviderSegmentT& s) const override
-        {
-            return providerSegmentProcessor.process(q, s);
-        }
-
-    private:
-        ProviderSegmentQueryProcessor providerSegmentProcessor;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.cpp
deleted file mode 100644
index c1c321b026b173c6552758fb9d8b9fdf722ea5a4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "EntityQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.h
deleted file mode 100644
index c57c2c2da39ca53ce97d27b498e69b648a16f25a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/EntityQueryProcessor.h
+++ /dev/null
@@ -1,42 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/EntityQueryProcessorBase.h"
-
-#include "../../../core/diskmemory/Entity.h"
-
-#include "EntityQueryProcessor.h"
-
-namespace armarx::armem::d_ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class EntityQueryProcessor :
-        virtual public BaseQueryProcessor<d_ltm::Entity, armem::query::data::EntityQuery>,
-        virtual public base::query_proc::EntityQueryProcessorBase<d_ltm::Entity>
-    {
-        using Base = BaseQueryProcessor<d_ltm::Entity, armem::query::data::EntityQuery>;
-
-    public:
-
-        EntityQueryProcessor() :
-            Base()
-        {}
-
-
-    private:
-
-        void addResultSnapshot(d_ltm::Entity& result, d_ltm::Entity::ContainerT::const_iterator it) const override
-        {
-            addResultSnapshot(result, it->second);
-        }
-
-        void addResultSnapshot(d_ltm::Entity& result, const d_ltm::EntitySnapshot& snapshot) const override
-        {
-            result.addSnapshot(snapshot.copy());
-        }
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.cpp
deleted file mode 100644
index 69b04de6c9e623286a5bda836dddfdc8b551b64a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "MemoryQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.h
deleted file mode 100644
index 038523950bfe399c2ef7a65b79fde43376651617..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/MemoryQueryProcessor.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/MemoryQueryProcessorBase.h"
-
-#include "../../../core/diskmemory/Memory.h"
-
-#include "CoreSegmentQueryProcessor.h"
-
-namespace armarx::armem::d_ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class MemoryQueryProcessor :
-        virtual public BaseQueryProcessor<d_ltm::Memory, armem::query::data::MemoryQuery>,
-        virtual public base::query_proc::MemoryQueryProcessorBase<d_ltm::Memory>
-    {
-        using Base = BaseQueryProcessor<d_ltm::Memory, armem::query::data::MemoryQuery>;
-
-    public:
-        MemoryQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual CoreSegmentT coreSegmentProcessorProcess(const armem::query::data::CoreSegmentQuerySeq& q, const CoreSegmentT& s) const override
-        {
-            return coreSegmentProcessor.process(q, s);
-        }
-
-    private:
-        CoreSegmentQueryProcessor coreSegmentProcessor;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.cpp
deleted file mode 100644
index 9a2a4405001f0904b74fc6afcf96813eef0879cd..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "ProviderSegmentQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.h
deleted file mode 100644
index 2043273ec7c5f3fee2d02410a145ef436c47459c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/diskmemory/ProviderSegmentQueryProcessor.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/ProviderSegmentQueryProcessorBase.h"
-
-#include "../../../core/diskmemory/ProviderSegment.h"
-
-#include "EntityQueryProcessor.h"
-
-namespace armarx::armem::d_ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class ProviderSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<d_ltm::ProviderSegment, armem::query::data::ProviderSegmentQuery>,
-        virtual public base::query_proc::ProviderSegmentQueryProcessorBase<d_ltm::ProviderSegment>
-    {
-        using Base = BaseQueryProcessor<d_ltm::ProviderSegment, armem::query::data::ProviderSegmentQuery>;
-
-    public:
-        ProviderSegmentQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual EntityT entityProcessorProcess(const armem::query::data::EntityQuerySeq& q, const EntityT& s) const override
-        {
-            return entityProcessor.process(q, s);
-        }
-
-    private:
-        EntityQueryProcessor entityProcessor;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.cpp
deleted file mode 100644
index 68821bcd95cdf2aaccf7126d4055495d39d0393d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "BaseQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.h
deleted file mode 100644
index 64f560afff93e5d0cfff4b036f68f0fb4e8cdaba..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/BaseQueryProcessor.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include <RobotAPI/interface/armem/query.h>
-#include <RobotAPI/libraries/armem/core/DataMode.h>
-
-#include "../base/BaseQueryProcessorBase.h"
-
-
-namespace armarx::armem::ltm::query_proc
-{
-    /**
-     * @brief Base class for memory query processors.
-     */
-    template <class DataT, class QueryT>
-    class BaseQueryProcessor :
-        virtual public base::query_proc::BaseQueryProcessorBase<DataT, QueryT>
-    {
-        using Base = base::query_proc::BaseQueryProcessorBase<DataT, QueryT>;
-
-    public:
-        BaseQueryProcessor()
-        {}
-
-    protected:
-
-        query::data::QueryTarget getTargetType() const override
-        {
-            return query::data::QueryTarget::LTM;
-        }
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.cpp
deleted file mode 100644
index afbe35ad15eea0342b0b0d4df0200aaf0d32aa2a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "CoreSegmentQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.h
deleted file mode 100644
index dc379f1d88fa82bbe886e412e0341079fa43fce9..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/CoreSegmentQueryProcessor.h
+++ /dev/null
@@ -1,36 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/CoreSegmentQueryProcessorBase.h"
-
-#include "../../../core/longtermmemory/CoreSegment.h"
-
-#include "ProviderSegmentQueryProcessor.h"
-
-
-namespace armarx::armem::ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class CoreSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<ltm::CoreSegment, armem::query::data::CoreSegmentQuery>,
-        virtual public base::query_proc::CoreSegmentQueryProcessorBase<ltm::CoreSegment>
-    {
-        using Base = BaseQueryProcessor<ltm::CoreSegment, armem::query::data::CoreSegmentQuery>;
-
-    public:
-        CoreSegmentQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual ProviderSegmentT providerSegmentProcessorProcess(const armem::query::data::ProviderSegmentQuerySeq& q, const ProviderSegmentT& s) const override
-        {
-            return providerSegmentProcessor.process(q, s);
-        }
-
-    private:
-        ProviderSegmentQueryProcessor providerSegmentProcessor;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.cpp
deleted file mode 100644
index c1c321b026b173c6552758fb9d8b9fdf722ea5a4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "EntityQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.h
deleted file mode 100644
index 5ec4c5dde481e16f0af30589d57ff2a447d81221..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/EntityQueryProcessor.h
+++ /dev/null
@@ -1,39 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/EntityQueryProcessorBase.h"
-
-#include "../../../core/longtermmemory/Entity.h"
-
-#include "EntityQueryProcessor.h"
-
-namespace armarx::armem::ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class EntityQueryProcessor :
-        virtual public BaseQueryProcessor<ltm::Entity, armem::query::data::EntityQuery>,
-        virtual public base::query_proc::EntityQueryProcessorBase<ltm::Entity>
-    {
-        using Base = BaseQueryProcessor<ltm::Entity, armem::query::data::EntityQuery>;
-
-    public:
-        EntityQueryProcessor() :
-            Base()
-        {}
-
-    private:
-        void addResultSnapshot(ltm::Entity& result, ltm::Entity::ContainerT::const_iterator it) const override
-        {
-            addResultSnapshot(result, it->second);
-        }
-
-        void addResultSnapshot(ltm::Entity& result, const ltm::EntitySnapshot& snapshot) const override
-        {
-            result.addSnapshot(snapshot.copy());
-        }
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.cpp
deleted file mode 100644
index 69b04de6c9e623286a5bda836dddfdc8b551b64a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "MemoryQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.h
deleted file mode 100644
index a5129417262515975efa247398602272865ee5ec..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/MemoryQueryProcessor.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/MemoryQueryProcessorBase.h"
-
-#include "../../../core/longtermmemory/Memory.h"
-
-#include "CoreSegmentQueryProcessor.h"
-
-namespace armarx::armem::ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class MemoryQueryProcessor :
-        virtual public BaseQueryProcessor<ltm::Memory, armem::query::data::MemoryQuery>,
-        virtual public base::query_proc::MemoryQueryProcessorBase<ltm::Memory>
-    {
-        using Base = BaseQueryProcessor<ltm::Memory, armem::query::data::MemoryQuery>;
-
-    public:
-        MemoryQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual CoreSegmentT coreSegmentProcessorProcess(const armem::query::data::CoreSegmentQuerySeq& q, const CoreSegmentT& s) const override
-        {
-            return coreSegmentProcessor.process(q, s);
-        }
-
-    private:
-        CoreSegmentQueryProcessor coreSegmentProcessor;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.cpp
deleted file mode 100644
index 9a2a4405001f0904b74fc6afcf96813eef0879cd..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "ProviderSegmentQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.h
deleted file mode 100644
index e0c6db9e3ef06e6241e9af8c572bb7fc78eec452..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/longtermmemory/ProviderSegmentQueryProcessor.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include "BaseQueryProcessor.h"
-#include "../base/ProviderSegmentQueryProcessorBase.h"
-
-#include "../../../core/longtermmemory/ProviderSegment.h"
-
-#include "EntityQueryProcessor.h"
-
-namespace armarx::armem::ltm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class ProviderSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<ltm::ProviderSegment, armem::query::data::ProviderSegmentQuery>,
-        virtual public base::query_proc::ProviderSegmentQueryProcessorBase<ltm::ProviderSegment>
-    {
-        using Base = BaseQueryProcessor<ltm::ProviderSegment, armem::query::data::ProviderSegmentQuery>;
-
-    public:
-        ProviderSegmentQueryProcessor() :
-            Base()
-        {}
-
-    protected:
-        virtual EntityT entityProcessorProcess(const armem::query::data::EntityQuerySeq& q, const EntityT& s) const override
-        {
-            return entityProcessor.process(q, s);
-        }
-
-    private:
-        EntityQueryProcessor entityProcessor;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/ltm.cpp b/source/RobotAPI/libraries/armem/server/query_proc/ltm.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..238cc4b8d1601bf1ffae131caabbf8ca8435899a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/ltm.cpp
@@ -0,0 +1,7 @@
+#include "ltm.h"
+
+
+namespace armarx::armem::server::query_proc::ltm
+{
+}
+
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/ltm.h b/source/RobotAPI/libraries/armem/server/query_proc/ltm.h
new file mode 100644
index 0000000000000000000000000000000000000000..ae0dc778c821ae138c98b8554a22237bf26e5989
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/ltm.h
@@ -0,0 +1,32 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
+#include <RobotAPI/libraries/armem/server/query_proc/base.h>
+
+
+namespace armarx::armem::server::query_proc::ltm
+{
+    static const base::QueryTarget queryTarget = query::data::QueryTarget::LTM;
+
+
+    class EntityQueryProcessor :
+        public base::EntityQueryProcessorBase<queryTarget, armem::ltm::Entity, armem::ltm::Entity>
+    {
+    };
+
+    class ProviderSegmentQueryProcessor :
+        public base::ProviderSegmentQueryProcessorBase <queryTarget, armem::ltm::ProviderSegment, armem::ltm::ProviderSegment, EntityQueryProcessor >
+    {
+    };
+
+    class CoreSegmentQueryProcessor :
+        public base::CoreSegmentQueryProcessorBase <queryTarget, armem::ltm::CoreSegment, armem::ltm::CoreSegment, ProviderSegmentQueryProcessor>
+    {
+    };
+
+    class MemoryQueryProcessor :
+        public base::MemoryQueryProcessorBase <queryTarget, armem::ltm::Memory, armem::ltm::Memory, CoreSegmentQueryProcessor >
+    {
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp b/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..4e968623d63aa57213507879608c81823d31c7d6
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/wm.cpp
@@ -0,0 +1,70 @@
+#include "wm.h"
+
+
+
+namespace armarx::armem::server::query_proc::wm::detail
+{
+
+    HasDataMode::HasDataMode(armem::DataMode dataMode) : dataMode(dataMode)
+    {
+    }
+
+}
+
+
+namespace armarx::armem::server::query_proc::wm
+{
+
+    ProviderSegmentQueryProcessor::ProviderSegmentQueryProcessor(DataMode dataMode) :
+        ProviderSegmentQueryProcessorBase(dataMode), HasDataMode(dataMode)
+    {
+    }
+
+
+    CoreSegmentQueryProcessor::CoreSegmentQueryProcessor(DataMode dataMode) :
+        CoreSegmentQueryProcessorBase(dataMode), HasDataMode(dataMode)
+    {
+    }
+
+
+    MemoryQueryProcessor::MemoryQueryProcessor(DataMode dataMode) :
+        MemoryQueryProcessorBase(dataMode), HasDataMode(dataMode)
+    {
+    }
+
+}
+
+
+namespace armarx::armem::server::query_proc::wm_server
+{
+    ProviderSegmentQueryProcessor::ProviderSegmentQueryProcessor(DataMode dataMode) :
+        ProviderSegmentQueryProcessorBase(dataMode), HasDataMode(dataMode)
+    {
+    }
+
+
+    CoreSegmentQueryProcessor::CoreSegmentQueryProcessor(DataMode dataMode) :
+        CoreSegmentQueryProcessorBase(dataMode),
+        HasDataMode(dataMode)
+    {
+    }
+
+
+    void CoreSegmentQueryProcessor::process(
+        armem::wm::CoreSegment& result,
+        const armem::query::data::CoreSegmentQuery& query,
+        const CoreSegment& coreSegment) const
+    {
+        std::scoped_lock lock(coreSegment.mutex());
+        CoreSegmentQueryProcessorBase::process(result, query, coreSegment);
+    }
+
+
+    MemoryQueryProcessor::MemoryQueryProcessor(DataMode dataMode) :
+        MemoryQueryProcessorBase(dataMode),
+        HasDataMode(dataMode)
+    {
+    }
+
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/wm.h b/source/RobotAPI/libraries/armem/server/query_proc/wm.h
new file mode 100644
index 0000000000000000000000000000000000000000..aa52b4ab22fe1c6ef194ef37d4e38f5c7720d6c5
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/query_proc/wm.h
@@ -0,0 +1,164 @@
+#pragma once
+
+#include <RobotAPI/libraries/armem/core/DataMode.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/query_proc/base.h>
+
+
+namespace armarx::armem::server::query_proc::wm
+{
+    static const base::QueryTarget queryTarget = query::data::QueryTarget::WM;
+}
+namespace armarx::armem::server::query_proc::wm::detail
+{
+
+    class HasDataMode
+    {
+    public:
+
+        HasDataMode(armem::DataMode dataMode);
+
+
+    protected:
+
+        armem::DataMode dataMode;
+
+    };
+
+
+
+    template <class SourceEntityT>
+    class EntityQueryProcessor :
+        public base::EntityQueryProcessorBase<queryTarget, SourceEntityT, armem::wm::Entity>,
+        public HasDataMode
+    {
+    public:
+
+        EntityQueryProcessor(DataMode dataMode = DataMode::WithData) :
+            HasDataMode(dataMode)
+        {}
+
+
+    protected:
+
+        void addResultSnapshot(armem::wm::Entity& result, const typename SourceEntityT::EntitySnapshotT& snapshot) const
+        {
+            bool withData = (dataMode == DataMode::WithData);
+            if (withData)
+            {
+                result.addSnapshot(server::wm::EntitySnapshot{ snapshot });
+            }
+            else
+            {
+                server::wm::EntitySnapshot copy = snapshot;
+                copy.forEachInstance([](server::wm::EntityInstance & i)
+                {
+                    i.data() = nullptr;
+                    return true;
+                });
+                result.addSnapshot(std::move(copy));
+            }
+        }
+
+    };
+}
+
+
+namespace armarx::armem::server::query_proc::wm
+{
+
+    using EntityQueryProcessor = detail::EntityQueryProcessor<armem::wm::Entity>;
+
+
+    class ProviderSegmentQueryProcessor :
+        public base::ProviderSegmentQueryProcessorBase<queryTarget, armem::wm::ProviderSegment, armem::wm::ProviderSegment, EntityQueryProcessor >,
+        public detail::HasDataMode
+    {
+    public:
+
+        ProviderSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+    };
+
+
+    class CoreSegmentQueryProcessor :
+        public base::CoreSegmentQueryProcessorBase <queryTarget, armem::wm::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor >,
+        public detail::HasDataMode
+    {
+        using Base = base::CoreSegmentQueryProcessorBase<queryTarget, armem::wm::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor>;
+        using CoreSegment = armem::wm::CoreSegment;
+        using ProviderSegment = armem::wm::ProviderSegment;
+
+    public:
+
+        CoreSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+    };
+
+
+    class MemoryQueryProcessor :
+        public base::MemoryQueryProcessorBase<queryTarget, armem::wm::Memory, armem::wm::Memory, CoreSegmentQueryProcessor>,
+        public detail::HasDataMode
+    {
+    public:
+
+        MemoryQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+    };
+
+}
+
+
+namespace armarx::armem::server::query_proc::wm_server
+{
+
+    using EntityQueryProcessor = wm::detail::EntityQueryProcessor<server::wm::Entity>;
+
+
+    class ProviderSegmentQueryProcessor :
+        public base::ProviderSegmentQueryProcessorBase<wm::queryTarget, server::wm::ProviderSegment, armem::wm::ProviderSegment, EntityQueryProcessor >,
+        public wm::detail::HasDataMode
+    {
+    public:
+
+        ProviderSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+    };
+
+
+    class CoreSegmentQueryProcessor :
+        public base::CoreSegmentQueryProcessorBase <wm::queryTarget, server::wm::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor >,
+        public wm::detail::HasDataMode
+    {
+        using Base = base::CoreSegmentQueryProcessorBase<wm::queryTarget, server::wm::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor>;
+        using CoreSegment = server::wm::CoreSegment;
+        using ProviderSegment = server::wm::ProviderSegment;
+
+    public:
+
+        CoreSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+
+        using Base::process;
+
+        /// Locks the core segment, then delegates back to `CoreSegmentQueryProcessorBase`.
+        void process(
+            armem::wm::CoreSegment& result,
+            const armem::query::data::CoreSegmentQuery& query,
+            const CoreSegment& coreSegment) const override;
+
+    };
+
+
+    class MemoryQueryProcessor :
+        public base::MemoryQueryProcessorBase<wm::queryTarget, server::wm::Memory, armem::wm::Memory, CoreSegmentQueryProcessor>,
+        public wm::detail::HasDataMode
+    {
+    public:
+
+        MemoryQueryProcessor(DataMode dataMode = DataMode::WithData);
+
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.cpp
deleted file mode 100644
index 68821bcd95cdf2aaccf7126d4055495d39d0393d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "BaseQueryProcessor.h"
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.h
deleted file mode 100644
index d4875053c93dc2278cdb9f327fc0739370811fe7..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/BaseQueryProcessor.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#pragma once
-
-#include <RobotAPI/interface/armem/query.h>
-#include <RobotAPI/libraries/armem/core/DataMode.h>
-
-#include <RobotAPI/libraries/armem/server/query_proc/base/BaseQueryProcessorBase.h>
-
-
-namespace armarx::armem::wm::query_proc
-{
-    /**
-     * @brief Base class for memory query processors.
-     */
-    template <class DataT, class QueryT>
-    class BaseQueryProcessor :
-        virtual public base::query_proc::BaseQueryProcessorBase<DataT, QueryT>
-    {
-        using Base = base::query_proc::BaseQueryProcessorBase<DataT, QueryT>;
-
-    public:
-
-        BaseQueryProcessor(DataMode dataMode = DataMode::WithData) :
-            dataMode(dataMode)
-        {}
-
-
-    protected:
-
-        query::data::QueryTarget getTargetType() const override
-        {
-            return query::data::QueryTarget::WM;
-        }
-
-        DataMode dataMode;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.cpp
deleted file mode 100644
index 4c41f16664af134b66b00355080d8de362d7eaf9..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1,39 +0,0 @@
-#include "CoreSegmentQueryProcessor.h"
-
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
-
-
-namespace armarx::armem::wm::query_proc
-{
-
-    CoreSegmentQueryProcessor::CoreSegmentQueryProcessor(DataMode dataMode) :
-        Base(dataMode), providerSegmentProcessor(dataMode)
-    {}
-
-
-    CoreSegmentQueryProcessor::~CoreSegmentQueryProcessor() = default;
-
-
-    void CoreSegmentQueryProcessor::process(
-        CoreSegment& result, const armem::query::data::CoreSegmentQuery& query, const CoreSegment& coreSegment) const
-    {
-        std::scoped_lock lock(coreSegment.mutex());
-        CoreSegmentQueryProcessorBase::process(result, query, coreSegment);
-    }
-
-
-    data::CoreSegment CoreSegmentQueryProcessor::processToIce(const armem::query::data::CoreSegmentQuery& query, const wm::CoreSegment& coreSegment) const
-    {
-        data::CoreSegment data;
-        toIce(data, process(query, coreSegment));
-        return data;
-    }
-
-
-    ProviderSegment CoreSegmentQueryProcessor::providerSegmentProcessorProcess(const armem::query::data::ProviderSegmentQuerySeq& q, const ProviderSegment& s) const
-    {
-        return providerSegmentProcessor.process(q, s);
-    }
-
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.h
deleted file mode 100644
index f9e1d59c9f75866e3817440bb163ec5789c0f359..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/CoreSegmentQueryProcessor.h
+++ /dev/null
@@ -1,48 +0,0 @@
-#pragma once
-
-#include <mutex>
-
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
-#include <RobotAPI/libraries/armem/server/query_proc/base/CoreSegmentQueryProcessorBase.h>
-
-#include "BaseQueryProcessor.h"
-#include "ProviderSegmentQueryProcessor.h"
-
-
-namespace armarx::armem::wm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class CoreSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<wm::CoreSegment, armem::query::data::CoreSegmentQuery>,
-        virtual public base::query_proc::CoreSegmentQueryProcessorBase<wm::CoreSegment>
-    {
-        using Base = BaseQueryProcessor<wm::CoreSegment, armem::query::data::CoreSegmentQuery>;
-
-    public:
-
-        CoreSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
-        virtual ~CoreSegmentQueryProcessor() override;
-
-        using Base::process;
-
-        /// Locks the core segment, then delegates back to `CoreSegmentQueryProcessorBase`.
-        void process(CoreSegment& result,
-                     const armem::query::data::CoreSegmentQuery& query,
-                     const CoreSegment& coreSegment) const override;
-
-        data::CoreSegment processToIce(const armem::query::data::CoreSegmentQuery& query, const wm::CoreSegment& coreSegment) const;
-
-
-    protected:
-
-        virtual ProviderSegment providerSegmentProcessorProcess(const armem::query::data::ProviderSegmentQuerySeq& q, const ProviderSegmentT& s) const override;
-
-
-    private:
-
-        ProviderSegmentQueryProcessor providerSegmentProcessor;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.cpp
deleted file mode 100644
index 005649b8f670586f16177f90a43c6e0f48b3879d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.cpp
+++ /dev/null
@@ -1,43 +0,0 @@
-#include "EntityQueryProcessor.h"
-
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
-
-
-namespace armarx::armem::wm::query_proc
-{
-    EntityQueryProcessor::EntityQueryProcessor(DataMode dataMode) :
-        BaseQueryProcessor<wm::Entity, armem::query::data::EntityQuery>(dataMode)
-    {}
-
-
-    EntityQueryProcessor::~EntityQueryProcessor() = default;
-
-
-    void EntityQueryProcessor::addResultSnapshot(wm::Entity& result, const wm::EntitySnapshot& snapshot) const
-    {
-        bool withData = (dataMode == DataMode::WithData);
-        if (withData)
-        {
-            result.addSnapshot(snapshot.copy());
-        }
-        else
-        {
-            result.addSnapshot(snapshot.copyWithoutData());
-        }
-    }
-
-
-    data::Entity EntityQueryProcessor::processToIce(const armem::query::data::EntityQuery& query, const wm::Entity& entity) const
-    {
-        data::Entity data;
-        toIce(data, process(query, entity));
-        return data;
-    }
-
-
-    void EntityQueryProcessor::addResultSnapshot(wm::Entity& result, wm::Entity::ContainerT::const_iterator it) const
-    {
-        addResultSnapshot(result, it->second);
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.h
deleted file mode 100644
index dde53a8ff3393dde385ccc49aa937fcf196476d0..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/EntityQueryProcessor.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/workingmemory/Entity.h>
-#include <RobotAPI/libraries/armem/server/query_proc/base/EntityQueryProcessorBase.h>
-
-#include "BaseQueryProcessor.h"
-
-
-namespace armarx::armem::wm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class EntityQueryProcessor :
-        virtual public BaseQueryProcessor<wm::Entity, armem::query::data::EntityQuery>,
-        virtual public base::query_proc::EntityQueryProcessorBase<wm::Entity>
-    {
-        using Base = BaseQueryProcessor<wm::Entity, armem::query::data::EntityQuery>;
-
-    public:
-
-        EntityQueryProcessor(DataMode dataMode = DataMode::WithData);
-        virtual ~EntityQueryProcessor() override;
-
-        data::Entity processToIce(const armem::query::data::EntityQuery& query, const wm::Entity& entity) const;
-
-
-    private:
-
-        void addResultSnapshot(wm::Entity& result, wm::Entity::ContainerT::const_iterator it) const override;
-        void addResultSnapshot(wm::Entity& result, const wm::EntitySnapshot& snapshot) const override;
-
-    };
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.cpp
deleted file mode 100644
index 7aa868af13bc525b42d93f230a8398c27531525d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.cpp
+++ /dev/null
@@ -1,22 +0,0 @@
-#include "MemoryQueryProcessor.h"
-
-
-namespace armarx::armem::wm::query_proc
-{
-
-    MemoryQueryProcessor::MemoryQueryProcessor(DataMode dataMode) :
-        Base(dataMode), coreSegmentProcessor(dataMode)
-    {}
-
-
-    MemoryQueryProcessor::~MemoryQueryProcessor()
-    {
-    }
-
-
-    CoreSegment MemoryQueryProcessor::coreSegmentProcessorProcess(const armem::query::data::CoreSegmentQuerySeq& q, const CoreSegment& s) const
-    {
-        return coreSegmentProcessor.process(q, s);
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.h
deleted file mode 100644
index c57eea94a464a2e2191e614b5f1d6095d716405a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.h
+++ /dev/null
@@ -1,39 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/server/query_proc/base/MemoryQueryProcessorBase.h>
-
-#include "BaseQueryProcessor.h"
-
-#include "CoreSegmentQueryProcessor.h"
-
-
-namespace armarx::armem::wm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class MemoryQueryProcessor :
-        virtual public BaseQueryProcessor<wm::Memory, armem::query::data::MemoryQuery>,
-        virtual public base::query_proc::MemoryQueryProcessorBase<wm::Memory>
-    {
-        using Base = BaseQueryProcessor<wm::Memory, armem::query::data::MemoryQuery>;
-
-    public:
-
-        MemoryQueryProcessor(DataMode dataMode = DataMode::WithData);
-        virtual ~MemoryQueryProcessor() override;
-
-
-    protected:
-
-        virtual CoreSegment coreSegmentProcessorProcess(
-            const armem::query::data::CoreSegmentQuerySeq& q, const CoreSegment& s) const override;
-
-
-    private:
-
-        CoreSegmentQueryProcessor coreSegmentProcessor;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.cpp b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.cpp
deleted file mode 100644
index eb2524631b4c1d2fb89eb3e7c36a3aaf86f31e29..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.cpp
+++ /dev/null
@@ -1,30 +0,0 @@
-#include "ProviderSegmentQueryProcessor.h"
-
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
-
-
-namespace armarx::armem::wm::query_proc
-{
-
-    ProviderSegmentQueryProcessor::ProviderSegmentQueryProcessor(DataMode dataMode) :
-        Base(dataMode), entityProcessor(dataMode)
-    {}
-
-
-    ProviderSegmentQueryProcessor::~ProviderSegmentQueryProcessor() = default;
-
-
-    data::ProviderSegment ProviderSegmentQueryProcessor::processToIce(const armem::query::data::ProviderSegmentQuery& query, const wm::ProviderSegment& providerSegment) const
-    {
-        data::ProviderSegment data;
-        toIce(data, process(query, providerSegment));
-        return data;
-    }
-
-
-    Entity ProviderSegmentQueryProcessor::entityProcessorProcess(const armem::query::data::EntityQuerySeq& q, const Entity& s) const
-    {
-        return entityProcessor.process(q, s);
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.h b/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.h
deleted file mode 100644
index 8e4f5a5e85d6c3c7f58433a0c2ddcd50074c7d7e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/query_proc/workingmemory/ProviderSegmentQueryProcessor.h
+++ /dev/null
@@ -1,40 +0,0 @@
-#pragma once
-
-#include <RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h>
-#include <RobotAPI/libraries/armem/server/query_proc/base/ProviderSegmentQueryProcessorBase.h>
-
-#include "BaseQueryProcessor.h"
-#include "EntityQueryProcessor.h"
-
-
-namespace armarx::armem::wm::query_proc
-{
-    /**
-     * @brief Handles memory queries.
-     */
-    class ProviderSegmentQueryProcessor :
-        virtual public BaseQueryProcessor<wm::ProviderSegment, armem::query::data::ProviderSegmentQuery>,
-        virtual public base::query_proc::ProviderSegmentQueryProcessorBase<wm::ProviderSegment>
-    {
-        using Base = BaseQueryProcessor<wm::ProviderSegment, armem::query::data::ProviderSegmentQuery>;
-
-    public:
-
-        ProviderSegmentQueryProcessor(DataMode dataMode = DataMode::WithData);
-        virtual ~ProviderSegmentQueryProcessor() override;
-
-
-        using Base::process;
-        data::ProviderSegment processToIce(const armem::query::data::ProviderSegmentQuery& query, const wm::ProviderSegment& providerSegment) const;
-
-
-    protected:
-
-        virtual Entity entityProcessorProcess(const armem::query::data::EntityQuerySeq& q, const Entity& s) const override;
-
-    private:
-
-        EntityQueryProcessor entityProcessor;
-
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/segment/Segment.cpp b/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
index ec25ce7843a6cca3555dc9789f3570e0bfb51425..050e77d392da77bc5c4e4edfcf11f76ee6e1e051 100644
--- a/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
+++ b/source/RobotAPI/libraries/armem/server/segment/Segment.cpp
@@ -1 +1,109 @@
 #include "Segment.h"
+
+#include <ArmarXCore/core/application/properties/PluginAll.h>
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+
+#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
+#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
+
+
+namespace armarx::armem::server::segment
+{
+
+    wm::CoreSegmentBase::CoreSegmentBase(
+        armem::server::MemoryToIceAdapter& iceMemory,
+        const std::string& defaultCoreSegmentName,
+        aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType,
+        int defaultMaxHistorySize) :
+        Base(iceMemory),
+        p({defaultCoreSegmentName, defaultMaxHistorySize}),
+    coreSegmentAronType(coreSegmentAronType)
+    {
+        Logging::setTag("armarx::armem::wm::Segment");
+    }
+
+
+    wm::CoreSegmentBase::~CoreSegmentBase()
+    {
+    }
+
+
+    void wm::CoreSegmentBase::defineProperties(
+        armarx::PropertyDefinitionsPtr defs,
+        const std::string& prefix)
+    {
+        ARMARX_CHECK_NOT_NULL(defs);
+
+        defs->optional(p.coreSegmentName, prefix + "CoreSegmentName", "Name of the '" + p.coreSegmentName + "' core segment.");
+        defs->optional(p.maxHistorySize, prefix + "MaxHistorySize", "Maximal size of '" + p.coreSegmentName + "' history (-1 for infinite).");
+    }
+
+
+    void wm::CoreSegmentBase::onInit()
+    {
+        ARMARX_CHECK_NOT_NULL(iceMemory.workingMemory);
+
+        segment = &iceMemory.workingMemory->addCoreSegment(p.coreSegmentName, coreSegmentAronType);
+        segment->setMaxHistorySize(p.maxHistorySize);
+    }
+
+
+    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,
+        aron::typenavigator::ObjectNavigatorPtr providerSegmentAronType,
+        const std::string& defaultCoreSegmentName,
+        aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType,
+        int defaultMaxHistorySize) :
+
+        Base(iceMemory),
+        p({defaultCoreSegmentName, defaultProviderSegmentName, defaultMaxHistorySize}),
+    coreSegmentAronType(coreSegmentAronType),
+    providerSegmentAronType(providerSegmentAronType)
+    {
+        Logging::setTag("armarx::armem::wm::Segment");
+    }
+
+
+    wm::ProviderSegmentBase::~ProviderSegmentBase()
+    {
+    }
+
+
+    void wm::ProviderSegmentBase::defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix)
+    {
+        ARMARX_CHECK_NOT_NULL(defs);
+
+        defs->optional(p.coreSegmentName, prefix + "CoreSegmentName", "Name of the '" + p.coreSegmentName + "' core segment.");
+        defs->optional(p.providerSegmentName, prefix + "ProviderSegmentName", "Name of the '" + p.providerSegmentName + "' provider segment.");
+        defs->optional(p.maxHistorySize, prefix + "MaxHistorySize", "Maximal size of '" + p.providerSegmentName + "' history (-1 for infinite).");
+    }
+
+
+    void wm::ProviderSegmentBase::onInit()
+    {
+        ARMARX_CHECK_NOT_NULL(iceMemory.workingMemory);
+
+        if (!iceMemory.workingMemory->hasCoreSegment(p.coreSegmentName))
+        {
+            coreSegment = &iceMemory.workingMemory->addCoreSegment(p.coreSegmentName, coreSegmentAronType);
+            coreSegment->setMaxHistorySize(p.maxHistorySize);
+        }
+        else
+        {
+            coreSegment = &iceMemory.workingMemory->getCoreSegment(p.coreSegmentName);
+        }
+
+        segment = &coreSegment->addProviderSegment(p.providerSegmentName, providerSegmentAronType);
+        segment->setMaxHistorySize(p.maxHistorySize);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/segment/Segment.h b/source/RobotAPI/libraries/armem/server/segment/Segment.h
index 6cd9761f89e50ea1e23ce75b27263242e0fe4f29..7808e99d31f4df3543bfbd5b882a408dda143ed5 100644
--- a/source/RobotAPI/libraries/armem/server/segment/Segment.h
+++ b/source/RobotAPI/libraries/armem/server/segment/Segment.h
@@ -6,12 +6,24 @@
 
 // ArmarX
 #include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/application/properties/PluginAll.h>
-#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+#include <ArmarXCore/core/application/properties/forward_declarations.h>
 
-#include "../MemoryToIceAdapter.h"
+#include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h>
 
 
+namespace armarx::armem
+{
+    namespace server
+    {
+        class MemoryToIceAdapter;
+
+        namespace wm
+        {
+            class CoreSegment;
+            class ProviderSegment;
+        }
+    }
+}
 namespace armarx::armem::server::segment
 {
     namespace detail
@@ -25,8 +37,9 @@ namespace armarx::armem::server::segment
         class SegmentBase : public armarx::Logging
         {
         public:
+
             SegmentBase() = delete;
-            SegmentBase(armem::server::MemoryToIceAdapter& iceMemory) :
+            SegmentBase(MemoryToIceAdapter& iceMemory) :
                 iceMemory(iceMemory)
             {
                 Logging::setTag("armarx::armem::Segment");
@@ -36,69 +49,50 @@ namespace armarx::armem::server::segment
 
             virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") = 0;
             virtual void onInit() = 0;
-            virtual void onConnect() = 0;
+            // virtual void onConnect() = 0;
+
 
         protected:
+
             // Memory connection
-            armem::server::MemoryToIceAdapter& iceMemory;
+            MemoryToIceAdapter& iceMemory;
 
             SegmentType* segment;
 
-        private:
         };
     }
 
+
     namespace wm
     {
         /**
          * @brief A base class for core segments
          */
-        class CoreSegmentBase : public detail::SegmentBase<armarx::armem::wm::CoreSegment>
+        class CoreSegmentBase : public detail::SegmentBase<server::wm::CoreSegment>
         {
-            using Base = detail::SegmentBase<armarx::armem::wm::CoreSegment>;
+            using Base = detail::SegmentBase<server::wm::CoreSegment>;
 
         public:
-            CoreSegmentBase(armem::server::MemoryToIceAdapter& iceMemory,
-                            const std::string& defaultCoreSegmentName = "",
-                            aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType = nullptr,
-                            int defaultMaxHistorySize = -1):
-                Base(iceMemory),
-                p({defaultCoreSegmentName, defaultMaxHistorySize}),
-            coreSegmentAronType(coreSegmentAronType)
-            {
-                Logging::setTag("armarx::armem::wm::Segment");
-            }
 
-            virtual ~CoreSegmentBase() = default;
+            CoreSegmentBase(
+                MemoryToIceAdapter& iceMemory,
+                const std::string& defaultCoreSegmentName = "",
+                aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType = nullptr,
+                int defaultMaxHistorySize = -1);
 
-            virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override
-            {
-                ARMARX_CHECK_NOT_NULL(defs);
+            virtual ~CoreSegmentBase() override;
 
-                defs->optional(p.coreSegmentName, prefix + "CoreSegmentName", "Name of the '" + p.coreSegmentName + "' core segment.");
-                defs->optional(p.maxHistorySize, prefix + "MaxHistorySize", "Maximal size of '" + p.coreSegmentName + "' history (-1 for infinite).");
-            }
 
-            virtual void onInit() override
-            {
-                ARMARX_CHECK_NOT_NULL(iceMemory.workingMemory);
+            virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override;
+            virtual void onInit() override;
+            // virtual void onConnect() override;
 
-                segment = &iceMemory.workingMemory->addCoreSegment(p.coreSegmentName, coreSegmentAronType);
-                segment->setMaxHistorySize(p.maxHistorySize);
-            }
-
-            virtual void onConnect() override
-            {
 
-            }
+            std::mutex& mutex() const;
 
-            std::mutex& mutex() const
-            {
-                ARMARX_CHECK_NOT_NULL(segment);
-                return segment->mutex();
-            }
 
         protected:
+
             struct Properties
             {
                 std::string coreSegmentName;
@@ -107,66 +101,37 @@ namespace armarx::armem::server::segment
             Properties p;
 
             aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType;
+
         };
 
 
         /**
          * @brief A base class for provider segments
          */
-        class ProviderSegmentBase : public detail::SegmentBase<armarx::armem::wm::ProviderSegment>
+        class ProviderSegmentBase : public detail::SegmentBase<server::wm::ProviderSegment>
         {
-            using Base = detail::SegmentBase<armarx::armem::wm::ProviderSegment>;
+            using Base = detail::SegmentBase<server::wm::ProviderSegment>;
 
         public:
-            ProviderSegmentBase(armem::server::MemoryToIceAdapter& iceMemory,
-                                const std::string& defaultProviderSegmentName = "",
-                                aron::typenavigator::ObjectNavigatorPtr providerSegmentAronType = nullptr,
-                                const std::string& defaultCoreSegmentName = "",
-                                aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType = nullptr,
-                                int defaultMaxHistorySize = -1):
-                Base(iceMemory),
-                p({defaultCoreSegmentName, defaultProviderSegmentName, defaultMaxHistorySize}),
-            coreSegmentAronType(coreSegmentAronType),
-            providerSegmentAronType(providerSegmentAronType)
-            {
-                Logging::setTag("armarx::armem::wm::Segment");
-            }
 
-            virtual ~ProviderSegmentBase() = default;
+            ProviderSegmentBase(
+                MemoryToIceAdapter& iceMemory,
+                const std::string& defaultProviderSegmentName = "",
+                aron::typenavigator::ObjectNavigatorPtr providerSegmentAronType = nullptr,
+                const std::string& defaultCoreSegmentName = "",
+                aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType = nullptr,
+                int defaultMaxHistorySize = -1);
 
-            virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override
-            {
-                ARMARX_CHECK_NOT_NULL(defs);
+            virtual ~ProviderSegmentBase() override;
 
-                defs->optional(p.coreSegmentName, prefix + "CoreSegmentName", "Name of the '" + p.coreSegmentName + "' core segment.");
-                defs->optional(p.providerSegmentName, prefix + "ProviderSegmentName", "Name of the '" + p.providerSegmentName + "' provider segment.");
-                defs->optional(p.maxHistorySize, prefix + "MaxHistorySize", "Maximal size of '" + p.providerSegmentName + "' history (-1 for infinite).");
-            }
 
-            virtual void onInit() override
-            {
-                ARMARX_CHECK_NOT_NULL(iceMemory.workingMemory);
-
-                if (!iceMemory.workingMemory->hasCoreSegment(p.coreSegmentName))
-                {
-                    coreSegment = &iceMemory.workingMemory->addCoreSegment(p.coreSegmentName, coreSegmentAronType);
-                    coreSegment->setMaxHistorySize(p.maxHistorySize);
-                }
-                else
-                {
-                    coreSegment = &iceMemory.workingMemory->getCoreSegment(p.coreSegmentName);
-                }
-
-                segment = &coreSegment->addProviderSegment(p.providerSegmentName, providerSegmentAronType);
-                segment->setMaxHistorySize(p.maxHistorySize);
-            }
+            virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override;
+            virtual void onInit() override;
+            // virtual void onConnect() override;
 
-            virtual void onConnect() override
-            {
-
-            }
 
         protected:
+
             struct Properties
             {
                 std::string coreSegmentName;
@@ -178,10 +143,11 @@ namespace armarx::armem::server::segment
             aron::typenavigator::ObjectNavigatorPtr coreSegmentAronType;
             aron::typenavigator::ObjectNavigatorPtr providerSegmentAronType;
 
-            armarx::armem::wm::CoreSegment* coreSegment;
+            server::wm::CoreSegment* coreSegment;
         };
 
 
+
         /**
          * @brief A base class for provider segments with an aron business object
          */
@@ -191,10 +157,13 @@ namespace armarx::armem::server::segment
             using Base = CoreSegmentBase;
 
         public:
-            AronTypedCoreSegmentBase(armem::server::MemoryToIceAdapter& iceMemory,
-                                     const std::string& defaultCoreSegmentName = "",
-                                     int defaultMaxHistorySize = -1):
-                Base(iceMemory, defaultCoreSegmentName, BusinessClassObject::toAronType(), defaultMaxHistorySize)
+
+            AronTypedCoreSegmentBase(
+                MemoryToIceAdapter& iceMemory,
+                const std::string& defaultCoreSegmentName = "",
+                int defaultMaxHistorySize = -1) :
+                Base(iceMemory, defaultCoreSegmentName, BusinessClassObject::toAronType(),
+                     defaultMaxHistorySize)
             {
             }
 
@@ -202,6 +171,7 @@ namespace armarx::armem::server::segment
         };
 
 
+
         /**
          * @brief A base class for provider segments with an aron business object
          */
@@ -211,15 +181,19 @@ namespace armarx::armem::server::segment
             using Base = ProviderSegmentBase;
 
         public:
-            AronTypedProviderSegmentBase(armem::server::MemoryToIceAdapter& iceMemory,
-                                         const std::string& defaultProviderSegmentName = "",
-                                         const std::string& defaultCoreSegmentName = "",
-                                         int defaultMaxHistorySize = -1):
-                Base(iceMemory, defaultProviderSegmentName, BusinessClassObject::toAronType(), defaultCoreSegmentName, nullptr, defaultMaxHistorySize)
+
+            AronTypedProviderSegmentBase(
+                MemoryToIceAdapter& iceMemory,
+                const std::string& defaultProviderSegmentName = "",
+                const std::string& defaultCoreSegmentName = "",
+                int defaultMaxHistorySize = -1) :
+                Base(iceMemory, defaultProviderSegmentName, BusinessClassObject::toAronType(),
+                     defaultCoreSegmentName, nullptr, defaultMaxHistorySize)
             {
             }
 
             virtual ~AronTypedProviderSegmentBase() = default;
+
         };
     }
 }
diff --git a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
index fd3a456c55d785471e86a0d3f1e12a5491d3e32c..460fbf3f0f0cd4ea6c2835d499071f2e43bf2a7d 100644
--- a/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
+++ b/source/RobotAPI/libraries/armem/server/segment/SpecializedSegment.h
@@ -6,21 +6,19 @@
 #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::aron::typenavigator
-{
-    using ObjectNavigatorPtr = std::shared_ptr<class ObjectNavigator>;
-}
 namespace armarx::armem
 {
     namespace server
     {
         class MemoryToIceAdapter;
-    }
 
-    namespace wm
-    {
-        class CoreSegment;
+        namespace wm
+        {
+            class CoreSegment;
+        }
     }
 }
 
@@ -31,15 +29,15 @@ namespace armarx::armem::server::segment
      * @brief Specialized management of a core segment.
      */
     class SpecializedSegment :
-            public armarx::Logging
+        public armarx::Logging
     {
     public:
 
         SpecializedSegment(
-                server::MemoryToIceAdapter& iceMemory,
-                aron::typenavigator::ObjectNavigatorPtr aronType = nullptr,
-                const std::string& defaultCoreSegmentName = "",
-                int64_t defaultMaxHistorySize = -1);
+            server::MemoryToIceAdapter& iceMemory,
+            aron::typenavigator::ObjectNavigatorPtr aronType = nullptr,
+            const std::string& defaultCoreSegmentName = "",
+            int64_t defaultMaxHistorySize = -1);
 
         virtual ~SpecializedSegment();
 
@@ -61,7 +59,7 @@ namespace armarx::armem::server::segment
     protected:
 
         server::MemoryToIceAdapter& iceMemory;
-        wm::CoreSegment* coreSegment = nullptr;
+        server::wm::CoreSegment* coreSegment = nullptr;
         aron::typenavigator::ObjectNavigatorPtr aronType;
 
         struct Properties
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/MaxHistorySize.cpp b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.cpp
similarity index 72%
rename from source/RobotAPI/libraries/armem/core/base/detail/MaxHistorySize.cpp
rename to source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.cpp
index 2c3b0554c65523826db0a7709599ed8e5140e0a1..d90756691871b6ad444a67fa76a733d0086b5b29 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/MaxHistorySize.cpp
+++ b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.cpp
@@ -1,12 +1,8 @@
 #include "MaxHistorySize.h"
 
 
-namespace armarx::armem::base::detail
+namespace armarx::armem::server::detail
 {
-    MaxHistorySize::~MaxHistorySize()
-    {
-    }
-
     void MaxHistorySize::setMaxHistorySize(long maxSize)
     {
         this->_maxHistorySize = maxSize;
diff --git a/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h
new file mode 100644
index 0000000000000000000000000000000000000000..e2f2d498c2945f4456c281abafe0f1ad66074e72
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/wm/detail/MaxHistorySize.h
@@ -0,0 +1,58 @@
+#pragma once
+
+
+namespace armarx::armem::server::detail
+{
+    // TODO: Replace by ConstrainedHistorySize (not only max entries, e.g. delete oldest / delete least accessed / ...)
+
+    class MaxHistorySize
+    {
+    public:
+
+        /**
+         * @brief Set the maximum number of snapshots to be contained in an entity.
+         * Affected entities are to be update right away.
+         */
+        void setMaxHistorySize(long maxSize);
+
+        long getMaxHistorySize() const;
+
+
+    protected:
+
+        /**
+         * @brief Maximum size of entity histories.
+         *
+         * If negative, the size of `history` is not limited.
+         *
+         * @see Entity::maxHstorySize
+         */
+        long _maxHistorySize = -1;
+
+    };
+
+
+
+    template <class DerivedT>
+    class MaxHistorySizeParent : public MaxHistorySize
+    {
+    public:
+
+        /**
+         * @brief Sets the maximum history size of entities in this container.
+         * This affects all current entities as well as new ones.
+         *
+         * @see MaxHistorySize::setMaxHistorySize()
+         */
+        void setMaxHistorySize(long maxSize)
+        {
+            MaxHistorySize::setMaxHistorySize(maxSize);
+            static_cast<DerivedT&>(*this).forEachChild([maxSize](auto & child)
+            {
+                child.setMaxHistorySize(maxSize);
+                return true;
+            });
+        }
+
+    };
+}
diff --git a/source/RobotAPI/libraries/armem/server/wm/ice_conversions.cpp b/source/RobotAPI/libraries/armem/server/wm/ice_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..1ba3352d6e8bb443693ebfa5752a46cad9c24267
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/wm/ice_conversions.cpp
@@ -0,0 +1,64 @@
+#include "ice_conversions.h"
+
+#include <RobotAPI/libraries/armem/core/base/ice_conversions.h>
+
+
+namespace armarx::armem::server
+{
+
+    void wm::toIce(data::EntityInstance& ice, const EntityInstance& data)
+    {
+        base::toIce(ice, data);
+    }
+    void wm::fromIce(const data::EntityInstance& ice, EntityInstance& data)
+    {
+        base::fromIce(ice, data);
+    }
+
+
+    void wm::toIce(data::EntitySnapshot& ice, const EntitySnapshot& snapshot)
+    {
+        base::toIce(ice, snapshot);
+    }
+    void wm::fromIce(const data::EntitySnapshot& ice, EntitySnapshot& snapshot)
+    {
+        base::fromIce(ice, snapshot);
+    }
+
+    void wm::toIce(data::Entity& ice, const Entity& entity)
+    {
+        base::toIce(ice, entity);
+    }
+    void wm::fromIce(const data::Entity& ice, Entity& entity)
+    {
+        base::fromIce(ice, entity);
+    }
+
+    void wm::toIce(data::ProviderSegment& ice, const ProviderSegment& providerSegment)
+    {
+        base::toIce(ice, providerSegment);
+    }
+    void wm::fromIce(const data::ProviderSegment& ice, ProviderSegment& providerSegment)
+    {
+        base::fromIce(ice, providerSegment);
+    }
+
+    void wm::toIce(data::CoreSegment& ice, const CoreSegment& coreSegment)
+    {
+        base::toIce(ice, coreSegment);
+    }
+    void wm::fromIce(const data::CoreSegment& ice, CoreSegment& coreSegment)
+    {
+        base::fromIce(ice, coreSegment);
+    }
+
+    void wm::toIce(data::Memory& ice, const Memory& memory)
+    {
+        base::toIce(ice, memory);
+    }
+    void wm::fromIce(const data::Memory& ice, Memory& memory)
+    {
+        base::fromIce(ice, memory);
+    }
+
+}
diff --git a/source/RobotAPI/libraries/armem/server/wm/ice_conversions.h b/source/RobotAPI/libraries/armem/server/wm/ice_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..c25b16775bc577c61d0c804cf4525b23ecd5e5d1
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/wm/ice_conversions.h
@@ -0,0 +1,30 @@
+#pragma once
+
+#include <RobotAPI/interface/armem/memory.h>
+
+#include "memory_definitions.h"
+
+
+namespace armarx::armem::server::wm
+{
+
+    void toIce(data::EntityInstance& ice, const EntityInstance& data);
+    void fromIce(const data::EntityInstance& ice, EntityInstance& data);
+
+
+    void toIce(data::EntitySnapshot& ice, const EntitySnapshot& snapshot);
+    void fromIce(const data::EntitySnapshot& ice, EntitySnapshot& snapshot);
+
+    void toIce(data::Entity& ice, const Entity& entity);
+    void fromIce(const data::Entity& ice, Entity& entity);
+
+
+    void toIce(data::ProviderSegment& ice, const ProviderSegment& providerSegment);
+    void fromIce(const data::ProviderSegment& ice, ProviderSegment& providerSegment);
+
+    void toIce(data::CoreSegment& ice, const CoreSegment& coreSegment);
+    void fromIce(const data::CoreSegment& ice, CoreSegment& coreSegment);
+
+    void toIce(data::Memory& ice, const Memory& memory);
+    void fromIce(const data::Memory& ice, Memory& memory);
+}
diff --git a/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..58be8027db2561979d3510b7d481715678b61eae
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.cpp
@@ -0,0 +1,202 @@
+#include "memory_definitions.h"
+
+#include "error.h"
+
+#include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <map>
+#include <vector>
+
+
+namespace armarx::armem::server::wm
+{
+
+    void Entity::setMaxHistorySize(long maxSize)
+    {
+        MaxHistorySize::setMaxHistorySize(maxSize);
+        truncate();
+    }
+
+
+    auto Entity::update(const EntityUpdate& update) -> UpdateResult
+    {
+        UpdateResult result = EntityBase::update(update);
+        result.removedSnapshots = this->truncate();
+        return result;
+    }
+
+
+    std::vector<EntitySnapshot> Entity::truncate()
+    {
+        std::vector<EntitySnapshot> removedElements;
+        if (_maxHistorySize >= 0)
+        {
+            while (this->_container.size() > size_t(_maxHistorySize))
+            {
+                removedElements.push_back(std::move(this->_container.begin()->second));
+                this->_container.erase(this->_container.begin());
+            }
+            ARMARX_CHECK_LESS_EQUAL(this->_container.size(), _maxHistorySize);
+        }
+        return removedElements;
+    }
+
+
+
+    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)
+    {
+        // Group updates by core segment, then update each core segment in a batch to only lock it once.
+        std::map<std::string, std::vector<const EntityUpdate*>> updatesPerCoreSegment;
+        for (const EntityUpdate& update : commit.updates)
+        {
+            updatesPerCoreSegment[update.entityID.coreSegmentName].push_back(&update);
+        }
+
+        std::vector<Memory::Base::UpdateResult> result;
+        // To throw an exception after the commit if a core segment is missing and the memory should not create new ones
+        std::vector<std::string> missingCoreSegmentNames;
+        for (const auto& [coreSegmentName, updates] : updatesPerCoreSegment)
+        {
+            auto it = this->_container.find(coreSegmentName);
+            if (it != this->_container.end())
+            {
+                CoreSegment& coreSegment = it->second;
+
+                // Lock the core segment for the whole batch.
+                std::scoped_lock lock(coreSegment.mutex());
+
+                for (const EntityUpdate* update : updates)
+                {
+                    auto r = coreSegment.update(*update);
+                    Base::UpdateResult ret { r };
+                    ret.memoryUpdateType = UpdateType::UpdatedExisting;
+                    result.push_back(ret);
+                }
+            }
+            else
+            {
+                // Perform the other updates first, then throw afterwards.
+                missingCoreSegmentNames.push_back(coreSegmentName);
+            }
+        }
+        // Throw an exception if something went wrong.
+        if (not missingCoreSegmentNames.empty())
+        {
+            // Just throw an exception for the first entry. We can extend this exception in the future.
+            throw armem::error::MissingEntry::create<CoreSegment>(missingCoreSegmentNames.front(), *this);
+        }
+        return result;
+    }
+
+
+    // TODO: Add core segment if param is set
+    Memory::Base::UpdateResult
+    Memory::updateLocking(const EntityUpdate& update)
+    {
+        this->_checkContainerName(update.entityID.memoryName, this->name());
+
+        CoreSegment& segment = getCoreSegment(update.entityID.coreSegmentName);
+        Base::UpdateResult result;
+        {
+            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
new file mode 100644
index 0000000000000000000000000000000000000000..4eb6fdbb3105b0ae2ce3148c8457b915040a170a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/wm/memory_definitions.h
@@ -0,0 +1,189 @@
+#pragma once
+
+#include "detail/MaxHistorySize.h"
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.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>
+#include <RobotAPI/libraries/armem/core/base/ProviderSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/base/CoreSegmentBase.h>
+#include <RobotAPI/libraries/armem/core/base/MemoryBase.h>
+
+#include <mutex>
+#include <optional>
+
+
+namespace armarx::armem::server::wm
+{
+    using EntityInstanceMetadata = base::EntityInstanceMetadata;
+    using EntityInstanceData = armarx::aron::datanavigator::DictNavigator;
+    using EntityInstanceDataPtr = armarx::aron::datanavigator::DictNavigatorPtr;
+
+    using EntityInstance = armem::wm::EntityInstance;
+    using EntitySnapshot = armem::wm::EntitySnapshot;
+
+
+    /// @see base::EntityBase
+    class Entity :
+        public base::EntityBase<EntitySnapshot, Entity>,
+        public detail::MaxHistorySize
+    {
+    public:
+
+        using base::EntityBase<EntitySnapshot, Entity>::EntityBase;
+
+
+        /**
+         * @brief Sets the maximum history size.
+         *
+         * The current history is truncated if necessary.
+         */
+        void setMaxHistorySize(long maxSize);
+
+        UpdateResult update(const EntityUpdate& update);
+
+
+    protected:
+
+        /// If maximum size is set, ensure `history`'s is not higher.
+        std::vector<EntitySnapshotT> truncate();
+
+    };
+
+
+
+    /// @see base::ProviderSegmentBase
+    class ProviderSegment :
+        public base::ProviderSegmentBase<Entity, ProviderSegment>,
+        public detail::MaxHistorySizeParent<ProviderSegment>
+    {
+    public:
+
+        using base::ProviderSegmentBase<Entity, ProviderSegment>::ProviderSegmentBase;
+
+
+        using ProviderSegmentBase::addEntity;
+        EntityT& addEntity(EntityT&& entity);
+
+    };
+
+
+
+    /// @brief base::CoreSegmentBase
+    class CoreSegment :
+        public base::CoreSegmentBase<ProviderSegment, CoreSegment>,
+        public detail::MaxHistorySizeParent<CoreSegment>
+    {
+        using Base = base::CoreSegmentBase<ProviderSegment, CoreSegment>;
+
+    public:
+
+        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);
+
+
+        // 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
+        {
+            // 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;
+            }
+        }
+
+
+    protected:
+
+        mutable std::mutex _mutex;
+
+    };
+
+
+
+    /// @see base::MemoryBase
+    class Memory :
+        public base::MemoryBase<CoreSegment, Memory>
+    {
+        using Base = base::MemoryBase<CoreSegment, Memory>;
+
+    public:
+
+        using Base::MemoryBase;
+
+
+        /**
+         * @brief Perform the commit, locking the core segments.
+         *
+         * Groups the commits by core segment, and updates each core segment
+         * in a batch, locking the core segment.
+         */
+        std::vector<Base::UpdateResult> updateLocking(const Commit& commit);
+
+        /**
+         * @brief Update the memory, locking the updated core segment.
+         */
+        Base::UpdateResult updateLocking(const EntityUpdate& update);
+
+    };
+
+}
+
diff --git a/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..cc34f7e2d7cb73d7a3e3715064508c3b73cab351
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
@@ -0,0 +1,187 @@
+/*
+ * 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/Test.h>
+#include <RobotAPI/libraries/armem/core/Commit.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
+#include <iostream>
+#include <set>
+
+
+namespace armem = armarx::armem;
+
+
+template <class ValueT>
+static
+std::vector<ValueT> toVector(const std::set<ValueT>& set)
+{
+    return {set.begin(), set.end()};
+}
+
+
+
+BOOST_AUTO_TEST_CASE(test_forEach)
+{
+    using namespace armarx::armem;
+
+    const MemoryID mid("memory");
+    const std::set<MemoryID> emptySet;  // For comparison.
+
+    wm::Memory memory(mid);
+    std::set<MemoryID> cids, pids, eids, sids, iids;
+
+    for (size_t c = 0; c <= 2; ++c)
+    {
+        const MemoryID cid = mid.withCoreSegmentName("core_" + std::to_string(c));
+        cids.insert(cid);
+        wm::CoreSegment& coreSeg = memory.addCoreSegment(cid.coreSegmentName);
+        for (size_t p = 0; p <= c; ++p)
+        {
+            const MemoryID pid = cid.withProviderSegmentName("prov_" + std::to_string(p));
+            pids.insert(pid);
+            for (size_t e = 0; e <= p; ++e)
+            {
+                const MemoryID eid = pid.withEntityName("entity_" + std::to_string(e));
+                eids.insert(eid);
+                for (size_t s = 0; s <= e; ++s)
+                {
+                    const MemoryID sid = eid.withTimestamp(Time::microSeconds(int(s)));
+                    sids.insert(sid);
+
+                    EntityUpdate update;
+                    update.entityID = eid;
+                    update.timeCreated = sid.timestamp;
+                    for (size_t i = 0; i <= s; ++i)
+                    {
+                        const MemoryID iid = sid.withInstanceIndex(int(i));
+                        iids.insert(iid);
+                        update.instancesData.emplace_back();
+                    }
+                    auto r = memory.update(update);
+
+                    BOOST_CHECK(coreSeg.hasProviderSegment(pid.providerSegmentName));
+                }
+            }
+
+            BOOST_CHECK_EQUAL(coreSeg.size(), p + 1);
+        }
+        BOOST_CHECK_EQUAL(memory.size(), c + 1);
+    }
+
+    BOOST_CHECK_GT(iids.size(), 0);
+    BOOST_CHECK_GT(sids.size(), 0);
+    BOOST_CHECK_GT(eids.size(), 0);
+    BOOST_CHECK_GT(pids.size(), 0);
+    BOOST_CHECK_GT(cids.size(), 0);
+
+    BOOST_TEST_MESSAGE("Memory: \n" << memory.dump());
+
+    memory.forEachInstance([&](const wm::EntityInstance & i) -> bool
+    {
+        BOOST_TEST_CONTEXT(wm::EntityInstance::getLevelName() << " " << i.id())
+        {
+            BOOST_TEST_INFO(toVector(iids));
+            BOOST_CHECK_EQUAL(iids.count(i.id()), 1);
+            iids.erase(i.id());
+        }
+        return true;
+    });
+    BOOST_TEST_CONTEXT(toVector(iids))
+    {
+        BOOST_CHECK_EQUAL(iids.size(), 0);
+    }
+
+    memory.forEachSnapshot([&](const wm::EntitySnapshot & s) -> bool
+    {
+        BOOST_TEST_CONTEXT(wm::EntitySnapshot::getLevelName() << " " << s.id())
+        {
+            BOOST_TEST_INFO(toVector(sids));
+            BOOST_CHECK_EQUAL(sids.count(s.id()), 1);
+            sids.erase(s.id());
+        }
+        return true;
+    });
+    BOOST_TEST_INFO(toVector(sids));
+    BOOST_CHECK_EQUAL(sids.size(), 0);
+
+    memory.forEachEntity([&](const wm::Entity & e) -> bool
+    {
+        BOOST_TEST_CONTEXT(wm::Entity::getLevelName() << " " << e.id())
+        {
+            BOOST_TEST_INFO(toVector(eids));
+            BOOST_CHECK_EQUAL(eids.count(e.id()), 1);
+            eids.erase(e.id());
+        }
+        return true;
+    });
+    BOOST_TEST_INFO(toVector(eids));
+    BOOST_CHECK_EQUAL(eids.size(), 0);
+
+    memory.forEachProviderSegment([&](const wm::ProviderSegment & p)  // -> bool
+    {
+        BOOST_TEST_CONTEXT(wm::ProviderSegment::getLevelName() << " " << p.id())
+        {
+            BOOST_TEST_INFO(toVector(pids));
+            BOOST_CHECK_EQUAL(pids.count(p.id()), 1);
+            pids.erase(p.id());
+        }
+        return true;
+    });
+    BOOST_TEST_INFO(toVector(pids));
+    BOOST_CHECK_EQUAL(pids.size(), 0);
+
+    memory.forEachCoreSegment([&](const wm::CoreSegment & c)  // -> bool
+    {
+        BOOST_TEST_CONTEXT(wm::CoreSegment::getLevelName() << " " << c.id())
+        {
+            BOOST_TEST_INFO(toVector(cids));
+            BOOST_CHECK_EQUAL(cids.count(c.id()), 1);
+            cids.erase(c.id());
+        }
+        return true;
+    });
+    BOOST_TEST_INFO(toVector(cids));
+    BOOST_CHECK_EQUAL(cids.size(), 0);
+
+}
+
+
+BOOST_AUTO_TEST_CASE(test_forEach_non_bool_func)
+{
+    // Check whether this compiles + runs without break.
+
+    armem::wm::Entity entity;
+    entity.addSnapshot(armem::Time::microSeconds(500));
+    entity.addSnapshot(armem::Time::microSeconds(1500));
+
+    int i = 0;
+    entity.forEachSnapshot([&i](const armem::wm::EntitySnapshot&) -> void
+    {
+        ++i;
+    });
+    BOOST_CHECK_EQUAL(i, 2);
+}
diff --git a/source/RobotAPI/libraries/armem/test/ArMemIceConversionsTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemIceConversionsTest.cpp
index a835f39bef74f745b22c4ee167e4755a031fec50..9fd00a4cf944f50cbd1c0d7bd06b9b56d812c161 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemIceConversionsTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemIceConversionsTest.cpp
@@ -25,7 +25,7 @@
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include "../core/workingmemory/ice_conversions.h"
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 
 
 #include <iostream>
@@ -59,12 +59,12 @@ BOOST_AUTO_TEST_CASE(test_entity)
     BOOST_CHECK_EQUAL(ice->id.providerSegmentName, entity.id().providerSegmentName);
     BOOST_CHECK_EQUAL(ice->id.entityName, entity.id().entityName);
 
-    BOOST_CHECK_EQUAL(ice->history.size(), entity.history().size());
+    BOOST_CHECK_EQUAL(ice->history.size(), entity.size());
 
     armem::wm::Entity entityOut;
     armem::fromIce(ice, entityOut);
 
-    BOOST_CHECK_EQUAL(entityOut.history().size(), entity.history().size());
+    BOOST_CHECK_EQUAL(entityOut.size(), entity.size());
 
     std::vector<armem::Time> timestamps = entityOut.getTimestamps();
     BOOST_CHECK_EQUAL_COLLECTIONS(timestamps.begin(), timestamps.end(), expectedTimestamps.begin(), expectedTimestamps.end());
diff --git a/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
index 24c0a22203aae81bfc52802a9f48fbb9755c9c5f..3ac3d50411854022aa31b781ba011e9ac8d91c75 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemLTMTest.cpp
@@ -25,8 +25,8 @@
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include "../core/workingmemory/Memory.h"
-#include "../core/error.h"
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/error.h>
 
 #include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h>
 #include <RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h>
@@ -122,7 +122,7 @@ namespace ArMemLTMTest
                 update.instancesData = q;
                 update.timeCreated = armem::Time::now();
                 BOOST_CHECK_NO_THROW(providerSegment.update(update));
-                BOOST_CHECK_EQUAL(providerSegment.entities().size(), 1);
+                BOOST_CHECK_EQUAL(providerSegment.size(), 1);
             }
             BOOST_CHECK(providerSegment.hasEntity("TestEntity"));
 
diff --git a/source/RobotAPI/libraries/armem/test/ArMemMemoryIDTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemMemoryIDTest.cpp
index aad3359b0d57cfed79d463cc27dcced44550ef00..72f09fb225aa22b50ed55a9482e7f973acbf0fd2 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemMemoryIDTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemMemoryIDTest.cpp
@@ -25,8 +25,8 @@
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include "../core/MemoryID.h"
-#include "../core/error.h"
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/error.h>
 
 #include <iostream>
 
diff --git a/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
index 984c1f8e508ec631527f53d5fdff8ea32081ad6e..376f2ec680f92e64a5c72b496543749a303e8cc1 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemMemoryTest.cpp
@@ -26,7 +26,8 @@
 
 #include <RobotAPI/Test.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#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>
@@ -34,6 +35,7 @@
 #include <iostream>
 #include <SimoxUtility/meta/type_name.h>
 #include <RobotAPI/libraries/aron/core/navigator/data/container/Dict.h>
+#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
 
 
 namespace armem = armarx::armem;
@@ -87,11 +89,11 @@ namespace ArMemMemoryTest
         using MemoryItem::MemoryItem;
         using MemoryItem::operator=;
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return "";
         }
-        std::string getLevelName() const  override
+        std::string getLevelName() const
         {
             return "";
         }
@@ -154,24 +156,29 @@ namespace ArMemMemoryTest
         using MemoryContainerBase::MemoryContainerBase;
         using MemoryContainerBase::operator=;
 
-        std::string getKeyString() const override
+        std::string getKeyString() const
         {
             return "";
         }
-        std::string getLevelName() const  override
+        std::string getLevelName() const
         {
             return "";
         }
+
+        void fill()
+        {
+            _container = std::vector<int> { -1, 2, -3 };
+        }
     };
     struct MemoryContainerCtorOpTestFixture
     {
-        const armem::MemoryID id {"A/B/C/123/1"};
-        const armem::MemoryID moved {"////1"};  // int is not moved
+        const armem::MemoryID id {"M/C/P/E/123/1"};
+        const armem::MemoryID moved {"////123/1"};  // Time and int are just copied, not moved
         TestMemoryContainer cont {id};
 
         MemoryContainerCtorOpTestFixture()
         {
-            cont.container() = std::vector<int> { -1, 2, -3 };
+            cont.fill();
             BOOST_CHECK_EQUAL(cont.id(), id);
             BOOST_CHECK_EQUAL(cont.size(), 3);
         }
@@ -244,17 +251,6 @@ BOOST_AUTO_TEST_CASE(test_key_ctors)
 }
 
 
-template <class ...Args>
-auto add_element(std::vector<Args...>& vector)
-{
-    return vector.emplace_back();
-}
-template <class ...Args>
-auto add_element(std::map<Args...>& map)
-{
-    return map.emplace();
-}
-
 
 template <class T>
 struct CustomChecks
@@ -370,14 +366,17 @@ struct CustomChecks<armem::d_ltm::Memory>
 
 struct CopyMoveCtorsOpsTestBase
 {
-    const armem::MemoryID id {"A/B/C/123000"};  // int index would not be moved
-    const armem::MemoryID idMoved;
+    const armem::MemoryID id {"M", "C", "P", "E", armem::Time::microSeconds(123000), 1};
+    //const armem::MemoryID idMoved {"", "", "", "", armem::Time::microSeconds(123000), 1};
+    armem::MemoryID idMoved = id;
 
     std::string typeName;
 
     CopyMoveCtorsOpsTestBase(const std::string& typeName) :
         typeName(typeName)
     {
+        armem::MemoryID copy = std::move(idMoved);
+        (void) copy;
     }
     virtual ~CopyMoveCtorsOpsTestBase()
     {
@@ -459,21 +458,25 @@ struct InstanceCopyMoveCtorsOpsTest : public CopyMoveCtorsOpsTestBase
     }
     void testMoveCtor() override
     {
+        T copy { in };
         T out { std::move(in) };
 
         BOOST_CHECK_EQUAL(in.id(), idMoved);
         BOOST_CHECK_EQUAL(out.id(), id);
 
+        CustomChecks<T>::checkEqual(out, copy);
         CustomChecks<T>::checkMoved(in);
     }
     void testMoveOp() override
     {
+        T copy { in };
         T out;
         out = std::move(in);
 
         BOOST_CHECK_EQUAL(in.id(), idMoved);
         BOOST_CHECK_EQUAL(out.id(), id);
 
+        CustomChecks<T>::checkEqual(out, copy);
         CustomChecks<T>::checkMoved(in);
     }
 };
@@ -492,7 +495,19 @@ struct CopyMoveCtorsOpsTest : public CopyMoveCtorsOpsTestBase
     void reset() override
     {
         in = T {id};
-        add_element(in.container());
+        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>)
+        {
+            in._addMissingCoreSegmentDuringUpdate = true;
+        }
+        {
+            armem::EntityUpdate update;
+            update.entityID = armem::MemoryID("M", "C", "P", "E", armem::Time::microSeconds(123000), 0);
+            update.timeCreated = update.entityID.timestamp;
+            update.instancesData.emplace_back();
+            in.update(update);
+        }
 
         BOOST_CHECK_EQUAL(in.id(), id);
         BOOST_CHECK_EQUAL(in.size(), 1);
@@ -652,17 +667,17 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
     update.timeCreated = armem::Time::milliSeconds(1000);
     BOOST_CHECK_NO_THROW(providerSegment.update(update));
 
-    BOOST_CHECK_EQUAL(providerSegment.entities().size(), 1);
+    BOOST_CHECK_EQUAL(providerSegment.size(), 1);
     BOOST_CHECK(providerSegment.hasEntity("image"));
     BOOST_CHECK(!providerSegment.hasEntity("other_image"));
 
     armem::wm::Entity& entity = providerSegment.getEntity("image");
     BOOST_CHECK_EQUAL(entity.name(), "image");
-    BOOST_CHECK_EQUAL(entity.history().size(), 1);
-    BOOST_CHECK_EQUAL(entity.history().count(update.timeCreated), 1);
+    BOOST_CHECK_EQUAL(entity.size(), 1);
+    BOOST_CHECK(entity.hasSnapshot(update.timeCreated));
 
-    armem::wm::EntitySnapshot& entitySnapshot = entity.history().at(update.timeCreated);
-    BOOST_CHECK_EQUAL(entitySnapshot.instances().size(), update.instancesData.size());
+    armem::wm::EntitySnapshot& entitySnapshot = entity.getSnapshot(update.timeCreated);
+    BOOST_CHECK_EQUAL(entitySnapshot.size(), update.instancesData.size());
 
 
     // Another update (on memory).
@@ -670,16 +685,16 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
     update.instancesData = { std::make_shared<aron::datanavigator::DictNavigator>() };
     update.timeCreated = armem::Time::milliSeconds(2000);
     memory.update(update);
-    BOOST_CHECK_EQUAL(entity.history().size(), 2);
-    BOOST_CHECK_EQUAL(entity.history().count(update.timeCreated), 1);
-    BOOST_CHECK_EQUAL(entity.history().at(update.timeCreated).instances().size(), update.instancesData.size());
+    BOOST_CHECK_EQUAL(entity.size(), 2);
+    BOOST_CHECK(entity.hasSnapshot(update.timeCreated));
+    BOOST_CHECK_EQUAL(entity.getSnapshot(update.timeCreated).size(), update.instancesData.size());
 
 
     // A third update (on entity).
     update.instancesData = { std::make_shared<aron::datanavigator::DictNavigator>() };
     update.timeCreated = armem::Time::milliSeconds(3000);
     entity.update(update);
-    BOOST_CHECK_EQUAL(entity.history().size(), 3);
+    BOOST_CHECK_EQUAL(entity.size(), 3);
 
 }
 
@@ -687,7 +702,7 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
 
 BOOST_AUTO_TEST_CASE(test_history_size_in_entity)
 {
-    armem::wm::Entity entity("entity");
+    armem::server::wm::Entity entity("entity");
 
     armem::EntityUpdate update;
     update.entityID.entityName = entity.name();
@@ -699,38 +714,38 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_entity)
     entity.update(update);
     update.timeCreated = armem::Time::milliSeconds(3000);
     entity.update(update);
-    BOOST_CHECK_EQUAL(entity.history().size(), 3);
+    BOOST_CHECK_EQUAL(entity.size(), 3);
 
     // Now with maximum history size.
     entity.setMaxHistorySize(2);
-    BOOST_CHECK_EQUAL(entity.history().size(), 2);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(1000)), 0);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(2000)), 1);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(3000)), 1);
+    BOOST_CHECK_EQUAL(entity.size(), 2);
+    BOOST_CHECK(not entity.hasSnapshot(armem::Time::milliSeconds(1000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(2000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(3000)));
 
 
     update.timeCreated = armem::Time::milliSeconds(4000);
     entity.update(update);
-    BOOST_CHECK_EQUAL(entity.history().size(), 2);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(2000)), 0);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(3000)), 1);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(4000)), 1);
+    BOOST_CHECK_EQUAL(entity.size(), 2);
+    BOOST_CHECK(not entity.hasSnapshot(armem::Time::milliSeconds(2000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(3000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(4000)));
 
     // Disable maximum history size.
     entity.setMaxHistorySize(-1);
 
     update.timeCreated = armem::Time::milliSeconds(5000);
     entity.update(update);
-    BOOST_CHECK_EQUAL(entity.history().size(), 3);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(3000)), 1);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(4000)), 1);
-    BOOST_CHECK_EQUAL(entity.history().count(armem::Time::milliSeconds(5000)), 1);
+    BOOST_CHECK_EQUAL(entity.size(), 3);
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(3000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(4000)));
+    BOOST_CHECK(entity.hasSnapshot(armem::Time::milliSeconds(5000)));
 }
 
 
 BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
 {
-    armem::wm::ProviderSegment providerSegment("SomeRGBImageProvider");
+    armem::server::wm::ProviderSegment providerSegment("SomeRGBImageProvider");
 
     armem::EntityUpdate update;
     update.entityID.providerSegmentName = providerSegment.name();
@@ -753,22 +768,22 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     update.timeCreated = armem::Time::milliSeconds(4000);
     providerSegment.update(update);
 
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").history().size(), 3);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").history().size(), 4);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").size(), 3);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").size(), 4);
 
 
     // Employ maximum history size.
     providerSegment.setMaxHistorySize(3);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").history().size(), 3);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").history().size(), 3);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").size(), 3);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").size(), 3);
 
     providerSegment.setMaxHistorySize(2);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").history().size(), 2);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").history().size(), 2);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").size(), 2);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").size(), 2);
 
     providerSegment.setMaxHistorySize(3);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").history().size(), 2);
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").history().size(), 2);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("A").size(), 2);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("B").size(), 2);
 
     // Add new entity.
     providerSegment.setMaxHistorySize(2);
@@ -784,7 +799,7 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     // Check correctly inherited history size.
     BOOST_CHECK_EQUAL(providerSegment.getEntity("C").getMaxHistorySize(), 2);
     // Check actual history size.
-    BOOST_CHECK_EQUAL(providerSegment.getEntity("C").history().size(), 2);
+    BOOST_CHECK_EQUAL(providerSegment.getEntity("C").size(), 2);
 
     // Remove maximum.
     providerSegment.setMaxHistorySize(-1);
@@ -795,58 +810,6 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
         update.entityID.entityName = name;
         update.timeCreated = armem::Time::milliSeconds(5000);
         providerSegment.update(update);
-        BOOST_CHECK_EQUAL(providerSegment.getEntity(name).history().size(), 3);
+        BOOST_CHECK_EQUAL(providerSegment.getEntity(name).size(), 3);
     }
 }
-
-
-
-template <class T>
-struct CopyTest
-{
-    CopyTest()
-    {
-    }
-
-    void test()
-    {
-        // At least check whether they can be called.
-        T t;
-        T t2 = t.copy();
-
-        if constexpr(!std::is_base_of_v<armem::base::EntityInstanceBase<T>, T>)
-        {
-            t2 = t.copyEmpty();
-        }
-    }
-};
-
-
-BOOST_AUTO_TEST_CASE(test_copy)
-{
-    {
-        CopyTest<armem::wm::EntityInstance>().test();
-        CopyTest<armem::wm::EntitySnapshot>().test();
-        CopyTest<armem::wm::Entity>().test();
-        CopyTest<armem::wm::ProviderSegment>().test();
-        CopyTest<armem::wm::CoreSegment>().test();
-        CopyTest<armem::wm::Memory>().test();
-    }
-    {
-        CopyTest<armem::ltm::EntityInstance>().test();
-        CopyTest<armem::ltm::EntitySnapshot>().test();
-        CopyTest<armem::ltm::Entity>().test();
-        CopyTest<armem::ltm::ProviderSegment>().test();
-        CopyTest<armem::ltm::CoreSegment>().test();
-        CopyTest<armem::ltm::Memory>().test();
-    }
-    {
-        CopyTest<armem::d_ltm::EntityInstance>().test();
-        CopyTest<armem::d_ltm::EntitySnapshot>().test();
-        CopyTest<armem::d_ltm::Entity>().test();
-        CopyTest<armem::d_ltm::ProviderSegment>().test();
-        CopyTest<armem::d_ltm::CoreSegment>().test();
-        CopyTest<armem::d_ltm::Memory>().test();
-    }
-}
-
diff --git a/source/RobotAPI/libraries/armem/test/ArMemQueryBuilderTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemQueryBuilderTest.cpp
index 535735b09eeb61d41cdf0dbaf658cebcdb08f4db..78d3077c082e41f32bf6dfd398e9e7d474e19dc3 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemQueryBuilderTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemQueryBuilderTest.cpp
@@ -25,9 +25,10 @@
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include "../client/query/Builder.h"
-#include "../client/query/query_fns.h"
-#include "../core/workingmemory/ice_conversions.h"
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/client/query/query_fns.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
+
 
 #include <iostream>
 
diff --git a/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
index 4b83fd43261e1d97da45495f5da94279931e606f..656842b3dcd23d49a84a51a04fc02143c14cada2 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemQueryTest.cpp
@@ -20,28 +20,26 @@
  *             GNU General Public License
  */
 
-#include "ArmarXCore/core/exceptions/LocalException.h"
-#include <RobotAPI/interface/armem/query.h>
-#include <boost/test/tools/old/interface.hpp>
 #define BOOST_TEST_MODULE RobotAPI::ArmarXLibraries::armem
 
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include "../server/query_proc/workingmemory/EntityQueryProcessor.h"
-#include "../error.h"
-
-
-#include <iostream>
+#include <RobotAPI/interface/armem/query.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h>
+#include <RobotAPI/libraries/armem/server/query_proc/wm.h>
 
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 #include <SimoxUtility/algorithm/string.h>
 
+#include <iostream>
+
 
 namespace armem = armarx::armem;
 namespace aron = armarx::aron;
 namespace query = armarx::armem::query::data;
-using EntityQueryProcessor = armarx::armem::wm::query_proc::EntityQueryProcessor;
+using EntityQueryProcessor = armarx::armem::server::query_proc::wm::EntityQueryProcessor;
 
 
 namespace ArMemQueryTest
@@ -55,8 +53,7 @@ namespace ArMemQueryTest
     {
         armem::wm::Entity entity;
 
-        armem::wm::query_proc::EntityQueryProcessor processor;
-        query::EntityQueryPtr entityQuery;
+        armem::server::query_proc::wm::EntityQueryProcessor processor;
 
         std::vector<armem::wm::Entity> results;
 
@@ -85,10 +82,10 @@ namespace ArMemQueryTest
         template <class QueryT>
         void addResults(QueryT query = {})
         {
-            entityQuery = new QueryT(query);
-
+            // Test whether we get the same result when we pass the concrete type
+            // (static resolution) and when we pass the base type (dynamic resolution).
             results.emplace_back(processor.process(query, entity));
-            results.emplace_back(processor.process(*entityQuery, entity));
+            results.emplace_back(processor.process(static_cast<query::EntityQuery const&>(query), entity));
         }
     };
 
@@ -126,8 +123,8 @@ BOOST_AUTO_TEST_CASE(test_entity_Single_latest)
     {
         BOOST_CHECK_EQUAL(result.name(), entity.name());
         BOOST_CHECK_EQUAL(result.size(), 1);
-        BOOST_CHECK_EQUAL(result.history().begin()->second.time(), entity.getLatestSnapshot().time());
-        BOOST_CHECK_NE(&result.history().begin()->second, &entity.history().rbegin()->second);
+        const armem::wm::EntitySnapshot& first = result.getFirstSnapshotAfterOrAt(armem::Time::microSeconds(0));
+        BOOST_CHECK_EQUAL(first.time(), armem::Time::microSeconds(5000));
     }
 }
 
@@ -140,8 +137,8 @@ BOOST_AUTO_TEST_CASE(test_entity_Single_existing)
     for (const armem::wm::Entity& result : results)
     {
         BOOST_CHECK_EQUAL(result.name(), entity.name());
-        BOOST_CHECK_EQUAL(result.size(), 1);
-        BOOST_CHECK_EQUAL(result.history().begin()->second.time(), armem::Time::microSeconds(3000));
+        BOOST_REQUIRE_EQUAL(result.size(), 1);
+        BOOST_CHECK_EQUAL(result.getFirstSnapshot().time(), armem::Time::microSeconds(3000));
     }
 }
 
@@ -168,12 +165,13 @@ BOOST_AUTO_TEST_CASE(test_entity_All)
     {
         BOOST_CHECK_EQUAL(result.name(), entity.name());
         BOOST_CHECK_EQUAL(result.size(), entity.size());
-        auto jt = entity.history().begin();
-        for (auto it = result.history().begin(); it != result.history().end(); ++it, ++jt)
+        for (armem::Time time : entity.getTimestamps())
         {
-            BOOST_CHECK_EQUAL(it->first, jt->first);
-            BOOST_CHECK_EQUAL(it->second.time(), jt->second.time());
-            BOOST_CHECK_NE(&it->second, &jt->second);
+            BOOST_REQUIRE(result.hasSnapshot(time));
+            const armem::wm::EntitySnapshot& rs = result.getSnapshot(time);
+            const armem::wm::EntitySnapshot& es = entity.getSnapshot(time);
+            BOOST_CHECK_EQUAL(rs.time(), es.time());
+            BOOST_CHECK_NE(&rs, &es);
         }
     }
 }
@@ -191,7 +189,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeRange_slice)
 
         BOOST_CHECK_EQUAL(result.size(), 2);
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         std::vector<armem::Time> expected
         {
             armem::Time::microSeconds(2000), armem::Time::microSeconds(3000)
@@ -212,7 +210,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeRange_exact)
 
         BOOST_CHECK_EQUAL(result.size(), 3);
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         std::vector<armem::Time> expected
         {
             armem::Time::microSeconds(2000), armem::Time::microSeconds(3000), armem::Time::microSeconds(4000)
@@ -233,8 +231,8 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeRange_all)
 
         BOOST_CHECK_EQUAL(result.size(), entity.size());
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
-        std::vector<armem::Time> expected = simox::alg::get_keys(entity.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
+        const std::vector<armem::Time> expected = entity.getTimestamps();
         BOOST_CHECK_EQUAL_COLLECTIONS(times.begin(), times.end(), expected.begin(), expected.end());
     }
 }
@@ -266,7 +264,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeRange_from_start)
 
         BOOST_CHECK_EQUAL(result.size(), 2);
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
         std::vector<armem::Time> expected
         {
             armem::Time::microSeconds(1000), armem::Time::microSeconds(2000)
@@ -284,10 +282,9 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeRange_to_end)
     for (const armem::wm::Entity& result : results)
     {
         BOOST_CHECK_EQUAL(result.name(), entity.name());
-
         BOOST_CHECK_EQUAL(result.size(), 3);
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
         std::vector<armem::Time> expected
         {
             armem::Time::microSeconds(3000), armem::Time::microSeconds(4000), armem::Time::microSeconds(5000)
@@ -307,12 +304,11 @@ BOOST_AUTO_TEST_CASE(test_entity_BeforeTime_1)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
-        BOOST_REQUIRE_EQUAL(times.front(),  armem::Time::microSeconds(3000));
+        BOOST_CHECK_EQUAL(times.front(), armem::Time::microSeconds(3000));
     }
-
 }
 
 BOOST_AUTO_TEST_CASE(test_entity_BeforeTime_2)
@@ -323,7 +319,7 @@ BOOST_AUTO_TEST_CASE(test_entity_BeforeTime_2)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 2);
 
         std::vector<armem::Time> expected
@@ -348,7 +344,7 @@ BOOST_AUTO_TEST_CASE(test_entity_BeforeOrAtTime_before)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         BOOST_REQUIRE_EQUAL(times.front(),  armem::Time::microSeconds(3000));
@@ -363,7 +359,7 @@ BOOST_AUTO_TEST_CASE(test_entity_BeforeOrAtTime_at)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         BOOST_REQUIRE_EQUAL(times.front(),  armem::Time::microSeconds(3000));
@@ -378,7 +374,7 @@ BOOST_AUTO_TEST_CASE(test_entity_BeforeOrAtTime_lookup_past)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE(times.empty());
     }
 }
@@ -398,7 +394,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_no_limit)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 2);
 
         std::vector<armem::Time> expected
@@ -424,7 +420,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_limit_600)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 2);
 
         std::vector<armem::Time> expected
@@ -450,7 +446,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_limit_too_small)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 0);
     }
 
@@ -469,7 +465,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_limit_only_next)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         std::vector<armem::Time> expected
@@ -494,7 +490,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_limit_only_previous)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         std::vector<armem::Time> expected
@@ -519,7 +515,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_perfect_match)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         std::vector<armem::Time> expected
@@ -544,7 +540,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_lookup_past)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE(times.empty());
     }
 }
@@ -562,7 +558,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_lookup_future)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE(times.empty());
     }
 }
@@ -580,7 +576,7 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_lookup_future_valid)
 
     for (const auto& result : results)
     {
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         BOOST_REQUIRE_EQUAL(times.size(), 1);
 
         std::vector<armem::Time> expected
@@ -601,33 +597,33 @@ BOOST_AUTO_TEST_CASE(test_entity_TimeApprox_lookup_invalid_timestamp)
 
 BOOST_AUTO_TEST_CASE(test_negative_index_semantics)
 {
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(0, 0), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(0, 1), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(0, 10), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(0, 0), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(0, 1), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(0, 10), 0);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(1, 1), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(5, 1), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(1, 1), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(5, 1), 0);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(1, 5), 1);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(5, 5), 4);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(5, 6), 5);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(5, 10), 5);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(1, 5), 1);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(5, 5), 4);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(5, 6), 5);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(5, 10), 5);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-1, 0), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 0), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-1, 0), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 0), 0);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-1, 1), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 1), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-1, 1), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 1), 0);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-1, 2), 1);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 2), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-1, 2), 1);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 2), 0);
 
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-1, 5), 4);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 5), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 6), 1);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-5, 10), 5);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-10, 10), 0);
-    BOOST_CHECK_EQUAL(EntityQueryProcessor::negativeIndexSemantics(-20, 10), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-1, 5), 4);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 5), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 6), 1);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-5, 10), 5);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-10, 10), 0);
+    BOOST_CHECK_EQUAL(armem::base::detail::negativeIndexSemantics(-20, 10), 0);
 }
 
 
@@ -643,8 +639,8 @@ BOOST_AUTO_TEST_CASE(test_entity_IndexRange_all_default)
 
         BOOST_CHECK_EQUAL(result.size(), entity.size());
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
-        std::vector<armem::Time> expected = simox::alg::get_keys(entity.history());
+        const std::vector<armem::Time> times = result.getTimestamps();
+        const std::vector<armem::Time> expected = entity.getTimestamps();
         BOOST_CHECK_EQUAL_COLLECTIONS(times.begin(), times.end(), expected.begin(), expected.end());
     }
 
@@ -666,7 +662,7 @@ BOOST_AUTO_TEST_CASE(test_entity_IndexRange_slice)
 
         BOOST_CHECK_EQUAL(result.size(), 3);
 
-        std::vector<armem::Time> times = simox::alg::get_keys(result.history());
+        std::vector<armem::Time> times = result.getTimestamps();
         std::vector<armem::Time> expected
         {
             armem::Time::microSeconds(2000), armem::Time::microSeconds(3000), armem::Time::microSeconds(4000)
diff --git a/source/RobotAPI/libraries/armem/test/CMakeLists.txt b/source/RobotAPI/libraries/armem/test/CMakeLists.txt
index e7fa876c119596f5c49352cfd0dca757ab01019c..b10935f95fedd6a1309248007422c53783d2c9e4 100644
--- a/source/RobotAPI/libraries/armem/test/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/test/CMakeLists.txt
@@ -8,3 +8,4 @@ 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}")
diff --git a/source/RobotAPI/libraries/armem/util/util.h b/source/RobotAPI/libraries/armem/util/util.h
index 35fc1538b78df0b817e7ae0676be68e9675d1f0f..3045d583a6a4144ed996a286257eb5ba2910b9c5 100644
--- a/source/RobotAPI/libraries/armem/util/util.h
+++ b/source/RobotAPI/libraries/armem/util/util.h
@@ -24,12 +24,12 @@
 #include <vector>
 #include <optional>
 
-#include "ArmarXCore/core/logging/Logging.h"
+#include <ArmarXCore/core/logging/Logging.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Entity.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/AronCppClass.h>
 
+
 namespace armarx::armem
 {
 
@@ -52,10 +52,13 @@ namespace armarx::armem
             return std::nullopt;
         }
 
+#if 0
+        // item.data() is by definition a DictNavigator
         if (item.data()->getDescriptor() != aron::data::Descriptor::eDict)
         {
             return std::nullopt;
         }
+#endif
 
         try
         {
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp
index 5016db50bf5da8dc10d0fac5b5c004b9178ddc40..38e4d8c88719541e7c4fca92964cfb069c22ba5e 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.cpp
@@ -4,6 +4,7 @@
 #include <QLineEdit>
 #include <QTimer>
 #include <QHBoxLayout>
+#include <QFileDialog>
 
 #include <cmath>
 
@@ -16,32 +17,53 @@ namespace armarx::armem::gui
         setSizePolicy(QSizePolicy::Policy::Minimum, QSizePolicy::Policy::Fixed);
 
         auto vlayout = new QVBoxLayout();
-        auto hlayout = new QHBoxLayout();
+        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(400);
+        _lineEdit->setMinimumWidth(150);
+
+        _openFileBrowserButton = new QPushButton("Search files", this);
+
+        _storeOnDiskButton = new QPushButton("Store query (Disk)", this);
+        _storeInLTMButton = new QPushButton("Store query (LTM)", this);
 
-        _storeOnDiskButton = new QPushButton("Store current result on local Disk", this);
+        hlayout1->addWidget(_lineEdit);
+        hlayout1->addWidget(_openFileBrowserButton);
 
-        _storeInLTMButton = new QPushButton("Store current result in LTM", this);
+        hlayout2->addWidget(_storeOnDiskButton);
+        hlayout2->addWidget(_storeInLTMButton);
 
-        vlayout->addWidget(_lineEdit);
-        hlayout->addWidget(_storeOnDiskButton);
-        hlayout->addWidget(_storeInLTMButton);
-        vlayout->addItem(hlayout);
+        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;
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h
index 19831694acc7b9251c7d372b8381f755df1bc292..c6b156db313b01180a7f5884959ffc21b0a73f9d 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/MemoryControlWidget.h
@@ -4,6 +4,7 @@
 
 class QPushButton;
 class QLineEdit;
+class QFileDialog;
 
 namespace armarx::armem::gui
 {
@@ -20,11 +21,15 @@ namespace armarx::armem::gui
         QLineEdit* pathInputBox();
         QString getEnteredPath();
 
+        QPushButton* openFileBrowserButton();
+
         QPushButton* storeInLTMButton();
         QPushButton* storeOnDiskButton();
 
     public slots:
 
+        void openFileBrowser();
+
     signals:
 
         void storeInLTM();
@@ -40,6 +45,8 @@ namespace armarx::armem::gui
 
         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 f88a2e1731c87de6fa163c307c90f4c6d3e01ae2..5e5431e41aa6a94ba8616247ec19a5529ca9927e 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
+++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
@@ -1,12 +1,12 @@
 #include "MemoryViewer.h"
 
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
+#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/MemoryQueryProcessor.h>
-#include <RobotAPI/libraries/armem/server/query_proc/workingmemory/MemoryQueryProcessor.h>
+#include <RobotAPI/libraries/armem/server/query_proc/diskmemory.h>
+#include <RobotAPI/libraries/armem/server/query_proc/wm.h>
 
 #include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
 
@@ -216,108 +216,111 @@ namespace armarx::armem::gui
 
     void MemoryViewer::updateMemories()
     {
+        int errorCount = 0;
+
         memoryReaders.clear();
         memoryData.clear();
 
         memoryReaders = mns.getAllReaders(true);
 
         bool dataChanged = false;
+        std::filesystem::path path(memoryControlWidget->getEnteredPath().toStdString());
 
-        QString qs = memoryControlWidget->getEnteredPath();
-        std::string utf8_text = qs.toUtf8().constData();
-
-        std::filesystem::path p(utf8_text);
+        armem::client::QueryInput input = memoryGroup->queryWidget()->queryInput();
 
         // first check if the local file system should be queried
         if (memoryGroup->queryWidget()->alsoQueryLocalDisk())
         {
-            if (std::filesystem::is_directory(p))
+            if (std::filesystem::is_directory(path))
             {
-                for (const auto& d : std::filesystem::directory_iterator(p))
+                for (const auto& directory : std::filesystem::directory_iterator(path))
                 {
-                    if (d.is_directory())
+                    if (directory.is_directory())
                     {
-                        std::string k = d.path().filename();
+                        std::string k = directory.path().filename();
                         armem::d_ltm::Memory dMem(k);
-                        dMem.reload(p / k);
+                        dMem.reload(path / k);
 
-                        armem::client::QueryInput input = memoryGroup->queryWidget()->queryInput();
-                        input.addQueryTargetToAll(armem::query::data::QueryTarget::Disk);
+                        input.addQueryTargetToAll(armem::query::data::QueryTarget::LTM); // We use LTM as query target for the disk
 
-                        armem::d_ltm::query_proc::MemoryQueryProcessor d_ltm_processor;
+                        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);
-                        dataChanged = true;
                     }
                 }
             }
             else
             {
-                ARMARX_WARNING << "Could not import a memory from '" << utf8_text << "'. Skipping import.";
+                ARMARX_WARNING << "Could not import a memory from '" << path << "'. Skipping import.";
             }
-        }
 
-        armem::client::QueryInput input = memoryGroup->queryWidget()->queryInput();
-        for (auto& [name, reader] : memoryReaders)
+            dataChanged = true; // in any case we update the view (even if there was no result)
+        }
+        else
         {
-            TIMING_START(MemoryQuery);
+            for (auto& [name, reader] : memoryReaders)
             {
-                armem::client::QueryResult result = reader.query(input);
-                if (result)
+                TIMING_START(MemoryQuery);
                 {
-                    if (result.memory.hasData())
+                    armem::client::QueryResult result = reader.query(input);
+                    if (result)
                     {
-                        if (const auto& it = memoryData.find(name); it != memoryData.end())
+                        if (auto it = memoryData.find(name); it != memoryData.end())
                         {
                             result.memory.append(it->second);
-
-                            // requery (e.g. to get only the last n values instead of the last n from disk and the last n from wm)
-                            armem::wm::query_proc::MemoryQueryProcessor wm_processor;
-                            result.memory = wm_processor.process(input.toIce(), result.memory);
-
-                            if (!result.memory.hasData())
+                            if (result.memory.empty())
                             {
                                 ARMARX_ERROR << "A memory which had data before lost data. This indicates that there is something wrong.";
                             }
-                        }
 
-                        dataChanged = true;
-                        memoryData[name] = std::move(result.memory);
+                            memoryData[name] = std::move(result.memory);
+                        }
+                        else
+                        {
+                            ARMARX_INFO << "The memory " << name << " has no data after querying.";
+                        }
+                        dataChanged = true; // in any case we update the view (even if there was no result)
                     }
                     else
                     {
-                        ARMARX_INFO << "The memory " << name << " has no data after querying.";
+                        ARMARX_WARNING << "A query for memory '" << name << "' produced an error: " << result.errorMessage;
+                        errorCount++;
                     }
                 }
-                else
+                TIMING_END_STREAM(MemoryQuery, ARMARX_VERBOSE);
+
+                if (debugObserver)
                 {
-                    ARMARX_WARNING << "A query for memory '" << name << "' produced an error: " << result.errorMessage;
-                    if (statusLabel)
-                    {
-                        statusLabel->setText(QString::fromStdString(result.errorMessage));
-                    }
+                    debugObserver->setDebugDatafield(Logging::tag.tagName, "Memory Query [ms]", new Variant(MemoryQuery.toMilliSecondsDouble()));
                 }
             }
-            TIMING_END_STREAM(MemoryQuery, ARMARX_VERBOSE);
-
-            if (debugObserver)
-            {
-                debugObserver->setDebugDatafield(Logging::tag.tagName, "Memory Query [ms]", new Variant(MemoryQuery.toMilliSecondsDouble()));
-            }
         }
 
+        // Code to output status label information
+        std::stringstream ss;
+        auto now = std::chrono::system_clock::now();
+        auto in_time_t = std::chrono::system_clock::to_time_t(now);
+        ss << "Last update: " ;// << std::put_time(std::localtime(&in_time_t), "%Y-%m-%d %X");
+
         if (dataChanged)
         {
             emit memoryDataChanged();
         }
         else
         {
-            if (statusLabel)
-            {
-                statusLabel->setText("No query result.");
-            }
+            ss << "- No query result. ";
+        }
+
+        if (errorCount > 0)
+        {
+            ss << "The query produced " << errorCount << " errors! Please check log.";
+        }
+
+        if (statusLabel)
+        {
+            statusLabel->setText(ss.str().c_str());
         }
     }
 
diff --git a/source/RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.cpp b/source/RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.cpp
index a62659cd78d4448bb72913ae432fc22f8f2b6eae..dd51a5e7f055f387e7580196874128c1f4bf2b12 100644
--- a/source/RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/PeriodicUpdateWidget.cpp
@@ -28,7 +28,7 @@ namespace armarx::armem::gui
         _frequencySpinBox->setValue(frequency);
         _frequencySpinBox->setMinimum(0);
         _frequencySpinBox->setMaximum(maxFrequency);
-        _frequencySpinBox->setSingleStep(1.0);
+        _frequencySpinBox->setSingleStep(0.5);
         _frequencySpinBox->setSuffix(" Hz");
 
 
diff --git a/source/RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h b/source/RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h
index 37de7699ce2c8d9245ced9e26fa8625d9b62159e..f3ca45cf17b05c72936a5afb8958e4eb5686aaab 100644
--- a/source/RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h
+++ b/source/RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h
@@ -16,10 +16,10 @@ namespace armarx
      * A class to efficiently build and maintain sorted items of `QTreeWidget`
      * or `QTreeWidgetItem` based on a sorted container matching the intended structure.
      */
-    template <class ContainerT>
+    template <class _ElementT>
     struct TreeWidgetBuilder
     {
-        using ElementT = typename ContainerT::value_type;
+        using ElementT = _ElementT;
 
         /// Return < 0 if `element < item`, 0 if `element == item`, and > 0 if `element > item`.
         using CompareFn = std::function<int(const ElementT& element, QTreeWidgetItem* item)>;
@@ -30,14 +30,15 @@ namespace armarx
 
         TreeWidgetBuilder() = default;
         /// Constructor to automatically derive the template argument.
-        TreeWidgetBuilder(const ContainerT&)
+        TreeWidgetBuilder(const ElementT&)
         {}
 
         TreeWidgetBuilder(CompareFn compareFn, MakeItemFn makeItemFn, UpdateItemFn updateItemFn = NoUpdate) :
             compareFn(compareFn), makeItemFn(makeItemFn), updateItemFn(updateItemFn)
         {}
-        TreeWidgetBuilder(NameFn nameFn, MakeItemFn makeItemFn, UpdateItemFn updateItemFn = NoUpdate) :
-            compareFn(MakeCompareNameFn(nameFn)), makeItemFn(makeItemFn), updateItemFn(updateItemFn)
+        TreeWidgetBuilder(NameFn nameFn, MakeItemFn makeItemFn, UpdateItemFn updateItemFn = NoUpdate,
+                          int nameColumn = 0) :
+            compareFn(MakeCompareNameFn(nameFn, nameColumn)), makeItemFn(makeItemFn), updateItemFn(updateItemFn)
         {}
 
 
@@ -45,9 +46,9 @@ namespace armarx
         {
             this->compareFn = compareFn;
         }
-        void setNameFn(NameFn nameFn)
+        void setNameFn(NameFn nameFn, int nameColumn = 0)
         {
-            compareFn = MakeCompareNameFn(nameFn);
+            compareFn = MakeCompareNameFn(nameFn, nameColumn);
         }
         void setMakeItemFn(MakeItemFn makeItemFn)
         {
@@ -64,8 +65,31 @@ namespace armarx
         }
 
 
-        template <class ParentT>
-        void updateTree(ParentT* parent, const ContainerT& elements);
+        /**
+         * @brief Update the tree according to the elements iterated over by `iteratorFn`.
+         *
+         * @param parent
+         *  The parent, i.e. the tree widget or a tree widget item.
+         * @param iteratorFn
+         *  Function taking a function `bool fn(const ElementT& element)`
+         *  and calling it for each element in the underlying container, i.e. like:
+         *  void iteratorFn(bool (*elementFn)(const ElementT& element));
+         */
+        template <class ParentT, class IteratorFn>
+        void updateTreeWithIterator(ParentT* parent, IteratorFn&& iteratorFn);
+
+        /**
+         * @brief Update the tree with the iterable container.
+         *
+         * @param parent
+         *  The parent, i.e. the tree widget or a tree widget item.
+         * @param iteratorFn
+         *  Function taking a function `bool fn(const ElementT& element)`
+         *  and calling it for each element in the underlying container, i.e. like:
+         *  void iteratorFn(bool (*elementFn)(const ElementT& element));
+         */
+        template <class ParentT, class ContainerT>
+        void updateTreeWithContainer(ParentT* parent, const ContainerT& elements);
 
 
         /// No update function (default).
@@ -76,7 +100,7 @@ namespace armarx
         }
 
         /// Uses the name for comparison.
-        static CompareFn MakeCompareNameFn(NameFn nameFn);
+        static CompareFn MakeCompareNameFn(NameFn nameFn, int nameColumn);
 
 
     private:
@@ -100,7 +124,7 @@ namespace armarx
     struct MapTreeWidgetBuilder
     {
         using MapT = std::map<KeyT, ValueT>;
-        using Base = TreeWidgetBuilder<MapT>;
+        using Base = TreeWidgetBuilder<typename MapT::value_type>;
         using ElementT = typename Base::ElementT;
 
         using CompareFn = std::function<int(const ElementT& element, QTreeWidgetItem* item)>;
@@ -170,7 +194,7 @@ namespace armarx
         template <class ParentT>
         void updateTree(ParentT* tree, const MapT& elements)
         {
-            builder.updateTree(tree, elements);
+            builder.updateTreeWithContainer(tree, elements);
         }
 
 
@@ -200,7 +224,7 @@ namespace armarx
 
     private:
 
-        TreeWidgetBuilder<MapT> builder;
+        TreeWidgetBuilder<typename MapT::value_type> builder;
 
     };
 
@@ -273,30 +297,52 @@ namespace armarx
     }
 
 
-    template <class ContainerT>
-    auto TreeWidgetBuilder<ContainerT>::MakeCompareNameFn(NameFn nameFn) -> CompareFn
+    template <class ElementT>
+    auto TreeWidgetBuilder<ElementT>::MakeCompareNameFn(NameFn nameFn, int nameColumn) -> CompareFn
     {
-        return [nameFn](const ElementT & element, QTreeWidgetItem * item)
+        return [nameFn, nameColumn](const ElementT & element, QTreeWidgetItem * item)
         {
-            return detail::compare(nameFn(element), item->text(0).toStdString());
+            return detail::compare(nameFn(element), item->text(nameColumn).toStdString());
         };
     }
 
 
-    template <class ContainerT>
-    template <typename ParentT>
-    void TreeWidgetBuilder<ContainerT>::updateTree(ParentT* parent, const ContainerT& elements)
+    template <class ElementT>
+    template <class ParentT, class ContainerT>
+    void TreeWidgetBuilder<ElementT>::updateTreeWithContainer(ParentT* parent, const ContainerT& elements)
+    {
+        this->updateTreeWithIterator(parent, [&elements](auto&& elementFn)
+        {
+            for (const auto& element : elements)
+            {
+                if (not elementFn(element))
+                {
+                    break;
+                }
+            }
+        });
+    }
+
+
+    template <class ElementT>
+    template <class ParentT, class IteratorFn>
+    void TreeWidgetBuilder<ElementT>::updateTreeWithIterator(ParentT* parent, IteratorFn&& iteratorFn)
     {
         using api = detail::ParentAPI<ParentT>;
 
+        ARMARX_CHECK_NOT_NULL(makeItemFn) << "makeItemFn must be set";
+        ARMARX_CHECK_NOT_NULL(updateItemFn) << "updateItemFn must be set";
+        ARMARX_CHECK_NOT_NULL(compareFn) << "compareFn must be set";
+
         int currentIndex = 0;
-        for (const auto& element : elements)
+        iteratorFn([this, &parent, &currentIndex](const auto & element)
         {
             bool inserted = false;
             QTreeWidgetItem* item = nullptr;
             if (currentIndex >= api::getItemCount(parent))
             {
                 // Add elements to the end of the list.
+                ARMARX_CHECK_NOT_NULL(makeItemFn);
                 item = makeItemFn(element);
                 api::insertItem(parent, api::getItemCount(parent), item);
                 ++currentIndex;
@@ -331,11 +377,8 @@ namespace armarx
             {
                 item->setExpanded(true);
             }
-            if (!cont)
-            {
-                break;
-            }
-        }
+            return cont;
+        });
         // Remove superfluous items. (currentIndex must point behind the last item)
         while (api::getItemCount(parent) > currentIndex)
         {
diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h
index 26f9d3be5fccfdce4fdb17a9ddbe430c2f334433..c331f2b450990614733819a7df47e61e8e20fb60 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h
+++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h
@@ -7,7 +7,7 @@
 
 #include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 class QGroupBox;
diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceViewList.h b/source/RobotAPI/libraries/armem_gui/instance/InstanceViewList.h
index 5f937f419cd3111daf1146a6640e0ea9348f6d42..8dc24e0dcd9759f3ab89e21e33ff600ad253f082 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/InstanceViewList.h
+++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceViewList.h
@@ -6,7 +6,7 @@
 
 #include <RobotAPI/libraries/aron/aroncore/navigators/typenavigator/AronObjectTypeNavigator.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
 
 class QGroupBox;
diff --git a/source/RobotAPI/libraries/armem_gui/instance/MemoryIDTreeWidgetItem.cpp b/source/RobotAPI/libraries/armem_gui/instance/MemoryIDTreeWidgetItem.cpp
index b8f568c79cdd1d84fa803df9ffaee737e24c9ea2..ebb4473bb1941a713526d646b37744f5a3314c1c 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/MemoryIDTreeWidgetItem.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/MemoryIDTreeWidgetItem.cpp
@@ -33,7 +33,11 @@ namespace armarx::armem::gui::instance
         // Timestamp in human-readable format
         if (id.hasTimestamp())
         {
-            child(4)->setText(valueColumn, QString::fromStdString(toDateTimeMilliSeconds(id.timestamp)));
+            static const char* mu = "\u03BC";
+            std::stringstream ss;
+            ss << toDateTimeMilliSeconds(id.timestamp)
+               << " (" << id.timestamp.toMicroSeconds() << " " << mu << "s)";
+            child(4)->setText(valueColumn, QString::fromStdString(ss.str()));
         }
     }
 
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilder.cpp b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilder.cpp
index a2811c0bc5a01ef29fbb9cc41d7b5f47118f5a9a..6793fd79513dd7b2ac7a287f4d9934a97e2d7c91 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilder.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilder.cpp
@@ -22,7 +22,7 @@ namespace armarx::armem::gui::instance
             return true;
         });
 
-        builder.updateTree(parent, data->getAllKeys());
+        builder.updateTreeWithContainer(parent, data->getAllKeys());
     }
 
     void DataTreeBuilder::updateTree(QTreeWidgetItem* parent, const aron::datanavigator::ListNavigatorPtr& data)
@@ -36,7 +36,7 @@ namespace armarx::armem::gui::instance
             return true;
         });
 
-        builder.updateTree(parent, getIndex(children.size()));
+        builder.updateTreeWithContainer(parent, getIndex(children.size()));
     }
 
 
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 b26a422ea71c90c2b769217a274eac7887eb8f9d..b225a093d4664d60313b882c1b3de750b48f96e8 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/DataTreeBuilderBase.h
@@ -28,8 +28,8 @@ namespace armarx::armem::gui::instance
 
     protected:
 
-        using DictBuilder = armarx::TreeWidgetBuilder<std::vector<std::string>>;
-        using ListBuilder = armarx::TreeWidgetBuilder<std::vector<size_t>>;
+        using DictBuilder = armarx::TreeWidgetBuilder<std::string>;
+        using ListBuilder = armarx::TreeWidgetBuilder<size_t>;
 
         DictBuilder getDictBuilder() const;
         ListBuilder getListBuilder() const;
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/TypedDataTreeBuilder.cpp b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/TypedDataTreeBuilder.cpp
index 56d204abf42573540c363c0973f4bf10db357317..4673f22f68c40dc54a8048291db623c79a82442a 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_builders/TypedDataTreeBuilder.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_builders/TypedDataTreeBuilder.cpp
@@ -40,7 +40,7 @@ namespace armarx::armem::gui::instance
                 return true;
             });
 
-            builder.updateTree(parent, data.getAllKeys());
+            builder.updateTreeWithContainer(parent, data.getAllKeys());
         }
     }
 
@@ -76,7 +76,7 @@ namespace armarx::armem::gui::instance
             return true;
         });
 
-        builder.updateTree(parent, type.getAllKeys());
+        builder.updateTreeWithContainer(parent, type.getAllKeys());
     }
 
 
@@ -100,7 +100,7 @@ namespace armarx::armem::gui::instance
                 return true;
             });
 
-            builder.updateTree(parent, getIndex(children.size()));
+            builder.updateTreeWithContainer(parent, getIndex(children.size()));
         }
     }
 
@@ -126,7 +126,7 @@ namespace armarx::armem::gui::instance
             return true;
         });
 
-        builder.updateTree(parent, getIndex(data.childrenSize()));
+        builder.updateTreeWithContainer(parent, getIndex(data.childrenSize()));
     }
 
 
@@ -150,7 +150,7 @@ namespace armarx::armem::gui::instance
             return true;
         });
 
-        builder.updateTree(parent, getIndex(type.getAcceptedTypes().size()));
+        builder.updateTreeWithContainer(parent, getIndex(type.getAcceptedTypes().size()));
     }
 
 
diff --git a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
index 1d4a2b908eba38fbb4be2d028030598c220aae44..29c137093ac9c75f0c904c6745c72473c205f1ec 100644
--- a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.cpp
@@ -66,13 +66,18 @@ namespace armarx::armem::gui::memory
             return true;
         });
 
+        auto nameFn = [](const auto & element)
+        {
+            return element.name();
+        };
 
         workingmemoryCoreSegmentBuilder.setExpand(true);
-        workingmemoryCoreSegmentBuilder.setMakeItemFn([this](const std::string & name, const wm::CoreSegment & coreSeg)
+        workingmemoryCoreSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
+        workingmemoryCoreSegmentBuilder.setMakeItemFn([this](const wm::CoreSegment & coreSeg)
         {
-            return makeItem(name, coreSeg);
+            return makeItem(coreSeg.name(), coreSeg);
         });
-        workingmemoryCoreSegmentBuilder.setUpdateItemFn([this](const std::string&, const wm::CoreSegment & coreSeg, QTreeWidgetItem * coreSegItem)
+        workingmemoryCoreSegmentBuilder.setUpdateItemFn([this](const wm::CoreSegment & coreSeg, QTreeWidgetItem * coreSegItem)
         {
             updateContainerItem(coreSeg, coreSegItem);
             updateChildren(coreSeg, coreSegItem);
@@ -80,11 +85,12 @@ namespace armarx::armem::gui::memory
         });
 
         workingmemoryProvSegmentBuilder.setExpand(true);
-        workingmemoryProvSegmentBuilder.setMakeItemFn([this](const std::string & name, const wm::ProviderSegment & provSeg)
+        workingmemoryProvSegmentBuilder.setNameFn(nameFn, int(Columns::KEY));
+        workingmemoryProvSegmentBuilder.setMakeItemFn([this](const wm::ProviderSegment & provSeg)
         {
-            return makeItem(name, provSeg);
+            return makeItem(provSeg.name(), provSeg);
         });
-        workingmemoryProvSegmentBuilder.setUpdateItemFn([this](const std::string&, const wm::ProviderSegment & provSeg, QTreeWidgetItem * provSegItem)
+        workingmemoryProvSegmentBuilder.setUpdateItemFn([this](const wm::ProviderSegment & provSeg, QTreeWidgetItem * provSegItem)
         {
             updateContainerItem(provSeg, provSegItem);
             updateChildren(provSeg, provSegItem);
@@ -92,30 +98,30 @@ namespace armarx::armem::gui::memory
         });
 
         // entityBuilder.setExpand(true);
-        workingmemoryEntityBuilder.setMakeItemFn([this](const std::string & name, const wm::Entity & entity)
+        workingmemoryEntityBuilder.setNameFn(nameFn, int(Columns::KEY));
+        workingmemoryEntityBuilder.setMakeItemFn([this](const wm::Entity & entity)
         {
-            return makeItem(name, entity);
+            return makeItem(entity.name(), entity);
         });
-        workingmemoryEntityBuilder.setUpdateItemFn([this](const std::string&, const wm::Entity & entity, QTreeWidgetItem *  entityItem)
+        workingmemoryEntityBuilder.setUpdateItemFn([this](const wm::Entity & entity, QTreeWidgetItem *  entityItem)
         {
             updateContainerItem(entity, entityItem);
             updateChildren(entity, entityItem);
             return true;
         });
 
-        workingmemorySnapshotBuilder.setMakeItemFn([this](const armem::Time & time, const wm::EntitySnapshot & snapshot)
+        workingmemorySnapshotBuilder.setMakeItemFn([this](const wm::EntitySnapshot & snapshot)
         {
-            QTreeWidgetItem* item = makeItem(toDateTimeMilliSeconds(time), 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 auto & pair, QTreeWidgetItem * item)
+        workingmemorySnapshotBuilder.setCompareFn([](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * item)
         {
-            const wm::EntitySnapshot& snapshot = pair.second;
             return armarx::detail::compare(static_cast<qlonglong>(snapshot.time().toMicroSeconds()),
                                            item->data(int(Columns::KEY), Qt::ItemDataRole::UserRole).toLongLong());
         });
-        workingmemorySnapshotBuilder.setUpdateItemFn([this](const armem::Time&, const wm::EntitySnapshot & snapshot, QTreeWidgetItem * snapshotItem)
+        workingmemorySnapshotBuilder.setUpdateItemFn([this](const wm::EntitySnapshot & snapshot, QTreeWidgetItem * snapshotItem)
         {
             updateContainerItem(snapshot, snapshotItem);
             updateChildren(snapshot, snapshotItem);
@@ -183,27 +189,27 @@ namespace armarx::armem::gui::memory
             _selectedID = id;
 
             const std::string levelName = item->data(int(Columns::LEVEL), Qt::UserRole).toString().toStdString();
-            if (levelName == wm::Memory().getLevelName())
+            if (levelName == wm::Memory::getLevelName())
             {
                 emit memorySelected(*_selectedID);
             }
-            else if (levelName == wm::CoreSegment().getLevelName())
+            else if (levelName == wm::CoreSegment::getLevelName())
             {
                 emit coreSegmentSelected(*_selectedID);
             }
-            else if (levelName == wm::ProviderSegment().getLevelName())
+            else if (levelName == wm::ProviderSegment::getLevelName())
             {
                 emit providerSegmentSelected(*_selectedID);
             }
-            else if (levelName == wm::Entity().getLevelName())
+            else if (levelName == wm::Entity::getLevelName())
             {
                 emit entitySelected(*_selectedID);
             }
-            else if (levelName == wm::EntitySnapshot().getLevelName())
+            else if (levelName == wm::EntitySnapshot::getLevelName())
             {
                 emit snapshotSelected(*_selectedID);
             }
-            else if (levelName == wm::EntityInstance().getLevelName())
+            else if (levelName == wm::EntityInstance::getLevelName())
             {
                 emit instanceSelected(*_selectedID);
             }
@@ -213,6 +219,16 @@ namespace armarx::armem::gui::memory
         emit selectedItemChanged(*_selectedID);
     }
 
+    template <class ContainerT>
+    static
+    auto makeIteratorFn(const ContainerT& container)
+    {
+        return [&container](auto&& elementFn)
+        {
+            container.forEachChild(elementFn);
+        };
+    }
+
 
     void TreeWidget::updateChildren(const armem::wm::Memory& memory, QTreeWidget* tree)
     {
@@ -227,27 +243,27 @@ namespace armarx::armem::gui::memory
 
     void TreeWidget::updateChildren(const armem::wm::Memory& memory, QTreeWidgetItem* memoryItem)
     {
-        workingmemoryCoreSegmentBuilder.updateTree(memoryItem, memory.coreSegments());
+        workingmemoryCoreSegmentBuilder.updateTreeWithIterator(memoryItem, makeIteratorFn(memory));
     }
 
     void TreeWidget::updateChildren(const armem::wm::CoreSegment& coreSeg, QTreeWidgetItem* coreSegItem)
     {
-        workingmemoryProvSegmentBuilder.updateTree(coreSegItem, coreSeg.providerSegments());
+        workingmemoryProvSegmentBuilder.updateTreeWithIterator(coreSegItem, makeIteratorFn(coreSeg));
     }
 
     void TreeWidget::updateChildren(const armem::wm::ProviderSegment& provSeg, QTreeWidgetItem* provSegItem)
     {
-        workingmemoryEntityBuilder.updateTree(provSegItem, provSeg.entities());
+        workingmemoryEntityBuilder.updateTreeWithIterator(provSegItem, makeIteratorFn(provSeg));
     }
 
     void TreeWidget::updateChildren(const armem::wm::Entity& entity, QTreeWidgetItem* entityItem)
     {
-        workingmemorySnapshotBuilder.updateTree(entityItem, entity.history());
+        workingmemorySnapshotBuilder.updateTreeWithIterator(entityItem, makeIteratorFn(entity));
     }
 
     void TreeWidget::updateChildren(const armem::wm::EntitySnapshot& snapshot, QTreeWidgetItem* snapshotItem)
     {
-        workingmemoryInstanceBuilder.updateTree(snapshotItem, snapshot.instances());
+        workingmemoryInstanceBuilder.updateTreeWithIterator(snapshotItem, makeIteratorFn(snapshot));
     }
 
     void TreeWidget::updateChildren(const armem::wm::EntityInstance& data, QTreeWidgetItem* dataItem)
@@ -255,19 +271,25 @@ namespace armarx::armem::gui::memory
         (void) data, (void) dataItem;
     }
 
-    QTreeWidgetItem* TreeWidget::makeItem(const std::string& key, const armem::base::detail::MemoryItem& memoryItem)
+    template <class MemoryItemT>
+    QTreeWidgetItem* TreeWidget::makeItem(const std::string& key, const MemoryItemT& memoryItem)
     {
         (void) key;
+        return makeItem(memoryItem.getKeyString(), MemoryItemT::getLevelName(), memoryItem.id());
+    }
+
+    QTreeWidgetItem* TreeWidget::makeItem(const std::string& key, const std::string& levelName, const MemoryID& id)
+    {
         QStringList columns;
-        columns.insert(int(Columns::KEY), QString::fromStdString(memoryItem.getKeyString()));
+        columns.insert(int(Columns::KEY), QString::fromStdString(key));
         columns.insert(int(Columns::SIZE), "");
         columns.insert(int(Columns::TYPE), "");
-        columns.insert(int(Columns::LEVEL), QString::fromStdString(simox::alg::capitalize_words(memoryItem.getLevelName())));
-        columns.insert(int(Columns::ID), QString::fromStdString(memoryItem.id().str()));
+        columns.insert(int(Columns::LEVEL), QString::fromStdString(simox::alg::capitalize_words(levelName)));
+        columns.insert(int(Columns::ID), QString::fromStdString(id.str()));
 
         QTreeWidgetItem* item = new QTreeWidgetItem(columns);
-        item->setData(int(Columns::LEVEL), Qt::UserRole, QString::fromStdString(memoryItem.getLevelName()));
-        item->setData(int(Columns::ID), Qt::UserRole, QString::fromStdString(memoryItem.id().str()));
+        item->setData(int(Columns::LEVEL), Qt::UserRole, QString::fromStdString(levelName));
+        item->setData(int(Columns::ID), Qt::UserRole, QString::fromStdString(id.str()));
         item->setTextAlignment(int(Columns::SIZE), Qt::AlignRight);
         return item;
     }
diff --git a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
index 2bcf0fa1b6135534407044a3ce341b86afeab442..72987cda1ef736a9f8943161cb8756a6e56b2cdc 100644
--- a/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/memory/TreeWidget.h
@@ -4,7 +4,7 @@
 
 #include <QTreeWidget>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/longtermmemory/Memory.h>
 
 #include <RobotAPI/libraries/armem_gui/TreeWidgetBuilder.h>
@@ -67,7 +67,9 @@ namespace armarx::armem::gui::memory
         void updateChildren(const armem::wm::EntityInstance& data, QTreeWidgetItem* parent);
 
 
-        QTreeWidgetItem* makeItem(const std::string& key, const armem::base::detail::MemoryItem& container);
+        template <class MemoryItemT>
+        QTreeWidgetItem* makeItem(const std::string& key, const MemoryItemT& memoryItem);
+        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>
@@ -77,11 +79,11 @@ namespace armarx::armem::gui::memory
     private:
 
         MapTreeWidgetBuilder<std::string, const wm::Memory*> workingmemoryBuilder;
-        MapTreeWidgetBuilder<std::string, wm::CoreSegment> workingmemoryCoreSegmentBuilder;
-        MapTreeWidgetBuilder<std::string, wm::ProviderSegment> workingmemoryProvSegmentBuilder;
-        MapTreeWidgetBuilder<std::string, wm::Entity> workingmemoryEntityBuilder;
-        MapTreeWidgetBuilder<armem::Time, wm::EntitySnapshot> workingmemorySnapshotBuilder;
-        TreeWidgetBuilder<std::vector<wm::EntityInstance>> workingmemoryInstanceBuilder;
+        TreeWidgetBuilder<wm::CoreSegment> workingmemoryCoreSegmentBuilder;
+        TreeWidgetBuilder<wm::ProviderSegment> workingmemoryProvSegmentBuilder;
+        TreeWidgetBuilder<wm::Entity> workingmemoryEntityBuilder;
+        TreeWidgetBuilder<wm::EntitySnapshot> workingmemorySnapshotBuilder;
+        TreeWidgetBuilder<wm::EntityInstance> workingmemoryInstanceBuilder;
 
         std::optional<MemoryID> _selectedID;
         /// While this is false, do not handle selection updates.
diff --git a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
index e41bed15cecbc599c7c97b4266a04e0e9a70e47e..9d5cc9ea6064bb6977892623649518791dcaffec 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.cpp
@@ -26,11 +26,23 @@ namespace armarx::armem::gui
         {
             targets.push_back(query::data::QueryTarget::LTM);
         }
-        if (_DiskMemoryQueryTargetCheckBox->isChecked())
+        return targets;
+    }
+
+    void SnapshotSelectorWidget::localDiskStateChanged()
+    {
+        if (_LocalDiskMemoryQueryTargetCheckBox->isChecked())
         {
-            targets.push_back(query::data::QueryTarget::Disk);
+            _WMQueryTargetCheckBox->setChecked(false);
+            _LTMQueryTargetCheckBox->setChecked(false);
+            _WMQueryTargetCheckBox->setEnabled(false);
+            _LTMQueryTargetCheckBox->setEnabled(false);
+        }
+        else
+        {
+            _WMQueryTargetCheckBox->setEnabled(true);
+            _LTMQueryTargetCheckBox->setEnabled(true);
         }
-        return targets;
     }
 
     bool SnapshotSelectorWidget::queryTargetContainsLocalDisk() const
@@ -59,13 +71,13 @@ namespace armarx::armem::gui
             // query type select box
             auto queryTargetLayout = new QHBoxLayout();
             _WMQueryTargetCheckBox = new QCheckBox("WM");
-            _LTMQueryTargetCheckBox = new QCheckBox("LTM (MongoDB)");
-            _DiskMemoryQueryTargetCheckBox = new QCheckBox("LTM (Disk)");
+            _LTMQueryTargetCheckBox = new QCheckBox("LTM");
             _LocalDiskMemoryQueryTargetCheckBox = new QCheckBox("Local Disk");
 
+            connect(_LocalDiskMemoryQueryTargetCheckBox, &QCheckBox::stateChanged, this, &This::localDiskStateChanged);
+
             queryTargetLayout->addWidget(_WMQueryTargetCheckBox);
             queryTargetLayout->addWidget(_LTMQueryTargetCheckBox);
-            queryTargetLayout->addWidget(_DiskMemoryQueryTargetCheckBox);
             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 6f6422c3cdbc7fd0e1899bce47efbaaa32589062..a0b69eb1b6f362e64880ab400c0bea29bcdc73fc 100644
--- a/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h
+++ b/source/RobotAPI/libraries/armem_gui/query_widgets/SnapshotSelectorWidget.h
@@ -45,14 +45,13 @@ namespace armarx::armem::gui
     signals:
         void queryChanged();
 
-
     private slots:
 
         //void updateSelector();
 
         void hideAllForms();
         void showSelectedFormForQuery(QString selected);
-
+        void localDiskStateChanged();
 
     signals:
         void queryOutdated();
@@ -68,7 +67,6 @@ namespace armarx::armem::gui
         QComboBox* _queryComboBox;
         QCheckBox* _WMQueryTargetCheckBox;
         QCheckBox* _LTMQueryTargetCheckBox;
-        QCheckBox* _DiskMemoryQueryTargetCheckBox;
         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 4f259c7af5a50ff198b139084eb604bfd06fead5..303a319bcd30566b8000e1d10cc6ab3ef812093d 100644
--- a/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp
+++ b/source/RobotAPI/libraries/armem_gui/test/ArMemGuiTest.cpp
@@ -44,13 +44,13 @@ BOOST_AUTO_TEST_CASE(test_sanitizeTypeName)
         BOOST_CHECK_EQUAL(sanitizeTypeName(dict.getName()), "Dict<Float>");
     }
     {
-        ListNavigator dict;
-        dict.setAcceptedType(std::make_shared<LongNavigator>());
-        BOOST_CHECK_EQUAL(sanitizeTypeName(dict.getName()), "Dict<Long>");
+        ListNavigator list;
+        list.setAcceptedType(std::make_shared<LongNavigator>());
+        BOOST_CHECK_EQUAL(sanitizeTypeName(list.getName()), "List<Long>");
     }
     {
-        ObjectNavigator dict;
-        dict.setObjectName("namespace::MyObjectName");
-        BOOST_CHECK_EQUAL(sanitizeTypeName(dict.getName()), "namespace::MyObjectName");
+        ObjectNavigator obj;
+        obj.setObjectName("namespace::MyObjectName");
+        BOOST_CHECK_EQUAL(sanitizeTypeName(obj.getName()), "MyObjectName    (namespace)");
     }
 }
diff --git a/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.cpp b/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.cpp
index 8fab7c2c6e113e5ba5eb9b6ba8d250d8fb6fec4f..5860b2f48f9659c7ac631e1270425f112a0efcab 100644
--- a/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.cpp
@@ -1,14 +1,21 @@
-// STD / STL
-#include <iostream>
-#include <fstream>
-#include <sstream>
-
 // BaseClass
 #include "Segment.h"
 
 // ArmarX
 #include "MotionConverter.h"
+
 #include <RobotAPI/libraries/PriorKnowledge/motions/MotionFinder.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+#include <ArmarXCore/core/application/properties/ProxyPropertyDefinition.h>
+
+// STD / STL
+#include <iostream>
+#include <fstream>
+#include <sstream>
+
 
 namespace armarx::armem::server::motions::mdb
 {
@@ -72,7 +79,7 @@ namespace armarx::armem::server::motions::mdb
                     instance.metadata().timeSent = IceUtil::Time::now();
                     instance.metadata().timeArrived = IceUtil::Time::now();
                     instance.metadata().confidence = 1.0;
-                    instance.setData(op->toAron());
+                    instance.data() = op->toAron();
                 }
                 else
                 {
diff --git a/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h b/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h
index 66e55f4107153532dd2df75a37fb369ba89817b1..f0dc4d726f83895876e23ab3bc52af36895df5b3 100644
--- a/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h
+++ b/source/RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h
@@ -22,7 +22,7 @@ namespace armarx::armem::server::motions::mdb
 
         virtual void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "") override;
         virtual void onInit() override;
-        virtual void onConnect() override;
+        virtual void onConnect();
 
     private:
         int loadByMotionFinder(const std::string&);
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.cpp b/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.cpp
index c973cf24801967244589677f9b044be099f5c306..976d5bf9abb8a7d7586a0501568e6c8240c1e45c 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.cpp
@@ -16,7 +16,7 @@
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot/aron_conversions.h>
 #include <RobotAPI/libraries/armem_robot/robot_conversions.h>
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Reader.cpp b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Reader.cpp
index d0bfb35708104712d2bebc33b4d7676b999ddac5..be9a624f46babcb192d606ef1bb4529c12aade2d 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Reader.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Reader.cpp
@@ -13,7 +13,7 @@
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot/aron_conversions.h>
 #include <RobotAPI/libraries/armem_robot/robot_conversions.h>
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/utils.h b/source/RobotAPI/libraries/armem_objects/client/articulated_object/utils.h
index 2e51a9e4b336bd4550027227d30a0236efa0f217..9c5b48f39864b16637739b022c0d1908de69c9a5 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/utils.h
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/utils.h
@@ -2,7 +2,7 @@
 
 #include <optional>
 
-#include "RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h"
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include "RobotAPI/libraries/armem_robot/types.h"
 #include <RobotAPI/libraries/armem_objects/aron/ObjectClass.aron.generated.h>
 
diff --git a/source/RobotAPI/libraries/armem_objects/client/attachment/Reader.cpp b/source/RobotAPI/libraries/armem_objects/client/attachment/Reader.cpp
index f723f30b2eb2d704dcfae73f47e9351cf659b7ad..938ba098681aca145efbeb131af9c7a6a1b6c054 100644
--- a/source/RobotAPI/libraries/armem_objects/client/attachment/Reader.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/attachment/Reader.cpp
@@ -9,7 +9,7 @@
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/util/util.h>
 #include <RobotAPI/libraries/armem_robot/robot_conversions.h>
 #include <RobotAPI/libraries/armem_robot/aron_conversions.h>
@@ -25,50 +25,42 @@ namespace armarx::armem::attachment
     namespace
     {
 
-        template<typename AronClass, typename ArmemClass>
+        template <typename AronClass, typename ArmemClass>
         auto getAttachments(const armarx::armem::wm::Memory& memory)
         {
             // using ArmemClass = decltype(fromAron(AronClass()));
             using ArmemClassVector = std::vector<ArmemClass>;
 
             ArmemClassVector attachments;
-
-            for (const auto&[_, coreSegment] : memory.coreSegments())
+            memory.forEachEntity([&attachments](const wm::Entity & entity)
             {
-                for (const auto& [providerName, providerSegment] : coreSegment.providerSegments())
+                if (entity.empty())
                 {
-                    for (const auto& [name, entity] : providerSegment.entities())
+                    ARMARX_WARNING << "No entity snapshot found";
+                    return true;
+                }
+
+                const armem::wm::EntityInstance& instance = entity.getFirstSnapshot().getInstance(0);
+                try
+                {
+                    AronClass aronAttachment;
+                    aronAttachment.fromAron(instance.data());
+
+                    ArmemClass attachment;
+                    fromAron(aronAttachment, attachment);
+
+                    if (attachment.active)
                     {
-                        if (entity.empty())
-                        {
-                            ARMARX_WARNING << "No entity found";
-                            continue;
-                        }
-
-                        const auto entitySnapshots = simox::alg::get_values(entity.history());
-                        const armem::wm::EntityInstance& instance = entitySnapshots.front().getInstance(0);
-
-                        try
-                        {
-                            AronClass aronAttachment;
-                            aronAttachment.fromAron(instance.data());
-
-                            ArmemClass attachment;
-                            fromAron(aronAttachment, attachment);
-
-                            if (attachment.active)
-                            {
-                                attachments.push_back(attachment);
-                            }
-
-                        }
-                        catch (const armarx::aron::error::AronException&)
-                        {
-                            continue;
-                        }
+                        attachments.push_back(attachment);
                     }
+
                 }
-            }
+                catch (const armarx::aron::error::AronException&)
+                {
+                    return true;
+                }
+                return true;
+            });
 
             return attachments;
         }
@@ -131,7 +123,9 @@ namespace armarx::armem::attachment
             return {};
         }
 
-        return getAttachments<::armarx::armem::arondto::attachment::ObjectAttachment, ::armarx::armem::attachment::ObjectAttachment>(qResult.memory);
+        return getAttachments <
+               ::armarx::armem::arondto::attachment::ObjectAttachment,
+               ::armarx::armem::attachment::ObjectAttachment > (qResult.memory);
     }
 
     std::vector<ObjectAttachment> Reader::queryObjectAttachments(const armem::Time& timestamp, const std::string& providerName) const
diff --git a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
index bb5d930da65b6ddb0e7966aa53e5e8fa766d383d..2ddcc827d80c0700f59cb5f9ee8638322f4e5633 100644
--- a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.cpp
@@ -3,15 +3,15 @@
 #include <sstream>
 
 #include <ArmarXCore/core/time/TimeUtil.h>
-#include "ArmarXCore/core/logging/Logging.h"
-#include <ArmarXCore/core/application/properties/forward_declarations.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+#include <ArmarXCore/core/application/properties/PluginAll.h>
 
-#include "RobotAPI/libraries/armem/util/util.h"
-#include "RobotAPI/libraries/aron/common/aron_conversions.h"
+#include <RobotAPI/libraries/armem/util/util.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
 
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
-#include "RobotAPI/libraries/armem/core/MemoryID.h"
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/client/Writer.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
@@ -50,34 +50,32 @@ namespace armarx::armem::server::obj::attachments
     {
     }
 
-    std::vector<armarx::armem::attachment::ObjectAttachment> Segment::getAttachments(const armem::Time& timestamp) const
+    std::vector<armarx::armem::attachment::ObjectAttachment>
+    Segment::getAttachments(const armem::Time& timestamp) const
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
         std::scoped_lock(coreSegment->mutex());
 
         std::vector<armarx::armem::attachment::ObjectAttachment> attachments;
-
-        for (const auto& [_, provSeg] : *coreSegment)
+        coreSegment->forEachEntity([this, &attachments](const wm::Entity & entity)
         {
-            for (const auto& [name, entity] :  provSeg.entities())
-            {
-                const auto& entityInstance = entity.getLatestSnapshot().getInstance(0);
-                const auto aronAttachment = tryCast<armarx::armem::arondto::attachment::ObjectAttachment>(entityInstance);
+            const wm::EntityInstance& entityInstance = entity.getLatestSnapshot().getInstance(0);
 
-                if (not aronAttachment)
-                {
-                    ARMARX_WARNING << "Could not convert entity instance to 'ObjectAttachment'";
-                    continue;
-                }
+            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_DEBUG << "Key is " << armem::MemoryID(entity.id());
+            ARMARX_DEBUG << "Key is " << armem::MemoryID(entity.id());
 
-                armarx::armem::attachment::ObjectAttachment attachment;
-                fromAron(*aronAttachment, attachment);
+            armarx::armem::attachment::ObjectAttachment attachment;
+            fromAron(*aronAttachment, attachment);
 
-                attachments.push_back(attachment);
-            }
-        }
+            attachments.push_back(attachment);
+            return true;
+        });
 
         return attachments;
     }
diff --git a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.h b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.h
index 0b9302d93390c473b87c67066bfe173237f3774b..4f8cd20ccd9a0ce456bb664f5f5eb8a25f1981e0 100644
--- a/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.h
+++ b/source/RobotAPI/libraries/armem_objects/server/attachments/Segment.h
@@ -21,41 +21,19 @@
 
 #pragma once
 
-#include <string>
-#include <optional>
-#include <mutex>
-#include <unordered_map>
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/forward_declarations.h>
+#include <RobotAPI/libraries/armem/server/forward_declarations.h>
+#include <RobotAPI/libraries/armem_objects/types.h>
 
-#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/application/properties/forward_declarations.h>
+#include <ArmarXCore/core/logging/Logging.h>
 
-// #include "ArmarXGui/libraries/RemoteGui/Client/Widgets.h"
-
-#include "RobotAPI/components/ArViz/Client/Client.h"
-
-#include "RobotAPI/libraries/armem/core/MemoryID.h"
-#include "RobotAPI/libraries/armem/core/Time.h"
-#include "RobotAPI/libraries/armem_objects/types.h"
-
-
-namespace armarx::armem
-{
-    namespace server
-    {
-        class MemoryToIceAdapter;
-    }
-
-    namespace wm
-    {
-        class CoreSegment;
-    }
-}  // namespace armarx::armem
+#include <string>
 
 
 namespace armarx::armem::server::obj::attachments
 {
-    class Visu;
-
 
     class Segment : public armarx::Logging
     {
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
index 08927d1e77d1963234f42ea9ab861ec9a33f86c4..1e9957aff7b0d093d3bd1d6e16f289d6a2a04afd 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.cpp
@@ -1,6 +1,7 @@
 #include "FloorVis.h"
 
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem_objects/aron/ObjectClass.aron.generated.h>
 
 #include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
@@ -13,16 +14,19 @@ namespace armarx::armem::server::obj::clazz
     {
     }
 
+
     void FloorVis::defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix)
     {
         properties.define(defs, prefix);
     }
 
+
     void FloorVis::setArViz(armarx::viz::Client arviz)
     {
         this->arviz = arviz;
     }
 
+
     void FloorVis::updateFloorObject(const wm::CoreSegment& classCoreSegment)
     {
         viz::Layer layer = arviz.layer(properties.layerName);
@@ -42,6 +46,7 @@ namespace armarx::armem::server::obj::clazz
         arviz.commit(layer);
     }
 
+
     armarx::viz::Object FloorVis::makeFloorObject(const wm::Entity& classEntity)
     {
         const wm::EntityInstance& instance = classEntity.getLatestSnapshot().getInstance(0);
@@ -50,6 +55,7 @@ namespace armarx::armem::server::obj::clazz
         return makeFloorObject(classEntity.name(), data);
     }
 
+
     armarx::viz::Object FloorVis::makeFloorObject(
         const std::string& name,
         const arondto::ObjectClass& objectClass)
@@ -61,7 +67,6 @@ namespace armarx::armem::server::obj::clazz
     }
 
 
-
     void FloorVis::Properties::define(armarx::PropertyDefinitionsPtr defs, const std::string& prefix)
     {
         defs->optional(show, prefix + "Show", "Whether to show the floor.");
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.h b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.h
index dcce63977438bdd0d646b50aa8e5dd9679354df8..49f8a6ddd71f5c24172ddfbbfd8e312dcea2fd3f 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.h
+++ b/source/RobotAPI/libraries/armem_objects/server/class/FloorVis.h
@@ -10,7 +10,7 @@ namespace armarx
 {
     using PropertyDefinitionsPtr = IceUtil::Handle<class PropertyDefinitionContainer>;
 }
-namespace armarx::armem::wm
+namespace armarx::armem::server::wm
 {
     class CoreSegment;
     class Entity;
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
index 22608257c1abcf39340643870b704c2dadfcd54d..cd10a49c91957e5fa86094597c7903f76fb04c13 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
@@ -285,16 +285,13 @@ namespace armarx::armem::server::obj::clazz
 
         showComboBox = {};
         showOptionsIndex.clear();
-        for (const auto& [_, prov] : *segment.coreSegment)
+        segment.coreSegment->forEachEntity([this](const wm::Entity & entity)
         {
-            for (const auto& [_, entity] : prov)
-            {
-                std::stringstream option;
-                option << entity.id().entityName << " (" << entity.id().providerSegmentName << ")";
-                showComboBox.addOption(option.str());
-                showOptionsIndex.push_back(entity.id());
-            }
-        }
+            std::stringstream option;
+            option << entity.id().entityName << " (" << entity.id().providerSegmentName << ")";
+            showComboBox.addOption(option.str());
+            showOptionsIndex.push_back(entity.id());
+        });
         if (showOptionsIndex.empty())
         {
             showComboBox.addOption("<none>");
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/Segment.h b/source/RobotAPI/libraries/armem_objects/server/class/Segment.h
index 15c7c4f373f20c43c0febfb142675c5058c45909..3e9717b3e51dc07491e55761664e5cc76add574b 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/Segment.h
+++ b/source/RobotAPI/libraries/armem_objects/server/class/Segment.h
@@ -9,7 +9,7 @@
 #include <RobotAPI/libraries/ArmarXObjects/ObjectID.h>
 #include <RobotAPI/libraries/ArmarXObjects/ObjectFinder.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/segment/SpecializedSegment.h>
 #include <RobotAPI/libraries/armem_objects/server/class/FloorVis.h>
 
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
index 09a412f4bfa40a1a6288e86dfe65fa8b50953061..d6d224fe0580e4aa73656515a671ba5753e33326 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
@@ -7,7 +7,6 @@
 
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
 #include <RobotAPI/libraries/armem/client/Writer.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
@@ -26,8 +25,9 @@
 #include <RobotAPI/libraries/core/FramedPose.h>
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 
-#include <ArmarXCore/core/time/TimeUtil.h>
+#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
 
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 #include <SimoxUtility/json.h>
@@ -143,7 +143,7 @@ namespace armarx::armem::server::obj::instance
 
             // Check whether we have an old snapshot for this object.
             std::optional<objpose::ObjectPose> previousPose;
-            const armem::wm::Entity* entity = findObjectEntity(armarx::fromIce(provided.objectID), providerName);
+            const wm::Entity* entity = findObjectEntity(armarx::fromIce(provided.objectID), providerName);
             if (entity)
             {
                 const arondto::ObjectInstance data = getLatestInstanceData(*entity);
@@ -250,21 +250,24 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    wm::CoreSegment& Segment::getCoreSegment()
+    wm::CoreSegment&
+    Segment::getCoreSegment()
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
         return *coreSegment;
     }
 
 
-    const wm::CoreSegment& Segment::getCoreSegment() const
+    const wm::CoreSegment&
+    Segment::getCoreSegment() const
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
         return *coreSegment;
     }
 
 
-    objpose::ObjectPoseMap Segment::getObjectPoses(IceUtil::Time now)
+    objpose::ObjectPoseMap
+    Segment::getObjectPoses(IceUtil::Time now)
     {
         ObjectPoseMap objectPoses = getLatestObjectPoses();
         updateObjectPoses(objectPoses, now);
@@ -273,7 +276,8 @@ namespace armarx::armem::server::obj::instance
 
 
 
-    objpose::ObjectPoseMap Segment::getObjectPosesByProvider(
+    objpose::ObjectPoseMap
+    Segment::getObjectPosesByProvider(
         const std::string& providerName,
         IceUtil::Time now)
     {
@@ -284,27 +288,31 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    armem::wm::Entity* Segment::findObjectEntity(const ObjectID& objectID, const std::string& providerName)
+    wm::Entity*
+    Segment::findObjectEntity(const ObjectID& objectID, const std::string& providerName)
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
         armem::MemoryID entityID = armem::MemoryID().withEntityName(objectID.str());
         if (providerName.empty())
         {
-            for (auto& [_, prov] : *coreSegment)
+            wm::Entity* result = nullptr;
+            coreSegment->forEachProviderSegment([&result, &entityID](wm::ProviderSegment & prov)
             {
                 if (prov.hasEntity(entityID.entityName))
                 {
-                    return &prov.getEntity(entityID);
+                    result = &prov.getEntity(entityID);
+                    return false;
                 }
-            }
-            return nullptr;
+                return true;
+            });
+            return result;
         }
         else
         {
             entityID.providerSegmentName = providerName;
             if (coreSegment->hasProviderSegment(providerName))
             {
-                armem::wm::ProviderSegment& prov = coreSegment->getProviderSegment(providerName);
+                wm::ProviderSegment& prov = coreSegment->getProviderSegment(providerName);
                 return prov.hasEntity(entityID.entityName) ? &prov.getEntity(entityID) : nullptr;
             }
             else
@@ -387,14 +395,16 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    objpose::ObjectPoseMap Segment::getLatestObjectPoses() const
+    objpose::ObjectPoseMap
+    Segment::getLatestObjectPoses() const
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
         return getLatestObjectPoses(*coreSegment);
     }
 
 
-    objpose::ObjectPoseMap Segment::getLatestObjectPoses(const armem::wm::CoreSegment& coreSeg)
+    objpose::ObjectPoseMap
+    Segment::getLatestObjectPoses(const wm::CoreSegment& coreSeg)
     {
         ObjectPoseMap result;
         getLatestObjectPoses(coreSeg, result);
@@ -402,7 +412,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    objpose::ObjectPoseMap Segment::getLatestObjectPoses(const armem::wm::ProviderSegment& provSeg)
+    objpose::ObjectPoseMap
+    Segment::getLatestObjectPoses(const wm::ProviderSegment& provSeg)
     {
         ObjectPoseMap result;
         getLatestObjectPoses(provSeg, result);
@@ -410,7 +421,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    objpose::ObjectPose Segment::getLatestObjectPose(const armem::wm::Entity& entity)
+    objpose::ObjectPose
+    Segment::getLatestObjectPose(const wm::Entity& entity)
     {
         ObjectPose result;
         getLatestObjectPose(entity, result);
@@ -418,18 +430,18 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    void Segment::getLatestObjectPoses(const armem::wm::CoreSegment& coreSeg, ObjectPoseMap& out)
+    void Segment::getLatestObjectPoses(const wm::CoreSegment& coreSeg, ObjectPoseMap& out)
     {
-        for (const auto& [_, provSegment] : coreSeg)
+        coreSeg.forEachProviderSegment([&out](const wm::ProviderSegment & provSegment)
         {
             getLatestObjectPoses(provSegment, out);
-        }
+        });
     }
 
 
-    void Segment::getLatestObjectPoses(const armem::wm::ProviderSegment& provSegment, ObjectPoseMap& out)
+    void Segment::getLatestObjectPoses(const wm::ProviderSegment& provSegment, ObjectPoseMap& out)
     {
-        for (const auto& [_, entity] : provSegment)
+        provSegment.forEachEntity([&out](const wm::Entity & entity)
         {
             if (!entity.empty())
             {
@@ -445,29 +457,29 @@ namespace armarx::armem::server::obj::instance
                     }
                 }
             }
-        }
+        });
     }
 
 
-    void Segment::getLatestObjectPose(const armem::wm::Entity& entity, ObjectPose& out)
+    void Segment::getLatestObjectPose(const wm::Entity& entity, ObjectPose& out)
     {
-        for (const armem::wm::EntityInstance& instance : entity.getLatestSnapshot())
+        entity.getLatestSnapshot().forEachInstance([&out](const wm::EntityInstance & instance)
         {
             arondto::ObjectInstance dto;
             dto.fromAron(instance.data());
 
             fromAron(dto, out);
-        }
+        });
     }
 
 
-    arondto::ObjectInstance Segment::getLatestInstanceData(const armem::wm::Entity& entity)
+    arondto::ObjectInstance Segment::getLatestInstanceData(const wm::Entity& entity)
     {
         ARMARX_CHECK_GREATER_EQUAL(entity.size(), 1);
-        const armem::wm::EntitySnapshot& snapshot = entity.getLatestSnapshot();
+        const wm::EntitySnapshot& snapshot = entity.getLatestSnapshot();
 
         ARMARX_CHECK_EQUAL(snapshot.size(), 1);
-        const armem::wm::EntityInstance& instance = snapshot.getInstance(0);
+        const wm::EntityInstance& instance = snapshot.getInstance(0);
 
         arondto::ObjectInstance data;
         data.fromAron(instance.data());
@@ -476,7 +488,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    ::armarx::armem::articulated_object::ArticulatedObjects Segment::getArticulatedObjects()
+    ::armarx::armem::articulated_object::ArticulatedObjects
+    Segment::getArticulatedObjects()
     {
         objpose::ObjectPoseMap objectPoses = getObjectPoses(IceUtil::Time::now());
 
@@ -589,7 +602,7 @@ namespace armarx::armem::server::obj::instance
 
 
         // Find object pose (provider name can be empty).
-        armem::wm::Entity* objectEntity = this->findObjectEntity(objectID, input.providerName);
+        wm::Entity* objectEntity = this->findObjectEntity(objectID, input.providerName);
         if (!objectEntity || objectEntity->empty())
         {
             ARMARX_WARNING << "Tried to attach object " << objectID << " to node '" << frameName
@@ -650,7 +663,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    objpose::DetachObjectFromRobotNodeOutput Segment::detachObjectFromRobotNode(
+    objpose::DetachObjectFromRobotNodeOutput
+    Segment::detachObjectFromRobotNode(
         const objpose::DetachObjectFromRobotNodeInput& input)
     {
         const armem::Time now = armem::Time::now();
@@ -662,7 +676,7 @@ namespace armarx::armem::server::obj::instance
         {
             // Remove from latest pose (if it was cached).
             // Find object pose (provider name can be empty).
-            armem::wm::Entity* entity = this->findObjectEntity(objectID, input.providerName);
+            wm::Entity* entity = this->findObjectEntity(objectID, input.providerName);
             if (entity)
             {
                 const arondto::ObjectInstance data = getLatestInstanceData(*entity);
@@ -697,48 +711,26 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    struct DetachVisitor : public armem::wm::Visitor
-    {
-        Segment& owner;
-        armem::Time now;
-        bool commitAttachedPose;
-
-        int numDetached = 0;
-
-        DetachVisitor(Segment& owner, armem::Time now, bool commitAttachedPose) :
-            owner(owner), now(now), commitAttachedPose(commitAttachedPose)
-        {
-        }
-
-        virtual bool visitEnter(armem::wm::Entity& entity) override;
-    };
-
-
-    bool DetachVisitor::visitEnter(armem::wm::Entity& entity)
-    {
-        const arondto::ObjectInstance data = owner.getLatestInstanceData(entity);
-        if (data.pose.attachmentValid)
-        {
-            numDetached++;
-            // Store non-attached pose in new snapshot.
-            owner.storeDetachedSnapshot(entity, data, now, commitAttachedPose);
-        }
-        return false; // Stop descending.
-    }
-
-
-    objpose::DetachAllObjectsFromRobotNodesOutput Segment::detachAllObjectsFromRobotNodes(
+    objpose::DetachAllObjectsFromRobotNodesOutput
+    Segment::detachAllObjectsFromRobotNodes(
         const objpose::DetachAllObjectsFromRobotNodesInput& input)
     {
         ARMARX_CHECK_NOT_NULL(coreSegment);
 
         const armem::Time now = armem::Time::now();
 
-        DetachVisitor visitor(*this, now, input.commitAttachedPose);
-        visitor.applyTo(*coreSegment);
-
         objpose::DetachAllObjectsFromRobotNodesOutput output;
-        output.numDetached = visitor.numDetached;
+        output.numDetached = 0;
+        coreSegment->forEachEntity([this, now, &input, &output](wm::Entity & entity)
+        {
+            const arondto::ObjectInstance data = this->getLatestInstanceData(entity);
+            if (data.pose.attachmentValid)
+            {
+                ++output.numDetached;
+                // Store non-attached pose in new snapshot.
+                this->storeDetachedSnapshot(entity, data, now, input.commitAttachedPose);
+            }
+        });
 
         ARMARX_INFO << "Detached all objects (" << output.numDetached << ") from robot nodes.";
 
@@ -747,9 +739,9 @@ namespace armarx::armem::server::obj::instance
 
 
     void Segment::storeDetachedSnapshot(
-        armem::wm::Entity& entity,
+        wm::Entity& entity,
         const arondto::ObjectInstance& data,
-        armem::Time now,
+        Time now,
         bool commitAttachedPose)
     {
         armem::EntityUpdate update;
@@ -781,21 +773,29 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    std::optional<wm::EntityInstance> Segment::findClassInstance(const ObjectID& objectID) const
+    std::optional<wm::EntityInstance>
+    Segment::findClassInstance(const ObjectID& objectID) const
     {
         const ObjectID classID = { objectID.dataset(), objectID.className() };
         try
         {
-            for (const auto& [_, provSeg] : iceMemory.workingMemory->getCoreSegment("Class"))
+            std::optional<wm::EntityInstance> result;
+            iceMemory.workingMemory->getCoreSegment("Class").forEachProviderSegment(
+                [&classID, &result](const wm::ProviderSegment & provSeg)
             {
                 if (provSeg.hasEntity(classID.str()))
                 {
-                    return provSeg.getEntity(classID.str()).getLatestSnapshot().getInstance(0);
+                    result = provSeg.getEntity(classID.str()).getLatestSnapshot().getInstance(0);
+                    return false;
                 }
-            }
+                return true;
+            });
 
-            ARMARX_WARNING << "No provider segment for classID " << classID.str() << " found";
-            return std::nullopt;
+            if (not result.has_value())
+            {
+                ARMARX_WARNING << "No provider segment for classID " << classID.str() << " found";
+            }
+            return result;
         }
         catch (const armem::error::ArMemError& e)
         {
@@ -824,7 +824,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    std::optional<armem::obj::SceneSnapshot> Segment::loadScene(const std::string& filename)
+    std::optional<armem::obj::SceneSnapshot>
+    Segment::loadScene(const std::string& filename)
     {
         if (const std::optional<std::filesystem::path> path = resolveSceneFilename(filename))
         {
@@ -837,7 +838,8 @@ namespace armarx::armem::server::obj::instance
     }
 
 
-    std::optional<armem::obj::SceneSnapshot> Segment::loadScene(const std::filesystem::path& path)
+    std::optional<armem::obj::SceneSnapshot>
+    Segment::loadScene(const std::filesystem::path& path)
     {
         ARMARX_INFO << "Loading scene snapshot from: \n" << path;
         nlohmann::json j;
@@ -859,7 +861,8 @@ namespace armarx::armem::server::obj::instance
     const std::string Segment::timestampPlaceholder = "%TIMESTAMP";
 
 
-    std::optional<std::filesystem::path> Segment::resolveSceneFilename(const std::string& _filename)
+    std::optional<std::filesystem::path>
+    Segment::resolveSceneFilename(const std::string& _filename)
     {
         std::string filename = _filename;
 
@@ -894,9 +897,7 @@ namespace armarx::armem::server::obj::instance
     armem::obj::SceneSnapshot Segment::getSceneSnapshot() const
     {
         armem::obj::SceneSnapshot scene;
-
-        wm::FunctionalVisitor visitor;
-        visitor.entityFn = [&scene](wm::Entity & entity)
+        coreSegment->forEachEntity([&scene](wm::Entity & entity)
         {
             try
             {
@@ -916,10 +917,8 @@ namespace armarx::armem::server::obj::instance
             {
                 ARMARX_WARNING_S << e.what();
             }
-            return false;
-        };
+        });
 
-        visitor.applyTo(*coreSegment);
         return scene;
     }
 
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.h b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.h
index 918a4efade3c596763d90fec427b18fa78a774bf..27ffbc746af05451b5fdd54f15a3afc4c7822e08 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.h
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.h
@@ -8,8 +8,6 @@
 #include <SimoxUtility/caching/CacheMap.h>
 #include <SimoxUtility/shapes/OrientedBox.h>
 
-#include <ArmarXCore/core/logging/Logging.h>
-
 #include <RobotAPI/interface/core/RobotState.h>
 #include <RobotAPI/interface/objectpose/ObjectPoseStorageInterface.h>
 
@@ -19,7 +17,7 @@
 #include <RobotAPI/libraries/ArmarXObjects/ObjectPose.h>
 #include <RobotAPI/libraries/ArmarXObjects/ObjectFinder.h>
 
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/segment/SpecializedSegment.h>
 
 #include "ArticulatedObjectVisu.h"
diff --git a/source/RobotAPI/libraries/armem_objects/types.h b/source/RobotAPI/libraries/armem_objects/types.h
index 976f438e7c39009fd5d37fb6afdf19378da488c4..5ca91ff285e5fc92d1d3523a504379d582dda8b5 100644
--- a/source/RobotAPI/libraries/armem_objects/types.h
+++ b/source/RobotAPI/libraries/armem_objects/types.h
@@ -21,13 +21,11 @@
 
 #pragma once
 
-#include "RobotAPI/libraries/armem/core/Time.h"
-#include <vector>
-
 #include <Eigen/Geometry>
 
-#include <RobotAPI/libraries/armem_robot/types.h>
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem_robot/types.h>
 
 
 namespace armarx::armem::attachment
@@ -97,4 +95,4 @@ namespace armarx::armem::articulated_object
 
     using ArticulatedObject  = armarx::armem::robot::Robot;
     using ArticulatedObjects = armarx::armem::robot::Robots;
-} // namespace armarx::armem::articulated_object
\ No newline at end of file
+} // namespace armarx::armem::articulated_object
diff --git a/source/RobotAPI/libraries/armem_robot/robot_conversions.cpp b/source/RobotAPI/libraries/armem_robot/robot_conversions.cpp
index 3bf4171486e35c33a1cca23a666baac2233a8356..6ba61bba4b70f7a4cbbdf8cb2d18b11e4b50bbd6 100644
--- a/source/RobotAPI/libraries/armem_robot/robot_conversions.cpp
+++ b/source/RobotAPI/libraries/armem_robot/robot_conversions.cpp
@@ -4,7 +4,7 @@
 
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
 
-#include "RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h"
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
 
 #include <RobotAPI/libraries/armem_robot/aron/RobotDescription.aron.generated.h>
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
index 7a500d1391c0f0942795b49af65740f350eecbed..85370141f880a72b26039c0af0c765f929e6a902 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
@@ -10,7 +10,7 @@
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem_robot/aron_conversions.h>
 #include <RobotAPI/libraries/armem_robot/robot_conversions.h>
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
@@ -214,30 +214,31 @@ namespace armarx::armem::robot_state
         const armem::wm::ProviderSegment& providerSegment = memory
                 .getCoreSegment(properties.proprioceptionCoreSegment)
                 .getProviderSegment(name);
-        // clang-format on
-        const auto entities = simox::alg::get_values(providerSegment.entities());
 
         // TODO entitiesToRobotState()
 
-        if (entities.empty())
+        if (providerSegment.empty())
         {
             ARMARX_WARNING << "No entity found";
             return std::nullopt;
         }
 
-        const auto entitySnapshots = simox::alg::get_values(entities.front().history());
+        // clang-format on
 
-        if (entitySnapshots.empty())
+        const armem::wm::EntityInstance* instance = nullptr;
+        providerSegment.forEachInstance([&instance](const wm::EntityInstance & i)
+        {
+            instance = &i;
+            return false;  // break
+        });
+        if (!instance)
         {
             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);
-
         // Here, we access the RobotUnit streaming data stored in the proprioception segment.
-        return robot::convertRobotState(instance);
+        return robot::convertRobotState(*instance);
     }
 
     // FIXME remove this, use armem/util/util.h
@@ -271,24 +272,19 @@ namespace armarx::armem::robot_state
                 .getCoreSegment(properties.proprioceptionCoreSegment);
         // clang-format on
 
-        for (const auto &[_, providerSegment] : coreSegment.providerSegments())
+        coreSegment.forEachEntity([&jointMap](const wm::Entity & entity)
         {
+            const auto& entityInstance = entity.getLatestSnapshot().getInstance(0);
 
-            for (const auto &[name, entity] : providerSegment.entities())
+            const auto jointState = tryCast<::armarx::armem::arondto::JointState>(entityInstance);
+            if (not jointState)
             {
-                const auto& entityInstance = entity.getLatestSnapshot().getInstance(0);
-
-                const auto jointState = tryCast<::armarx::armem::arondto::JointState>(entityInstance);
-
-                if (not jointState)
-                {
-                    // ARMARX_WARNING << "Could not convert entity instance to 'JointState'";
-                    continue;
-                }
-
-                jointMap.emplace(jointState->name, jointState->position);
+                // ARMARX_WARNING << "Could not convert entity instance to 'JointState'";
+                return;
             }
-        }
+
+            jointMap.emplace(jointState->name, jointState->position);
+        });
 
         if (jointMap.empty())
         {
@@ -307,26 +303,19 @@ namespace armarx::armem::robot_state
                 .getCoreSegment(properties.descriptionCoreSegment)
                 .getProviderSegment(name); // TODO(fabian.reister): all
         // clang-format on
-        const auto entities = simox::alg::get_values(providerSegment.entities());
 
-        if (entities.empty())
+        const armem::wm::EntityInstance* instance = nullptr;
+        providerSegment.forEachInstance([&instance](const wm::EntityInstance & i)
         {
-            ARMARX_WARNING << "No entity found";
-            return std::nullopt;
-        }
-
-        const auto entitySnapshots = simox::alg::get_values(entities.front().history());
-
-        if (entitySnapshots.empty())
+            instance = &i;
+        });
+        if (!instance)
         {
             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 robot::convertRobotDescription(instance);
+        return robot::convertRobotDescription(*instance);
     }
 
 } // namespace armarx::armem::robot_state
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 6aa026431e7d9efd0128a9007d23918b291b54bc..32da2d6450e67eb228e7d8099123842a4b8f84d9 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformReader.cpp
@@ -48,9 +48,9 @@
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.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>
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
index 4230394aa823c96e2382fd73af68d9663513b989..608dfa3947153985dc4f528bb0746ab95df706fc 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
@@ -37,9 +37,9 @@
 
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ice_conversions.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #include <RobotAPI/libraries/aron/core/navigator/type/NavigatorFactory.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
diff --git a/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.cpp b/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.cpp
index c4d0e05b4a1120b0ba6d256ad646508d7556ab7d..18b84d7c665c593369b4bd15dd5505d5c5fa88d1 100644
--- a/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.cpp
@@ -2,104 +2,119 @@
 
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 #include <SimoxUtility/algorithm/string/string_tools.h>
-#include <SimoxUtility/color/cmaps.h>
 #include <SimoxUtility/math/pose/interpolate.h>
 
-#include "ArmarXCore/core/exceptions/LocalException.h"
-#include "RobotAPI/libraries/core/FramedPose.h"
+#include <ArmarXCore/core/exceptions/LocalException.h>
+#include <RobotAPI/libraries/core/FramedPose.h>
 
-#include "RobotAPI/libraries/aron/common/aron_conversions.h"
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
 
-#include "RobotAPI/libraries/armem/core/error/ArMemError.h"
-#include "RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h"
-#include "RobotAPI/libraries/armem/core/workingmemory/Memory.h"
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/error/ArMemError.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 #include <RobotAPI/libraries/armem_robot_state/aron/Transform.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot_state/aron_conversions.h>
 
+
 namespace armarx::armem::common::robot_state::localization
 {
 
-    TransformChainResult TransformHelper::lookupTransformChain(const armem::wm::CoreSegment& localizationCoreSegment,
-            const TransformQuery& query)
+    template <class ...Args>
+    TransformResult
+    TransformHelper::_lookupTransform(
+        const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+        const TransformQuery& query)
     {
-        const std::vector<std::string> tfChain =
-            buildTransformChain(localizationCoreSegment, query);
-
+        const std::vector<std::string> tfChain = _buildTransformChain(localizationCoreSegment, query);
         if (tfChain.empty())
         {
-            return {.header = query.header,
-                    .transforms    = std::vector<Eigen::Affine3f>{},
-                    .status       = TransformChainResult::Status::ErrorFrameNotAvailable,
+            return {.transform    = {.header = query.header},
+                    .status       = TransformResult::Status::ErrorFrameNotAvailable,
                     .errorMessage = "Cannot create tf lookup chain '" +
                                     query.header.parentFrame + " -> " + query.header.frame +
                                     "'"};
         }
 
-        const std::vector<Eigen::Affine3f> transforms = obtainTransforms(
+        const std::vector<Eigen::Affine3f> transforms = _obtainTransforms(
                     localizationCoreSegment, tfChain, query.header.agent, query.header.timestamp);
-
         if (transforms.empty())
         {
             ARMARX_WARNING << deactivateSpam(1) << "No transform available.";
-            return {.header = query.header,
-                    .transforms    = {},
-                    .status       = TransformChainResult::Status::ErrorFrameNotAvailable,
+            return {.transform    = {.header = query.header},
+                    .status       = TransformResult::Status::ErrorFrameNotAvailable,
                     .errorMessage = "Error in TF loookup:  '" + query.header.parentFrame +
                                     " -> " + query.header.frame +
                                     "'. No memory data in time range."};
         }
 
+        const Eigen::Affine3f transform = std::accumulate(transforms.begin(),
+                                          transforms.end(),
+                                          Eigen::Affine3f::Identity(),
+                                          std::multiplies<>());
 
         ARMARX_DEBUG << "Found valid transform";
 
-        return {.header = query.header,
-                .transforms = transforms,
-                .status    = TransformChainResult::Status::Success};
+        return {.transform = {.header = query.header, .transform = transform},
+                .status    = TransformResult::Status::Success};
     }
 
-    TransformResult TransformHelper::lookupTransform(const armem::wm::CoreSegment& localizationCoreSegment,
-            const TransformQuery& query)
-    {
-        const std::vector<std::string> tfChain =
-            buildTransformChain(localizationCoreSegment, query);
 
+    template <class ...Args>
+    TransformChainResult
+    TransformHelper::_lookupTransformChain(
+        const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+        const TransformQuery& query)
+    {
+        const std::vector<std::string> tfChain = _buildTransformChain(localizationCoreSegment, query);
         if (tfChain.empty())
         {
-            return {.transform    = {.header = query.header},
-                    .status       = TransformResult::Status::ErrorFrameNotAvailable,
-                    .errorMessage = "Cannot create tf lookup chain '" +
-                                    query.header.parentFrame + " -> " + query.header.frame +
-                                    "'"};
+            return
+            {
+                .header = query.header,
+                .transforms    = std::vector<Eigen::Affine3f>{},
+                .status       = TransformChainResult::Status::ErrorFrameNotAvailable,
+                .errorMessage = "Cannot create tf lookup chain '" +
+                query.header.parentFrame + " -> " + query.header.frame +
+                "'"
+            };
         }
 
-        const std::vector<Eigen::Affine3f> transforms = obtainTransforms(
+        const std::vector<Eigen::Affine3f> transforms = _obtainTransforms(
                     localizationCoreSegment, tfChain, query.header.agent, query.header.timestamp);
-
         if (transforms.empty())
         {
             ARMARX_WARNING << deactivateSpam(1) << "No transform available.";
-            return {.transform    = {.header = query.header},
-                    .status       = TransformResult::Status::ErrorFrameNotAvailable,
-                    .errorMessage = "Error in TF loookup:  '" + query.header.parentFrame +
-                                    " -> " + query.header.frame +
-                                    "'. No memory data in time range."};
+            return
+            {
+                .header = query.header,
+                .transforms    = {},
+                .status       = TransformChainResult::Status::ErrorFrameNotAvailable,
+                .errorMessage = "Error in TF loookup:  '" + query.header.parentFrame +
+                " -> " + query.header.frame +
+                "'. No memory data in time range."
+            };
         }
 
-        const Eigen::Affine3f transform = std::accumulate(transforms.begin(),
-                                          transforms.end(),
-                                          Eigen::Affine3f::Identity(),
-                                          std::multiplies<>());
 
         ARMARX_DEBUG << "Found valid transform";
 
-        return {.transform = {.header = query.header, .transform = transform},
-                .status    = TransformResult::Status::Success};
+        return
+        {
+            .header = query.header,
+            .transforms = transforms,
+            .status    = TransformChainResult::Status::Success
+        };
     }
 
+
+
+    template <class ...Args>
     std::vector<std::string>
-    TransformHelper::buildTransformChain(const armem::wm::CoreSegment& localizationCoreSegment,
-                                         const TransformQuery& query)
+    TransformHelper::_buildTransformChain(
+        const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+        const TransformQuery& query)
     {
         ARMARX_DEBUG << "Building transform chain";
 
@@ -172,8 +187,100 @@ namespace armarx::armem::common::robot_state::localization
         return chain;
     }
 
-    inline ::armarx::armem::robot_state::Transform
-    convertEntityToTransform(const armem::wm::EntityInstance& item)
+
+    template <class ...Args>
+    std::vector<Eigen::Affine3f>
+    TransformHelper::_obtainTransforms(
+        const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+        const std::vector<std::string>& tfChain,
+        const std::string& agent,
+        const armem::Time& timestamp)
+    {
+        const auto& agentProviderSegment = localizationCoreSegment.getProviderSegment(agent);
+
+        ARMARX_DEBUG << "Provider segments" << localizationCoreSegment.getProviderSegmentNames();
+        ARMARX_DEBUG << "Entities: " << agentProviderSegment.getEntityNames();
+
+        try
+        {
+            std::vector<Eigen::Affine3f> transforms;
+            transforms.reserve(tfChain.size());
+            std::transform(tfChain.begin(),
+                           tfChain.end(),
+                           std::back_inserter(transforms),
+                           [&](const std::string & entityName)
+            {
+                return _obtainTransform(entityName, agentProviderSegment, timestamp);
+            });
+            return transforms;
+        }
+        catch (const armem::error::MissingEntry& missingEntryError)
+        {
+            ARMARX_WARNING << missingEntryError.what();
+        }
+        catch (const ::armarx::exceptions::local::ExpressionException& ex)
+        {
+            ARMARX_WARNING << "local exception: " << ex.what();
+        }
+        catch (...)
+        {
+            ARMARX_WARNING << "Error: " << GetHandledExceptionString();
+        }
+
+        return {};
+    }
+
+
+    template <class ...Args>
+    Eigen::Affine3f
+    TransformHelper::_obtainTransform(
+        const std::string& entityName,
+        const armem::base::ProviderSegmentBase<Args...>& agentProviderSegment,
+        const armem::Time& timestamp)
+    {
+        ARMARX_DEBUG << "getEntity:" + entityName;
+        const auto& entity = agentProviderSegment.getEntity(entityName);
+
+        ARMARX_DEBUG << "History (size: " << entity.size() << "): " << entity.getTimestamps();
+
+        // if (entity.history.empty())
+        // {
+        //     // TODO(fabian.reister): fixme boom
+        //     ARMARX_ERROR << "No snapshots received.";
+        //     return Eigen::Affine3f::Identity();
+        // }
+
+        std::vector<::armarx::armem::robot_state::Transform> transforms;
+        transforms.push_back(_convertEntityToTransform(entity.getLatestSnapshot().getInstance(0)));
+
+        ARMARX_DEBUG << "obtaining transform";
+        if (transforms.size() > 1)
+        {
+            // TODO(fabian.reister): remove
+            return transforms.front().transform;
+
+            ARMARX_DEBUG << "More than one snapshots received: " << transforms.size();
+            const auto p = _interpolateTransform(transforms, timestamp);
+            ARMARX_DEBUG << "Done interpolating transform";
+            return p;
+        }
+
+        // accept this to fail (will raise armem::error::MissingEntry)
+        if (transforms.empty())
+        {
+            ARMARX_DEBUG << "empty transform";
+
+            throw armem::error::MissingEntry("foo", "bar", "foo2", "bar2", 0);
+        }
+
+        ARMARX_DEBUG << "single transform";
+
+        return transforms.front().transform;
+    }
+
+
+    ::armarx::armem::robot_state::Transform
+    TransformHelper::_convertEntityToTransform(const armem::wm::EntityInstance& item)
     {
         arondto::Transform aronTransform;
         aronTransform.fromAron(item.data());
@@ -211,8 +318,9 @@ namespace armarx::armem::common::robot_state::localization
     }
 
     Eigen::Affine3f
-    interpolateTransform(const std::vector<::armarx::armem::robot_state::Transform>& queue,
-                         armem::Time timestamp)
+    TransformHelper::_interpolateTransform(
+        const std::vector<::armarx::armem::robot_state::Transform>& queue,
+        armem::Time timestamp)
     {
         ARMARX_TRACE;
 
@@ -255,109 +363,33 @@ namespace armarx::armem::common::robot_state::localization
         return simox::math::interpolatePose(posePreIt->transform, poseNextIt->transform, static_cast<float>(t));
     }
 
-    std::vector<Eigen::Affine3f>
-    TransformHelper::obtainTransforms(const armem::wm::CoreSegment& localizationCoreSegment,
-                                      const std::vector<std::string>& tfChain,
-                                      const std::string& agent,
-                                      const armem::Time& timestamp)
-    {
-        const auto& agentProviderSegment = localizationCoreSegment.getProviderSegment(agent);
-
-        ARMARX_DEBUG << "Provider segments"
-                     << simox::alg::get_keys(localizationCoreSegment.providerSegments());
-
-        ARMARX_DEBUG << "Entities: " << simox::alg::get_keys(agentProviderSegment.entities());
-
-        try
-        {
-            std::vector<Eigen::Affine3f> transforms;
-            transforms.reserve(tfChain.size());
-            std::transform(tfChain.begin(),
-                           tfChain.end(),
-                           std::back_inserter(transforms),
-                           [&](const std::string & entityName)
-            {
-                return obtainTransform(
-                           entityName, agentProviderSegment, timestamp);
-            });
-            return transforms;
-        }
-        catch (const armem::error::MissingEntry& missingEntryError)
-        {
-            ARMARX_WARNING << missingEntryError.what();
-        }
-        catch (const ::armarx::exceptions::local::ExpressionException& ex)
-        {
-            ARMARX_WARNING << "local exception: " << ex.what();
-        }
-        catch (...)
-        {
-            ARMARX_WARNING << "Error: " << GetHandledExceptionString();
-        }
-
 
-
-        return {};
+    TransformResult TransformHelper::lookupTransform(
+        const armem::wm::CoreSegment& localizationCoreSegment,
+        const TransformQuery& query)
+    {
+        return _lookupTransform(localizationCoreSegment, query);
     }
-
-    Eigen::Affine3f
-    TransformHelper::obtainTransform(const std::string& entityName,
-                                     const armem::wm::ProviderSegment& agentProviderSegment,
-                                     const armem::Time& timestamp)
+    TransformResult TransformHelper::lookupTransform(
+        const armem::server::wm::CoreSegment& localizationCoreSegment,
+        const TransformQuery& query)
     {
+        return _lookupTransform(localizationCoreSegment, query);
+    }
 
-        ARMARX_DEBUG << "getEntity:" + entityName;
-        const auto& entity = agentProviderSegment.getEntity(entityName);
-
-        ARMARX_DEBUG << "History (size: " << entity.history().size() << ")"
-                     << simox::alg::get_keys(entity.history());
-
-        // if (entity.history.empty())
-        // {
-        //     // TODO(fabian.reister): fixme boom
-        //     ARMARX_ERROR << "No snapshots received.";
-        //     return Eigen::Affine3f::Identity();
-        // }
-
-        std::vector<::armarx::armem::robot_state::Transform> transforms;
-        transforms.reserve(entity.history().size());
-
-        // const auto entitySnapshots = simox::alg::get_values(entity.history());
-
-        const std::vector<wm::EntitySnapshot> entitySnapshots = {entity.getLatestSnapshot()};
-
-        std::transform(
-            entitySnapshots.begin(),
-            entitySnapshots.end(),
-            std::back_inserter(transforms),
-            [](const auto & entitySnapshot)
-        {
-            return convertEntityToTransform(entitySnapshot.getInstance(0));
-        });
-
-        ARMARX_DEBUG << "obtaining transform";
-
-        if (transforms.size() > 1)
-        {
-            // TODO(fabian.reister): remove
-            return transforms.front().transform;
-
-            ARMARX_DEBUG << "More than one snapshots received: " << transforms.size();
-            const auto p = interpolateTransform(transforms, timestamp);
-            ARMARX_DEBUG << "Done interpolating transform";
-            return p;
-        }
-
-        // accept this to fail (will raise armem::error::MissingEntry)
-        if (transforms.empty())
-        {
-            ARMARX_DEBUG << "empty transform";
 
-            throw armem::error::MissingEntry("foo", "bar", "foo2", "bar2", 0);
-        }
+    TransformChainResult TransformHelper::lookupTransformChain(
+        const armem::wm::CoreSegment& localizationCoreSegment,
+        const TransformQuery& query)
+    {
+        return _lookupTransformChain(localizationCoreSegment, query);
+    }
+    TransformChainResult TransformHelper::lookupTransformChain(
+        const armem::server::wm::CoreSegment& localizationCoreSegment,
+        const TransformQuery& query)
+    {
+        return _lookupTransformChain(localizationCoreSegment, query);
+    }
 
-        ARMARX_DEBUG << "single transform";
 
-        return transforms.front().transform;
-    }
 } // namespace armarx::armem::common::robot_state::localization
diff --git a/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.h b/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.h
index cafbedcbca60f859f6fe158190a5985350ddad65..9de1fbd994f5a17c00987ce70d31525db7d9d1dd 100644
--- a/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.h
+++ b/source/RobotAPI/libraries/armem_robot_state/common/localization/TransformHelper.h
@@ -26,44 +26,102 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
+#include <RobotAPI/libraries/armem/core/forward_declarations.h>
 #include <RobotAPI/libraries/armem_robot_state/common/localization/types.h>
 
-namespace armarx::armem::wm
-{
-    class CoreSegment;
-    class ProviderSegment;
-} // namespace armarx::armem::wm
 
 namespace armarx::armem::common::robot_state::localization
 {
     using armarx::armem::common::robot_state::localization::TransformQuery;
     using armarx::armem::common::robot_state::localization::TransformResult;
 
+
+
     class TransformHelper
     {
     public:
-        static TransformResult
-        lookupTransform(const armem::wm::CoreSegment& localizationCoreSegment,
-                        const TransformQuery& query);
 
-        static TransformChainResult
-        lookupTransformChain(const armem::wm::CoreSegment& localizationCoreSegment,
-                             const TransformQuery& query);
+        static
+        TransformResult
+        lookupTransform(
+            const armem::wm::CoreSegment& localizationCoreSegment,
+            const TransformQuery& query);
+
+        static
+        TransformResult
+        lookupTransform(
+            const armem::server::wm::CoreSegment& localizationCoreSegment,
+            const TransformQuery& query);
+
+
+        static
+        TransformChainResult
+        lookupTransformChain(
+            const armem::wm::CoreSegment& localizationCoreSegment,
+            const TransformQuery& query);
+
+        static
+        TransformChainResult
+        lookupTransformChain(
+            const armem::server::wm::CoreSegment& localizationCoreSegment,
+            const TransformQuery& query);
+
 
     private:
-        static std::vector<std::string>
-        buildTransformChain(const armem::wm::CoreSegment& localizationCoreSegment,
-                            const TransformQuery& query);
-
-        static std::vector<Eigen::Affine3f>
-        obtainTransforms(const armem::wm::CoreSegment& localizationCoreSegment,
-                         const std::vector<std::string>& tfChain,
-                         const std::string& agent,
-                         const armem::Time& timestamp);
-
-        static Eigen::Affine3f
-        obtainTransform(const std::string& entityName,
-                        const armem::wm::ProviderSegment& agentProviderSegment,
-                        const armem::Time& timestamp);
+
+        template <class ...Args>
+        static
+        TransformResult
+        _lookupTransform(
+            const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+            const TransformQuery& query);
+
+
+        template <class ...Args>
+        static
+        TransformChainResult
+        _lookupTransformChain(
+            const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+            const TransformQuery& query);
+
+
+        template <class ...Args>
+        static
+        std::vector<std::string>
+        _buildTransformChain(
+            const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+            const TransformQuery& query);
+
+
+        template <class ...Args>
+        static
+        std::vector<Eigen::Affine3f>
+        _obtainTransforms(
+            const armem::base::CoreSegmentBase<Args...>& localizationCoreSegment,
+            const std::vector<std::string>& tfChain,
+            const std::string& agent,
+            const armem::Time& timestamp);
+
+
+        template <class ...Args>
+        static
+        Eigen::Affine3f
+        _obtainTransform(
+            const std::string& entityName,
+            const armem::base::ProviderSegmentBase<Args...>& agentProviderSegment,
+            const armem::Time& timestamp);
+
+
+        static
+        Eigen::Affine3f
+        _interpolateTransform(
+            const std::vector<::armarx::armem::robot_state::Transform>& queue,
+            armem::Time timestamp);
+
+        static
+        ::armarx::armem::robot_state::Transform
+        _convertEntityToTransform(
+            const armem::wm::EntityInstance& item);
+
     };
-} // namespace armarx::armem::common::robot_state::localization
\ No newline at end of file
+} // namespace armarx::armem::common::robot_state::localization
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 bd1e9c4fc9f8d95f2abbfd86f3eee5081e8f8ab4..e4e9dc4f7b45910a4f0c50b729e8881ad5a69a4e 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
@@ -19,7 +19,6 @@
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/query_fns.h>
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
 #include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
@@ -41,8 +40,6 @@ namespace armarx::armem::server::robot_state::description
 
     void Segment::onConnect(const RobotUnitInterfacePrx& robotUnitPrx)
     {
-        Base::onConnect();
-
         robotUnit = robotUnitPrx;
 
         // store the robot description linked to the robot unit in this segment
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 ce82f0afad8872d6e660078ce9e2425ce824ad3b..118123c6b2aadea5b2e246dcde6db6a641a76b6a 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
@@ -26,7 +26,6 @@
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
 #include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 
 #include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
@@ -48,6 +47,10 @@ namespace armarx::armem::server::robot_state::localization
 
     Segment::~Segment() = default;
 
+    void Segment::onConnect()
+    {
+    }
+
 
     Segment::RobotFramePoseMap
     Segment::getRobotFramePosesLocking(const armem::Time& timestamp) const
@@ -64,14 +67,17 @@ namespace armarx::armem::server::robot_state::localization
         using common::robot_state::localization::TransformQuery;
 
         RobotFramePoseMap frames;
-
-        const auto knownRobots = simox::alg::get_keys(*segment);
-        for (const auto& robotName : knownRobots)
+        for (const auto& [robotName, _] : *segment)
         {
-            TransformQuery query{.header{.parentFrame = GlobalFrame,
-                                         .frame       = "root", // TODO, FIXME
-                                         .agent       = robotName,
-                                         .timestamp   = timestamp}};
+            TransformQuery query
+            {
+                .header{
+                    .parentFrame = GlobalFrame,
+                    .frame       = "root", // TODO, FIXME
+                    .agent       = robotName,
+                    .timestamp   = timestamp
+                }
+            };
 
             const auto result = TransformHelper::lookupTransformChain(*segment, query);
             if (not result)
@@ -105,16 +111,17 @@ namespace armarx::armem::server::robot_state::localization
         using common::robot_state::localization::TransformQuery;
 
         RobotPoseMap robotGlobalPoses;
-
-        const std::vector<std::string> knownRobots = simox::alg::get_keys(*segment);
-
-        for (const std::string& robotName : knownRobots)
+        for (const auto& [robotName, _] : *segment)
         {
-
-            TransformQuery query{.header{.parentFrame = GlobalFrame,
-                                         .frame       = "root", // TODO, FIXME
-                                         .agent       = robotName,
-                                         .timestamp   = timestamp}};
+            TransformQuery query
+            {
+                .header{
+                    .parentFrame = GlobalFrame,
+                    .frame       = "root", // TODO, FIXME
+                    .agent       = robotName,
+                    .timestamp   = timestamp
+                }
+            };
 
             const auto result = TransformHelper::lookupTransform(*segment, query);
             if (not result)
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.h b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.h
index 53d11236231f9e6e7017f4de984c5ad4da97e6c2..31fffb4207e7bfe40a0d3f6ed23b554069076a6a 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.h
+++ b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.h
@@ -41,7 +41,7 @@
 
 namespace armarx::armem
 {
-    class EntityUpdate;
+    struct EntityUpdate;
 }  // namespace armarx::armem
 
 namespace armarx::armem::server::robot_state::localization
@@ -61,6 +61,8 @@ namespace armarx::armem::server::robot_state::localization
         Segment(server::MemoryToIceAdapter& iceMemory);
         virtual ~Segment() override;
 
+        void onConnect();
+
         RobotPoseMap getRobotGlobalPoses(const armem::Time& timestamp) const;
         RobotPoseMap getRobotGlobalPosesLocking(const armem::Time& timestamp) const;
 
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 9f2fadcf5b12906a63de4a08d05ce4b40ea33419..d08ae0866342e033946e93acb3a77d94f7345676 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/proprioception/Segment.cpp
@@ -11,7 +11,6 @@
 #include <RobotAPI/libraries/armem_robot_state/types.h>
 
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/visitor.h>
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/client/Writer.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
@@ -40,8 +39,6 @@ namespace armarx::armem::server::robot_state::proprioception
 
     void Segment::onConnect(RobotUnitInterfacePrx robotUnitPrx)
     {
-        Base::onConnect();
-
         this->robotUnit = robotUnitPrx;
 
         std::string providerSegmentName = "Robot";
diff --git a/source/RobotAPI/libraries/armem_vision/client/laser_scans/Reader.cpp b/source/RobotAPI/libraries/armem_vision/client/laser_scans/Reader.cpp
index 9c46b0c4729dfe6ca038c1f31ef81255f56d4968..4bc22306d7d26603d1edba2c8fc8f8aed40b1a8d 100644
--- a/source/RobotAPI/libraries/armem_vision/client/laser_scans/Reader.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/laser_scans/Reader.cpp
@@ -33,22 +33,20 @@
 #include <RobotAPI/libraries/aron/core/navigator/data/complex/NDArray.h>
 
 // RobotAPI Armem
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/util/util.h>
+
 #include <RobotAPI/libraries/armem/client/Query.h>
 #include <RobotAPI/libraries/armem/client/Reader.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/selectors.h>
 
-#include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Entity.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h>
-#include <RobotAPI/libraries/armem/util/util.h>
 #include <RobotAPI/libraries/armem_vision/aron/LaserScan.aron.generated.h>
 #include <RobotAPI/libraries/armem_vision/aron_conversions.h>
 #include <RobotAPI/libraries/armem_vision/types.h>
 
+
 namespace armarx::armem::vision::laser_scans::client
 {
 
@@ -124,11 +122,10 @@ namespace armarx::armem::vision::laser_scans::client
     }
 
     std::vector<LaserScanStamped>
-    asLaserScans(const std::map<std::string, wm::Entity>& entities)
+    asLaserScans(const wm::ProviderSegment& providerSegment)
     {
         std::vector<LaserScanStamped> outV;
-
-        if (entities.empty())
+        if (providerSegment.empty())
         {
             ARMARX_WARNING << "No entities!";
         }
@@ -153,29 +150,25 @@ namespace armarx::armem::vision::laser_scans::client
         };
 
         // loop over all entities and their snapshots
-        for (const auto& [s, entity] : entities)
+        providerSegment.forEachEntity([&outV, &convert](const wm::Entity & entity)
         {
+            // If we don't need this warning, we could directly iterate over the snapshots.
             if (entity.empty())
             {
-                ARMARX_WARNING << "Empty history for " << s;
+                ARMARX_WARNING << "Empty history for " << entity.id();
             }
-
             ARMARX_DEBUG << "History size: " << entity.size();
 
-            for (const auto& [ss, entitySnapshot] : entity)
+            entity.forEachInstance([&outV, &convert](const wm::EntityInstance & entityInstance)
             {
-                for (const auto& entityInstance : entitySnapshot.instances())
+                if (const auto o = tryCast<arondto::LaserScanStamped>(entityInstance))
                 {
-                    const auto o =
-                        tryCast<arondto::LaserScanStamped>(entityInstance);
-
-                    if (o)
-                    {
-                        outV.push_back(convert(*o, entityInstance));
-                    }
+                    outV.push_back(convert(*o, entityInstance));
                 }
-            }
-        }
+                return true;
+            });
+            return true;
+        });
 
         return outV;
     }
@@ -202,13 +195,16 @@ namespace armarx::armem::vision::laser_scans::client
         }
 
         // now create result from memory
-        const auto& entities =
-            qResult.memory.getCoreSegment(properties.memoryName)
-            .getProviderSegment(query.agent)
-            .entities();
+        const wm::ProviderSegment& providerSegment =
+            qResult.memory.getCoreSegment(properties.memoryName).getProviderSegment(query.agent);
 
-        const auto laserScans = asLaserScans(entities);
-        const auto sensors    = simox::alg::get_keys(entities);
+        const auto laserScans = asLaserScans(providerSegment);
+        std::vector<std::string> sensors;
+        providerSegment.forEachEntity([&sensors](const wm::Entity & entity)
+        {
+            sensors.push_back(entity.name());
+            return true;
+        });
 
         return {.laserScans   = laserScans,
                 .sensors      = sensors,
diff --git a/source/RobotAPI/libraries/armem_vision/client/laser_scans/Writer.cpp b/source/RobotAPI/libraries/armem_vision/client/laser_scans/Writer.cpp
index 7358e504ffecf3a2a710bd77b1631437e3818a42..861e02c4c9fcabbc40caebba3451b69e81e5016c 100644
--- a/source/RobotAPI/libraries/armem_vision/client/laser_scans/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/laser_scans/Writer.cpp
@@ -1,7 +1,7 @@
 #include "Writer.h"
 
 #include <RobotAPI/libraries/armem/core/error.h>
-#include "RobotAPI/libraries/armem_vision/aron_conversions.h"
+#include <RobotAPI/libraries/armem_vision/aron_conversions.h>
 #include <RobotAPI/libraries/armem_vision/aron/LaserScan.aron.generated.h>
 
 
diff --git a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp
index ba7edf547d1d45873609d723b92934b18d7f5c88..717a2ec98e5283515a5454bfa31eb7c00636b01c 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp
@@ -19,13 +19,13 @@
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 
 // ArmarXCore
-#include "ArmarXCore/core/exceptions/LocalException.h"
+#include <ArmarXCore/core/exceptions/LocalException.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/LogSender.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
 // RobotAPI Interfaces
-#include "RobotAPI/libraries/aron/converter/eigen/EigenConverter.h"
+#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
 #include <RobotAPI/interface/armem/server/ReadingMemoryInterface.h>
 #include <RobotAPI/interface/units/LaserScannerUnit.h>
@@ -40,11 +40,7 @@
 #include <RobotAPI/libraries/armem/client/Reader.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/client/query/selectors.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/CoreSegment.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Entity.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/EntityInstance.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/Memory.h>
-#include <RobotAPI/libraries/armem/core/workingmemory/ProviderSegment.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/util/util.h>
 #include <RobotAPI/libraries/armem_vision/aron/LaserScan.aron.generated.h>
 #include <RobotAPI/libraries/armem_vision/aron_conversions.h>
@@ -68,20 +64,23 @@ namespace armarx::armem::vision::occupancy_grid::client
         return qb;
     }
 
-    OccupancyGrid asOccupancyGrid(const std::map<std::string, wm::Entity>& entities)
+    OccupancyGrid asOccupancyGrid(const wm::ProviderSegment& providerSegment)
     {
-        ARMARX_CHECK(not entities.empty()) << "No entities";
-        ARMARX_CHECK(entities.size() == 1) << "There should be only one entity!";
+        ARMARX_CHECK(not providerSegment.empty()) << "No entities";
+        ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
 
-        const wm::Entity& entity = entities.begin()->second;
-        ARMARX_CHECK(not entity.empty()) << "No snapshots";
-
-        const auto& entitySnapshot = entity.getLatestSnapshot();
-        ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
+        const wm::EntityInstance* entityInstance = nullptr;
+        providerSegment.forEachEntity([&entityInstance](const wm::Entity & entity)
+        {
+            const auto& entitySnapshot = entity.getLatestSnapshot();
+            ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
 
-        const auto& entityInstance = entitySnapshot.instances().front();
+            entityInstance = &entitySnapshot.getInstance(0);
+            return false;
+        });
+        ARMARX_CHECK_NOT_NULL(entityInstance);
 
-        const auto aronDto = tryCast<arondto::OccupancyGrid>(entityInstance);
+        const auto aronDto = tryCast<arondto::OccupancyGrid>(*entityInstance);
         ARMARX_CHECK(aronDto) << "Failed casting to OccupancyGrid";
 
         OccupancyGrid occupancyGrid;
@@ -89,7 +88,7 @@ namespace armarx::armem::vision::occupancy_grid::client
 
         // direct access to grid data
         const auto ndArrayNavigator = aron::datanavigator::NDArrayNavigator::DynamicCast(
-                                          entityInstance.data()->getElement("grid"));
+                                          entityInstance->data()->getElement("grid"));
         ARMARX_CHECK_NOT_NULL(ndArrayNavigator);
 
         occupancyGrid.grid = aron::converter::AronEigenConverter::ConvertToArray<float>(*ndArrayNavigator);
@@ -118,11 +117,10 @@ namespace armarx::armem::vision::occupancy_grid::client
         }
 
         // now create result from memory
-        const auto& entities = qResult.memory.getCoreSegment(properties().memoryName)
-                               .getProviderSegment(query.providerName)
-                               .entities();
+        const wm::ProviderSegment& providerSegment = qResult.memory.getCoreSegment(properties().memoryName)
+                .getProviderSegment(query.providerName);
 
-        if (entities.empty())
+        if (providerSegment.empty())
         {
             ARMARX_WARNING << "No entities.";
             return {.occupancyGrid = std::nullopt,
@@ -132,7 +130,7 @@ namespace armarx::armem::vision::occupancy_grid::client
 
         try
         {
-            const auto occupancyGrid = asOccupancyGrid(entities);
+            const auto occupancyGrid = asOccupancyGrid(providerSegment);
             return Result{.occupancyGrid = occupancyGrid,
                           .status        = Result::Status::Success};
         }
diff --git a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h
index a43c2c7c1151223358d5b1ab608f824fd3cdf66f..eaf9b2fdfa2021db7f8e1215baedc6aba907dec3 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.h
@@ -23,9 +23,9 @@
 
 #include <mutex>
 
-#include "RobotAPI/libraries/armem/client/util/SimpleReaderBase.h"
-#include "RobotAPI/libraries/armem/core/Time.h"
-#include "RobotAPI/libraries/armem_vision/types.h"
+#include <RobotAPI/libraries/armem/client/util/SimpleReaderBase.h>
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem_vision/types.h>
 #include <RobotAPI/libraries/armem/client/query/Builder.h>
 
 namespace armarx::armem::vision::occupancy_grid::client
diff --git a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
index f2930f14f479d9ae68ee222f2643edf327392a43..ce5883afb6eeb72c7ebb9337d0b4980eee7e462e 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
@@ -1,8 +1,9 @@
 #include "Writer.h"
 
-#include "RobotAPI/libraries/armem_vision/aron_conversions.h"
+#include <RobotAPI/libraries/armem_vision/aron_conversions.h>
 #include <RobotAPI/libraries/armem_vision/aron/OccupancyGrid.aron.generated.h>
 
+
 namespace armarx::armem::vision::occupancy_grid::client
 {
     Writer::~Writer() = default;
@@ -67,4 +68,4 @@ namespace armarx::armem::vision::occupancy_grid::client
         return SimpleWriterBase::Properties{.memoryName      = "Vision",
                                             .coreSegmentName = "OccupancyGrid"};
     }
-} // namespace armarx::armem::vision::occupancy_grid::client
\ No newline at end of file
+} // namespace armarx::armem::vision::occupancy_grid::client
diff --git a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.h b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.h
index bf1268444c333d10bb3c2f9efb68da11fe697cc8..b2a900321224d2c4617cab541c7b1cf77f41d1f1 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.h
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.h
@@ -24,8 +24,8 @@
 
 #include <mutex>
 
-#include "RobotAPI/libraries/armem/client/util/SimpleWriterBase.h"
-#include "RobotAPI/libraries/armem_vision/types.h"
+#include <RobotAPI/libraries/armem/client/util/SimpleWriterBase.h>
+#include <RobotAPI/libraries/armem_vision/types.h>
 
 namespace armarx::armem::vision::occupancy_grid::client
 {
diff --git a/source/RobotAPI/libraries/aron/core/CMakeLists.txt b/source/RobotAPI/libraries/aron/core/CMakeLists.txt
index 62548c29719f3942afee49a45e9a3f24a4232634..c5282fb54aba97b583f15f2df1876c0dde3e4ead 100644
--- a/source/RobotAPI/libraries/aron/core/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/core/CMakeLists.txt
@@ -151,6 +151,7 @@ set(LIB_HEADERS
     navigator/data/primitive/Bool.h
     navigator/data/AllNavigators.h
     navigator/data/NavigatorFactory.h
+    navigator/data/forward_declarations.h
 
     navigator/type/Navigator.h
     navigator/type/detail/NavigatorBase.h
@@ -181,6 +182,7 @@ set(LIB_HEADERS
     navigator/type/primitive/Time.h
     navigator/type/AllNavigators.h
     navigator/type/NavigatorFactory.h
+    navigator/type/forward_declarations.h
 
     navigator/visitors/DataVisitor.h
     navigator/visitors/TypedDataVisitor.h
diff --git a/source/RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h b/source/RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h
new file mode 100644
index 0000000000000000000000000000000000000000..d76939c317aafd2acc4eb797d38d1ba1ff96da26
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/core/navigator/data/forward_declarations.h
@@ -0,0 +1,22 @@
+#pragma once
+
+#include <memory>
+
+
+namespace armarx::aron::datanavigator
+{
+    class Navigator;
+    using NavigatorPtr = std::shared_ptr<Navigator>;
+
+    using DictNavigatorPtr = std::shared_ptr<class DictNavigator>;
+    using ListNavigatorPtr = std::shared_ptr<class ListNavigator>;
+    using NDArrayNavigatorPtr = std::shared_ptr<class NDArrayNavigator>;
+
+    using IntNavigatorPtr = std::shared_ptr<class IntNavigator>;
+    using LongNavigatorPtr = std::shared_ptr<class LongNavigator>;
+    using FloatNavigatorPtr = std::shared_ptr<class FloatNavigator>;
+    using DoubleNavigatorPtr = std::shared_ptr<class DoubleNavigator>;
+    using StringNavigatorPtr = std::shared_ptr<class StringNavigator>;
+    using BoolNavigatorPtr = std::shared_ptr<class BoolNavigator>;
+
+}
diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h b/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h
index 51ea5a762037da7b7e4a3808c42d36a468d9c6b1..82702de998bb7e6b0972afd9e96ae027b433eae3 100644
--- a/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h
+++ b/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h
@@ -12,7 +12,6 @@
 #include "ndarray/OpenCVMat.h"
 #include "ndarray/Orientation.h"
 #include "ndarray/PCLPointCloud.h"
-#include "ndarray/PCLPointCloud.h"
 #include "ndarray/Pose.h"
 #include "ndarray/Position.h"
 #include "enum/IntEnum.h"
diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h b/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h
new file mode 100644
index 0000000000000000000000000000000000000000..af5d62e7c0decbc296cea942fa1983b0e0cb5924
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h
@@ -0,0 +1,34 @@
+#pragma once
+
+#include <memory>
+
+
+namespace armarx::aron::typenavigator
+{
+    using NavigatorPtr = std::shared_ptr<class Navigator>;
+
+    using DictNavigatorPtr = std::shared_ptr<class DictNavigator>;
+    using ListNavigatorPtr = std::shared_ptr<class ListNavigator>;
+    using ObjectNavigatorPtr = std::shared_ptr<class ObjectNavigator>;
+    using PoseNavigatorPtr = std::shared_ptr<class PoseNavigator>;
+    using TupleNavigatorPtr = std::shared_ptr<class TupleNavigator>;
+    using NDArrayNavigatorPtr = std::shared_ptr<class NDArrayNavigator>;
+    using EigenMatrixNavigatorPtr = std::shared_ptr<class EigenMatrixNavigator>;
+    using EigenQuaternionNavigatorPtr = std::shared_ptr<class EigenQuaternionNavigator>;
+    using IVTCByteImageNavigatorPtr = std::shared_ptr<class IVTCByteImageNavigator>;
+    using OpenCVMatNavigatorPtr = std::shared_ptr<class OpenCVMatNavigator>;
+    using OrientationNavigatorPtr = std::shared_ptr<class OrientationNavigator>;
+    using PCLPointCloudNavigatorPtr = std::shared_ptr<class PCLPointCloudNavigator>;
+    using PositionNavigatorPtr = std::shared_ptr<class PositionNavigator>;
+    using IntEnumNavigatorPtr = std::shared_ptr<class IntEnumNavigator>;
+
+    using IntNavigatorPtr = std::shared_ptr<class IntNavigator>;
+    using LongNavigatorPtr = std::shared_ptr<class LongNavigator>;
+    using FloatNavigatorPtr = std::shared_ptr<class FloatNavigator>;
+    using DoubleNavigatorPtr = std::shared_ptr<class DoubleNavigator>;
+    using StringNavigatorPtr = std::shared_ptr<class StringNavigator>;
+    using BoolNavigatorPtr = std::shared_ptr<class BoolNavigator>;
+    using TimeNavigatorPtr = std::shared_ptr<class TimeNavigator>;
+
+}
+