diff --git a/.gitignore b/.gitignore
index aba6e15d3795100181de6448968fc7d75a77e367..f5491d4d94d0abcb88550a41c0ef97e4949665d5 100644
--- a/.gitignore
+++ b/.gitignore
@@ -76,3 +76,5 @@ etc/python/dist/*
 data/RobotAPI/ArVizStorage/
 
 .vscode/
+.clang-format
+.clang-tidy
diff --git a/source/RobotAPI/components/ArViz/ArVizStorage.cpp b/source/RobotAPI/components/ArViz/ArVizStorage.cpp
index 261ac386dc405948deba78bebe3a556e2af5574e..decbf95c39a16482ee3bc6975396812397c3d37e 100644
--- a/source/RobotAPI/components/ArViz/ArVizStorage.cpp
+++ b/source/RobotAPI/components/ArViz/ArVizStorage.cpp
@@ -22,6 +22,7 @@
 
 #include "ArVizStorage.h"
 
+#include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/util/IceBlobToObject.h>
 #include <ArmarXCore/core/util/ObjectToIceBlob.h>
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
@@ -138,6 +139,15 @@ namespace armarx
 
         for (auto& update : updates)
         {
+            if (update.component.empty())
+            {
+                ARMARX_INFO << deactivateSpam(120)
+                            << "Discarding ArViz update with empty component name. Check whether "
+                            << "you correctly create your ArViz client (`armarx::viz::Client`) "
+                            << "in your code.";
+                continue;
+            }
+
             auto& historyEntry = history.emplace_back();
             historyEntry.revision = revision;
             historyEntry.timestampInMicroseconds = nowInMicroSeconds;
diff --git a/source/RobotAPI/components/ArViz/Client/Client.cpp b/source/RobotAPI/components/ArViz/Client/Client.cpp
index 268da627405450db9c12ac2dcba4871fff505f7b..d6281ea2098784dc7ca6b948eec6c8daf17e86e0 100644
--- a/source/RobotAPI/components/ArViz/Client/Client.cpp
+++ b/source/RobotAPI/components/ArViz/Client/Client.cpp
@@ -28,6 +28,7 @@ Client::Client(ManagedIceObject& obj,
                std::string const& storageName)
 {
     componentName = obj.getName();
+    ARMARX_CHECK_NOT_EMPTY(componentName) << "ArViz client must be created with non-empty component name.";
     obj.getTopic(topic, topicName);
     obj.getProxy(storage, storageName);
 }
@@ -35,6 +36,7 @@ Client::Client(ManagedIceObject& obj,
 Client Client::createFromTopic(std::string const& componentName, Topic::ProxyType const& topic)
 {
     Client client;
+    ARMARX_CHECK_NOT_EMPTY(componentName);
     client.componentName = componentName;
     client.topic = topic;
     return client;
@@ -68,6 +70,13 @@ Client Client::createForGuiPlugin(Component& component,
     return client;
 }
 
+Layer Client::layer(const std::string &name) const
+{
+    ARMARX_CHECK_NOT_EMPTY(componentName) << "Layers must be created with non-empty component name.";
+    ARMARX_CHECK_NOT_EMPTY(name) << "Layers must be created with non-empty layer name.";
+    return Layer(componentName, name);
+}
+
 CommitResult Client::commit(const StagedCommit& commit)
 {
     CommitResult result;
diff --git a/source/RobotAPI/components/ArViz/Client/Client.h b/source/RobotAPI/components/ArViz/Client/Client.h
index d05dc398064559ecdbb8c9610afd520419494f5d..f2d406fece5753b91d89cc56f26c824711efde62 100644
--- a/source/RobotAPI/components/ArViz/Client/Client.h
+++ b/source/RobotAPI/components/ArViz/Client/Client.h
@@ -130,10 +130,7 @@ namespace viz
                                          std::string const& topicName = "ArVizTopic",
                                          std::string const& storageName = "ArVizStorage");
 
-        Layer layer(std::string const& name) const
-        {
-            return Layer(componentName, name);
-        }
+        Layer layer(std::string const& name) const;
 
         StagedCommit stage()
         {
diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
index cde81dc6801e7205867c6ff6cd679c69a1db9d92..e7fdc5eaa92b960a964d78deecce66dfd242227f 100644
--- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
+++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
@@ -22,73 +22,66 @@
 
 #include "ExampleMemoryClient.h"
 
-#include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h>
-
-#include <random>
 #include <algorithm>
+#include <random>
 
+#include <Eigen/Geometry>
+
+#include <opencv2/imgcodecs.hpp>
+#include <opencv2/imgproc.hpp>
 #include <opencv2/opencv.hpp>
 
 #include <SimoxUtility/color/cmaps.h>
+#include <SimoxUtility/math/pose/pose.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/time/CycleUtil.h>
 
+#include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h>
 #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
-#include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #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/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/core/operations.h>
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
-
-#include <RobotAPI/libraries/aron/core/data/variant/All.h>
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-#include <ArmarXCore/core/time/CycleUtil.h>
-
-#include <SimoxUtility/color/cmaps.h>
-#include <SimoxUtility/math/pose/pose.h>
-
-#include <Eigen/Geometry>
-
-#include <random>
-
-#include <opencv2/imgcodecs.hpp>
-#include <opencv2/imgproc.hpp>
-
-#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
+#include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 #include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
 
 namespace armarx
 {
 
-    armarx::PropertyDefinitionsPtr ExampleMemoryClient::createPropertyDefinitions()
+    armarx::PropertyDefinitionsPtr
+    ExampleMemoryClient::createPropertyDefinitions()
     {
-        armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier());
+        armarx::PropertyDefinitionsPtr defs =
+            new ComponentPropertyDefinitions(getConfigIdentifier());
 
         defs->topic(debugObserver);
 
         defs->optional(p.usedMemoryName, "mem.UsedMemoryName", "Name of the memory to use.");
-        defs->optional(p.commitFrequency, "ex.CommitFrequency", "Frequency in which example data is commited. (max = 50Hz)");
+        defs->optional(p.commitFrequency,
+                       "ex.CommitFrequency",
+                       "Frequency in which example data is commited. (max = 50Hz)");
 
         return defs;
     }
 
-
-    std::string ExampleMemoryClient::getDefaultName() const
+    std::string
+    ExampleMemoryClient::getDefaultName() const
     {
         return "ExampleMemoryClient";
     }
 
-
-    void ExampleMemoryClient::onInitComponent()
+    void
+    ExampleMemoryClient::onInitComponent()
     {
     }
 
-
-    void ExampleMemoryClient::onConnectComponent()
+    void
+    ExampleMemoryClient::onConnectComponent()
     {
         p.commitFrequency = std::min(p.commitFrequency, 50.f);
 
@@ -116,33 +109,36 @@ namespace armarx
 
         // Subscribe to example_entity updates
         // Using a lambda:
-        memoryNameSystem().subscribe(
-            exampleEntityID,
-            [&](const armem::MemoryID & exampleEntityID, const std::vector<armem::MemoryID>& snapshotIDs)
-        {
-            ARMARX_INFO << "Entity " << exampleEntityID << " was updated by " << snapshotIDs.size() << " snapshots.";
-        });
+        memoryNameSystem().subscribe(exampleEntityID,
+                                     [&](const armem::MemoryID& exampleEntityID,
+                                         const std::vector<armem::MemoryID>& snapshotIDs)
+                                     {
+                                         ARMARX_INFO << "Entity " << exampleEntityID
+                                                     << " was updated by " << snapshotIDs.size()
+                                                     << " snapshots.";
+                                     });
         // Using a member function:
-        memoryNameSystem().subscribe(exampleEntityID, this, &ExampleMemoryClient::processExampleEntityUpdate);
+        memoryNameSystem().subscribe(
+            exampleEntityID, this, &ExampleMemoryClient::processExampleEntityUpdate);
 
 
         task = new RunningTask<ExampleMemoryClient>(this, &ExampleMemoryClient::run);
         task->start();
     }
 
-
-    void ExampleMemoryClient::onDisconnectComponent()
+    void
+    ExampleMemoryClient::onDisconnectComponent()
     {
         task->stop();
     }
 
-
-    void ExampleMemoryClient::onExitComponent()
+    void
+    ExampleMemoryClient::onExitComponent()
     {
     }
 
-
-    void ExampleMemoryClient::run()
+    void
+    ExampleMemoryClient::run()
     {
         ARMARX_IMPORTANT << "Running example.";
         runStarted = armem::Time::Now();
@@ -195,8 +191,8 @@ namespace armarx
         }
     }
 
-
-    armem::MemoryID ExampleMemoryClient::addProviderSegment()
+    armem::MemoryID
+    ExampleMemoryClient::addProviderSegment()
     {
         armem::data::AddSegmentInput input;
         input.coreSegmentName = "ExampleModality";
@@ -209,8 +205,8 @@ namespace armarx
         return armem::MemoryID(result.segmentID);
     }
 
-
-    armem::MemoryID ExampleMemoryClient::commitSingleSnapshot(const armem::MemoryID& entityID)
+    armem::MemoryID
+    ExampleMemoryClient::commitSingleSnapshot(const armem::MemoryID& entityID)
     {
         std::default_random_engine gen(std::random_device{}());
         std::uniform_int_distribution<int> distrib(-20, 20);
@@ -239,11 +235,7 @@ namespace armarx
         dict2->addElement("lin", lin);
         dict2->addElement("rand", rand);
 
-        update.instancesData =
-        {
-            dict1,
-            dict2
-        };
+        update.instancesData = {dict1, dict2};
 
         ARMARX_IMPORTANT << "Committing " << update;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
@@ -256,8 +248,8 @@ namespace armarx
         return updateResult.snapshotID;
     }
 
-
-    void ExampleMemoryClient::commitMultipleSnapshots(const armem::MemoryID& entityID, int num)
+    void
+    ExampleMemoryClient::commitMultipleSnapshots(const armem::MemoryID& entityID, int num)
     {
         // Commit a number of updates with different timestamps and number of instances.
         armem::Commit commit;
@@ -280,20 +272,21 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::queryLatestSnapshot(const armem::MemoryID& entityID)
+    void
+    ExampleMemoryClient::queryLatestSnapshot(const armem::MemoryID& entityID)
     {
-        ARMARX_IMPORTANT
-                << "Querying latest snapshot: "
-                << "\n- entityID:     \t'" << entityID << "'"
-                ;
+        ARMARX_IMPORTANT << "Querying latest snapshot: "
+                         << "\n- entityID:     \t'" << entityID << "'";
 
         armem::client::query::Builder builder;
-        builder
-        .coreSegments().withID(entityID)
-        .providerSegments().withID(entityID)
-        .entities().withID(entityID)
-        .snapshots().latest();
+        builder.coreSegments()
+            .withID(entityID)
+            .providerSegments()
+            .withID(entityID)
+            .entities()
+            .withID(entityID)
+            .snapshots()
+            .latest();
 
         armem::client::QueryResult qResult = memoryReader.query(builder.buildQueryInput());
         ARMARX_INFO << qResult;
@@ -306,17 +299,15 @@ namespace armarx
 
             const armem::wm::Entity* entity = memory.findEntity(entityID);
             ARMARX_CHECK_NOT_NULL(entity)
-                    << "Entity " << entityID << " was not found in " << armem::print(memory);
+                << "Entity " << entityID << " was not found in " << armem::print(memory);
             ARMARX_CHECK_GREATER_EQUAL(entity->size(), 1);
 
             const armem::wm::EntitySnapshot& snapshot = entity->getLatestSnapshot();
             ARMARX_CHECK_GREATER_EQUAL(snapshot.size(), 1);
 
             ARMARX_INFO << "Result: "
-                        << "\n- entity:       \t" << entity->name()
-                        << "\n- snapshot:     \t" << snapshot.time()
-                        << "\n- #instances:   \t" << snapshot.size()
-                        ;
+                        << "\n- entity:       \t" << entity->name() << "\n- snapshot:     \t"
+                        << snapshot.time() << "\n- #instances:   \t" << snapshot.size();
 
             // Show memory contents in remote gui.
             tab.queryResult = std::move(memory);
@@ -328,13 +319,11 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::queryExactSnapshot(const armem::MemoryID& snapshotID)
+    void
+    ExampleMemoryClient::queryExactSnapshot(const armem::MemoryID& snapshotID)
     {
-        ARMARX_IMPORTANT
-                << "Querying exact snapshot: "
-                << "\n- snapshotID:     \t'" << snapshotID << "'"
-                ;
+        ARMARX_IMPORTANT << "Querying exact snapshot: "
+                         << "\n- snapshotID:     \t'" << snapshotID << "'";
 
         namespace qf = armem::client::query_fns;
         armem::client::query::Builder qb;
@@ -346,12 +335,12 @@ namespace armarx
         if (qResult.success)
         {
             armem::wm::Memory memory = std::move(qResult.memory);
-            const armem::wm::EntitySnapshot& entitySnapshot = memory.getEntity(snapshotID).getLatestSnapshot();
+            const armem::wm::EntitySnapshot& entitySnapshot =
+                memory.getEntity(snapshotID).getLatestSnapshot();
 
             ARMARX_INFO << "Result snapshot: "
-                        << "\n- time:        \t" << entitySnapshot.time()
-                        << "\n- # instances: \t" << entitySnapshot.size()
-                        ;
+                        << "\n- time:        \t" << entitySnapshot.time() << "\n- # instances: \t"
+                        << entitySnapshot.size();
         }
         else
         {
@@ -359,10 +348,12 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::commitExampleData()
+    void
+    ExampleMemoryClient::commitExampleData()
     {
-        ARMARX_IMPORTANT << "Adding segment " << "ExampleData" << "/" << getName();
+        ARMARX_IMPORTANT << "Adding segment "
+                         << "ExampleData"
+                         << "/" << getName();
 
         auto addSegmentResult = memoryWriter.addSegment("ExampleData", getName());
         if (!addSegmentResult.success)
@@ -393,7 +384,7 @@ namespace armarx
             toAron(data.memoryID, armem::MemoryID());
             toAron(data.memoryLink.memoryID, armem::MemoryID());
             ARMARX_CHECK_NOT_NULL(data.toAron());
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
 
@@ -410,29 +401,27 @@ namespace armarx
             data.the_int = 42;
             data.the_long = 424242;
             data.the_string = "fourty two";
-            data.the_float_list = { 21, 42, 84 };
-            data.the_int_list = { 21, 42, 84 };
+            data.the_float_list = {21, 42, 84};
+            data.the_int_list = {21, 42, 84};
             data.the_string_list = simox::alg::multi_to_string(data.the_int_list);
             data.the_object_list.emplace_back();
 
-            data.the_float_dict =
-            {
-                { "one", 1.0 },
-                { "two", 2.0 },
-                { "three", 3.0 },
+            data.the_float_dict = {
+                {"one", 1.0},
+                {"two", 2.0},
+                {"three", 3.0},
             };
-            data.the_int_dict =
-            {
-                { "one", 1 },
-                { "two", 2 },
-                { "three", 3 },
+            data.the_int_dict = {
+                {"one", 1},
+                {"two", 2},
+                {"three", 3},
             };
 
-            data.the_position = { 42, 24, 4224 };
+            data.the_position = {42, 24, 4224};
             data.the_orientation = Eigen::AngleAxisf(1.57f, Eigen::Vector3f(1, 1, 1).normalized());
             data.the_pose = simox::math::pose(data.the_position, data.the_orientation);
 
-            data.the_3x1_vector = { 24, 42, 2442 };
+            data.the_3x1_vector = {24, 42, 2442};
             data.the_4x4_matrix = 42 * Eigen::Matrix4f::Identity();
 
             toAron(data.memoryID, armem::MemoryID()); // ////1/1
@@ -444,13 +433,14 @@ namespace armarx
                 image.create(10, 20, image.type());
                 cmap.set_vlimits(0, float(image.cols + image.rows));
                 using Pixel = cv::Point3_<uint8_t>;
-                image.forEach<Pixel>([&cmap](Pixel& pixel, const int index[]) -> void
-                {
-                    simox::Color color = cmap(float(index[0] + index[1]));
-                    pixel.x = color.r;
-                    pixel.y = color.g;
-                    pixel.z = color.b;
-                });
+                image.forEach<Pixel>(
+                    [&cmap](Pixel& pixel, const int index[]) -> void
+                    {
+                        simox::Color color = cmap(float(index[0] + index[1]));
+                        pixel.x = color.r;
+                        pixel.y = color.g;
+                        pixel.z = color.b;
+                    });
 
                 //cv::Mat out;
                 //cv::cvtColor(image, out, /*CV_RGB2BGR*/);
@@ -459,21 +449,21 @@ namespace armarx
             {
                 cv::Mat& image = data.the_depth32_image;
                 image.create(20, 10, image.type());
-                image.forEach<float>([&image](float& pixel, const int index[]) -> void
-                {
-                    pixel = 100 * float(index[0] + index[1]) / float(image.rows + image.cols);
-                });
+                image.forEach<float>(
+                    [&image](float& pixel, const int index[]) -> void
+                    { pixel = 100 * float(index[0] + index[1]) / float(image.rows + image.cols); });
 
                 cmap.set_vlimits(0, 100);
                 cv::Mat rgb(image.rows, image.cols, CV_8UC3);
                 using Pixel = cv::Point3_<uint8_t>;
-                rgb.forEach<Pixel>([&image, &cmap](Pixel& pixel, const int index[]) -> void
-                {
-                    simox::Color color = cmap(image.at<float>(index));
-                    pixel.x = color.r;
-                    pixel.y = color.g;
-                    pixel.z = color.b;
-                });
+                rgb.forEach<Pixel>(
+                    [&image, &cmap](Pixel& pixel, const int index[]) -> void
+                    {
+                        simox::Color color = cmap(image.at<float>(index));
+                        pixel.x = color.r;
+                        pixel.y = color.g;
+                        pixel.z = color.b;
+                    });
 
                 //cv::Mat out;
                 //cv::cvtColor(rgb, out, CV_RGB2BGR);
@@ -481,7 +471,7 @@ namespace armarx
             }
 
             ARMARX_CHECK_NOT_NULL(data.toAron());
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
         // commit to linked data
@@ -497,7 +487,7 @@ namespace armarx
             data.yet_another_object.element_float = -1e3;
             data.yet_another_object.element_string = "I'm a nested object in some linked data.";
             ARMARX_CHECK_NOT_NULL(data.toAron());
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
         armem::CommitResult commitResult = memoryWriter.commit(commit);
@@ -512,16 +502,19 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::queryExampleData()
+    void
+    ExampleMemoryClient::queryExampleData()
     {
         // Query all entities from provider.
         armem::client::query::Builder qb;
-        qb
-        .coreSegments().withID(exampleProviderID)
-        .providerSegments().withID(exampleProviderID)
-        .entities().all()
-        .snapshots().all();
+        qb.coreSegments()
+            .withID(exampleProviderID)
+            .providerSegments()
+            .withID(exampleProviderID)
+            .entities()
+            .all()
+            .snapshots()
+            .all();
 
         armem::client::QueryResult result = memoryReader.query(qb.buildQueryInput());
         if (result.success)
@@ -535,8 +528,8 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::commitExamplesWithIDs()
+    void
+    ExampleMemoryClient::commitExamplesWithIDs()
     {
         ARMARX_IMPORTANT << "Committing multiple entity updates with links ...";
         const armem::Time time = armem::Time::Now();
@@ -551,7 +544,7 @@ namespace armarx
             armem::toAron(data.memoryID, theAnswerSnapshotID);
             armem::toAron(data.memoryLink.memoryID, armem::MemoryID());
 
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
         {
             armem::EntityUpdate& update = commit.add();
@@ -562,19 +555,19 @@ namespace armarx
             armem::toAron(data.memoryID, update.entityID.withTimestamp(time));
             armem::toAron(data.memoryLink.memoryID, armem::MemoryID());
 
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("id to previous snapshot");
-            update.referencedTime = time - armem::Duration::Seconds(1);  // 1 sec in the past
+            update.referencedTime = time - armem::Duration::Seconds(1); // 1 sec in the past
 
             armem::example::ExampleData data;
-            armem::toAron(data.memoryID, armem::MemoryID());  // First entry - invalid link
+            armem::toAron(data.memoryID, armem::MemoryID()); // First entry - invalid link
             armem::toAron(data.memoryLink.memoryID, armem::MemoryID());
 
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
         {
             armem::EntityUpdate& update = commit.add();
@@ -582,10 +575,11 @@ namespace armarx
             update.referencedTime = time;
 
             armem::example::ExampleData data;
-            armem::toAron(data.memoryID, update.entityID.withTimestamp(time - armem::Duration::Seconds(1)));
+            armem::toAron(data.memoryID,
+                          update.entityID.withTimestamp(time - armem::Duration::Seconds(1)));
             armem::toAron(data.memoryLink.memoryID, armem::MemoryID());
 
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
         ARMARX_CHECK_EQUAL(commit.updates.size(), 4);
@@ -608,11 +602,11 @@ namespace armarx
             ARMARX_CHECK_EQUAL(ids.size(), commit.updates.size());
 
             std::map<armem::MemoryID, armem::wm::EntityInstance> instances =
-                    memoryNameSystem().resolveEntityInstances(ids);
+                memoryNameSystem().resolveEntityInstances(ids);
             ARMARX_CHECK_EQUAL(instances.size(), commit.updates.size());
 
             std::stringstream ss;
-            for (const auto& [id, instance]: instances)
+            for (const auto& [id, instance] : instances)
             {
                 ss << "- Snapshot " << id << " "
                    << "\n--> Instance" << instance.id()
@@ -623,8 +617,8 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::commitExamplesWithLinks()
+    void
+    ExampleMemoryClient::commitExamplesWithLinks()
     {
         ARMARX_IMPORTANT << "Committing an entity update with a link...";
 
@@ -640,7 +634,7 @@ namespace armarx
             armem::toAron(data.memoryID, armem::MemoryID());
             armem::toAron(data.memoryLink.memoryID, yetMoreDataSnapshotID);
 
-            update.instancesData = { data.toAron() };
+            update.instancesData = {data.toAron()};
         }
 
         ARMARX_CHECK_EQUAL(commit.updates.size(), 1);
@@ -663,11 +657,11 @@ namespace armarx
             ARMARX_CHECK_EQUAL(ids.size(), commit.updates.size());
 
             std::map<armem::MemoryID, armem::wm::EntityInstance> instances =
-                    memoryNameSystem().resolveEntityInstances(ids);
+                memoryNameSystem().resolveEntityInstances(ids);
             ARMARX_CHECK_EQUAL(instances.size(), commit.updates.size());
 
             std::stringstream ss;
-            for (const auto& [id, instance]: instances)
+            for (const auto& [id, instance] : instances)
             {
                 ss << "- Snapshot " << id << " "
                    << "\n--> Instance" << instance.id()
@@ -678,7 +672,8 @@ namespace armarx
         }
     }
 
-    void ExampleMemoryClient::commitExampleImages()
+    void
+    ExampleMemoryClient::commitExampleImages()
     {
         const armem::Time time = armem::Time::Now();
 
@@ -689,18 +684,22 @@ namespace armarx
             update.referencedTime = time;
 
             auto currentFolder = std::filesystem::current_path();
-            auto opencv_img = cv::imread((currentFolder / "images" / (std::to_string(imageCounter + 1) + ".jpg")).string());
+            auto opencv_img = cv::imread(
+                (currentFolder / "images" / (std::to_string(imageCounter + 1) + ".jpg")).string());
             imageCounter++;
             imageCounter %= 10;
 
             auto data = std::make_shared<aron::data::Dict>();
-            data->addElement("opencv_image", aron::converter::AronOpenCVConverter::ConvertFromMat(opencv_img));
+            data->addElement(
+                "opencv_image",
+                aron::data::converter::AronOpenCVConverter::ConvertFromMat(opencv_img));
 
-            update.instancesData = { data };
+            update.instancesData = {data};
         }
     }
 
-    void ExampleMemoryClient::commitExamplesWithUntypedData()
+    void
+    ExampleMemoryClient::commitExamplesWithUntypedData()
     {
         const armem::Time time = armem::Time::Now();
 
@@ -715,14 +714,15 @@ namespace armarx
             toAron(data.memoryLink.memoryID, armem::MemoryID());
 
             aron::data::DictPtr aron = data.toAron();
-            aron->addElement("unexpectedString", std::make_shared<aron::data::String>("unexpected value"));
-            aron->addElement("unexpectedDict", std::make_shared<aron::data::Dict>(
-                                 std::map<std::string, aron::data::VariantPtr>{
-                                    { "key43", std::make_shared<aron::data::Int>(43) },
-                                    { "keyABC", std::make_shared<aron::data::String>("ABC") },
-                                 }
-                                 ));
-            update.instancesData = { aron };
+            aron->addElement("unexpectedString",
+                             std::make_shared<aron::data::String>("unexpected value"));
+            aron->addElement(
+                "unexpectedDict",
+                std::make_shared<aron::data::Dict>(std::map<std::string, aron::data::VariantPtr>{
+                    {"key43", std::make_shared<aron::data::Int>(43)},
+                    {"keyABC", std::make_shared<aron::data::String>("ABC")},
+                }));
+            update.instancesData = {aron};
         }
 
         armem::CommitResult commitResult = memoryWriter.commit(commit);
@@ -732,11 +732,11 @@ namespace armarx
         }
     }
 
-
-    void ExampleMemoryClient::queryPredictionEngines()
+    void
+    ExampleMemoryClient::queryPredictionEngines()
     {
         const std::map<armem::MemoryID, std::vector<armem::PredictionEngine>> predictionEngines =
-                memoryReader.getAvailablePredictionEngines();
+            memoryReader.getAvailablePredictionEngines();
 
         std::stringstream ss;
         ss << "Prediction engines available in the server:" << std::endl;
@@ -753,9 +753,9 @@ namespace armarx
         ARMARX_INFO << ss.str();
     }
 
-
-    void ExampleMemoryClient::processExampleEntityUpdate(
-        const armem::MemoryID& subscriptionID, const std::vector<armem::MemoryID>& snapshotIDs)
+    void
+    ExampleMemoryClient::processExampleEntityUpdate(const armem::MemoryID& subscriptionID,
+                                                    const std::vector<armem::MemoryID>& snapshotIDs)
     {
         std::stringstream ss;
         ss << "example_entity got updated: " << subscriptionID << "\n";
@@ -768,8 +768,8 @@ namespace armarx
         // Fetch new data of example_entity and do something with it.
     }
 
-
-    void ExampleMemoryClient::createRemoteGuiTab()
+    void
+    ExampleMemoryClient::createRemoteGuiTab()
     {
         using namespace armarx::RemoteGui::Client;
 
@@ -781,7 +781,8 @@ namespace armarx
         RemoteGui_createTab(getName(), root, &tab);
     }
 
-    void ExampleMemoryClient::RemoteGui_update()
+    void
+    ExampleMemoryClient::RemoteGui_update()
     {
         if (tab.rebuild.exchange(false))
         {
@@ -789,4 +790,4 @@ namespace armarx
         }
     }
 
-}
+} // namespace armarx
diff --git a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
index 985ef8171792570e6dad35d7a0abb09d78492006..9b16109a96f01e951974f84c70f7e7b159558de5 100644
--- a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
+++ b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
@@ -2,19 +2,19 @@
 
 #include "SkillProviderExample.h"
 
+#include <RobotAPI/components/skills/SkillProviderExample/aron/HelloWorldAcceptedType.aron.generated.h>
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
 #include <RobotAPI/libraries/aron/core/type/variant/container/Object.h>
 #include <RobotAPI/libraries/aron/core/type/variant/primitive/String.h>
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
-
-#include <RobotAPI/components/skills/SkillProviderExample/aron/HelloWorldAcceptedType.aron.generated.h>
 
 namespace armarx::skills::provider
 {
-    HelloWorldSkill::HelloWorldSkill() :
-        Skill(GetSkillDescription())
-    {}
+    HelloWorldSkill::HelloWorldSkill() : Skill(GetSkillDescription())
+    {
+    }
 
-    SkillDescription HelloWorldSkill::GetSkillDescription()
+    SkillDescription
+    HelloWorldSkill::GetSkillDescription()
     {
         armarx::skills::Example::HelloWorldAcceptedType default_params;
         default_params.some_float = 5;
@@ -23,41 +23,43 @@ namespace armarx::skills::provider
         default_params.some_list_of_matrices.push_back(Eigen::Matrix3f::Zero());
         //default_params.some_matrix = Eigen::Matrix3f::Zero();
 
-        return SkillDescription{
-            "HelloWorld",
-            "This skill logs a message on ARMARX_IMPORTANT",
-            {},
-            armarx::core::time::Duration::MilliSeconds(1000),
-            armarx::skills::Example::HelloWorldAcceptedType::ToAronType(),
-            default_params.toAron()
-        };
+        return SkillDescription{"HelloWorld",
+                                "This skill logs a message on ARMARX_IMPORTANT",
+                                {},
+                                armarx::core::time::Duration::MilliSeconds(1000),
+                                armarx::skills::Example::HelloWorldAcceptedType::ToAronType(),
+                                default_params.toAron()};
     }
 
-    Skill::MainResult HelloWorldSkill::main(const MainInput& in)
+    Skill::MainResult
+    HelloWorldSkill::main(const MainInput& in)
     {
-        ARMARX_IMPORTANT << "Hi, from the Hello World Skill.\n" <<
-                                "I received the following data: \n" <<
-                                aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(in.params).dump(2) << "\n" <<
-                                "(executed at: " << IceUtil::Time::now() << ")";
+        ARMARX_IMPORTANT << "Hi, from the Hello World Skill.\n"
+                         << "I received the following data: \n"
+                         << aron::data::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(
+                                in.params)
+                                .dump(2)
+                         << "\n"
+                         << "(executed at: " << IceUtil::Time::now() << ")";
         return {TerminatedSkillStatus::Succeeded, nullptr};
     }
 
-    ChainingSkill::ChainingSkill() :
-        Skill(GetSkillDescription())
-    {}
+    ChainingSkill::ChainingSkill() : Skill(GetSkillDescription())
+    {
+    }
 
-    SkillDescription ChainingSkill::GetSkillDescription()
+    SkillDescription
+    ChainingSkill::GetSkillDescription()
     {
-        return SkillDescription{
-            "ChainingSkill",
-            "This skill calls the HelloWorld skill three times.",
-            {},
-            armarx::core::time::Duration::MilliSeconds(3000),
-            nullptr
-        };
+        return SkillDescription{"ChainingSkill",
+                                "This skill calls the HelloWorld skill three times.",
+                                {},
+                                armarx::core::time::Duration::MilliSeconds(3000),
+                                nullptr};
     }
 
-    Skill::MainResult ChainingSkill::main(const MainInput& in)
+    Skill::MainResult
+    ChainingSkill::main(const MainInput& in)
     {
         armarx::skills::Example::HelloWorldAcceptedType exec1;
         armarx::skills::Example::HelloWorldAcceptedType exec2;
@@ -78,20 +80,21 @@ namespace armarx::skills::provider
 
     TimeoutSkill::TimeoutSkill() :
         PeriodicSkill(GetSkillDescription(), armarx::core::time::Frequency::Hertz(5))
-    {}
+    {
+    }
 
-    SkillDescription TimeoutSkill::GetSkillDescription()
+    SkillDescription
+    TimeoutSkill::GetSkillDescription()
     {
-        return SkillDescription{
-            "Timeout",
-            "This fails with timeout reached",
-            {},
-            armarx::core::time::Duration::MilliSeconds(1000),
-            nullptr
-        };
+        return SkillDescription{"Timeout",
+                                "This fails with timeout reached",
+                                {},
+                                armarx::core::time::Duration::MilliSeconds(1000),
+                                nullptr};
     }
 
-    PeriodicSkill::StepResult TimeoutSkill::step(const MainInput& in)
+    PeriodicSkill::StepResult
+    TimeoutSkill::step(const MainInput& in)
     {
         // do heavy work
         std::this_thread::sleep_for(std::chrono::milliseconds(200));
@@ -99,22 +102,22 @@ namespace armarx::skills::provider
         return {ActiveOrTerminatedSkillStatus::Running, nullptr};
     }
 
-    CallbackSkill::CallbackSkill() :
-        Skill(GetSkillDescription())
-    {}
+    CallbackSkill::CallbackSkill() : Skill(GetSkillDescription())
+    {
+    }
 
-    SkillDescription CallbackSkill::GetSkillDescription()
+    SkillDescription
+    CallbackSkill::GetSkillDescription()
     {
-        return SkillDescription{
-            "ShowMeCallbacks",
-            "This skill does shows callbacks",
-            {},
-            armarx::core::time::Duration::MilliSeconds(1000),
-            nullptr
-        };
+        return SkillDescription{"ShowMeCallbacks",
+                                "This skill does shows callbacks",
+                                {},
+                                armarx::core::time::Duration::MilliSeconds(1000),
+                                nullptr};
     }
 
-    Skill::MainResult CallbackSkill::main(const MainInput& in)
+    Skill::MainResult
+    CallbackSkill::main(const MainInput& in)
     {
         ARMARX_IMPORTANT << "Logging three updates via the callback";
         auto up1 = std::make_shared<aron::data::Dict>();
@@ -132,23 +135,26 @@ namespace armarx::skills::provider
         return {TerminatedSkillStatus::Succeeded, nullptr};
     }
 
+    SkillProviderExample::SkillProviderExample() : SkillProviderComponentPluginUser()
+    {
+    }
 
-    SkillProviderExample::SkillProviderExample() :
-        SkillProviderComponentPluginUser()
-    {}
-
-    armarx::PropertyDefinitionsPtr SkillProviderExample::createPropertyDefinitions()
+    armarx::PropertyDefinitionsPtr
+    SkillProviderExample::createPropertyDefinitions()
     {
-        armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier());
+        armarx::PropertyDefinitionsPtr defs =
+            new ComponentPropertyDefinitions(getConfigIdentifier());
         return defs;
     }
 
-    std::string SkillProviderExample::getDefaultName() const
+    std::string
+    SkillProviderExample::getDefaultName() const
     {
         return "SkillProviderExample";
     }
 
-    void SkillProviderExample::onInitComponent()
+    void
+    SkillProviderExample::onInitComponent()
     {
         // Add example skill
         addSkill(std::make_unique<HelloWorldSkill>());
@@ -160,10 +166,14 @@ namespace armarx::skills::provider
             fooDesc.description = "This skill does exactly nothing.";
             fooDesc.skillName = "Foo";
             fooDesc.timeout = armarx::core::time::Duration::MilliSeconds(1000);
-            addSkill([](const std::string& clientId, const aron::data::DictPtr&){
-                std::cout << "Hello from Foo. The skill was called from " << clientId << "." << std::endl;
-                return TerminatedSkillStatus::Succeeded;
-            }, fooDesc);
+            addSkill(
+                [](const std::string& clientId, const aron::data::DictPtr&)
+                {
+                    std::cout << "Hello from Foo. The skill was called from " << clientId << "."
+                              << std::endl;
+                    return TerminatedSkillStatus::Succeeded;
+                },
+                fooDesc);
         }
 
         // Add another example skill
@@ -176,18 +186,18 @@ namespace armarx::skills::provider
         addSkill(std::make_unique<ChainingSkill>());
     }
 
-    void SkillProviderExample::onConnectComponent()
+    void
+    SkillProviderExample::onConnectComponent()
     {
-
     }
 
-    void SkillProviderExample::onDisconnectComponent()
+    void
+    SkillProviderExample::onDisconnectComponent()
     {
-
     }
 
-    void SkillProviderExample::onExitComponent()
+    void
+    SkillProviderExample::onExitComponent()
     {
-
     }
-}
+} // namespace armarx::skills::provider
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
index edc9eebb6d619dd09de033ac2959b4858d263246..0fba47d76eb851d528c306f46d24e17c24661223 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
@@ -55,16 +55,19 @@ namespace armarx
         }
         return qobject_cast<SimpleConfigDialog*>(dialog);
     }
+
     void
     SkillManagerMonitorWidgetController::configured()
     {
         observerName = dialog->getProxyName("SkillManager");
     }
+
     void
     SkillManagerMonitorWidgetController::loadSettings(QSettings* settings)
     {
         observerName = settings->value("SkillManager", "SkillManager").toString().toStdString();
     }
+
     void
     SkillManagerMonitorWidgetController::saveSettings(QSettings* settings)
     {
@@ -124,10 +127,9 @@ namespace armarx
 
     SkillManagerMonitorWidgetController::~SkillManagerMonitorWidgetController()
     {
-
     }
 
-    void 
+    void
     SkillManagerMonitorWidgetController::reconnectToSkillManager()
     {
         if (connected)
@@ -136,13 +138,12 @@ namespace armarx
         }
     }
 
-    void 
+    void
     SkillManagerMonitorWidgetController::onInitComponent()
     {
         usingProxy(observerName);
     }
 
-
     void
     SkillManagerMonitorWidgetController::onConnectComponent()
     {
@@ -479,7 +480,7 @@ namespace armarx
             return;
         }
 
-        auto json = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
+        auto json = aron::data::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
         QClipboard* clipboard = QApplication::clipboard();
         clipboard->setText(QString::fromStdString(json.dump(2)));
     }
@@ -490,7 +491,8 @@ namespace armarx
         QClipboard* clipboard = QApplication::clipboard();
         std::string s = clipboard->text().toStdString();
         nlohmann::json json = nlohmann::json::parse(s);
-        auto data = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(json);
+        auto data =
+            aron::data::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(json);
 
         if (!aronTreeWidgetController)
         {
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
index c0a8088db7b5ad4e4e1db955b42e9316164038b3..2e52ed4cf4854583641d1a83f85822096d8f5226 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
@@ -39,7 +39,6 @@
 #include "../widgets/IntEnumWidget.h"
 #include "../widgets/QuaternionWidget.h"
 
-
 namespace armarx
 {
     bool
@@ -83,7 +82,6 @@ namespace armarx
         aronItem->setValueErrorState(isDirectError, false);
     }
 
-
     void
     AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
     {
@@ -152,7 +150,6 @@ namespace armarx
         }
     }
 
-
     void
     AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::PairPtr& i)
     {
@@ -221,8 +218,28 @@ namespace armarx
                 dataSize = 8;
                 break;
         };
+
+        // UGLY HACK: FIX ME!!!
+        switch (i->getElementType())
+        {
+            case armarx::aron::type::matrix::INT16:
+                createdMatrix->setType("short");
+                break;
+            case armarx::aron::type::matrix::INT32:
+                createdMatrix->setType("int");
+                break;
+            case armarx::aron::type::matrix::FLOAT32:
+                createdMatrix->setType("float");
+                break;
+            case armarx::aron::type::matrix::FLOAT64:
+                createdMatrix->setType("double");
+                break;
+            case armarx::aron::type::matrix::INT64:
+                createdMatrix->setType("long");
+                break;
+        };
+
         createdMatrix->setShape({i->getRows(), i->getCols(), dataSize});
-        createdMatrix->setType(i->getFullName());
         int totalByteSize = i->getRows() * i->getCols() * dataSize;
         createdAron = createdMatrix;
 
diff --git a/source/RobotAPI/libraries/armem/CMakeLists.txt b/source/RobotAPI/libraries/armem/CMakeLists.txt
index 5d6ed01da11647da7bd64177aabb439d276efa96..676c1fd0752baf0c2995e479dfad2cca4f3d9960 100644
--- a/source/RobotAPI/libraries/armem/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/CMakeLists.txt
@@ -43,6 +43,7 @@ set(LIB_FILES
     core/wm/memory_definitions.cpp
     core/wm/aron_conversions.cpp
     core/wm/ice_conversions.cpp
+    core/wm/memory_conversions.cpp
     core/wm/detail/data_lookup_mixins.cpp
     core/wm/visitor/Visitor.cpp
     core/wm/visitor/FunctionalVisitor.cpp
@@ -126,6 +127,7 @@ set(LIB_HEADERS
     core/wm/memory_definitions.h
     core/wm/aron_conversions.h
     core/wm/ice_conversions.h
+    core/wm/memory_conversions.h
     core/wm/detail/data_lookup_mixins.h
     core/wm/visitor/Visitor.h
     core/wm/visitor/FunctionalVisitor.h
diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
index 6440155ce3bdd247f78c48b6c384d38be59ae1e0..e07429591954279d478321c1ecc14a76e917b0a3 100644
--- a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
+++ b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp
@@ -127,9 +127,11 @@ namespace armarx::armem::client
             input.name = memoryID.memoryName;
 
             ARMARX_CHECK_NOT_NULL(mns);
+            ARMARX_INFO << "Waiting for memory server for " << memoryID << " ...";
             mns::dto::WaitForServerResult result = mns->waitForServer(input);
             if (result.success)
             {
+                ARMARX_INFO << "Resolved memory for " << memoryID << ".";
                 return result.server;
             }
             else
diff --git a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
index 8c1ed546b3d8699ea4eed9225f055323510745d6..559d3a38eaa391bbc9893fec991327fc08165fba 100644
--- a/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/CoreSegmentBase.h
@@ -3,14 +3,14 @@
 #include <map>
 #include <string>
 
+#include <ArmarXCore/core/logging/Logging.h>
+
 #include "ProviderSegmentBase.h"
 #include "detail/AronTyped.h"
 #include "detail/MemoryContainerBase.h"
+#include "detail/Predictive.h"
 #include "detail/iteration_mixins.h"
 #include "detail/lookup_mixins.h"
-#include "detail/Predictive.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
 
 namespace armarx::armem::base
 {
@@ -20,22 +20,22 @@ namespace armarx::armem::base
      */
     template <class _ProviderSegmentT, class _Derived>
     class CoreSegmentBase :
-        public detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>
-        , public detail::AronTyped
-        , public detail::PredictiveContainer<_Derived>
-        , public detail::ForEachEntityInstanceMixin<_Derived>
-        , public detail::ForEachEntitySnapshotMixin<_Derived>
-        , public detail::ForEachEntityMixin<_Derived>
-        , public detail::GetFindInstanceMixin<_Derived>
-        , public detail::GetFindSnapshotMixin<_Derived>
-        , public detail::GetFindEntityMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>,
+        public detail::AronTyped,
+        public detail::PredictiveContainer<_Derived>,
+        public detail::ForEachEntityInstanceMixin<_Derived>,
+        public detail::ForEachEntitySnapshotMixin<_Derived>,
+        public detail::ForEachEntityMixin<_Derived>,
+        public detail::GetFindInstanceMixin<_Derived>,
+        public detail::GetFindSnapshotMixin<_Derived>,
+        public detail::GetFindEntityMixin<_Derived>
     {
-        using Base = detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>;
+        using Base =
+            detail::MemoryContainerBase<std::map<std::string, _ProviderSegmentT>, _Derived>;
 
     public:
-
-        using typename Base::DerivedT;
         using typename Base::ContainerT;
+        using typename Base::DerivedT;
 
         using ProviderSegmentT = _ProviderSegmentT;
         using EntityT = typename ProviderSegmentT::EntityT;
@@ -44,7 +44,6 @@ namespace armarx::armem::base
 
         using ChildT = ProviderSegmentT;
 
-
         struct UpdateResult
         {
             armarx::armem::UpdateType coreSegmentUpdateType;
@@ -54,26 +53,29 @@ namespace armarx::armem::base
             std::vector<EntitySnapshotT> removedSnapshots;
 
             UpdateResult() = default;
+
             UpdateResult(const typename ProviderSegmentT::UpdateResult& c) :
                 providerSegmentUpdateType(c.providerSegmentUpdateType),
                 entityUpdateType(c.entityUpdateType),
                 id(c.id),
                 removedSnapshots(c.removedSnapshots)
-            {}
+            {
+            }
         };
 
 
     public:
-
         CoreSegmentBase()
         {
         }
+
         explicit CoreSegmentBase(const std::string& name,
                                  aron::type::ObjectPtr aronType = nullptr,
                                  const std::vector<PredictionEngine>& predictionEngines = {}) :
             CoreSegmentBase(name, MemoryID(), aronType, predictionEngines)
         {
         }
+
         explicit CoreSegmentBase(const std::string& name,
                                  const MemoryID& parentID,
                                  aron::type::ObjectPtr aronType = nullptr,
@@ -81,6 +83,7 @@ namespace armarx::armem::base
             CoreSegmentBase(parentID.withCoreSegmentName(name), aronType, predictionEngines)
         {
         }
+
         explicit CoreSegmentBase(const MemoryID& id,
                                  aron::type::ObjectPtr aronType = nullptr,
                                  const std::vector<PredictionEngine>& predictionEngines = {}) :
@@ -93,71 +96,86 @@ namespace armarx::armem::base
         CoreSegmentBase& operator=(const CoreSegmentBase& other) = default;
         CoreSegmentBase& operator=(CoreSegmentBase&& other) = default;
 
-
         // READ ACCESS
 
         // Get key
-        inline std::string& name()
+        inline std::string&
+        name()
         {
             return this->id().coreSegmentName;
         }
-        inline const std::string& name() const
+
+        inline const std::string&
+        name() const
         {
             return this->id().coreSegmentName;
         }
 
-
         // Has child by key
-        bool hasProviderSegment(const std::string& name) const
+        bool
+        hasProviderSegment(const std::string& name) const
         {
             return this->findProviderSegment(name) != nullptr;
         }
+
         // Has child by memory ID
-        bool hasProviderSegment(const MemoryID& providerSegmentID) const
+        bool
+        hasProviderSegment(const MemoryID& providerSegmentID) const
         {
             return this->findProviderSegment(providerSegmentID) != nullptr;
         }
 
-
         // Find child by key
-        ProviderSegmentT* findProviderSegment(const std::string& name)
+        ProviderSegmentT*
+        findProviderSegment(const std::string& name)
         {
             return detail::findChildByKey(name, this->_container);
         }
-        const ProviderSegmentT* findProviderSegment(const std::string& name) const
+
+        const ProviderSegmentT*
+        findProviderSegment(const std::string& name) const
         {
             return detail::findChildByKey(name, this->_container);
         }
 
         // Get child by key
-        ProviderSegmentT& getProviderSegment(const std::string& name)
+        ProviderSegmentT&
+        getProviderSegment(const std::string& name)
         {
             return detail::getChildByKey(name, this->_container, *this);
         }
-        const ProviderSegmentT& getProviderSegment(const std::string& name) const
+
+        const ProviderSegmentT&
+        getProviderSegment(const std::string& name) const
         {
             return detail::getChildByKey(name, this->_container, *this);
         }
 
         // Find child by MemoryID
-        ProviderSegmentT* findProviderSegment(const MemoryID& providerSegmentID)
+        ProviderSegmentT*
+        findProviderSegment(const MemoryID& providerSegmentID)
         {
             detail::checkHasProviderSegmentName(providerSegmentID);
             return this->findProviderSegment(providerSegmentID.providerSegmentName);
         }
-        const ProviderSegmentT* findProviderSegment(const MemoryID& providerSegmentID) const
+
+        const ProviderSegmentT*
+        findProviderSegment(const MemoryID& providerSegmentID) const
         {
             detail::checkHasProviderSegmentName(providerSegmentID);
             return this->findProviderSegment(providerSegmentID.providerSegmentName);
         }
 
         // Get child by MemoryID
-        ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID)
+        ProviderSegmentT&
+        getProviderSegment(const MemoryID& providerSegmentID)
         {
             detail::checkHasProviderSegmentName(providerSegmentID);
             return this->getProviderSegment(providerSegmentID.providerSegmentName);
         }
-        const ProviderSegmentT& getProviderSegment(const MemoryID& providerSegmentID) const
+
+        const ProviderSegmentT&
+        getProviderSegment(const MemoryID& providerSegmentID) const
         {
             detail::checkHasProviderSegmentName(providerSegmentID);
             return this->getProviderSegment(providerSegmentID.providerSegmentName);
@@ -171,35 +189,42 @@ namespace armarx::armem::base
 
         // Search all provider segments for the first matching entity.
 
-        bool hasEntity(const std::string& entityName) const
+        bool
+        hasEntity(const std::string& entityName) const
         {
             return this->findEntity(entityName) != nullptr;
         }
-        EntityT* findEntity(const std::string& entityName)
+
+        EntityT*
+        findEntity(const std::string& entityName)
         {
             return _findEntity(*this, entityName);
         }
-        const EntityT* findEntity(const std::string& entityName) const
+
+        const EntityT*
+        findEntity(const std::string& entityName) const
         {
             return _findEntity(*this, entityName);
         }
 
-
         // ITERATION
 
         /**
          * @param func Function like: bool process(ProviderSegmentT& provSeg)
          */
         template <class ProviderSegmentFunctionT>
-        bool forEachProviderSegment(ProviderSegmentFunctionT&& func)
+        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
+        bool
+        forEachProviderSegment(ProviderSegmentFunctionT&& func) const
         {
             return this->forEachChild(func);
         }
@@ -213,33 +238,41 @@ namespace armarx::armem::base
          * @param func Function like void process(EntityInstanceT& instance)>
          */
         template <class InstanceFunctionT>
-        bool forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func)
+        bool
+        forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func)
         {
-            return detail::forEachInstanceIn(
-                        id, func, *this,
-                        id.hasProviderSegmentName(),
-                        id.hasProviderSegmentName() ? this->findProviderSegment(id.providerSegmentName) : nullptr);
+            return detail::forEachInstanceIn(id,
+                                             func,
+                                             *this,
+                                             id.hasProviderSegmentName(),
+                                             id.hasProviderSegmentName()
+                                                 ? this->findProviderSegment(id.providerSegmentName)
+                                                 : nullptr);
         }
+
         /**
          * @param func Function like void process(EntityInstanceT& instance)>
          */
         template <class InstanceFunctionT>
-        bool forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func) const
+        bool
+        forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func) const
         {
-            return detail::forEachInstanceIn(
-                        id, func, *this,
-                        id.hasProviderSegmentName(),
-                        id.hasProviderSegmentName() ? this->findProviderSegment(id.providerSegmentName) : nullptr);
+            return detail::forEachInstanceIn(id,
+                                             func,
+                                             *this,
+                                             id.hasProviderSegmentName(),
+                                             id.hasProviderSegmentName()
+                                                 ? this->findProviderSegment(id.providerSegmentName)
+                                                 : nullptr);
         }
 
-
         // Get child keys
-        std::vector<std::string> getProviderSegmentNames() const
+        std::vector<std::string>
+        getProviderSegmentNames() const
         {
             return simox::alg::get_keys(this->_container);
         }
 
-
         // MODIFICATION
 
         /**
@@ -247,11 +280,13 @@ namespace armarx::armem::base
          *
          * Missing entity entries are added before updating.
          */
-        UpdateResult update(const EntityUpdate& update)
+        UpdateResult
+        update(const EntityUpdate& update)
         {
             this->_checkContainerName(update.entityID.coreSegmentName, this->name());
 
-            auto [inserted, provSeg] = _addProviderSegmentIfMissing(update.entityID.providerSegmentName);
+            auto [inserted, provSeg] =
+                _addProviderSegmentIfMissing(update.entityID.providerSegmentName);
 
 
             // Update entry.
@@ -267,20 +302,34 @@ namespace armarx::armem::base
             return ret;
         }
 
-
         template <class OtherDerivedT>
-        void append(const OtherDerivedT& other)
+        void
+        append(const OtherDerivedT& other)
         {
-            other.forEachProviderSegment([this](const auto& provSeg)
-            {
-                auto it = this->_container.find(provSeg.name());
-                if (it == this->_container.end())
+            other.forEachProviderSegment(
+                [this](const auto& provSeg)
                 {
-                    it = this->_container.emplace(provSeg.name(), this->id().withProviderSegmentName(provSeg.name())).first;
-                }
-                it->second.append(provSeg);
-                return true;
-            });
+                    auto it = this->_container.find(provSeg.name());
+                    if (it == this->_container.end())
+                    {
+                        it = this->_container
+                                 .emplace(provSeg.name(),
+                                          this->id().withProviderSegmentName(provSeg.name()))
+                                 .first;
+                        it->second.aronType() = provSeg.aronType();
+                    }
+
+                    /*TODO: if (it->second.aronType() != provSeg.aronType())
+                    {
+                        ARMARX_WARNING
+                            << "When appending a coreseg to another coreseg type conflicts have "
+                               "been found. Setting the type to NULL...";
+                        it->second.aronType() = nullptr;
+                    }*/
+
+                    it->second.append(provSeg);
+                    return true;
+                });
         }
 
         /**
@@ -296,36 +345,41 @@ namespace armarx::armem::base
                            aron::type::ObjectPtr providerSegmentType = nullptr,
                            const std::vector<PredictionEngine>& predictionEngines = {})
         {
-            aron::type::ObjectPtr type = providerSegmentType ? providerSegmentType : this->aronType();
+            aron::type::ObjectPtr type =
+                providerSegmentType ? providerSegmentType : this->aronType();
             return this->_derived().addProviderSegment(name, name, type, predictionEngines);
         }
 
         /// Copy and insert a provider segment.
-        ProviderSegmentT& addProviderSegment(const ProviderSegmentT& providerSegment)
+        ProviderSegmentT&
+        addProviderSegment(const ProviderSegmentT& providerSegment)
         {
-            return this->_derived().addProviderSegment(providerSegment.name(), ProviderSegmentT(providerSegment));
+            return this->_derived().addProviderSegment(providerSegment.name(),
+                                                       ProviderSegmentT(providerSegment));
         }
 
         /// Move and insert a provider segment.
-        ProviderSegmentT& addProviderSegment(ProviderSegmentT&& providerSegment)
+        ProviderSegmentT&
+        addProviderSegment(ProviderSegmentT&& providerSegment)
         {
-            const std::string name = providerSegment.name();  // Copy before move.
+            const std::string name = providerSegment.name(); // Copy before move.
             return this->_derived().addProviderSegment(name, std::move(providerSegment));
         }
 
         /// Insert a provider segment in-place.
-        template <class ...Args>
-        ProviderSegmentT& addProviderSegment(const std::string& name, Args... args)
+        template <class... Args>
+        ProviderSegmentT&
+        addProviderSegment(const std::string& name, Args... args)
         {
             ChildT& child = this->template _addChild<ChildT>(name, args...);
             child.id() = this->id().withProviderSegmentName(name);
             return child;
         }
 
-
         // MISC
 
-        bool equalsDeep(const DerivedT& other) const
+        bool
+        equalsDeep(const DerivedT& other) const
         {
             //std::cout << "CoreSegment::equalsDeep" << std::endl;
             if (this->size() != other.size())
@@ -346,34 +400,34 @@ namespace armarx::armem::base
             return true;
         }
 
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "core segment";
         }
 
-        std::string getKeyString() const
+        std::string
+        getKeyString() const
         {
             return this->name();
         }
 
 
     protected:
-
         template <class ParentT>
-        static
-        auto*
+        static auto*
         _findEntity(ParentT&& parent, const std::string& entityName)
         {
             decltype(parent.findEntity(entityName)) result = nullptr;
-            parent.forEachProviderSegment([&result, &entityName](auto & provSeg)
-            {
-                result = provSeg.findEntity(entityName);
-                return result == nullptr;  // Keep going if null, break if not null.
-            });
+            parent.forEachProviderSegment(
+                [&result, &entityName](auto& provSeg)
+                {
+                    result = provSeg.findEntity(entityName);
+                    return result == nullptr; // Keep going if null, break if not null.
+                });
             return result;
         }
 
-
         std::pair<bool, ProviderSegmentT*>
         _addProviderSegmentIfMissing(const std::string& providerSegmentName)
         {
@@ -402,9 +456,7 @@ namespace armarx::armem::base
 
 
     private:
-
         bool _addMissingProviderSegmentDuringUpdate = true;
-
     };
 
-}
+} // namespace armarx::armem::base
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
index 2dadcbc6784ac89dff3658c4d3c4c5282d3e7ef1..0bd03af1448d99536640c0b9f4a2f83036afc307 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
@@ -132,6 +132,16 @@ namespace armarx::armem::base
             return _data;
         }
 
+        void setData(DataT& d)
+        {
+            _data = d;
+        }
+
+        void setMetadata(MetadataT& m)
+        {
+            _metadata = m;
+        }
+
         /**
          * @brief Get the data converted to a generated Aron DTO class.
          */
diff --git a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
index efc18d58c99ee298b71ce2e775a012d7e6050b04..1ab0659f1b65ecf17897475d885bb2568558c31d 100644
--- a/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/MemoryBase.h
@@ -5,10 +5,9 @@
 
 #include "CoreSegmentBase.h"
 #include "detail/MemoryContainerBase.h"
+#include "detail/Predictive.h"
 #include "detail/iteration_mixins.h"
 #include "detail/lookup_mixins.h"
-#include "detail/Predictive.h"
-
 
 namespace armarx::armem::base
 {
@@ -18,23 +17,22 @@ namespace armarx::armem::base
      */
     template <class _CoreSegmentT, class _Derived>
     class MemoryBase :
-        public detail::MemoryContainerBase<std::map<std::string, _CoreSegmentT>, _Derived>
-        , public detail::PredictiveContainer<_Derived>
-        , public detail::ForEachEntityInstanceMixin<_Derived>
-        , public detail::ForEachEntitySnapshotMixin<_Derived>
-        , public detail::ForEachEntityMixin<_Derived>
-        , public detail::ForEachProviderSegmentMixin<_Derived>
-        , public detail::GetFindInstanceMixin<_Derived>
-        , public detail::GetFindSnapshotMixin<_Derived>
-        , public detail::GetFindEntityMixin<_Derived>
-        , public detail::GetFindProviderSegmentMixin<_Derived>
+        public detail::MemoryContainerBase<std::map<std::string, _CoreSegmentT>, _Derived>,
+        public detail::PredictiveContainer<_Derived>,
+        public detail::ForEachEntityInstanceMixin<_Derived>,
+        public detail::ForEachEntitySnapshotMixin<_Derived>,
+        public detail::ForEachEntityMixin<_Derived>,
+        public detail::ForEachProviderSegmentMixin<_Derived>,
+        public detail::GetFindInstanceMixin<_Derived>,
+        public detail::GetFindSnapshotMixin<_Derived>,
+        public detail::GetFindEntityMixin<_Derived>,
+        public detail::GetFindProviderSegmentMixin<_Derived>
     {
         using Base = detail::MemoryContainerBase<std::map<std::string, _CoreSegmentT>, _Derived>;
 
     public:
-
-        using typename Base::DerivedT;
         using typename Base::ContainerT;
+        using typename Base::DerivedT;
 
         using CoreSegmentT = _CoreSegmentT;
         using ProviderSegmentT = typename CoreSegmentT::ProviderSegmentT;
@@ -44,7 +42,6 @@ namespace armarx::armem::base
 
         using ChildT = CoreSegmentT;
 
-
         struct UpdateResult
         {
             armarx::armem::UpdateType memoryUpdateType;
@@ -55,25 +52,28 @@ namespace armarx::armem::base
             std::vector<EntitySnapshotT> removedSnapshots;
 
             UpdateResult() = default;
+
             UpdateResult(const typename CoreSegmentT::UpdateResult& c) :
                 coreSegmentUpdateType(c.coreSegmentUpdateType),
                 providerSegmentUpdateType(c.providerSegmentUpdateType),
                 entityUpdateType(c.entityUpdateType),
                 id(c.id),
                 removedSnapshots(c.removedSnapshots)
-            {}
+            {
+            }
         };
 
     public:
-
         MemoryBase()
         {
         }
+
         explicit MemoryBase(const std::string& name,
                             const std::vector<PredictionEngine>& predictionEngines = {}) :
             MemoryBase(MemoryID().withMemoryName(name), predictionEngines)
         {
         }
+
         explicit MemoryBase(const MemoryID& id,
                             const std::vector<PredictionEngine>& predictionEngines = {}) :
             Base(id), detail::PredictiveContainer<_Derived>(predictionEngines)
@@ -85,70 +85,86 @@ namespace armarx::armem::base
         MemoryBase& operator=(const MemoryBase& other) = default;
         MemoryBase& operator=(MemoryBase&& other) = default;
 
-
         // READ ACCESS
 
         // Get key
-        inline std::string& name()
+        inline std::string&
+        name()
         {
             return this->id().memoryName;
         }
-        inline const std::string& name() const
+
+        inline const std::string&
+        name() const
         {
             return this->id().memoryName;
         }
 
-
         // Has child by key
-        bool hasCoreSegment(const std::string& name) const
+        bool
+        hasCoreSegment(const std::string& name) const
         {
             return this->findCoreSegment(name) != nullptr;
         }
+
         // Has child by MemoryID
-        bool hasCoreSegment(const MemoryID& coreSegmentID) const
+        bool
+        hasCoreSegment(const MemoryID& coreSegmentID) const
         {
             return this->findCoreSegment(coreSegmentID) != nullptr;
         }
 
         // Find child by key
-        CoreSegmentT* findCoreSegment(const std::string& name)
+        CoreSegmentT*
+        findCoreSegment(const std::string& name)
         {
             return detail::findChildByKey(name, this->_container);
         }
-        const CoreSegmentT* findCoreSegment(const std::string& name) const
+
+        const CoreSegmentT*
+        findCoreSegment(const std::string& name) const
         {
             return detail::findChildByKey(name, this->_container);
         }
 
         // Get child by key
-        CoreSegmentT& getCoreSegment(const std::string& name)
+        CoreSegmentT&
+        getCoreSegment(const std::string& name)
         {
             return detail::getChildByKey(name, this->_container, *this);
         }
-        const CoreSegmentT& getCoreSegment(const std::string& name) const
+
+        const CoreSegmentT&
+        getCoreSegment(const std::string& name) const
         {
             return detail::getChildByKey(name, this->_container, *this);
         }
 
         // Find child by MemoryID
-        CoreSegmentT* findCoreSegment(const MemoryID& coreSegmentID)
+        CoreSegmentT*
+        findCoreSegment(const MemoryID& coreSegmentID)
         {
             detail::checkHasCoreSegmentName(coreSegmentID);
             return this->findCoreSegment(coreSegmentID.coreSegmentName);
         }
-        const CoreSegmentT* findCoreSegment(const MemoryID& coreSegmentID) const
+
+        const CoreSegmentT*
+        findCoreSegment(const MemoryID& coreSegmentID) const
         {
             detail::checkHasCoreSegmentName(coreSegmentID);
             return this->findCoreSegment(coreSegmentID.coreSegmentName);
         }
 
         // Get child by MemoryID
-        CoreSegmentT& getCoreSegment(const MemoryID& coreSegmentID)
+        CoreSegmentT&
+        getCoreSegment(const MemoryID& coreSegmentID)
         {
             detail::checkHasCoreSegmentName(coreSegmentID);
             return this->getCoreSegment(coreSegmentID.coreSegmentName);
         }
-        const CoreSegmentT& getCoreSegment(const MemoryID& coreSegmentID) const
+
+        const CoreSegmentT&
+        getCoreSegment(const MemoryID& coreSegmentID) const
         {
             detail::checkHasCoreSegmentName(coreSegmentID);
             return this->getCoreSegment(coreSegmentID.coreSegmentName);
@@ -160,22 +176,24 @@ namespace armarx::armem::base
         // get/findProviderSegment are provided by GetFindProviderSegmentMixin
 
 
-
         // ITERATION
 
         /**
          * @param func Function like: bool process(CoreSegmentT& coreSeg)
          */
         template <class CoreSegmentFunctionT>
-        bool forEachCoreSegment(CoreSegmentFunctionT&& func)
+        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
+        bool
+        forEachCoreSegment(CoreSegmentFunctionT&& func) const
         {
             return this->forEachChild(func);
         }
@@ -190,34 +208,46 @@ namespace armarx::armem::base
          * @param func Function like void process(EntityInstanceT& instance)>
          */
         template <class InstanceFunctionT>
-        bool forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func)
+        bool
+        forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func)
         {
             return detail::forEachInstanceIn(
-                        id, func, *this,
-                        id.hasCoreSegmentName(),
-                        id.hasCoreSegmentName() ? this->findCoreSegment(id.coreSegmentName) : nullptr);
+                id,
+                func,
+                *this,
+                id.hasCoreSegmentName(),
+                id.hasCoreSegmentName() ? this->findCoreSegment(id.coreSegmentName) : nullptr);
         }
+
         /**
          * @param func Function like void process(EntityInstanceT& instance)>
          */
         template <class InstanceFunctionT>
-        bool forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func) const
+        bool
+        forEachInstanceIn(const MemoryID& id, InstanceFunctionT&& func) const
         {
             return detail::forEachInstanceIn(
-                        id, func, *this,
-                        id.hasCoreSegmentName(),
-                        id.hasCoreSegmentName() ? this->findCoreSegment(id.coreSegmentName) : nullptr);
+                id,
+                func,
+                *this,
+                id.hasCoreSegmentName(),
+                id.hasCoreSegmentName() ? this->findCoreSegment(id.coreSegmentName) : nullptr);
         }
 
-
-        std::vector<std::string> getCoreSegmentNames() const
+        std::vector<std::string>
+        getCoreSegmentNames() const
         {
             return simox::alg::get_keys(this->_container);
         }
 
-
         // MODIFICATION
 
+        void
+        setName(const std::string& name)
+        {
+            this->id().memoryName = name;
+        }
+
         /**
          * @brief Add an empty core segment with the given name, type and prediction engines.
          * @param name The core segment name.
@@ -234,39 +264,45 @@ namespace armarx::armem::base
         }
 
         /// Copy and insert a core segment.
-        CoreSegmentT& addCoreSegment(const CoreSegmentT& coreSegment)
+        CoreSegmentT&
+        addCoreSegment(const CoreSegmentT& coreSegment)
         {
             return this->_derived().addCoreSegment(coreSegment.name(), CoreSegmentT(coreSegment));
         }
 
         /// Move and insert a core segment.
-        CoreSegmentT& addCoreSegment(CoreSegmentT&& coreSegment)
+        CoreSegmentT&
+        addCoreSegment(CoreSegmentT&& coreSegment)
         {
-            const std::string name = coreSegment.name();  // Copy before move.
+            const std::string name = coreSegment.name(); // Copy before move.
             return this->_derived().addCoreSegment(name, std::move(coreSegment));
         }
 
         /// Move and insert a core segment.
-        template <class ...Args>
-        CoreSegmentT& addCoreSegment(const std::string& name, Args... args)
+        template <class... Args>
+        CoreSegmentT&
+        addCoreSegment(const std::string& name, Args... args)
         {
             CoreSegmentT& child = this->template _addChild<ChildT>(name, args...);
             child.id() = this->id().withCoreSegmentName(name);
             return child;
         }
 
-
         /**
          * @brief Store all updates in `commit`.
          * @param commit The commit.
          * @return The resulting memory IDs.
          */
-        std::vector<UpdateResult> update(const Commit& commit, const bool addMissingCoreSegmentDuringUpdate = false, const bool checkMemoryName = true)
+        std::vector<UpdateResult>
+        update(const Commit& commit,
+               const bool addMissingCoreSegmentDuringUpdate = false,
+               const bool checkMemoryName = true)
         {
             std::vector<UpdateResult> results;
             for (const EntityUpdate& update : commit.updates)
             {
-                results.push_back(this->update(update, addMissingCoreSegmentDuringUpdate, checkMemoryName));
+                results.push_back(
+                    this->update(update, addMissingCoreSegmentDuringUpdate, checkMemoryName));
             }
             return results;
         }
@@ -276,14 +312,18 @@ namespace armarx::armem::base
          * @param update The update.
          * @return The resulting entity snapshot's ID.
          */
-        UpdateResult update(const EntityUpdate& update, const bool addMissingCoreSegmentDuringUpdate = false, const bool checkMemoryName = true)
+        UpdateResult
+        update(const EntityUpdate& update,
+               const bool addMissingCoreSegmentDuringUpdate = false,
+               const bool checkMemoryName = true)
         {
             if (checkMemoryName)
             {
                 this->_checkContainerName(update.entityID.memoryName, this->name());
             }
 
-            auto [inserted, coreSeg] = _addCoreSegmentIfMissing(update.entityID.coreSegmentName, addMissingCoreSegmentDuringUpdate);
+            auto [inserted, coreSeg] = _addCoreSegmentIfMissing(update.entityID.coreSegmentName,
+                                                                addMissingCoreSegmentDuringUpdate);
 
             // Update entry.
             UpdateResult ret(coreSeg->update(update));
@@ -298,27 +338,42 @@ namespace armarx::armem::base
             return ret;
         }
 
-
         /**
-         * @brief Merge another memory into this one. Append all data
+         * @brief Merge another memory into this one. Append all data and types if possible
          * @param m The other memory
          */
         template <class OtherDerivedT>
-        void append(const OtherDerivedT& other)
+        void
+        append(const OtherDerivedT& other)
         {
-            other.forEachCoreSegment([this](const auto& coreSeg)
-            {
-                auto it = this->_container.find(coreSeg.name());
-                if (it == this->_container.end())
+            other.forEachCoreSegment(
+                [this](const auto& coreSeg)
                 {
-                    it = this->_container.emplace(coreSeg.name(), this->id().withCoreSegmentName(coreSeg.name())).first;
-                }
-                it->second.append(coreSeg);
-                return true;
-            });
+                    auto it = this->_container.find(coreSeg.name());
+                    if (it == this->_container.end())
+                    {
+                        it = this->_container
+                                 .emplace(coreSeg.name(),
+                                          this->id().withCoreSegmentName(coreSeg.name()))
+                                 .first;
+                        it->second.aronType() = coreSeg.aronType();
+                    }
+
+                    /*TODO: if (it->second.aronType() != coreSeg.aronType())
+                    {
+                        ARMARX_WARNING << "When appending a wm to another wm type conflicts have "
+                                          "been found. Setting the type to NULL...";
+                        it->second.aronType() = nullptr;
+                    }*/
+
+                    it->second.append(coreSeg);
+                    return true;
+                });
         }
 
-        bool equalsDeep(const MemoryBase& other) const
+        bool
+        equalsDeep(const MemoryBase& other) const
+
         {
             //std::cout << "Memory::equalsDeep" << std::endl;
             if (this->size() != other.size())
@@ -339,20 +394,23 @@ namespace armarx::armem::base
             return true;
         }
 
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "memory";
         }
 
-        std::string getKeyString() const
+        std::string
+        getKeyString() const
         {
             return this->name();
         }
 
 
     protected:
-
-        std::pair<bool, CoreSegmentT*> _addCoreSegmentIfMissing(const std::string& coreSegmentName, const bool addMissingCoreSegmentDuringUpdate)
+        std::pair<bool, CoreSegmentT*>
+        _addCoreSegmentIfMissing(const std::string& coreSegmentName,
+                                 const bool addMissingCoreSegmentDuringUpdate)
         {
             CoreSegmentT* coreSeg = nullptr;
 
@@ -377,4 +435,4 @@ namespace armarx::armem::base
             }
         }
     };
-}
+} // namespace armarx::armem::base
diff --git a/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h
index 006a5fbcef24dd6c3978d78546cd15dff03a72bc..ce63b1ee78d4dbc97fe99b9efddd783dc6e5e315 100644
--- a/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h
+++ b/source/RobotAPI/libraries/armem/core/base/detail/lookup_mixins.h
@@ -1,10 +1,9 @@
 #pragma once
 
-#include "derived.h"
-
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/error/ArMemError.h>
 
+#include "derived.h"
 
 namespace armarx::armem::base::detail
 {
@@ -16,9 +15,9 @@ namespace armarx::armem::base::detail
     void checkHasCoreSegmentName(const MemoryID& coreSegmentID);
     void checkHasMemoryName(const MemoryID& memory);
 
-
     template <class KeyT, class ContainerT>
-    auto* findChildByKey(const KeyT& key, ContainerT&& container)
+    auto*
+    findChildByKey(const KeyT& key, ContainerT&& container)
     {
         auto it = container.find(key);
         return it != container.end() ? &it->second : nullptr;
@@ -26,11 +25,10 @@ namespace armarx::armem::base::detail
 
     template <class KeyT, class ContainerT, class ParentT, class KeyStringFn>
     auto&
-    getChildByKey(
-        const KeyT& key,
-        ContainerT&& container,
-        const ParentT& parent,
-        KeyStringFn&& keyStringFn)
+    getChildByKey(const KeyT& key,
+                  ContainerT&& container,
+                  const ParentT& parent,
+                  KeyStringFn&& keyStringFn)
     {
         if (auto* child = findChildByKey(key, container))
         {
@@ -38,29 +36,25 @@ namespace armarx::armem::base::detail
         }
         else
         {
-            throw armem::error::MissingEntry::create<typename ParentT::ChildT>(keyStringFn(key), parent);
+            throw armem::error::MissingEntry::create<typename ParentT::ChildT>(keyStringFn(key),
+                                                                               parent);
         }
     }
+
     template <class KeyT, class ContainerT, class ParentT>
     auto&
-    getChildByKey(
-        const KeyT& key,
-        ContainerT&& container,
-        const ParentT& parent)
+    getChildByKey(const KeyT& key, ContainerT&& container, const ParentT& parent)
     {
-        return getChildByKey(key, container, parent, [](const KeyT & key)
-        {
-            return key;
-        });
+        return getChildByKey(key, container, parent, [](const KeyT& key) { return key; });
     }
 
-
     template <class DerivedT>
     struct GetFindInstanceMixin
     {
         // Relies on this->find/getSnapshot()
 
-        bool hasInstance(const MemoryID& instanceID) const
+        bool
+        hasInstance(const MemoryID& instanceID) const
         {
             return derived<DerivedT>(this).findInstance(instanceID) != nullptr;
         }
@@ -76,6 +70,7 @@ namespace armarx::armem::base::detail
             auto* snapshot = derived<DerivedT>(this).findSnapshot(instanceID);
             return snapshot ? snapshot->findInstance(instanceID) : nullptr;
         }
+
         const auto*
         findInstance(const MemoryID& instanceID) const
         {
@@ -94,6 +89,7 @@ namespace armarx::armem::base::detail
         {
             return derived<DerivedT>(this).getSnapshot(instanceID).getInstance(instanceID);
         }
+
         const auto&
         getInstance(const MemoryID& instanceID) const
         {
@@ -101,13 +97,13 @@ namespace armarx::armem::base::detail
         }
     };
 
-
     template <class DerivedT>
     struct GetFindSnapshotMixin
     {
         // Relies on this->find/getEntity()
 
-        bool hasSnapshot(const MemoryID& snapshotID) const
+        bool
+        hasSnapshot(const MemoryID& snapshotID) const
         {
             return derived<DerivedT>(this).findSnapshot(snapshotID) != nullptr;
         }
@@ -123,6 +119,7 @@ namespace armarx::armem::base::detail
             auto* entity = derived<DerivedT>(this).findEntity(snapshotID);
             return entity ? entity->findSnapshot(snapshotID) : nullptr;
         }
+
         const auto*
         findSnapshot(const MemoryID& snapshotID) const
         {
@@ -141,47 +138,51 @@ namespace armarx::armem::base::detail
         {
             return derived<DerivedT>(this).getEntity(snapshotID).getSnapshot(snapshotID);
         }
+
         const auto&
         getSnapshot(const MemoryID& snapshotID) const
         {
             return derived<DerivedT>(this).getEntity(snapshotID).getSnapshot(snapshotID);
         }
 
-
         // More elaborate cases
 
-        auto* findLatestSnapshot(const MemoryID& entityID)
+        auto*
+        findLatestSnapshot(const MemoryID& entityID)
         {
             auto* entity = derived<DerivedT>(this).findEntity(entityID);
             return entity ? entity->findLatestSnapshot() : nullptr;
         }
-        const auto* findLatestSnapshot(const MemoryID& entityID) const
+
+        const auto*
+        findLatestSnapshot(const MemoryID& entityID) const
         {
             auto* entity = derived<DerivedT>(this).findEntity(entityID);
             return entity ? entity->findLatestSnapshot() : nullptr;
         }
 
-        auto* findLatestInstance(const MemoryID& entityID, int instanceIndex = 0)
+        auto*
+        findLatestInstance(const MemoryID& entityID, int instanceIndex = 0)
         {
             auto* snapshot = derived<DerivedT>(this).findLatestSnapshot(entityID);
             return snapshot ? snapshot->findInstance(instanceIndex) : nullptr;
         }
-        const auto* findLatestInstance(const MemoryID& entityID, int instanceIndex = 0) const
+
+        const auto*
+        findLatestInstance(const MemoryID& entityID, int instanceIndex = 0) const
         {
             auto* snapshot = derived<DerivedT>(this).findLatestSnapshot(entityID);
             return snapshot ? snapshot->findInstance(instanceIndex) : nullptr;
         }
-
     };
 
-
-
     template <class DerivedT>
     struct GetFindEntityMixin
     {
         // Relies on this->find/getProviderSegment()
 
-        bool hasEntity(const MemoryID& entityID) const
+        bool
+        hasEntity(const MemoryID& entityID) const
         {
             return derived<DerivedT>(this).findEntity(entityID) != nullptr;
         }
@@ -197,6 +198,7 @@ namespace armarx::armem::base::detail
             auto* provSeg = derived<DerivedT>(this).findProviderSegment(entityID);
             return provSeg ? provSeg->findEntity(entityID) : nullptr;
         }
+
         const auto*
         findEntity(const MemoryID& entityID) const
         {
@@ -215,6 +217,7 @@ namespace armarx::armem::base::detail
         {
             return derived<DerivedT>(this).getProviderSegment(entityID).getEntity(entityID);
         }
+
         const auto&
         getEntity(const MemoryID& entityID) const
         {
@@ -222,14 +225,13 @@ namespace armarx::armem::base::detail
         }
     };
 
-
-
     template <class DerivedT>
     struct GetFindProviderSegmentMixin
     {
         // Relies on this->find/getCoreSegment()
 
-        bool hasProviderSegment(const MemoryID& providerSegmentID) const
+        bool
+        hasProviderSegment(const MemoryID& providerSegmentID) const
         {
             return derived<DerivedT>(this).findProviderSegment(providerSegmentID) != nullptr;
         }
@@ -245,6 +247,7 @@ namespace armarx::armem::base::detail
             auto* provSeg = derived<DerivedT>(this).findCoreSegment(providerSegmentID);
             return provSeg ? provSeg->findProviderSegment(providerSegmentID) : nullptr;
         }
+
         const auto*
         findProviderSegment(const MemoryID& providerSegmentID) const
         {
@@ -261,14 +264,18 @@ namespace armarx::armem::base::detail
         auto&
         getProviderSegment(const MemoryID& providerSegmentID)
         {
-            return derived<DerivedT>(this).getCoreSegment(providerSegmentID).getProviderSegment(providerSegmentID);
+            return derived<DerivedT>(this)
+                .getCoreSegment(providerSegmentID)
+                .getProviderSegment(providerSegmentID);
         }
+
         const auto&
         getProviderSegment(const MemoryID& providerSegmentID) const
         {
-            return derived<DerivedT>(this).getCoreSegment(providerSegmentID).getProviderSegment(providerSegmentID);
+            return derived<DerivedT>(this)
+                .getCoreSegment(providerSegmentID)
+                .getProviderSegment(providerSegmentID);
         }
-
     };
 
-}
+} // namespace armarx::armem::base::detail
diff --git a/source/RobotAPI/libraries/armem/core/wm/memory_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/memory_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..5856407816fe423e2f93bd0375a631863c304a89
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_conversions.cpp
@@ -0,0 +1,111 @@
+#include "memory_conversions.h"
+
+namespace armarx::armem::wm
+{
+    void
+    toMemory(Memory& m, const std::vector<CoreSegment>& e)
+    {
+        m.clear();
+        for (const auto& s : e)
+        {
+            m.addCoreSegment(s);
+        }
+    }
+
+    void
+    toMemory(Memory& m, const std::vector<ProviderSegment>& e)
+    {
+        m.clear();
+        for (const auto& s : e)
+        {
+            if (!m.hasCoreSegment(s.id().coreSegmentName))
+            {
+                m.addCoreSegment(s.id().coreSegmentName);
+            }
+            auto* c = m.findCoreSegment(s.id().coreSegmentName);
+            c->addProviderSegment(s);
+        }
+    }
+
+    void
+    toMemory(Memory& m, const std::vector<Entity>& e)
+    {
+        m.clear();
+        for (const auto& s : e)
+        {
+            if (!m.hasCoreSegment(s.id().coreSegmentName))
+            {
+                m.addCoreSegment(s.id().coreSegmentName);
+            }
+            auto* c = m.findCoreSegment(s.id().coreSegmentName);
+
+            if (!c->hasProviderSegment(s.id().providerSegmentName))
+            {
+                c->addProviderSegment(s.id().providerSegmentName);
+            }
+            auto* p = c->findProviderSegment(s.id().providerSegmentName);
+            p->addEntity(s);
+        }
+    }
+
+    void
+    toMemory(Memory& m, const std::vector<EntitySnapshot>& e)
+    {
+        m.clear();
+        for (const auto& s : e)
+        {
+            if (!m.hasCoreSegment(s.id().coreSegmentName))
+            {
+                m.addCoreSegment(s.id().coreSegmentName);
+            }
+            auto* c = m.findCoreSegment(s.id().coreSegmentName);
+
+            if (!c->hasProviderSegment(s.id().providerSegmentName))
+            {
+                c->addProviderSegment(s.id().providerSegmentName);
+            }
+            auto* p = c->findProviderSegment(s.id().providerSegmentName);
+
+            if (!p->hasEntity(s.id().entityName))
+            {
+                p->addEntity(s.id().entityName);
+            }
+            auto* en = p->findEntity(s.id().entityName);
+            en->addSnapshot(s);
+        }
+    }
+
+    void
+    toMemory(Memory& m, const std::vector<EntityInstance>& e)
+    {
+        m.clear();
+        for (const auto& s : e)
+        {
+            if (!m.hasCoreSegment(s.id().coreSegmentName))
+            {
+                m.addCoreSegment(s.id().coreSegmentName);
+            }
+            auto* c = m.findCoreSegment(s.id().coreSegmentName);
+
+            if (!c->hasProviderSegment(s.id().providerSegmentName))
+            {
+                c->addProviderSegment(s.id().providerSegmentName);
+            }
+            auto* p = c->findProviderSegment(s.id().providerSegmentName);
+
+            if (!p->hasEntity(s.id().entityName))
+            {
+                p->addEntity(s.id().entityName);
+            }
+            auto* en = p->findEntity(s.id().entityName);
+
+            if (!en->hasSnapshot(s.id().timestamp))
+            {
+                en->addSnapshot(s.id().timestamp);
+            }
+            auto* sn = p->findSnapshot(s.id());
+
+            sn->addInstance(s);
+        }
+    }
+} // namespace armarx::armem::wm
diff --git a/source/RobotAPI/libraries/armem/core/wm/memory_conversions.h b/source/RobotAPI/libraries/armem/core/wm/memory_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..53ac02bfc5536150b2d0f01b9457537bb236d95a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_conversions.h
@@ -0,0 +1,14 @@
+#pragma once
+
+#include <vector>
+
+#include "memory_definitions.h"
+
+namespace armarx::armem::wm
+{
+    void toMemory(Memory& m, const std::vector<CoreSegment>& e);
+    void toMemory(Memory& m, const std::vector<ProviderSegment>& e);
+    void toMemory(Memory& m, const std::vector<Entity>& e);
+    void toMemory(Memory& m, const std::vector<EntitySnapshot>& e);
+    void toMemory(Memory& m, const std::vector<EntityInstance>& e);
+} // namespace armarx::armem::wm
diff --git a/source/RobotAPI/libraries/armem/server/CMakeLists.txt b/source/RobotAPI/libraries/armem/server/CMakeLists.txt
index f2967422eaf548e5f040bd5b1685f7555e42bdb5..de2a911560d8d13c2516db3f22348c59cfa38365 100644
--- a/source/RobotAPI/libraries/armem/server/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem/server/CMakeLists.txt
@@ -7,18 +7,9 @@ SET(INSTALL_SCRIPT_MSG
     "Please use the installation script in RobotAPI/etc/mongocxx to install libmongocxx and libbsoncxx."
 )
 
-
-
 # MongoLTM
-#find_package(libmongocxx QUIET)
-#armarx_build_if(libmongocxx_FOUND "libmongocxx not available. ${INSTALL_SCRIPT_MSG}")
-
-# DiskLTM TODO: switch to FindMinizip file?
-INCLUDE (FindPkgConfig)
-if (PKG_CONFIG_FOUND)
-    PKG_CHECK_MODULES(UNZIP minizip)
-endif (PKG_CONFIG_FOUND)
-armarx_build_if(UNZIP_FOUND "MiniZip not available.")
+find_package(libmongocxx QUIET)
+armarx_build_if(libmongocxx_FOUND "libmongocxx not available. ${INSTALL_SCRIPT_MSG}")
 
 # LTM Encoding stuff
 find_package(libbsoncxx QUIET)
@@ -35,9 +26,8 @@ set(LIBS
     # LTM
     RobotAPI::aron::converter::json
     RobotAPI::aron::converter::opencv
-    #${LIBMONGOCXX_LIBRARIES}
+    ${LIBMONGOCXX_LIBRARIES}
     ${LIBBSONCXX_LIBRARIES}
-    ${UNZIP_LIBRARIES}
 )
 
 set(LIB_FILES
@@ -45,50 +35,57 @@ set(LIB_FILES
     MemoryRemoteGui.cpp
     RemoteGuiAronDataVisitor.cpp
 
+
+    # LTM
     ltm/io/Recording.cpp
     ltm/io/Replaying.cpp
 
-    ltm/base/detail/Processors.cpp
-    ltm/base/detail/MemoryItem.cpp
-    ltm/base/detail/MemoryBase.cpp
-    ltm/base/detail/BufferedMemoryBase.cpp
-    ltm/base/detail/LUTMemoryBase.cpp
-    ltm/base/detail/CoreSegmentBase.cpp
-    ltm/base/detail/ProviderSegmentBase.cpp
-    ltm/base/detail/EntityBase.cpp
-    ltm/base/detail/EntitySnapshotBase.cpp
-
-    ltm/base/filter/Filter.cpp
-    ltm/base/filter/frequencyFilter/FrequencyFilter.cpp
-    ltm/base/filter/equalityFilter/EqualityFilter.cpp
-
-    ltm/base/extractor/Extractor.cpp
-    ltm/base/extractor/imageExtractor/ImageExtractor.cpp
-    ltm/base/extractor/imageExtractor/DepthImageExtractor.cpp
-
-    ltm/base/converter/Converter.cpp
-    ltm/base/typeConverter/Converter.cpp
-    ltm/base/typeConverter/json/JsonConverter.cpp
-    ltm/base/converter/object/Converter.cpp
-    ltm/base/converter/object/json/JsonConverter.cpp
-    ltm/base/converter/object/bson/BsonConverter.cpp
-    ltm/base/converter/image/Converter.cpp
-    ltm/base/converter/image/png/PngConverter.cpp
-    ltm/base/converter/image/exr/ExrConverter.cpp
-
-    ltm/base/forgetter/Forgetter.cpp
-    ltm/base/forgetter/LRUForgetter/LRUForgetter.cpp
-
-    ltm/disk/detail/util/util.cpp
-    ltm/disk/detail/util/filesystem_util.cpp
-    ltm/disk/detail/util/minizip_util.cpp
-    ltm/disk/detail/DiskStorage.cpp
-    ltm/disk/Memory.cpp
-    ltm/disk/CoreSegment.cpp
-    ltm/disk/ProviderSegment.cpp
-    ltm/disk/Entity.cpp
-    ltm/disk/EntitySnapshot.cpp
+    ltm/detail/mixins/util/filesystem.cpp
+    ltm/detail/mixins/util/mongodb.cpp
+    ltm/detail/mixins/CachedMemoryMixin.cpp
+    ltm/detail/mixins/BufferedMemoryMixin.cpp
+    ltm/detail/mixins/DiskStorageMixin.cpp
+    ltm/detail/mixins/MongoDBStorageMixin.cpp
+
+    ltm/detail/MemoryItem.cpp
+    ltm/detail/MemoryBase.cpp
+    ltm/detail/CoreSegmentBase.cpp
+    ltm/detail/ProviderSegmentBase.cpp
+    ltm/detail/EntityBase.cpp
+    ltm/detail/EntitySnapshotBase.cpp
+    ltm/detail/EntityInstanceBase.cpp
+
+    ltm/processors/Processors.cpp
+
+    ltm/processors/filter/Filter.cpp
+    ltm/processors/filter/frequencyFilter/FrequencyFilter.cpp
+    ltm/processors/filter/equalityFilter/EqualityFilter.cpp
+
+    ltm/processors/extractor/Extractor.cpp
+    ltm/processors/extractor/imageExtractor/ImageExtractor.cpp
+    ltm/processors/extractor/imageExtractor/DepthImageExtractor.cpp
+
+    ltm/processors/converter/type/Converter.cpp
+    ltm/processors/converter/type/object/Converter.cpp
+    ltm/processors/converter/type/object/json/JsonConverter.cpp
+    ltm/processors/converter/data/Converter.cpp
+    ltm/processors/converter/data/object/Converter.cpp
+    ltm/processors/converter/data/object/json/JsonConverter.cpp
+    ltm/processors/converter/data/object/bson/BsonConverter.cpp
+    ltm/processors/converter/data/image/Converter.cpp
+    ltm/processors/converter/data/image/png/PngConverter.cpp
+    ltm/processors/converter/data/image/exr/ExrConverter.cpp
+
+    ltm/Memory.cpp
+    ltm/CoreSegment.cpp
+    ltm/ProviderSegment.cpp
+    ltm/Entity.cpp
+    ltm/EntitySnapshot.cpp
+    ltm/EntityInstance.cpp
 
+    ltm/disk/Memory.h
+
+    # WM
     wm/memory_definitions.cpp
     wm/ice_conversions.cpp
     wm/detail/MaxHistorySize.cpp
@@ -128,51 +125,54 @@ set(LIB_HEADERS
     MemoryRemoteGui.h
     RemoteGuiAronDataVisitor.h
 
+    # LTM
     ltm/io/Recording.h
     ltm/io/Replaying.h
 
-    ltm/base/detail/Processors.h
-    ltm/base/detail/MemoryItem.h
-    ltm/base/detail/MemoryBase.h
-    ltm/base/detail/BufferedMemoryBase.h
-    ltm/base/detail/LUTMemoryBase.h
-    ltm/base/detail/CoreSegmentBase.h
-    ltm/base/detail/ProviderSegmentBase.h
-    ltm/base/detail/EntityBase.h
-    ltm/base/detail/EntitySnapshotBase.h
-
-    ltm/base/filter/Filter.h
-    ltm/base/filter/frequencyFilter/FrequencyFilter.h
-    ltm/base/filter/equalityFilter/EqualityFilter.h
-
-    ltm/base/extractor/Extractor.h
-    ltm/base/extractor/imageExtractor/ImageExtractor.h
-    ltm/base/extractor/imageExtractor/DepthImageExtractor.h
-
-    ltm/base/converter/Converter.h
-    ltm/base/typeConverter/Converter.h
-    ltm/base/typeConverter/json/JsonConverter.h
-    ltm/base/converter/object/Converter.h
-    ltm/base/converter/object/json/JsonConverter.h
-    ltm/base/converter/object/bson/BsonConverter.h
-    ltm/base/converter/image/Converter.h
-    ltm/base/converter/image/png/PngConverter.h
-    ltm/base/converter/image/exr/ExrConverter.h
-
-
-    ltm/base/forgetter/Forgetter.h
-    ltm/base/forgetter/LRUForgetter/LRUForgetter.h
-
-    ltm/disk/detail/util/util.h
-    ltm/disk/detail/util/filesystem_util.h
-    ltm/disk/detail/util/minizip_util.h
-    ltm/disk/detail/DiskStorage.h
-    ltm/disk/Memory.h
-    ltm/disk/CoreSegment.h
-    ltm/disk/ProviderSegment.h
-    ltm/disk/Entity.h
-    ltm/disk/EntitySnapshot.h
-
+    ltm/detail/mixins/util/filesystem.h
+    ltm/detail/mixins/util/mongodb.h
+    ltm/detail/mixins/CachedMemoryMixin.h
+    ltm/detail/mixins/BufferedMemoryMixin.h
+    ltm/detail/mixins/DiskStorageMixin.h
+    ltm/detail/mixins/MongoDBStorageMixin.h
+
+    ltm/detail/MemoryItem.h
+    ltm/detail/MemoryBase.h
+    ltm/detail/CoreSegmentBase.h
+    ltm/detail/ProviderSegmentBase.h
+    ltm/detail/EntityBase.h
+    ltm/detail/EntitySnapshotBase.h
+    ltm/detail/EntityInstanceBase.h
+
+    ltm/processors/Processors.h
+
+    ltm/processors/filter/Filter.h
+    ltm/processors/filter/frequencyFilter/FrequencyFilter.h
+    ltm/processors/filter/equalityFilter/EqualityFilter.h
+
+    ltm/processors/extractor/Extractor.h
+    ltm/processors/extractor/imageExtractor/ImageExtractor.h
+    ltm/processors/extractor/imageExtractor/DepthImageExtractor.h
+
+    ltm/processors/converter/type/Converter.h
+    ltm/processors/converter/type/object/Converter.h
+    ltm/processors/converter/type/object/json/JsonConverter.h
+    ltm/processors/converter/data/Converter.h
+    ltm/processors/converter/data/object/Converter.h
+    ltm/processors/converter/data/object/json/JsonConverter.h
+    ltm/processors/converter/data/object/bson/BsonConverter.h
+    ltm/processors/converter/data/image/Converter.h
+    ltm/processors/converter/data/image/png/PngConverter.h
+    ltm/processors/converter/data/image/exr/ExrConverter.h
+
+    ltm/Memory.h
+    ltm/CoreSegment.h
+    ltm/ProviderSegment.h
+    ltm/Entity.h
+    ltm/EntitySnapshot.h
+    ltm/EntityInstance.h
+
+    # WM
     wm/memory_definitions.h
     wm/ice_conversions.h
     wm/detail/MaxHistorySize.h
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
index 858f715c4ec5728edbf646e587cd4f02d5958798..1dbb15e5cbcb3e1d5275fcfc9ea174a684c0f7fb 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
@@ -1,38 +1,36 @@
 #include "MemoryToIceAdapter.h"
 
-#include "query_proc/wm/wm.h"
-#include "query_proc/ltm/disk/ltm.h"
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/ice_conversions/ice_conversions_templates.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/ice_conversions.h>
 
-#include <RobotAPI/libraries/aron/core/Exception.h>
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
 #include <RobotAPI/libraries/armem/core/error.h>
 #include <RobotAPI/libraries/armem/core/ice_conversions.h>
 #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
-
-#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_conversions.h>
 #include <RobotAPI/libraries/armem/server/wm/ice_conversions.h>
+#include <RobotAPI/libraries/aron/core/Exception.h>
 
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-#include <ArmarXCore/core/ice_conversions/ice_conversions_templates.h>
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/time/ice_conversions.h>
-
+#include "query_proc/ltm/disk/ltm.h"
+#include "query_proc/wm/wm.h"
 
 namespace armarx::armem::server
 {
 
-    MemoryToIceAdapter::MemoryToIceAdapter(wm::Memory* workingMemory, server::ltm::disk::Memory* longtermMemory) :
+    MemoryToIceAdapter::MemoryToIceAdapter(wm::Memory* workingMemory,
+                                           server::ltm::Memory* longtermMemory) :
         workingMemory(workingMemory), longtermMemory(longtermMemory)
     {
     }
 
-
     void
     MemoryToIceAdapter::setMemoryListener(client::MemoryListenerInterfacePrx memoryListener)
     {
         this->memoryListenerTopic = memoryListener;
     }
 
-
     // WRITING
     data::AddSegmentResult
     MemoryToIceAdapter::addSegment(const data::AddSegmentInput& input, bool addCoreSegments)
@@ -64,22 +62,24 @@ namespace armarx::armem::server
 
         if (input.providerSegmentName.size() > 0)
         {
-            coreSegment->doLocked([&coreSegment, &input]()
-            {
-                try
-                {
-                    coreSegment->addProviderSegment(input.providerSegmentName);
-                }
-                catch (const armem::error::ContainerEntryAlreadyExists&)
+            coreSegment->doLocked(
+                [&coreSegment, &input]()
                 {
-                    // This is ok.
-                    if (input.clearWhenExists)
+                    try
                     {
-                        server::wm::ProviderSegment& provider = coreSegment->getProviderSegment(input.providerSegmentName);
-                        provider.clear();
+                        coreSegment->addProviderSegment(input.providerSegmentName);
                     }
-                }
-            });
+                    catch (const armem::error::ContainerEntryAlreadyExists&)
+                    {
+                        // This is ok.
+                        if (input.clearWhenExists)
+                        {
+                            server::wm::ProviderSegment& provider =
+                                coreSegment->getProviderSegment(input.providerSegmentName);
+                            provider.clear();
+                        }
+                    }
+                });
         }
 
         armem::MemoryID segmentID;
@@ -92,7 +92,6 @@ namespace armarx::armem::server
         return output;
     }
 
-
     data::AddSegmentsResult
     MemoryToIceAdapter::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments)
     {
@@ -107,13 +106,12 @@ namespace armarx::armem::server
         return output;
     }
 
-
     data::CommitResult
     MemoryToIceAdapter::commit(const data::Commit& commitIce, Time timeArrived)
     {
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
-        auto handleException = [](const std::string & what)
+        auto handleException = [](const std::string& what)
         {
             data::CommitResult result;
             data::EntityUpdateResult& r = result.results.emplace_back();
@@ -145,7 +143,6 @@ namespace armarx::armem::server
         return resultIce;
     }
 
-
     data::CommitResult
     MemoryToIceAdapter::commit(const data::Commit& commitIce)
     {
@@ -153,7 +150,6 @@ namespace armarx::armem::server
         return commit(commitIce, armem::Time::Now());
     }
 
-
     armem::CommitResult
     MemoryToIceAdapter::commit(const armem::Commit& commit)
     {
@@ -161,15 +157,15 @@ namespace armarx::armem::server
         return this->_commit(commit, false);
     }
 
-
-    armem::CommitResult MemoryToIceAdapter::commitLocking(const armem::Commit& commit)
+    armem::CommitResult
+    MemoryToIceAdapter::commitLocking(const armem::Commit& commit)
     {
         ARMARX_TRACE;
         return this->_commit(commit, true);
     }
 
-
-    armem::CommitResult MemoryToIceAdapter::_commit(const armem::Commit& commit, bool locking)
+    armem::CommitResult
+    MemoryToIceAdapter::_commit(const armem::Commit& commit, bool locking)
     {
         ARMARX_TRACE;
         std::vector<data::MemoryID> updatedIDs;
@@ -181,9 +177,8 @@ namespace armarx::armem::server
             EntityUpdateResult& result = commitResult.results.emplace_back();
             try
             {
-                auto updateResult = locking
-                                    ? workingMemory->updateLocking(update)
-                                    : workingMemory->update(update);
+                auto updateResult =
+                    locking ? workingMemory->updateLocking(update) : workingMemory->update(update);
 
                 result.success = true;
                 result.snapshotID = updateResult.id;
@@ -200,30 +195,10 @@ namespace armarx::armem::server
                     //ARMARX_IMPORTANT << longtermMemory->id().str();
                     //ARMARX_IMPORTANT << longtermMemory->getPath();
 
-                    // Create Memory out of list TODO: make nicer
+                    // convert removedSnapshots to Memory
                     armem::wm::Memory m(longtermMemory->name());
-                    for (const auto& snapshot : updateResult.removedSnapshots)
-                    {
-                        if (!m.hasCoreSegment(snapshot.id().coreSegmentName))
-                        {
-                            m.addCoreSegment(snapshot.id().coreSegmentName);
-                        }
-                        auto* c = m.findCoreSegment(snapshot.id().coreSegmentName);
-
-                        if (!c->hasProviderSegment(snapshot.id().providerSegmentName))
-                        {
-                            c->addProviderSegment(snapshot.id().providerSegmentName);
-                        }
-                        auto* p = c->findProviderSegment(snapshot.id().providerSegmentName);
-
-                        if (!p->hasEntity(snapshot.id().entityName))
-                        {
-                            p->addEntity(snapshot.id().entityName);
-                        }
-                        auto* e = p->findEntity(snapshot.id().entityName);
+                    armem::wm::toMemory(m, updateResult.removedSnapshots);
 
-                        e->addSnapshot(snapshot);
-                    }
                     // store memory
                     longtermMemory->store(m);
                 }
@@ -259,7 +234,6 @@ namespace armarx::armem::server
         return commitResult;
     }
 
-
     // READING
     armem::query::data::Result
     MemoryToIceAdapter::query(const armem::query::data::Input& input)
@@ -269,12 +243,13 @@ namespace armarx::armem::server
         ARMARX_CHECK_NOT_NULL(longtermMemory);
 
         // Core segment processors will aquire the core segment locks.
-        query_proc::wm_server::MemoryQueryProcessor wmServerProcessor(armem::query::boolToDataMode(input.withData));
+        query_proc::wm_server::MemoryQueryProcessor wmServerProcessor(
+            armem::query::boolToDataMode(input.withData));
         armem::wm::Memory wmResult = wmServerProcessor.process(input, *workingMemory);
 
         armem::query::data::Result result;
 
-        query_proc::ltm_server::disk::MemoryQueryProcessor ltmProcessor;
+        /*query_proc::ltm_server::MemoryQueryProcessor ltmProcessor;
         armem::wm::Memory ltmResult = ltmProcessor.process(input, *longtermMemory);
 
         if (not ltmResult.empty())
@@ -306,7 +281,7 @@ namespace armarx::armem::server
                 // mark removed entries of wm in viewer
                 // TODO
             }
-        }
+        }*/
 
         result.memory = armarx::toIce<data::MemoryPtr>(wmResult);
 
@@ -319,14 +294,15 @@ namespace armarx::armem::server
         return result;
     }
 
-
-    client::QueryResult MemoryToIceAdapter::query(const client::QueryInput& input)
+    client::QueryResult
+    MemoryToIceAdapter::query(const client::QueryInput& input)
     {
         ARMARX_TRACE;
         return client::QueryResult::fromIce(query(input.toIce()));
     }
 
-    armem::structure::data::GetServerStructureResult MemoryToIceAdapter::getServerStructure()
+    armem::structure::data::GetServerStructureResult
+    MemoryToIceAdapter::getServerStructure()
     {
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(workingMemory);
@@ -355,11 +331,11 @@ namespace armarx::armem::server
         return ret;
     }
 
-
     // LTM LOADING FROM LTM
 
     // LTM STORING AND RECORDING
-    dto::DirectlyStoreResult MemoryToIceAdapter::directlyStore(const dto::DirectlyStoreInput& directlStoreInput)
+    dto::DirectlyStoreResult
+    MemoryToIceAdapter::directlyStore(const dto::DirectlyStoreInput& directlStoreInput)
     {
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(longtermMemory);
@@ -373,7 +349,8 @@ namespace armarx::armem::server
         return output;
     }
 
-    dto::StartRecordResult MemoryToIceAdapter::startRecord(const dto::StartRecordInput& startRecordInput)
+    dto::StartRecordResult
+    MemoryToIceAdapter::startRecord(const dto::StartRecordInput& startRecordInput)
     {
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(longtermMemory);
@@ -386,7 +363,8 @@ namespace armarx::armem::server
         return ret;
     }
 
-    dto::StopRecordResult MemoryToIceAdapter::stopRecord()
+    dto::StopRecordResult
+    MemoryToIceAdapter::stopRecord()
     {
         ARMARX_TRACE;
         ARMARX_CHECK_NOT_NULL(longtermMemory);
@@ -399,24 +377,30 @@ namespace armarx::armem::server
         return ret;
     }
 
-    dto::RecordStatusResult MemoryToIceAdapter::getRecordStatus()
+    dto::RecordStatusResult
+    MemoryToIceAdapter::getRecordStatus()
     {
         dto::RecordStatusResult ret;
         ret.success = true;
 
         long savedSnapshots;
         long totalSnapshots;
-        longtermMemory->forEachCoreSegment([&savedSnapshots, &totalSnapshots](const auto& c){
-            c.forEachProviderSegment([&savedSnapshots, &totalSnapshots](const auto& p){
-                p.forEachEntity([&savedSnapshots, &totalSnapshots](const auto& e){
-                    savedSnapshots += e.getStatistics().recordedSnapshots;
-
-                    e.forEachSnapshot([&totalSnapshots](const auto&){
-                        totalSnapshots++;
+        longtermMemory->forEachCoreSegment(
+            [&savedSnapshots, &totalSnapshots](const auto& c)
+            {
+                c.forEachProviderSegment(
+                    [&savedSnapshots, &totalSnapshots](const auto& p)
+                    {
+                        p.forEachEntity(
+                            [&savedSnapshots, &totalSnapshots](const auto& e)
+                            {
+                                savedSnapshots += e.getStatistics().recordedSnapshots;
+
+                                e.forEachSnapshot([&totalSnapshots](const auto&)
+                                                  { totalSnapshots++; });
+                            });
                     });
-                });
             });
-        });
 
         ret.status.savedSnapshots = savedSnapshots;
         ret.status.totalSnapshots = totalSnapshots;
@@ -433,7 +417,8 @@ namespace armarx::armem::server
         return armarx::toIce<prediction::data::PredictionResultSeq>(res);
     }
 
-    prediction::data::EngineSupportMap MemoryToIceAdapter::getAvailableEngines()
+    prediction::data::EngineSupportMap
+    MemoryToIceAdapter::getAvailableEngines()
     {
         prediction::data::EngineSupportMap result;
         armarx::toIce(result, workingMemory->getAllPredictionEngines());
@@ -462,4 +447,4 @@ namespace armarx::armem::server
         return result;
     }
 
-}
+} // namespace armarx::armem::server
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
index 41b0312e6518ebcf78471f42efe23d5bf0eb9634..a451054a2fb667e99c9472d847c86e3e2cb48dea 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.h
@@ -1,14 +1,12 @@
 #pragma once
 
-#include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/interface/armem/client/MemoryListenerInterface.h>
-
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h>
+#include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/libraries/armem/client/Query.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
-
 namespace armarx::armem::server
 {
 
@@ -21,20 +19,19 @@ namespace armarx::armem::server
     class MemoryToIceAdapter
     {
     public:
-
         /// Construct an MemoryToIceAdapter from an existing Memory.
         MemoryToIceAdapter(server::wm::Memory* workingMemory = nullptr,
-                           server::ltm::disk::Memory* longtermMemory = nullptr);
+                           server::ltm::Memory* longtermMemory = nullptr);
 
         void setMemoryListener(client::MemoryListenerInterfacePrx memoryListenerTopic);
 
 
         // WRITING
-        data::AddSegmentResult addSegment(
-            const data::AddSegmentInput& input, bool addCoreSegments = false);
+        data::AddSegmentResult addSegment(const data::AddSegmentInput& input,
+                                          bool addCoreSegments = false);
 
-        data::AddSegmentsResult addSegments(
-            const data::AddSegmentsInput& input, bool addCoreSegments = false);
+        data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input,
+                                            bool addCoreSegments = false);
 
 
         data::CommitResult commit(const data::Commit& commitIce, Time timeArrived);
@@ -63,18 +60,15 @@ namespace armarx::armem::server
         prediction::data::EngineSupportMap getAvailableEngines();
 
     public:
-
         server::wm::Memory* workingMemory;
-        server::ltm::disk::Memory* longtermMemory;
+        server::ltm::Memory* longtermMemory;
 
         client::MemoryListenerInterfacePrx memoryListenerTopic;
 
 
     private:
-
         armem::CommitResult _commit(const armem::Commit& commit, bool locking);
-
     };
 
 
-}
+} // namespace armarx::armem::server
diff --git a/source/RobotAPI/libraries/armem/server/forward_declarations.h b/source/RobotAPI/libraries/armem/server/forward_declarations.h
index 956a92b96ea8a75f7526fc5d111b0cc63bec26b8..5239bb8784473afe300d95d933f6920350fc9f28 100644
--- a/source/RobotAPI/libraries/armem/server/forward_declarations.h
+++ b/source/RobotAPI/libraries/armem/server/forward_declarations.h
@@ -2,11 +2,11 @@
 
 #include <RobotAPI/libraries/armem/core/forward_declarations.h>
 
-
 namespace armarx::armem::server
 {
     class MemoryToIceAdapter;
 }
+
 namespace armarx::armem::server::wm
 {
     using EntityInstance = armem::wm::EntityInstance;
@@ -15,12 +15,9 @@ namespace armarx::armem::server::wm
     class ProviderSegment;
     class CoreSegment;
     class Memory;
-}
-namespace armarx::armem::server::ltm::mongodb
-{
-    class Memory;
-}
-namespace armarx::armem::server::ltm::disk
+} // namespace armarx::armem::server::wm
+
+namespace armarx::armem::server::ltm
 {
     class Memory;
 }
diff --git a/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.cpp b/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..5e0f1908bc411d1270503a273d62d8508707f4be
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.cpp
@@ -0,0 +1,214 @@
+#include "CoreSegment.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm
+{
+    CoreSegment::CoreSegment(const detail::mixin::Path& p,
+                             const detail::mixin::MongoDBSettings& s,
+
+                             const std::string& exportName,
+                             const armem::MemoryID& id /* UNESCAPED */,
+                             const std::shared_ptr<Processors>& filters) :
+        CoreSegmentBase(exportName, id, filters),
+        DiskMemoryItemMixin(p, exportName, id),
+        MongoDBStorageMixin(s, exportName, id)
+    {
+        //start();
+    }
+
+    bool
+    CoreSegment::forEachProviderSegment(std::function<void(ProviderSegment&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            for (const auto& doc : getAllDocuments())
+            {
+                std::string id_str = doc[FOREIGN_KEY];
+                armem::MemoryID segment_id(id_str);
+                ProviderSegment c(
+                    getMemoryBasePath(), getSettings(), getExportName(), segment_id, processors);
+                func(c);
+            }
+        } else */
+
+        // legacy
+        if (fullPathExists())
+        {
+            for (const auto& subdirName : getAllDirectories())
+            {
+                std::string segmentName = util::fs::detail::unescapeName(subdirName);
+                ProviderSegment c(getMemoryBasePath(),
+                                  getSettings(),
+                                  getExportName(),
+                                  id().withProviderSegmentName(segmentName),
+                                  processors);
+                func(c);
+            }
+        }
+        return true;
+    }
+
+    bool
+    CoreSegment::hasProviderSegment(const std::string& name) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            auto c = ProviderSegment(getMemoryBasePath(),
+                                     getSettings(),
+                                     getExportName(),
+                                     id().withProviderSegmentName(name),
+                                     processors);
+
+            return (bool)c.collectionExists();
+        }*/
+
+        if (fullPathExists())
+        {
+            auto c = ProviderSegment(getMemoryBasePath(),
+                                     getSettings(),
+                                     getExportName(),
+                                     id().withProviderSegmentName(name),
+                                     processors);
+
+            return c.fullPathExists();
+        }
+
+        return false;
+    }
+
+    std::shared_ptr<ProviderSegment>
+    CoreSegment::findProviderSegment(const std::string& providerSegmentName) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (!hasProviderSegment(providerSegmentName))
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<ProviderSegment>(getMemoryBasePath(),
+                                                 getSettings(),
+                                                 getExportName(),
+                                                 id().withProviderSegmentName(providerSegmentName),
+                                                 processors);
+    }
+
+    void
+    CoreSegment::_loadAllReferences(armem::wm::CoreSegment& e)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        e.id() = id();
+
+        auto& conv = processors->defaultTypeConverter;
+        auto setType = [&conv, &e](const std::vector<unsigned char>& aronJson)
+        {
+            auto typeAron = conv.convert(aronJson, "");
+            e.aronType() = aron::type::Object::DynamicCastAndCheck(typeAron);
+        };
+
+        /*if (connected() && collectionExists())
+        {
+            // TODO:
+        } else */
+
+        if (std::string filename = TYPE_FILENAME + conv.suffix;
+            fullPathExists() && fileExists(filename))
+        {
+            auto typeFileContent = readDataFromFile(filename);
+            setType(typeFileContent);
+        }
+
+        forEachProviderSegment(
+            [&e](auto& x)
+            {
+                armem::wm::ProviderSegment s;
+                x.loadAllReferences(s);
+                e.addProviderSegment(s);
+            });
+    }
+
+    void
+    CoreSegment::_resolve(armem::wm::CoreSegment& c)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (/*(connected() && collectionExists()) ||*/ fullPathExists())
+        {
+            c.forEachProviderSegment(
+                [&](auto& e)
+                {
+                    ProviderSegment c(getMemoryBasePath(),
+                                      getSettings(),
+                                      getExportName(),
+                                      id().withProviderSegmentName(e.id().providerSegmentName),
+                                      processors);
+                    c.resolve(e);
+                });
+        }
+    }
+
+    void
+    CoreSegment::_store(const armem::wm::CoreSegment& c)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (id().coreSegmentName.empty())
+        {
+            ARMARX_WARNING
+                << "During storage of segment '" << c.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            id().coreSegmentName = c.id().coreSegmentName;
+        };
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM CORE SEGMENT NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return;
+        }*/
+
+        // add foreign key to memory collection
+        if (c.hasAronType())
+        {
+            auto& conv = processors->defaultTypeConverter;
+
+            auto [vec, modeSuffix] = conv.convert(c.aronType());
+            ARMARX_CHECK_EMPTY(modeSuffix);
+
+            //std::string dataStr{vec.begin(), vec.end()};
+            /*auto dataJson = nlohmann::json::parse(dataStr);
+
+            writeForeignKeyToPreviousDocument(dataJson);*/
+
+            ensureFullPathExists(true);
+            std::string filename = (TYPE_FILENAME + conv.suffix);
+            writeDataToFile(filename, vec);
+        }
+        else
+        {
+            /*writeForeignKeyToPreviousDocument();*/
+        }
+
+        c.forEachProviderSegment(
+            [&](const auto& prov)
+            {
+                ProviderSegment c(getMemoryBasePath(),
+                                  getSettings(),
+                                  getExportName(),
+                                  id().withProviderSegmentName(prov.id().providerSegmentName),
+                                  processors);
+
+                c.store(prov);
+                statistics.recordedProviderSegments++;
+            });
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.h b/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.h
new file mode 100644
index 0000000000000000000000000000000000000000..14d8b0abab73608e6eba0de5fa97734764a1a9ad
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/CoreSegment.h
@@ -0,0 +1,37 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "ProviderSegment.h"
+#include "detail/CoreSegmentBase.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+namespace armarx::armem::server::ltm
+{
+    class CoreSegment :
+        public detail::CoreSegmentBase<ProviderSegment>,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        CoreSegment(const detail::mixin::Path&,
+                    const detail::mixin::MongoDBSettings&,
+                    const std::string&,
+                    const MemoryID&,
+                    const std::shared_ptr<Processors>&);
+
+        bool forEachProviderSegment(std::function<void(ProviderSegment&)> func) const override;
+        bool hasProviderSegment(const std::string& name) const override;
+        std::shared_ptr<ProviderSegment> findProviderSegment(const std::string&) const override;
+
+    protected:
+        void _loadAllReferences(armem::wm::CoreSegment&) override;
+        void _resolve(armem::wm::CoreSegment&) override;
+        void _store(const armem::wm::CoreSegment&) override;
+
+    private:
+    };
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/Entity.cpp b/source/RobotAPI/libraries/armem/server/ltm/Entity.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b34d9d5167b9f505d70e3c20caf8e317b7680be3
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/Entity.cpp
@@ -0,0 +1,475 @@
+// Header
+#include "Entity.h"
+
+// SImox
+#include <SimoxUtility/algorithm/string.h>
+
+// ArmarX
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+#include "processors/filter/frequencyFilter/FrequencyFilter.h"
+
+namespace armarx::armem::server::ltm
+{
+    namespace util
+    {
+
+
+    } // namespace util
+
+    Entity::Entity(const detail::mixin::Path& p,
+                   const detail::mixin::MongoDBSettings& s,
+
+                   const std::string& exportName,
+                   const armem::MemoryID& id /* UNESCAPED */,
+                   const std::shared_ptr<Processors>& filters) :
+        EntityBase(exportName, id, filters),
+        DiskMemoryItemMixin(p, exportName, id),
+        MongoDBStorageMixin(s, exportName, id)
+    {
+        //start();
+    }
+
+    bool
+    Entity::forEachSnapshot(std::function<void(EntitySnapshot&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            for (const auto& doc : getAllDocuments())
+            {
+                std::string id_str = doc[ID];
+
+                armem::MemoryID segment_id = id();
+                segment_id.timestampFromStr(id_str);
+
+                EntitySnapshot c(
+                    getMemoryBasePath(), getSettings(), getExportName(), segment_id, processors);
+                func(c);
+            }
+        } else */
+        if (fullPathExists())
+        {
+
+            for (const auto& d : getAllDirectories()) // days
+            {
+                if (!util::fs::detail::isDateString(d.filename()))
+                {
+                    ARMARX_WARNING << "Found a non-date folder inside an entity '" << id().str()
+                                   << "' with name '" << d.filename() << "'. "
+                                   << "Ignoring this folder, however this is a bad situation.";
+                    continue;
+                }
+
+
+                // check if this is already a microsec folder (legacy export support)
+                //if (std::stol(secName) > 1647524607 ) // the time in us the new export was implemented
+                //{
+                //    EntitySnapshot c(memoryParentPath, id().withTimestamp(timeFromStringMicroSeconds(secName)), processors, currentMode, currentExport);
+                //    func(c);
+                //    continue;
+                //}
+
+
+                for (const auto& s : util::fs::getAllDirectories(d)) // seconds
+                {
+                    if (!util::fs::detail::isNumberString(s.filename()))
+                    {
+                        ARMARX_WARNING << "Found a non-timestamp folder inside an entity '"
+                                       << id().str() << "' hours folder with name '" << s.filename()
+                                       << "'. "
+                                       << "Ignoring this folder, however this is a bad situation.";
+                        continue;
+                    }
+
+                    for (const auto& us : util::fs::getAllDirectories(s)) // microseconds
+                    {
+                        if (!util::fs::detail::isNumberString(us.filename()))
+                        {
+                            ARMARX_WARNING
+                                << "Found a non-timestamp folder inside an entity '" << id().str()
+                                << "' seconds folder with name '" << us.filename() << "'. "
+                                << "Ignoring this folder, however this is a bad situation.";
+                            continue;
+                        }
+
+
+                        EntitySnapshot c(
+                            getMemoryBasePath(),
+                            getSettings(),
+                            getExportName(),
+                            id().withTimestamp(timeFromStringMicroSeconds(us.filename())),
+                            processors);
+                        func(c);
+                    }
+                }
+            }
+        }
+
+        return true;
+    }
+
+    bool
+    Entity::forEachSnapshotInIndexRange(long first,
+                                        long last,
+                                        std::function<void(EntitySnapshot&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+        //ARMARX_WARNING << "PLEASE NOTE THAT QUERYING THE LTM INDEX WISE MAY BE BUGGY BECAUSE THE FILESYSTEM ITERATOR IS UNSORTED!";
+
+        if (first < 0 or last < 0)
+        {
+            // We need to know what the size of the memory is... May be slow
+            unsigned long size = 0;
+            auto f = [&](EntitySnapshot& e) { size++; };
+            forEachSnapshot(std::move(f));
+
+            first = armarx::armem::base::detail::negativeIndexSemantics(first, size);
+            last = armarx::armem::base::detail::negativeIndexSemantics(last, size);
+        }
+
+        long checked = 0;
+        auto f = [&](EntitySnapshot& e)
+        {
+            if (checked >= first && checked <= last)
+            {
+                func(e);
+            }
+            checked++;
+        };
+
+        return forEachSnapshot(std::move(f));
+    }
+
+    bool
+    Entity::forEachSnapshotInTimeRange(const Time& min,
+                                       const Time& max,
+                                       std::function<void(EntitySnapshot&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts >= min && ts <= max)
+            {
+                func(e);
+            }
+        };
+
+        return forEachSnapshot(std::move(f));
+    }
+
+    bool
+    Entity::forEachSnapshotBeforeOrAt(const Time& time,
+                                      std::function<void(EntitySnapshot&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts <= time)
+            {
+                func(e);
+            }
+        };
+
+        return forEachSnapshot(std::move(f));
+    }
+
+    bool
+    Entity::forEachSnapshotBefore(const Time& time, std::function<void(EntitySnapshot&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts < time)
+            {
+                func(e);
+            }
+        };
+
+        return forEachSnapshot(std::move(f));
+    }
+
+    bool
+    Entity::hasSnapshot(const Time& n) const
+    {
+        std::lock_guard l(ltm_mutex);
+        /*if (connected() && collectionExists())
+        {
+            auto c = EntitySnapshot(getMemoryBasePath(),
+                                    getSettings(),
+                                    getExportName(),
+                                    id().withTimestamp(n),
+                                    processors);
+            return (bool)c.documentExists();
+        }*/
+
+        if (fullPathExists())
+        {
+            auto c = EntitySnapshot(getMemoryBasePath(),
+                                    getSettings(),
+                                    getExportName(),
+                                    id().withTimestamp(n),
+                                    processors);
+            return c.fullPathExists();
+        }
+        return false;
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findSnapshot(const Time& n) const
+    {
+        std::lock_guard l(ltm_mutex);
+        if (!hasSnapshot(n))
+        {
+            return nullptr;
+        }
+        return std::make_shared<EntitySnapshot>(
+            getMemoryBasePath(), getSettings(), getExportName(), id().withTimestamp(n), processors);
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findLatestSnapshot() const
+    {
+        std::lock_guard l(ltm_mutex);
+        Time bestMatch = Time::Invalid();
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts > bestMatch)
+            {
+                bestMatch = ts;
+            }
+        };
+
+        forEachSnapshot(std::move(f));
+
+        if (bestMatch == Time::Invalid())
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<EntitySnapshot>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withTimestamp(bestMatch),
+                                                processors);
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findLatestSnapshotBefore(const Time& time) const
+    {
+        std::lock_guard l(ltm_mutex);
+        Time bestMatch = Time::Invalid();
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts < time && ts > bestMatch)
+            {
+                bestMatch = ts;
+            }
+        };
+
+        forEachSnapshot(std::move(f));
+
+        if (bestMatch == Time::Invalid())
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<EntitySnapshot>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withTimestamp(bestMatch),
+                                                processors);
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findLatestSnapshotBeforeOrAt(const Time& time) const
+    {
+        std::lock_guard l(ltm_mutex);
+        Time bestMatch = Time::Invalid();
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts <= time && ts > bestMatch)
+            {
+                bestMatch = ts;
+            }
+        };
+
+        forEachSnapshot(std::move(f));
+
+        if (bestMatch == Time::Invalid())
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<EntitySnapshot>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withTimestamp(bestMatch),
+                                                processors);
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findFirstSnapshotAfter(const Time& time) const
+    {
+        std::lock_guard l(ltm_mutex);
+        Time bestMatch{Duration::MicroSeconds(std::numeric_limits<long>::max())};
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts > time && ts < bestMatch)
+            {
+                bestMatch = ts;
+            }
+        };
+
+        forEachSnapshot(std::move(f));
+
+        if (bestMatch == Time(Duration::MicroSeconds(std::numeric_limits<long>::max())))
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<EntitySnapshot>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withTimestamp(bestMatch),
+                                                processors);
+    }
+
+    std::shared_ptr<EntitySnapshot>
+    Entity::findFirstSnapshotAfterOrAt(const Time& time) const
+    {
+        std::lock_guard l(ltm_mutex);
+        Time bestMatch{Duration::MicroSeconds(std::numeric_limits<long>::max())};
+        auto f = [&](EntitySnapshot& e)
+        {
+            auto ts = e.id().timestamp;
+            if (ts >= time && ts < bestMatch)
+            {
+                bestMatch = ts;
+            }
+        };
+
+        forEachSnapshot(std::move(f));
+
+        if (bestMatch == Time(Duration::MicroSeconds(std::numeric_limits<long>::max())))
+        {
+            return nullptr;
+        }
+
+        return std::make_shared<EntitySnapshot>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withTimestamp(bestMatch),
+                                                processors);
+    }
+
+    void
+    Entity::_loadAllReferences(armem::wm::Entity& e)
+    {
+        std::lock_guard l(ltm_mutex);
+        e.id() = id();
+
+        forEachSnapshot(
+            [&e](auto& x)
+            {
+                if (!e.hasSnapshot(
+                        x.id()
+                            .timestamp)) // we only load the references if the snapshot is not existant
+                {
+                    armem::wm::EntitySnapshot s;
+                    x.loadAllReferences(s);
+                    e.addSnapshot(s);
+                }
+            });
+    }
+
+    void
+    Entity::_resolve(armem::wm::Entity& p)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (/*(connected() && collectionExists()) ||*/ fullPathExists())
+        {
+
+            p.forEachSnapshot(
+                [&](auto& e)
+                {
+                    EntitySnapshot c(getMemoryBasePath(),
+                                     getSettings(),
+                                     getExportName(),
+                                     id().withTimestamp(e.id().timestamp),
+                                     processors);
+                    c.resolve(e);
+                });
+        }
+    }
+
+    void
+    Entity::_store(const armem::wm::Entity& c)
+    {
+        std::lock_guard l(ltm_mutex);
+        if (id().entityName.empty())
+        {
+            ARMARX_WARNING
+                << "During storage of segment '" << c.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            id().entityName = c.id().entityName;
+        }
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM ENTITY NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return;
+        }*/
+
+        //writeForeignKeyToPreviousDocument();
+
+        c.forEachSnapshot(
+            [&](const auto& snap)
+            {
+                EntitySnapshot c(getMemoryBasePath(),
+                                 getSettings(),
+                                 getExportName(),
+                                 id().withTimestamp(snap.id().timestamp),
+                                 processors);
+
+                // check if snapshot already exists
+
+                if (hasSnapshot(snap.id().timestamp))
+                {
+                    ARMARX_INFO << deactivateSpam()
+                                << "Ignoring to put an EntitiySnapshot into the LTM because "
+                                   "the timestamp already existed (we assume snapshots are "
+                                   "const and do not change outside the ltm).";
+                    return;
+                }
+
+                for (auto& f : processors->snapFilters)
+                {
+                    if (!f->accept(snap))
+                    {
+                        ARMARX_INFO << deactivateSpam()
+                                    << "Ignoring to put an EntitiySnapshot into the LTM because it "
+                                       "got filtered.";
+                        return;
+                    }
+                }
+
+                c.store(snap);
+                statistics.recordedSnapshots++;
+            });
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/Entity.h b/source/RobotAPI/libraries/armem/server/ltm/Entity.h
new file mode 100644
index 0000000000000000000000000000000000000000..6afeed78767669a6ac6a445be7324a53d667967a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/Entity.h
@@ -0,0 +1,56 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "EntitySnapshot.h"
+#include "detail/EntityBase.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+namespace armarx::armem::server::ltm
+{
+    /// @brief A memory storing data in mongodb (needs 'armarx memory start' to start the mongod instance)
+    class Entity :
+        public detail::EntityBase<EntitySnapshot>,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        Entity(const detail::mixin::Path&,
+               const detail::mixin::MongoDBSettings&,
+               const std::string&,
+               const MemoryID& id,
+               const std::shared_ptr<Processors>&);
+
+        bool hasSnapshot(const Time&) const override;
+
+        bool forEachSnapshot(std::function<void(EntitySnapshot&)> func) const override;
+        bool forEachSnapshotInIndexRange(long first,
+                                         long last,
+                                         std::function<void(EntitySnapshot&)> func) const override;
+        bool forEachSnapshotInTimeRange(const Time& min,
+                                        const Time& max,
+                                        std::function<void(EntitySnapshot&)> func) const override;
+        bool forEachSnapshotBeforeOrAt(const Time& time,
+                                       std::function<void(EntitySnapshot&)> func) const override;
+        bool forEachSnapshotBefore(const Time& time,
+                                   std::function<void(EntitySnapshot&)> func) const override;
+
+        std::shared_ptr<EntitySnapshot> findSnapshot(const Time&) const override;
+        std::shared_ptr<EntitySnapshot> findLatestSnapshot() const override;
+        std::shared_ptr<EntitySnapshot> findLatestSnapshotBefore(const Time& time) const override;
+        std::shared_ptr<EntitySnapshot>
+        findLatestSnapshotBeforeOrAt(const Time& time) const override;
+        std::shared_ptr<EntitySnapshot> findFirstSnapshotAfter(const Time& time) const override;
+        std::shared_ptr<EntitySnapshot> findFirstSnapshotAfterOrAt(const Time& time) const override;
+
+    protected:
+        void _loadAllReferences(armem::wm::Entity&) override;
+        void _resolve(armem::wm::Entity&) override;
+        void _store(const armem::wm::Entity&) override;
+
+    private:
+    };
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.cpp b/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b5800ec11fd3cfaa5f8c3fd3fcff6e4a4b5bf599
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.cpp
@@ -0,0 +1,232 @@
+// Header
+#include "EntityInstance.h"
+
+// STD / STL
+#include <fstream>
+#include <iostream>
+
+// ArmarX
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+namespace armarx::armem::server::ltm
+{
+    EntityInstance::EntityInstance(const detail::mixin::Path& p,
+                                   const detail::mixin::MongoDBSettings& s,
+
+                                   const std::string& exportName,
+                                   const armem::MemoryID& id /* UNESCAPED */,
+                                   const std::shared_ptr<Processors>& filters) :
+        EntityInstanceBase(exportName, id, filters),
+        DiskMemoryItemMixin(p, exportName, id),
+        MongoDBStorageMixin(s, exportName, id)
+    {
+        //start();
+    }
+
+    void
+    EntityInstance::_loadAllReferences(armem::wm::EntitySnapshot& e) const
+    {
+        std::lock_guard l(ltm_mutex);
+        // assure that we put the right index to the snapshot
+        ARMARX_CHECK(e.size() == (size_t)id().instanceIndex);
+
+        // add instance. Do not set data, since we only return references
+        e.addInstance();
+    }
+
+    void
+    EntityInstance::_resolve(armem::wm::EntityInstance& e) const
+    {
+        std::lock_guard l(ltm_mutex);
+        auto& dictConverter = processors->defaultObjectConverter;
+
+        aron::data::DictPtr datadict = nullptr;
+        aron::data::DictPtr metadatadict = nullptr;
+
+        /*if (connected() && collectionExists())
+        {
+            if (auto d = documentExists(); d)
+            {
+                nlohmann::json doc = *d;
+
+                if (doc.contains(DATA))
+                {
+                    std::vector<nlohmann::json> instances = doc[DATA];
+                    if (instances.size() > (size_t)id().instanceIndex)
+                    {
+                        nlohmann::json data = instances[id().instanceIndex];
+                        std::string dataStr = data.dump();
+
+                        std::vector<unsigned char> dataVec{dataStr.begin(), dataStr.end()};
+                        auto dataaron = dictConverter.convert({dataVec, ""}, {});
+                        datadict = aron::data::Dict::DynamicCastAndCheck(dataaron);
+                    }
+                    else
+                    {
+                        ARMARX_ERROR << "Could not find the instance key. Continuing without data.";
+                    }
+                }
+                else
+                {
+                    ARMARX_ERROR << "Could not find the data key. Continuing without data.";
+                }
+
+                if (doc.contains(METADATA))
+                {
+                    nlohmann::json metadata = doc[METADATA];
+                    std::string metadataStr = metadata.dump();
+                    std::vector<unsigned char> metadataVec{metadataStr.begin(), metadataStr.end()};
+                    auto metadataaron = dictConverter.convert({metadataVec, ""}, {});
+                    metadatadict = aron::data::Dict::DynamicCastAndCheck(metadataaron);
+                }
+                else
+                {
+                    ARMARX_ERROR << "Could not find the metadata key. Continuing without metadata.";
+                }
+            }
+        } else */
+
+        if (fullPathExists())
+        {
+
+            std::string dataFilename = (DATA_FILENAME + dictConverter.suffix);
+            std::string metadataFilename = (METADATA_FILENAME + dictConverter.suffix);
+            std::filesystem::path dataPath = getFullPath() / dataFilename;
+            std::filesystem::path metadataPath = getFullPath() / metadataFilename;
+
+            if (util::fs::fileExists(dataPath))
+            {
+                //ARMARX_INFO << "Convert data for entity " << id();
+                auto datafilecontent = readDataFromFile(dataFilename);
+                auto dataaron = dictConverter.convert({datafilecontent, ""}, {});
+                datadict = aron::data::Dict::DynamicCastAndCheck(dataaron);
+            }
+            else
+            {
+                ARMARX_ERROR << "Could not find the data file '" << dataPath.string()
+                             << "'. Continuing without data.";
+            }
+
+            //ARMARX_INFO << "Convert metadata for entity " << id();
+            if (util::fs::fileExists(metadataPath))
+            {
+                auto metadatafilecontent = readDataFromFile(metadataFilename);
+                auto metadataaron = dictConverter.convert({metadatafilecontent, ""}, {});
+                metadatadict = aron::data::Dict::DynamicCastAndCheck(metadataaron);
+            }
+            else
+            {
+                ARMARX_ERROR << "Could not find the metadata file '" << metadataPath.string()
+                             << "'. Continuing without metadata.";
+            }
+        }
+
+        // check for special members TODO: only allowed for direct children?
+        auto allFilesInIndexFolder = getAllFiles();
+        for (const auto& [key, m] : datadict->getElements())
+        {
+            for (auto& f : processors->converters)
+            {
+                // iterate over all files and search for matching ones.
+                // We cannot simply check for the existence of a file because we do not know the
+                // mode (filename = memberName.mode.suffix)
+                for (const auto& filepath : allFilesInIndexFolder)
+                {
+                    if (simox::alg::starts_with(filepath.filename(), key) and
+                        simox::alg::ends_with(filepath, f->suffix))
+                    {
+                        std::string mode = simox::alg::remove_suffix(
+                            simox::alg::remove_prefix(filepath.filename(), key), f->suffix);
+
+                        auto memberfilecontent = readDataFromFile(filepath.filename());
+                        auto memberaron = f->convert(
+                            {memberfilecontent, mode},
+                            armarx::aron::Path(datadict->getPath(), std::vector<std::string>{key}));
+                        datadict->setElement(key, memberaron);
+                        break;
+                    }
+                }
+            }
+        }
+
+        from_aron(metadatadict, datadict, e);
+    }
+
+    nlohmann::json
+    EntityInstance::_store(const armem::wm::EntityInstance& e)
+    {
+        std::lock_guard l(ltm_mutex);
+        if (id().instanceIndex < 0)
+        {
+            ARMARX_WARNING
+                << "During storage of segment '" << e.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            id().timestamp = e.id().timestamp;
+        }
+
+        auto& dictConverter = processors->defaultObjectConverter;
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM ENTITY INSTANCE NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return {};
+        }*/
+
+        ensureFullPathExists(true);
+
+        // data
+        auto dataAron = std::make_shared<aron::data::Dict>();
+        auto metadataAron = std::make_shared<aron::data::Dict>();
+        to_aron(metadataAron, dataAron, e);
+
+        // check special members for special converters
+        for (auto& c : processors->converters)
+        {
+            ARMARX_CHECK_NOT_NULL(c);
+            ARMARX_CHECK_NOT_NULL(c->extractor);
+
+            auto dataExt = c->extractor->extract(dataAron);
+
+            for (const auto& [memberName, var] : dataExt.extraction)
+            {
+                ARMARX_CHECK_NOT_NULL(var);
+
+                auto [memberDataVec, memberDataModeSuffix] = c->convert(var);
+
+                std::string filename = (memberName + memberDataModeSuffix + c->suffix);
+
+                ensureFileExists(filename, true);
+                writeDataToFile(filename, memberDataVec);
+            }
+
+            dataAron = dataExt.dataWithoutExtraction;
+        }
+
+        // convert dict and metadata
+        auto [dataVec, dataVecModeSuffix] = dictConverter.convert(dataAron);
+        auto [metadataVec, metadataVecModeSuffix] = dictConverter.convert(metadataAron);
+        ARMARX_CHECK_EMPTY(dataVecModeSuffix);
+        ARMARX_CHECK_EMPTY(metadataVecModeSuffix);
+
+        auto dataToReturn = nlohmann::json::parse(std::string(dataVec.begin(), dataVec.end()));
+
+        {
+            std::string dataFilename = (DATA_FILENAME + dictConverter.suffix);
+            std::string metadataFilename = (METADATA_FILENAME + dictConverter.suffix);
+            std::filesystem::path dataPath = getFullPath() / dataFilename;
+            std::filesystem::path metadataPath = getFullPath() / metadataFilename;
+
+            writeDataToFile(dataFilename, dataVec);
+            writeDataToFile(metadataFilename, metadataVec);
+        }
+
+        statistics.recordedData++;
+        statistics.recordedMetaData++;
+
+        return dataToReturn;
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.h b/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.h
new file mode 100644
index 0000000000000000000000000000000000000000..d6f0b48a474a8b0b59aadb8f52d4f2a4e6ef0ef1
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/EntityInstance.h
@@ -0,0 +1,33 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "detail/EntityInstanceBase.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+namespace armarx::armem::server::ltm
+{
+
+    class EntityInstance :
+        public detail::EntityInstanceBase,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        EntityInstance(const detail::mixin::Path&,
+                       const detail::mixin::MongoDBSettings&,
+                       const std::string&,
+                       const MemoryID& id,
+                       const std::shared_ptr<Processors>& p);
+
+    protected:
+        void _loadAllReferences(armem::wm::EntitySnapshot&) const override;
+        void _resolve(armem::wm::EntityInstance&) const override;
+        nlohmann::json _store(const armem::wm::EntityInstance&) override;
+
+    private:
+    };
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..693f015a20130142699eb5900eac0824a1728768
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.cpp
@@ -0,0 +1,187 @@
+// Header
+#include "EntitySnapshot.h"
+
+// STD / STL
+#include <fstream>
+#include <iostream>
+
+// ArmarX
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+namespace armarx::armem::server::ltm
+{
+    EntitySnapshot::EntitySnapshot(const detail::mixin::Path& p,
+                                   const detail::mixin::MongoDBSettings& s,
+
+                                   const std::string& exportName,
+                                   const armem::MemoryID& id /* UNESCAPED */,
+                                   const std::shared_ptr<Processors>& filters) :
+        EntitySnapshotBase(exportName, id, filters),
+        DiskMemoryItemMixin(p, exportName, id),
+        MongoDBStorageMixin(s, exportName, id)
+    {
+        //start();
+    }
+
+    bool
+    EntitySnapshot::forEachInstance(std::function<void(EntityInstance&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            if (auto d = documentExists(); d)
+            {
+                nlohmann::json doc = *d;
+                std::vector<nlohmann::json> instances = doc[DATA];
+                for (unsigned int i = 0; i < instances.size(); ++i)
+                {
+                    EntityInstance c(getMemoryBasePath(),
+                                     getSettings(),
+                                     getExportName(),
+                                     id().withInstanceIndex(i),
+                                     processors);
+                    func(c);
+                }
+            }
+        } else */
+
+        if (fullPathExists())
+        {
+            for (const auto& i : getAllDirectories())
+            {
+                if (!util::fs::detail::isNumberString(i.filename()))
+                {
+                    ARMARX_WARNING << "Found a non-index folder inside an entity '" << id().str()
+                                   << "' with name '" << i.filename() << "'. "
+                                   << "Ignoring this folder, however this is a bad situation.";
+                    continue;
+                }
+
+                EntityInstance c(getMemoryBasePath(),
+                                 getSettings(),
+                                 getExportName(),
+                                 id().withInstanceIndex(std::stoi(i.filename())),
+                                 processors);
+                func(c);
+            }
+        }
+        return true;
+    }
+
+    bool
+    EntitySnapshot::hasInstance(const int index) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            if (auto d = documentExists(); d)
+            {
+                nlohmann::json doc = *d;
+                std::vector<nlohmann::json> instances = doc[DATA];
+                return (size_t)index < instances.size();
+            }
+        }*/
+
+        if (fullPathExists())
+        {
+            auto c = EntityInstance(getMemoryBasePath(),
+                                    getSettings(),
+                                    getExportName(),
+                                    id().withInstanceIndex(index),
+                                    processors);
+            return c.fullPathExists();
+        }
+
+        return false;
+    }
+
+    std::shared_ptr<EntityInstance>
+    EntitySnapshot::findInstance(const int index) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (!hasInstance(index))
+        {
+            return nullptr;
+        }
+        return std::make_shared<EntityInstance>(getMemoryBasePath(),
+                                                getSettings(),
+                                                getExportName(),
+                                                id().withInstanceIndex(index),
+                                                processors);
+    }
+
+    void
+    EntitySnapshot::_loadAllReferences(armem::wm::EntitySnapshot& e) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        e.id() = id();
+        forEachInstance([&e](auto& x) { x.loadAllReferences(e); });
+    }
+
+    void
+    EntitySnapshot::_resolve(armem::wm::EntitySnapshot& p) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (/*(connected() && collectionExists() && documentExists()) ||*/ fullPathExists())
+        {
+            p.forEachInstance(
+                [&](auto& e)
+                {
+                    EntityInstance c(getMemoryBasePath(),
+                                     getSettings(),
+                                     getExportName(),
+                                     id().withInstanceIndex(e.id().instanceIndex),
+                                     processors);
+                    c.resolve(e);
+                });
+        }
+    }
+
+    void
+    EntitySnapshot::_store(const armem::wm::EntitySnapshot& p)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (id().timestamp.isInvalid())
+        {
+            ARMARX_WARNING
+                << "During storage of segment '" << p.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            id().timestamp = p.id().timestamp;
+        }
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM ENTITY SNAPSHOT NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return;
+        }*/
+
+        //nlohmann::json data;
+        //data[DATA] = std::vector<nlohmann::json>();
+
+        p.forEachInstance(
+            [&](const auto& e)
+            {
+                EntityInstance c(getMemoryBasePath(),
+                                 getSettings(),
+                                 getExportName(),
+                                 id().withInstanceIndex(e.id().instanceIndex),
+                                 processors);
+                c.store(e);
+
+                //data[DATA].push_back(c.store(e));
+                statistics.recordedInstances++;
+            });
+
+        //writeDataToDocument(data);
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.h b/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.h
new file mode 100644
index 0000000000000000000000000000000000000000..58c7d41bdae3009d60664680859ea902894f0c04
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/EntitySnapshot.h
@@ -0,0 +1,38 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "EntityInstance.h"
+#include "detail/EntitySnapshotBase.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+namespace armarx::armem::server::ltm
+{
+
+    class EntitySnapshot :
+        public detail::EntitySnapshotBase<EntityInstance>,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        EntitySnapshot(const detail::mixin::Path&,
+                       const detail::mixin::MongoDBSettings&,
+                       const std::string&,
+                       const MemoryID& id,
+                       const std::shared_ptr<Processors>& p);
+
+        bool forEachInstance(std::function<void(EntityInstance&)> func) const override;
+        bool hasInstance(const int) const override;
+        std::shared_ptr<EntityInstance> findInstance(const int) const override;
+
+    protected:
+        void _loadAllReferences(armem::wm::EntitySnapshot&) const override;
+        void _resolve(armem::wm::EntitySnapshot&) const override;
+        void _store(const armem::wm::EntitySnapshot&) override;
+
+    private:
+    };
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/Memory.cpp b/source/RobotAPI/libraries/armem/server/ltm/Memory.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..06f81e22c947328998187c84d79a7e8a1c5058c8
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/Memory.cpp
@@ -0,0 +1,251 @@
+#include "Memory.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm
+{
+    void
+    Memory::_configure(const nlohmann::json& json)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        BufferedBase::configureMixin(json);
+        CachedBase::configureMixin(json);
+        DiskMemoryBase::configureMixin(json);
+        MongoDBStorageMixin::configureMixin(json);
+    }
+
+    Memory::Memory() : Memory(std::filesystem::path("/tmp"), {}, "MemoryExport", "Test")
+    {
+    }
+
+    Memory::Memory(const detail::mixin::Path& p,
+
+                   const std::string& exportName,
+                   const std::string& memoryName /* UNESCAPED */) :
+        Memory(p, {}, exportName, memoryName)
+    {
+    }
+
+    Memory::Memory(const detail::mixin::Path& p,
+                   const detail::mixin::MongoDBSettings& s,
+
+                   const std::string& exportName,
+                   const std::string& memoryName /* UNESCAPED */) :
+        MemoryBase(exportName, MemoryID(memoryName, "")),
+        BufferedBase(MemoryID(memoryName, "")),
+        CachedBase(MemoryID(memoryName, "")),
+        DiskMemoryItemMixin(p, exportName, MemoryID(memoryName, "")),
+        MongoDBStorageMixin(s, exportName, MemoryID(memoryName, ""))
+    {
+    }
+
+    void
+    Memory::_setExportName(const std::string& n)
+    {
+        DiskMemoryBase::setMixinExportName(n);
+        MongoDBStorageMixin::setMixinExportName(n);
+    }
+
+    void
+    Memory::_enable()
+    {
+        BufferedBase::start();
+        //MongoDBStorageMixin::start();
+    }
+
+    void
+    Memory::_disable()
+    {
+        BufferedBase::stop();
+        MongoDBStorageMixin::stop();
+    }
+
+    void
+    Memory::_setMemoryID(const MemoryID& id)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        BufferedBase::setMixinMemoryID(id);
+        CachedBase::setMixinMemoryID(id);
+        DiskMemoryBase::setMixinMemoryID(id);
+        MongoDBStorageMixin::setMixinMemoryID(id);
+    }
+
+    bool
+    Memory::forEachCoreSegment(std::function<void(CoreSegment&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        // for each
+        /*if (connected() && collectionExists())
+        {
+            for (const auto& doc : getAllDocuments())
+            {
+                std::string segmentName = doc[FOREIGN_KEY];
+                CoreSegment c(getMemoryBasePath(),
+                              getSettings(),
+                              getExportName(),
+                              id().withCoreSegmentName(segmentName),
+                              processors);
+                func(c);
+            }
+        } else */
+
+        // legacy: check fs
+        if (fullPathExists())
+        {
+            for (const auto& subdirName : getAllDirectories())
+            {
+                std::string segmentName = util::fs::detail::unescapeName(subdirName);
+                CoreSegment c(getMemoryBasePath(),
+                              getSettings(),
+                              getExportName(),
+                              id().withCoreSegmentName(segmentName),
+                              processors);
+                func(c);
+            }
+        }
+
+        return true;
+    }
+
+    bool
+    Memory::hasCoreSegment(const std::string& name) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (cacheHasCoreSegment(name))
+        {
+            return true;
+        }
+
+        // check if collection exists
+        /*if (connected() && collectionExists())
+        {
+            auto c = CoreSegment(getMemoryBasePath(),
+                                 getSettings(),
+                                 getExportName(),
+                                 id().withCoreSegmentName(name),
+                                 processors);
+
+            return (bool)c.collectionExists();
+        }*/
+
+        // legacy: check if segment is stored on hard drive without db
+        if (fullPathExists())
+        {
+            auto c = CoreSegment(getMemoryBasePath(),
+                                 getSettings(),
+                                 getExportName(),
+                                 id().withCoreSegmentName(name),
+                                 processors);
+
+            return c.fullPathExists();
+        }
+
+        return false;
+    }
+
+    std::unique_ptr<CoreSegment>
+    Memory::findCoreSegment(const std::string& coreSegmentName) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (!hasCoreSegment(coreSegmentName))
+        {
+            return nullptr;
+        }
+
+        return std::make_unique<CoreSegment>(getMemoryBasePath(),
+                                             getSettings(),
+                                             getExportName(),
+                                             id().withCoreSegmentName(coreSegmentName),
+                                             processors);
+    }
+
+    void
+    Memory::_loadAllReferences(armem::wm::Memory& m)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        m.id() = id();
+
+        forEachCoreSegment(
+            [&m](auto& x)
+            {
+                armem::wm::CoreSegment s;
+                x.loadAllReferences(s);
+                m.addCoreSegment(s);
+            });
+    }
+
+    void
+    Memory::_resolve(armem::wm::Memory& m)
+    {
+        std::lock_guard l(ltm_mutex); // we cannot load a memory multiple times simultaneously
+
+        if (/*(connected() && collectionExists()) ||*/ fullPathExists())
+        {
+            m.forEachCoreSegment(
+                [&](auto& e)
+                {
+                    CoreSegment c(getMemoryBasePath(),
+                                  getSettings(),
+                                  getExportName(),
+                                  id().withCoreSegmentName(e.id().coreSegmentName),
+                                  processors);
+                    c.resolve(e);
+                });
+        }
+    }
+
+    void
+    Memory::_store(const armem::wm::Memory& m)
+    {
+        BufferedBase::addToBuffer(m);
+    }
+
+    void
+    Memory::_directlyStore(const armem::wm::Memory& memory)
+    {
+        std::lock_guard l(ltm_mutex); // we cannot store a memory multiple times simultaneously
+
+        if (id().memoryName.empty())
+        {
+            ARMARX_WARNING
+                << "During storage of memory '" << memory.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            setMemoryID(memory.id());
+        }
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return;
+        }*/
+
+        memory.forEachCoreSegment(
+            [&](const auto& core)
+            {
+                CoreSegment c(getMemoryBasePath(),
+                              getSettings(),
+                              getExportName(),
+                              id().withCoreSegmentName(core.id().coreSegmentName),
+                              processors);
+
+                // 2. store data
+                c.store(core);
+
+                // 3. update statistics
+                statistics.recordedCoreSegments++;
+            });
+
+        // 4. update cache
+        CachedBase::addToCache(memory);
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/Memory.h b/source/RobotAPI/libraries/armem/server/ltm/Memory.h
new file mode 100644
index 0000000000000000000000000000000000000000..30e1929dd3156dfb0f9d4412ac78e44bb62ce664
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/Memory.h
@@ -0,0 +1,56 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "detail/MemoryBase.h"
+#include "detail/mixins/BufferedMemoryMixin.h"
+#include "detail/mixins/CachedMemoryMixin.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+// Segmnet Type
+#include "CoreSegment.h"
+
+namespace armarx::armem::server::ltm
+{
+    /// @brief A memory storing data on the hard drive and in mongodb (needs 'armarx memory start' to start the mongod instance)
+    class Memory :
+        public detail::MemoryBase<CoreSegment>,
+        public detail::mixin::BufferedMemoryMixin<CoreSegment>,
+        public detail::mixin::CachedMemoryMixin<CoreSegment>,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        using MemoryBase = detail::MemoryBase<CoreSegment>;
+        using BufferedBase = detail::mixin::BufferedMemoryMixin<CoreSegment>;
+        using CachedBase = detail::mixin::CachedMemoryMixin<CoreSegment>;
+        using DiskMemoryBase = detail::mixin::DiskMemoryItemMixin;
+        using MongoDBStorageMixin = detail::mixin::MongoDBStorageMixin;
+
+        Memory();
+        Memory(const detail::mixin::Path&, const std::string&, const std::string&);
+        Memory(const detail::mixin::Path&,
+               const detail::mixin::MongoDBSettings&,
+               const std::string&,
+               const std::string&);
+
+        void _setExportName(const std::string& n) final;
+        void _setMemoryID(const MemoryID& id) final;
+        void _enable() final;
+        void _disable() final;
+        void _configure(const nlohmann::json& config) final;
+
+        bool forEachCoreSegment(std::function<void(CoreSegment&)> func) const final;
+        bool hasCoreSegment(const std::string& name) const final;
+        std::unique_ptr<CoreSegment>
+        findCoreSegment(const std::string& coreSegmentName) const final;
+
+    protected:
+        void _loadAllReferences(armem::wm::Memory&) final;
+        void _resolve(armem::wm::Memory&) final;
+        void _store(const armem::wm::Memory&) final;
+        void _directlyStore(const armem::wm::Memory&) final;
+    };
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0cb941e1fa61aaef583b8d54d3005794039b47ed
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.cpp
@@ -0,0 +1,214 @@
+// Header
+#include "ProviderSegment.h"
+
+// ArmarX
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm
+{
+    ProviderSegment::ProviderSegment(const detail::mixin::Path& p,
+                                     const detail::mixin::MongoDBSettings& s,
+
+                                     const std::string& exportName,
+                                     const armem::MemoryID& id /* UNESCAPED */,
+                                     const std::shared_ptr<Processors>& filters) :
+        ProviderSegmentBase(exportName, id, filters),
+        DiskMemoryItemMixin(p, exportName, id),
+        MongoDBStorageMixin(s, exportName, id)
+    {
+        //start();
+    }
+
+    bool
+    ProviderSegment::forEachEntity(std::function<void(Entity&)> func) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            for (const auto& doc : getAllDocuments())
+            {
+                std::string id_str = doc[FOREIGN_KEY];
+                armem::MemoryID segment_id(id_str);
+                Entity c(
+                    getMemoryBasePath(), getSettings(), getExportName(), segment_id, processors);
+                func(c);
+            }
+        } else */
+
+        if (fullPathExists())
+        {
+
+            for (const auto& subdirName : getAllDirectories())
+            {
+                std::string segmentName = util::fs::detail::unescapeName(subdirName);
+                Entity c(getMemoryBasePath(),
+                         getSettings(),
+                         getExportName(),
+                         id().withEntityName(segmentName),
+                         processors);
+                func(c);
+            }
+        }
+        return true;
+    }
+
+    bool
+    ProviderSegment::hasEntity(const std::string& name) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        /*if (connected() && collectionExists())
+        {
+            auto c = Entity(getMemoryBasePath(),
+                            getSettings(),
+                            getExportName(),
+                            id().withEntityName(name),
+                            processors);
+            return (bool)c.collectionExists();
+        }*/
+
+        if (fullPathExists())
+        {
+            auto c = Entity(getMemoryBasePath(),
+                            getSettings(),
+                            getExportName(),
+                            id().withEntityName(name),
+                            processors);
+            return c.fullPathExists();
+        }
+
+        return false;
+    }
+
+    std::shared_ptr<Entity>
+    ProviderSegment::findEntity(const std::string& entityName) const
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (!hasEntity(entityName))
+        {
+            return nullptr;
+        }
+        return std::make_shared<Entity>(getMemoryBasePath(),
+                                        getSettings(),
+                                        getExportName(),
+                                        id().withEntityName(entityName),
+                                        processors);
+    }
+
+    void
+    ProviderSegment::_loadAllReferences(armem::wm::ProviderSegment& e)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        e.id() = id();
+
+        auto& conv = processors->defaultTypeConverter;
+        auto setType = [&conv, &e](const std::vector<unsigned char>& aronJson)
+        {
+            auto typeAron = conv.convert(aronJson, "");
+            e.aronType() = aron::type::Object::DynamicCastAndCheck(typeAron);
+        };
+
+        /*if (connected() && collectionExists())
+        {
+            // TODO:
+        } else */
+
+        if (std::string filename = TYPE_FILENAME + conv.suffix;
+            fullPathExists() && fileExists(filename))
+        {
+            auto typeFileContent = readDataFromFile(filename);
+            setType(typeFileContent);
+        }
+
+        forEachEntity(
+            [&e](auto& x)
+            {
+                armem::wm::Entity s;
+                x.loadAllReferences(s);
+                e.addEntity(s);
+            });
+    }
+
+    void
+    ProviderSegment::_resolve(armem::wm::ProviderSegment& p)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (/*(connected() && collectionExists()) ||*/ fullPathExists())
+        {
+            p.forEachEntity(
+                [&](auto& e)
+                {
+                    Entity c(getMemoryBasePath(),
+                             getSettings(),
+                             getExportName(),
+                             id().withEntityName(e.id().entityName),
+                             processors);
+                    c.resolve(e);
+                });
+        }
+    }
+
+    void
+    ProviderSegment::_store(const armem::wm::ProviderSegment& p)
+    {
+        std::lock_guard l(ltm_mutex);
+
+        if (id().providerSegmentName.empty())
+        {
+            ARMARX_WARNING
+                << "During storage of segment '" << p.id().str()
+                << "' I noticed that the corresponding LTM has no id set. "
+                << "I set the id of the LTM to the same name, however this should not happen!";
+            id().providerSegmentName = p.id().providerSegmentName;
+        }
+
+        /*if (!connected())
+        {
+            ARMARX_WARNING << "LTM PROVIDER SEGMENT NOT CONNECTED ALTHOUGH ENABLED " << id().str();
+            return;
+        }*/
+
+        // add foreign key to memory collection
+        if (p.hasAronType())
+        {
+            auto& conv = processors->defaultTypeConverter;
+
+            auto [vec, modeSuffix] = conv.convert(p.aronType());
+            ARMARX_CHECK_EMPTY(modeSuffix);
+
+            //std::string dataStr{vec.begin(), vec.end()};
+            //auto dataJson = nlohmann::json::parse(dataStr);
+
+            //writeForeignKeyToPreviousDocument(dataJson);
+
+            ensureFullPathExists(true);
+            std::string filename = (TYPE_FILENAME + conv.suffix);
+            writeDataToFile(filename, vec);
+        }
+        else
+        {
+            //writeForeignKeyToPreviousDocument();
+        }
+
+        p.forEachEntity(
+            [&](const auto& e)
+            {
+                Entity c(getMemoryBasePath(),
+                         getSettings(),
+                         getExportName(),
+                         id().withEntityName(e.id().entityName),
+                         processors);
+
+                c.store(e);
+                statistics.recordedEntities++;
+            });
+    }
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.h b/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.h
new file mode 100644
index 0000000000000000000000000000000000000000..5f880676c43f483c6ae66a65c41a7a17bf93aa70
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/ProviderSegment.h
@@ -0,0 +1,37 @@
+#pragma once
+
+#include <filesystem>
+
+// Base Class
+#include "Entity.h"
+#include "detail/ProviderSegmentBase.h"
+#include "detail/mixins/DiskStorageMixin.h"
+#include "detail/mixins/MongoDBStorageMixin.h"
+
+namespace armarx::armem::server::ltm
+{
+    class ProviderSegment :
+        public detail::ProviderSegmentBase<Entity>,
+        public detail::mixin::DiskMemoryItemMixin,
+        public detail::mixin::MongoDBStorageMixin
+    {
+    public:
+        ProviderSegment(const detail::mixin::Path&,
+                        const detail::mixin::MongoDBSettings&,
+                        const std::string&,
+                        const MemoryID& id,
+                        const std::shared_ptr<Processors>&);
+
+        bool forEachEntity(std::function<void(Entity&)> func) const override;
+        bool hasEntity(const std::string&) const override;
+        std::shared_ptr<Entity> findEntity(const std::string&) const override;
+
+    protected:
+        void _loadAllReferences(armem::wm::ProviderSegment&) override;
+        void _resolve(armem::wm::ProviderSegment&) override;
+        void _store(const armem::wm::ProviderSegment&) override;
+
+    private:
+    };
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.cpp
deleted file mode 100644
index fd719807eb069bcf62db065ed42bb649c38d225d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "Converter.h"
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.h
deleted file mode 100644
index 0ed3d9b08188179d17e5baaf0087b0c33e75eaa0..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/Converter.h
+++ /dev/null
@@ -1,38 +0,0 @@
-#pragma once
-
-// STD/STL
-#include <memory>
-
-// ArmarX
-#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
-
-namespace armarx::armem::server::ltm
-{
-    class Converter
-    {
-    public:
-        enum class ConverterType
-        {
-            Str,
-            Binary
-        };
-
-        Converter(const ConverterType t, const std::string& id, const std::string& s, const aron::type::Descriptor c):
-            type(t),
-            identifier(id),
-            suffix(s),
-            convertsType(c)
-        {}
-        virtual ~Converter() = default;
-
-        virtual std::pair<std::vector<unsigned char>, std::string> convert(const aron::data::VariantPtr& data) = 0;
-        virtual aron::data::VariantPtr convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) = 0;
-
-    public:
-        const ConverterType type;
-        const std::string identifier;
-        const std::string suffix;
-        const aron::type::Descriptor convertsType;
-        bool enabled = false;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.cpp
deleted file mode 100644
index 30349fd4faa55ab513d6c080251138cb16bafe77..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-#include "Converter.h"
-
-namespace armarx::armem::server::ltm
-{
-
-    std::pair<std::vector<unsigned char>, std::string> ImageConverter::convert(const aron::data::VariantPtr& data)
-    {
-        auto d = aron::data::NDArray::DynamicCastAndCheck(data);
-        return _convert(d);
-    }
-
-    aron::data::VariantPtr ImageConverter::convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string& m)
-    {
-        auto d = _convert(data, p, m);
-        return d;
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.h
deleted file mode 100644
index 440c1c6c50815eb56576fca2cd1bb65d1185f0ec..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/Converter.h
+++ /dev/null
@@ -1,30 +0,0 @@
-#pragma once
-
-// STD/STL
-#include <memory>
-
-// BaseClass
-#include "../Converter.h"
-
-// ArmarX
-#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
-
-namespace armarx::armem::server::ltm
-{
-    class ImageConverter : public Converter
-    {
-    public:
-        ImageConverter(const ConverterType t, const std::string& id, const std::string& s):
-            Converter(t, id, s, aron::type::Descriptor::IMAGE)
-        {}
-
-        virtual ~ImageConverter() = default;
-
-        std::pair<std::vector<unsigned char>, std::string> convert(const aron::data::VariantPtr& data) final;
-        aron::data::VariantPtr convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-
-    protected:
-        virtual std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::NDArrayPtr& data) = 0;
-        virtual aron::data::NDArrayPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) = 0;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.cpp
deleted file mode 100644
index 6bf18cff45eea27f018c9dc7c371becbb5baf90a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.cpp
+++ /dev/null
@@ -1,33 +0,0 @@
-#include "ExrConverter.h"
-
-// ArmarX
-#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
-
-#include <opencv2/opencv.hpp>
-#include <opencv2/imgcodecs.hpp>
-#include <opencv2/imgproc.hpp>
-
-
-namespace armarx::armem::server::ltm::converter::image
-{
-    std::pair<std::vector<unsigned char>, std::string> ExrConverter::_convert(const aron::data::NDArrayPtr& data)
-    {
-        ARMARX_CHECK_NOT_NULL(data);
-
-        auto img = aron::converter::AronOpenCVConverter::ConvertToMat(data);
-        std::vector<unsigned char> buffer;
-
-        auto shape = data->getShape(); // we know from the extraction that the shape has 3 elements
-        ARMARX_CHECK_EQUAL(shape.size(), 3);
-        ARMARX_CHECK_EQUAL(shape[2], 4);
-
-        cv::imencode(".exr", img, buffer);
-        return std::make_pair(buffer, "");
-    }
-
-    aron::data::NDArrayPtr ExrConverter::_convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string& m)
-    {
-        cv::Mat img = cv::imdecode(data, cv::IMREAD_ANYDEPTH);
-        return aron::converter::AronOpenCVConverter::ConvertFromMat(img, p);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.h
deleted file mode 100644
index 07e94a5b2c8ef2951949854600e25f4a901d6478..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.h
+++ /dev/null
@@ -1,21 +0,0 @@
-#pragma once
-
-// Base Class
-#include "../Converter.h"
-
-namespace armarx::armem::server::ltm::converter::image
-{
-    class ExrConverter : public ImageConverter
-    {
-    public:
-        ExrConverter() :
-            ImageConverter(ConverterType::Binary, "depthimage", ".exr")
-        {
-            enabled = true; // enabled by default
-        }
-
-    protected:
-        std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::NDArrayPtr& data) final;
-        aron::data::NDArrayPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.cpp
deleted file mode 100644
index 03453e6f6c4432e1efd0445ae393d1d14242a4bd..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.cpp
+++ /dev/null
@@ -1,61 +0,0 @@
-#include "PngConverter.h"
-
-// ArmarX
-#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
-
-#include <opencv2/opencv.hpp>
-#include <opencv2/imgcodecs.hpp>
-#include <opencv2/imgproc.hpp>
-
-
-namespace armarx::armem::server::ltm::converter::image
-{
-    std::pair<std::vector<unsigned char>, std::string> PngConverter::_convert(const aron::data::NDArrayPtr& data)
-    {
-        ARMARX_CHECK_NOT_NULL(data);
-
-        auto img = aron::converter::AronOpenCVConverter::ConvertToMat(data);
-        std::vector<unsigned char> buffer;
-
-
-        auto shape = data->getShape(); // we know from the extraction that the shape has 3 elements
-        ARMARX_CHECK_EQUAL(shape.size(), 3);
-
-        if (shape[2] == 3) // its probably a rgb image
-        {
-            cv::cvtColor(img, img, CV_RGB2BGR);
-            cv::imencode(suffix, img, buffer);
-            return std::make_pair(buffer, ".rgb");
-        }
-
-        if (shape[2] == 1) // its probably a grayscale image
-        {
-            cv::imencode(suffix, img, buffer);
-            return std::make_pair(buffer, ".gs");
-        }
-
-        // try to export without conversion
-        cv::imencode(suffix, img, buffer);
-        return std::make_pair(buffer, "");
-    }
-
-    aron::data::NDArrayPtr PngConverter::_convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string& m)
-    {
-        if (m == ".rgb")
-        {
-            cv::Mat img = cv::imdecode(data, cv::IMREAD_COLOR);
-            cv::cvtColor(img, img, CV_BGR2RGB);
-            return aron::converter::AronOpenCVConverter::ConvertFromMat(img, p);
-        }
-
-        if (m == ".gs")
-        {
-            cv::Mat img = cv::imdecode(data, cv::IMREAD_GRAYSCALE);
-            return aron::converter::AronOpenCVConverter::ConvertFromMat(img, p);
-        }
-
-        // try to load without conversion
-        cv::Mat img = cv::imdecode(data, cv::IMREAD_ANYCOLOR);
-        return aron::converter::AronOpenCVConverter::ConvertFromMat(img, p);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.h
deleted file mode 100644
index 0c443fa794d22a6a7a6f5c837565693f8cf2e28c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/png/PngConverter.h
+++ /dev/null
@@ -1,21 +0,0 @@
-#pragma once
-
-// Base Class
-#include "../Converter.h"
-
-namespace armarx::armem::server::ltm::converter::image
-{
-    class PngConverter : public ImageConverter
-    {
-    public:
-        PngConverter() :
-            ImageConverter(ConverterType::Binary, "image", ".png")
-        {
-            enabled = true; // enabled by default
-        }
-
-    protected:
-        std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::NDArrayPtr& data) final;
-        aron::data::NDArrayPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.cpp
deleted file mode 100644
index e6c3345028e9c3af35636d0f509412c4e8ca925a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.cpp
+++ /dev/null
@@ -1,18 +0,0 @@
-#include "Converter.h"
-
-namespace armarx::armem::server::ltm
-{
-
-    std::pair<std::vector<unsigned char>, std::string> ObjectConverter::convert(const aron::data::VariantPtr& data)
-    {
-        auto d = aron::data::Dict::DynamicCastAndCheck(data);
-        return _convert(d);
-    }
-
-    aron::data::VariantPtr ObjectConverter::convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string& m)
-    {
-        auto d = _convert(data, p, m);
-        return d;
-    }
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.h
deleted file mode 100644
index 113dd7a5b726f9b75efa07875f0a07fa443fc3a1..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/Converter.h
+++ /dev/null
@@ -1,30 +0,0 @@
-#pragma once
-
-// STD/STL
-#include <memory>
-
-// BaseClass
-#include "../Converter.h"
-
-// ArmarX
-#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
-
-namespace armarx::armem::server::ltm
-{
-    class ObjectConverter : public Converter
-    {
-    public:
-        ObjectConverter(const ConverterType t, const std::string& id, const std::string& s):
-            Converter(t, id, s, aron::type::Descriptor::OBJECT)
-        {}
-
-        virtual ~ObjectConverter() = default;
-
-        std::pair<std::vector<unsigned char>, std::string> convert(const aron::data::VariantPtr& data) final;
-        aron::data::VariantPtr convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-
-    protected:
-        virtual std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::DictPtr& data) = 0;
-        virtual aron::data::DictPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) = 0;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.h
deleted file mode 100644
index fddf6870f2bbcbc6580e1eb8bf8907e40416e3a0..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.h
+++ /dev/null
@@ -1,28 +0,0 @@
-#pragma once
-
-// Base Class
-#include "../Converter.h"
-
-// ArmarX
-#include "../json/JsonConverter.h"
-
-namespace armarx::armem::server::ltm::converter::object
-{
-    class BsonConverter;
-    using BsonConverterPtr = std::shared_ptr<BsonConverter>;
-
-    class BsonConverter : public ObjectConverter
-    {
-    public:
-        BsonConverter() :
-            ObjectConverter(ConverterType::Binary, "dict", ".bson")
-        {}
-
-    protected:
-        std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::DictPtr& data) final;
-        aron::data::DictPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-
-    private:
-        JsonConverter jsonConverter;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.cpp
deleted file mode 100644
index c24125140309ee7c3c597fbd2a57eba5fff4caaa..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.cpp
+++ /dev/null
@@ -1,21 +0,0 @@
-#include "JsonConverter.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
-
-namespace armarx::armem::server::ltm::converter::object
-{
-    std::pair<std::vector<unsigned char>, std::string> JsonConverter::_convert(const aron::data::DictPtr& data)
-    {
-        nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
-        auto str = j.dump(2);
-        return std::make_pair(std::vector<unsigned char>(str.begin(), str.end()), "");
-    }
-
-    aron::data::DictPtr JsonConverter::_convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&)
-    {
-        std::string str(data.begin(), data.end());
-        nlohmann::json j = nlohmann::json::parse(str);
-        return aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(j, p);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.h
deleted file mode 100644
index 0c6d71d119396ff7e0293ea5196c252c9ba3cc7c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/json/JsonConverter.h
+++ /dev/null
@@ -1,24 +0,0 @@
-#pragma once
-
-// Base Class
-#include "../Converter.h"
-
-// Simox
-#include <SimoxUtility/json.h>
-
-namespace armarx::armem::server::ltm::converter::object
-{
-    class JsonConverter : public ObjectConverter
-    {
-    public:
-        JsonConverter() :
-            ObjectConverter(ConverterType::Str, "dict", ".json")
-        {
-            enabled = true; // always true!
-        }
-
-    protected:
-        std::pair<std::vector<unsigned char>, std::string> _convert(const aron::data::DictPtr& data) final;
-        aron::data::DictPtr _convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string&) final;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.cpp
deleted file mode 100644
index 864266ce87d1e01a2f8eea0e0133a67ed14e7528..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.cpp
+++ /dev/null
@@ -1,7 +0,0 @@
-#include "BufferedMemoryBase.h"
-
-namespace armarx::armem::server::ltm
-{
-
-
-} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.cpp
deleted file mode 100644
index 1078e776d6ef68d2f7e102bff78676bb28d9b351..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.cpp
+++ /dev/null
@@ -1,6 +0,0 @@
-#include "LUTMemoryBase.h"
-
-namespace armarx::armem::server::ltm
-{
-
-} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.h b/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.h
deleted file mode 100644
index be92704ab2c2e3a8c14d380bfa1b62f4826f34fb..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/LUTMemoryBase.h
+++ /dev/null
@@ -1,48 +0,0 @@
-#pragma once
-
-#include "MemoryBase.h"
-
-namespace armarx::armem::server::ltm
-{
-    /*// TODO refactor to mixin (see buffered)
-    template <class _CoreSegmentT>
-    class CachedMemoryBase : virtual public MemoryBase<_CoreSegmentT>
-    {
-    public:
-        using MemoryBase<_CoreSegmentT>::MemoryBase;
-
-        armem::wm::Memory getCache() const
-        {
-            std::lock_guard l(this->ltm_mutex);
-            return cache;
-        }
-
-        void setMemoryID(const MemoryID& id) override
-        {
-            MemoryBase<_CoreSegmentT>::setMemoryID(id);
-            cache.name() = this->name();
-        }
-
-    protected:
-        static bool EntitySnapshotHasData(const armem::wm::EntitySnapshot& e)
-        {
-            // check whether all data is nullptr
-            bool allDataIsNull = e.size() > 0;
-            e.forEachInstance([&allDataIsNull](armem::wm::EntityInstance & e)
-            {
-                if (e.data())
-                {
-                    allDataIsNull = false;
-                    return false; // means break
-                }
-                return true;
-            });
-            return !allDataIsNull;
-        }
-
-    protected:
-
-        armem::wm::Memory cache;
-
-    };*/
-} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.cpp
deleted file mode 100644
index d5318e1f1e6ec9933ddc7e6b50f3894044111917..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.cpp
+++ /dev/null
@@ -1,41 +0,0 @@
-#include "MemoryItem.h"
-
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/time/TimeUtil.h>
-
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-
-namespace armarx::armem::server::ltm
-{
-    MemoryItem::MemoryItem(const MemoryID& id) :
-        processors(std::make_shared<Processors>()),
-        _id(id)
-    {
-    }
-
-    MemoryItem::MemoryItem(const MemoryID& id, const std::shared_ptr<Processors>& p) :
-        processors(p),
-        _id(id)
-    {
-    }
-
-    void MemoryItem::setMemoryID(const MemoryID& id)
-    {
-        _id = id;
-    }
-
-    MemoryID MemoryItem::id() const
-    {
-        return _id;
-    }
-
-    std::string MemoryItem::name() const
-    {
-        return _id.getLeafItem();
-    }
-
-    void MemoryItem::setMemoryName(const std::string& memoryName)
-    {
-        _id.memoryName = memoryName;
-    }
-} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.h b/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.h
deleted file mode 100644
index b8d17fe471c17e62aa188406648515e5a32f384a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryItem.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include <map>
-#include <mutex>
-#include <optional>
-#include <string>
-
-#include "Processors.h"
-
-namespace armarx::armem::server::ltm
-{
-    /// @brief Interface functions for the longterm memory classes
-    class MemoryItem
-    {
-    public:
-        MemoryItem(const MemoryID&); // only used by memory
-        MemoryItem(const MemoryID&, const std::shared_ptr<Processors>&); // used by all other segments
-        virtual ~MemoryItem() = default;
-
-        MemoryID id() const;
-        std::string name() const;
-
-        virtual void setMemoryID(const MemoryID&);
-        void setMemoryName(const std::string& memoryName);
-
-    protected:
-        std::shared_ptr<Processors> processors;
-
-    private:
-        MemoryID _id;
-    };
-} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.cpp
deleted file mode 100644
index 33934e1af67f1b1b11c72c54fdc43335a115fe42..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.cpp
+++ /dev/null
@@ -1,21 +0,0 @@
-#include "Processors.h"
-
-namespace armarx::armem::server::ltm
-{
-    Processors::Processors()
-    {
-        // setup containers
-        memFilters.push_back(&memFreqFilter);
-        snapFilters.push_back(&snapFreqFilter);
-        snapFilters.push_back(&snapEqFilter);
-        extractors.push_back(&imageExtractor);
-        extractors.push_back(&depthImageExtractor);
-        converters.insert({pngConverter.identifier, &pngConverter});
-        converters.insert({exrConverter.identifier, &exrConverter});
-    }
-
-    void Processors::configure(const nlohmann::json& config)
-    {
-
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.h b/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.h
deleted file mode 100644
index 43677cb9bb019fb61610ff977b0e57b2ce9b238a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/Processors.h
+++ /dev/null
@@ -1,54 +0,0 @@
-#pragma once
-
-#include <map>
-#include <mutex>
-#include <optional>
-#include <string>
-
-#include <ArmarXCore/core/application/properties/Properties.h>
-
-#include "../filter/frequencyFilter/FrequencyFilter.h"
-#include "../filter/equalityFilter/EqualityFilter.h"
-#include "../extractor/imageExtractor/ImageExtractor.h"
-#include "../extractor/imageExtractor/DepthImageExtractor.h"
-#include "../converter/object/json/JsonConverter.h"
-#include "../converter/image/png/PngConverter.h"
-#include "../converter/image/exr/ExrConverter.h"
-#include "../typeConverter/json/JsonConverter.h"
-
-#include <RobotAPI/libraries/armem/core/MemoryID.h>
-
-namespace armarx::armem::server::ltm
-{
-    /// all necessary classes to filter and convert an entry of the ltm to some other format(s)
-    class Processors
-    {
-    public:
-        Processors();
-        void configure(const nlohmann::json& config);
-
-    public:
-        // Unique Memory Filters
-        std::vector<MemoryFilter*> memFilters;
-        filter::MemoryFrequencyFilter memFreqFilter;
-
-        // Unique Snapshot filters
-        std::vector<SnapshotFilter*> snapFilters;
-        filter::SnapshotFrequencyFilter snapFreqFilter;
-        filter::SnapshotEqualityFilter snapEqFilter;
-
-        // Special Extractors
-        std::vector<Extractor*> extractors;
-        extractor::ImageExtractor imageExtractor;
-        extractor::DepthImageExtractor depthImageExtractor;
-
-        // Special Converters
-        std::map<std::string, Converter*> converters;
-        converter::image::PngConverter pngConverter;
-        converter::image::ExrConverter exrConverter;
-
-        // Default converter
-        converter::object::JsonConverter defaultObjectConverter;
-        converter::type::JsonConverter defaultTypeConverter;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.cpp
deleted file mode 100644
index 57443153937c94fc7f218ec2ce427d7c5f45a7b5..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "Extractor.h"
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.cpp
deleted file mode 100644
index 088af9712ebf2e93637acfa5ec982e05e9cfd66e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.cpp
+++ /dev/null
@@ -1,2 +0,0 @@
-#include "Filter.h"
-
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.cpp
deleted file mode 100644
index 6ca0a944c2f2bd59681128ac22f86eaa58e50b51..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.cpp
+++ /dev/null
@@ -1,52 +0,0 @@
-#include "EqualityFilter.h"
-
-#include <IceUtil/Time.h>
-
-namespace armarx::armem::server::ltm::filter
-{
-    bool SnapshotEqualityFilter::accept(const armem::wm::EntitySnapshot& e)
-    {
-        auto entityID = e.id().getEntityID();
-        auto genMs = e.time().toMilliSecondsSinceEpoch();
-
-        long lastMs = 0;
-        std::vector<aron::data::DictPtr> lastData;
-        if (timestampLastCommitInMs.count(entityID) > 0)
-        {
-            lastData = dataLastCommit.at(entityID);
-            lastMs = timestampLastCommitInMs.at(entityID);
-        }
-
-        auto timePassedSinceLastStored = genMs - lastMs;
-        if (maxWaitingTimeInMs < 0 || timePassedSinceLastStored > maxWaitingTimeInMs)
-        {
-            bool accept = false;
-            std::vector<aron::data::DictPtr> genData;
-            for (unsigned int i = 0; i != e.size(); ++i)
-            {
-                const auto& d = e.getInstance(i).data();
-                genData.push_back(d);
-
-                if (lastMs == 0 || e.size() != lastData.size()) // nothing stored yet or we cannot compare
-                {
-                    accept = true;
-                    break;
-                }
-
-                const auto& el = lastData.at(i);
-                if ((!d and el) || (d and !el) || (d && el && !(*d == *el))) // data unequal?
-                {
-                    accept = true;
-                    break;
-                }
-            }
-
-            if (!accept) return false;
-
-            dataLastCommit[entityID] = genData;
-            timestampLastCommitInMs[entityID] = genMs;
-            return true;
-        }
-        return false;
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.h b/source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.h
deleted file mode 100644
index f8427b2b70e41cd603702cb60b5664ddef3126da..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.h
+++ /dev/null
@@ -1,39 +0,0 @@
-#pragma once
-
-#include <map>
-
-// Base Class
-#include "../Filter.h"
-
-namespace armarx::armem::server::ltm::filter
-{
-    class MemoryFrequencyFilter :
-            public MemoryFilter
-    {
-    public:
-        MemoryFrequencyFilter() = default;
-
-        virtual bool accept(const armem::wm::Memory& e) override;
-
-    public:
-        int waitingTimeInMs = -1;
-
-    private:
-        long timestampLastCommitInMs = 0;
-    };
-
-    class SnapshotFrequencyFilter :
-            public SnapshotFilter
-    {
-    public:
-        SnapshotFrequencyFilter() = default;
-
-        virtual bool accept(const armem::wm::EntitySnapshot& e) override;
-
-    public:
-        int waitingTimeInMs = -1;
-
-    private:
-        std::map<MemoryID, long> timestampLastCommitInMs;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.cpp
deleted file mode 100644
index c846adcbd45ddb152a4525207a9bbde30bd897af..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.cpp
+++ /dev/null
@@ -1,6 +0,0 @@
-#include "Converter.h"
-
-namespace armarx::armem::server::ltm
-{
-
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.h
deleted file mode 100644
index 8290e17c03f3e32e4d7b417b2269699869a85a0a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/Converter.h
+++ /dev/null
@@ -1,28 +0,0 @@
-#pragma once
-
-// STD/STL
-#include <memory>
-
-// ArmarX
-#include <RobotAPI/libraries/aron/core/type/variant/container/Object.h>
-
-namespace armarx::armem::server::ltm
-{
-    class TypeConverter
-    {
-    public:
-        TypeConverter(const std::string& id, const std::string& s):
-            identifier(id),
-            suffix(s)
-        {}
-        virtual ~TypeConverter() = default;
-
-        virtual std::pair<std::vector<unsigned char>, std::string> convert(const aron::type::ObjectPtr& data) = 0;
-        virtual aron::type::ObjectPtr convert(const std::vector<unsigned char>& data, const std::string&) = 0;
-
-    public:
-        const std::string identifier;
-        const std::string suffix;
-        bool enabled = false;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.cpp
deleted file mode 100644
index cc558297e32f82b6db21a2649f283292a0a11518..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.cpp
+++ /dev/null
@@ -1,20 +0,0 @@
-#include "JsonConverter.h"
-
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
-
-namespace armarx::armem::server::ltm::converter::type
-{
-    std::pair<std::vector<unsigned char>, std::string> JsonConverter::convert(const aron::type::ObjectPtr& data)
-    {
-        nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
-        auto str = j.dump(2);
-        return std::make_pair(std::vector<unsigned char>(str.begin(), str.end()), "");
-    }
-
-    aron::type::ObjectPtr JsonConverter::convert(const std::vector<unsigned char>& data, const std::string&)
-    {
-        std::string str(data.begin(), data.end());
-        nlohmann::json j = nlohmann::json::parse(str);
-        return aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONTypeObject(j);
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.h
deleted file mode 100644
index 1f95674b5398d910468b1335617efdb3591a9f7c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.h
+++ /dev/null
@@ -1,23 +0,0 @@
-#pragma once
-
-// Base Class
-#include "../Converter.h"
-
-// Simox
-#include <SimoxUtility/json.h>
-
-namespace armarx::armem::server::ltm::converter::type
-{
-    class JsonConverter : public TypeConverter
-    {
-    public:
-        JsonConverter() :
-            TypeConverter("dict", ".json")
-        {
-            enabled = true; // always true!
-        }
-
-        std::pair<std::vector<unsigned char>, std::string> convert(const aron::type::ObjectPtr& data) final;
-        aron::type::ObjectPtr convert(const std::vector<unsigned char>& data, const std::string&) final;
-    };
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.cpp
similarity index 62%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.cpp
index cdeac54146741ac16c611098a57166b7316bb5e6..bb0860e4228ac731fb03e67f9b05befcab0c5059 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.cpp
@@ -1,6 +1,6 @@
 #include "CoreSegmentBase.h"
 
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::detail
 {
 
 } // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.h
similarity index 75%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.h
index ebe21f4c1c35a03ab8a0b5219d26e57417c4533a..e5a425016e06ff19c46ef7d768cf4e18b8dc8a02 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/CoreSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/CoreSegmentBase.h
@@ -3,15 +3,14 @@
 #include <functional>
 
 // BaseClass
-#include "MemoryItem.h"
-
-#include "ProviderSegmentBase.h"
-
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+#include "MemoryItem.h"
+#include "ProviderSegmentBase.h"
+
+namespace armarx::armem::server::ltm::detail
 {
     /// @brief Interface functions for the longterm memory classes
     template <class _ProviderSegmentT>
@@ -21,7 +20,6 @@ namespace armarx::armem::server::ltm
         struct Statistics
         {
             long recordedProviderSegments = 0;
-
         };
 
     public:
@@ -31,35 +29,35 @@ namespace armarx::armem::server::ltm
 
         /// return the full sub-ltm as a wm::CoreSegment with only references
         /// the ltm may be huge, use with caution
-        void loadAllReferences(armem::wm::CoreSegment& coreSeg)
+        void
+        loadAllReferences(armem::wm::CoreSegment& coreSeg)
         {
             _loadAllReferences(coreSeg);
         }
 
         /// convert the references of the input into a wm::Memory
-        void resolve(armem::wm::CoreSegment& coreSeg)
+        void
+        resolve(armem::wm::CoreSegment& coreSeg)
         {
             _resolve(coreSeg);
         }
 
         /// encode the content of a wm::Memory and store
-        void store(const armem::wm::CoreSegment& coreSeg)
+        void
+        store(const armem::wm::CoreSegment& coreSeg)
         {
             _store(coreSeg);
         }
 
-        /// store the type of the core segment
-        void storeType(const armem::wm::CoreSegment& coreSeg)
-        {
-            _storeType(coreSeg);
-        }
-
         /// statistics
-        void resetStatistics()
+        void
+        resetStatistics()
         {
             statistics.recordedProviderSegments = 0;
         }
-        Statistics getStatistics() const
+
+        Statistics
+        getStatistics() const
         {
             return statistics;
         }
@@ -67,17 +65,22 @@ namespace armarx::armem::server::ltm
         /// iterate over all provider segments of this ltm
         virtual bool forEachProviderSegment(std::function<void(ProviderSegmentT&)> func) const = 0;
 
+        /// check if provider segment exists
+        virtual bool hasProviderSegment(const std::string&) const = 0;
+
         /// find provider segment
         virtual std::shared_ptr<ProviderSegmentT> findProviderSegment(const std::string&) const = 0;
 
         /// get aron type
-        aron::type::ObjectPtr aronType() const
+        aron::type::ObjectPtr
+        aronType() const
         {
             return nullptr;
         }
 
         /// get level name
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "LT-CoreSegment";
         }
@@ -86,11 +89,10 @@ namespace armarx::armem::server::ltm
         virtual void _loadAllReferences(armem::wm::CoreSegment&) = 0;
         virtual void _resolve(armem::wm::CoreSegment&) = 0;
         virtual void _store(const armem::wm::CoreSegment&) = 0;
-        virtual void _storeType(const armem::wm::CoreSegment&) = 0;
 
     protected:
         mutable std::recursive_mutex ltm_mutex;
 
         Statistics statistics;
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.cpp
similarity index 83%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.cpp
index a0f93fc4711a3dec9e1a2be658ab749134aa0013..8b2d05c28d61ede50f8bbe9643d4fc3d05c56be1 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.cpp
@@ -5,6 +5,6 @@
 
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::detail
 {
 } // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.h
similarity index 55%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.h
index 15ebde328ec72b9f189f542087fd7753c2a3faf0..ab61c63e0b82cfa6fba6cbb16d76331ff0027d73 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntityBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityBase.h
@@ -3,15 +3,14 @@
 #include <functional>
 
 // BaseClass
-#include "MemoryItem.h"
-
-#include "EntitySnapshotBase.h"
-
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+#include "EntitySnapshotBase.h"
+#include "MemoryItem.h"
+
+namespace armarx::armem::server::ltm::detail
 {
     /// @brief Interface functions for the longterm memory classes
     template <class _EntitySnapshotT>
@@ -21,7 +20,6 @@ namespace armarx::armem::server::ltm
         struct Statistics
         {
             long recordedSnapshots = 0;
-
         };
 
     public:
@@ -31,49 +29,71 @@ namespace armarx::armem::server::ltm
 
         /// return the full sub-ltm as a wm::Entity with only references
         /// the ltm may be huge, use with caution
-        void loadAllReferences(armem::wm::Entity& e)
+        void
+        loadAllReferences(armem::wm::Entity& e)
         {
             _loadAllReferences(e);
         }
 
         /// convert the references of the input into a wm::Memory
-        void resolve(armem::wm::Entity& e)
+        void
+        resolve(armem::wm::Entity& e)
         {
             _resolve(e);
         }
 
         /// encode the content of a wm::Memory and store
-        void store(const armem::wm::Entity& e)
+        void
+        store(const armem::wm::Entity& e)
         {
             _store(e);
         }
 
         /// statistics
-        void resetStatistics()
+        void
+        resetStatistics()
         {
             statistics.recordedSnapshots = 0;
         }
-        Statistics getStatistics() const
+
+        Statistics
+        getStatistics() const
         {
             return statistics;
         }
 
         /// iterate over all entity snapshots of this ltm
         virtual bool forEachSnapshot(std::function<void(EntitySnapshotT&)> func) const = 0;
-        virtual bool forEachSnapshotInIndexRange(long first, long last, std::function<void(EntitySnapshotT&)> func) const = 0;
-        virtual bool forEachSnapshotInTimeRange(const Time& min, const Time& max, std::function<void(EntitySnapshotT&)> func) const = 0;
-        virtual bool forEachSnapshotBeforeOrAt(const Time& time, std::function<void(EntitySnapshotT&)> func) const = 0;
-        virtual bool forEachSnapshotBefore(const Time& time, std::function<void(EntitySnapshotT&)> func) const = 0;
+        virtual bool
+        forEachSnapshotInIndexRange(long first,
+                                    long last,
+                                    std::function<void(EntitySnapshotT&)> func) const = 0;
+        virtual bool
+        forEachSnapshotInTimeRange(const Time& min,
+                                   const Time& max,
+                                   std::function<void(EntitySnapshotT&)> func) const = 0;
+        virtual bool
+        forEachSnapshotBeforeOrAt(const Time& time,
+                                  std::function<void(EntitySnapshotT&)> func) const = 0;
+        virtual bool forEachSnapshotBefore(const Time& time,
+                                           std::function<void(EntitySnapshotT&)> func) const = 0;
+
+        /// check if snapshot segment exists
+        virtual bool hasSnapshot(const Time&) const = 0;
 
         /// find entity snapshot segment
         virtual std::shared_ptr<EntitySnapshotT> findSnapshot(const Time&) const = 0;
         virtual std::shared_ptr<EntitySnapshotT> findLatestSnapshot() const = 0;
-        virtual std::shared_ptr<EntitySnapshotT> findLatestSnapshotBefore(const Time& time) const = 0;
-        virtual std::shared_ptr<EntitySnapshotT> findLatestSnapshotBeforeOrAt(const Time& time) const = 0;
+        virtual std::shared_ptr<EntitySnapshotT>
+        findLatestSnapshotBefore(const Time& time) const = 0;
+        virtual std::shared_ptr<EntitySnapshotT>
+        findLatestSnapshotBeforeOrAt(const Time& time) const = 0;
         virtual std::shared_ptr<EntitySnapshotT> findFirstSnapshotAfter(const Time& time) const = 0;
-        virtual std::shared_ptr<EntitySnapshotT> findFirstSnapshotAfterOrAt(const Time& time) const = 0;
+        virtual std::shared_ptr<EntitySnapshotT>
+        findFirstSnapshotAfterOrAt(const Time& time) const = 0;
 
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "LT-Entity";
         }
@@ -88,4 +108,4 @@ namespace armarx::armem::server::ltm
 
         Statistics statistics;
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..7b3c23fddbf72565312d291da8e3c179b2293d57
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.cpp
@@ -0,0 +1,15 @@
+#include "EntityInstanceBase.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm::detail
+{
+    std::string
+    EntityInstanceBase::getLevelName()
+    {
+        return "LT-EntityInstance";
+    }
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.h
new file mode 100644
index 0000000000000000000000000000000000000000..4568f1827e924b0be22296fec71bce303096a069
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntityInstanceBase.h
@@ -0,0 +1,75 @@
+#pragma once
+
+#include <functional>
+
+// BaseClass
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
+#include "MemoryItem.h"
+
+namespace armarx::armem::server::ltm::detail
+{
+    /// @brief Interface functions for the longterm memory classes
+    class EntityInstanceBase : public MemoryItem
+    {
+    public:
+        struct Statistics
+        {
+            long recordedData = 0;
+            long recordedMetaData = 0;
+        };
+
+    public:
+        using MemoryItem::MemoryItem;
+
+        /// return the full sub-ltm as a wm::EntitySnapshot with only references
+        /// the ltm may be huge, use with caution
+        void
+        loadAllReferences(armem::wm::EntitySnapshot& e) const
+        {
+            _loadAllReferences(e);
+        }
+
+        /// convert the references of the input into a wm::Memory
+        void
+        resolve(armem::wm::EntityInstance& e) const
+        {
+            _resolve(e);
+        }
+
+        /// encode the content of a wm::Memory and store
+        nlohmann::json
+        store(const armem::wm::EntityInstance& e)
+        {
+            return _store(e);
+        }
+
+        /// statistics
+        void
+        resetStatistics()
+        {
+            statistics.recordedData = 0;
+            statistics.recordedMetaData = 0;
+        }
+
+        Statistics
+        getStatistics() const
+        {
+            return statistics;
+        }
+
+        static std::string getLevelName();
+
+    protected:
+        virtual void _loadAllReferences(armem::wm::EntitySnapshot&) const = 0;
+        virtual void _resolve(armem::wm::EntityInstance&) const = 0;
+        virtual nlohmann::json _store(const armem::wm::EntityInstance&) = 0;
+
+    protected:
+        mutable std::recursive_mutex ltm_mutex;
+
+        Statistics statistics;
+    };
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.cpp
similarity index 51%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.cpp
index 1b053d008f1900e323628c5be5b2324be6d0eb22..5b64878d0371bbe47a28a92f71f3502156e9bb2c 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.cpp
@@ -5,10 +5,6 @@
 
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::detail
 {
-    std::string EntitySnapshotBase::getLevelName()
-    {
-        return "LT-EntitySnapshot";
-    }
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.h
similarity index 60%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.h
index 411dd43cca301fda3c835572406ea175d231c8b5..cebbca9555f09e09da6b143056a024ac15b9d6a9 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/EntitySnapshotBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/EntitySnapshotBase.h
@@ -3,58 +3,77 @@
 #include <functional>
 
 // BaseClass
-#include "MemoryItem.h"
-
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+#include "EntityBase.h"
+#include "MemoryItem.h"
+
+namespace armarx::armem::server::ltm::detail
 {
     /// @brief Interface functions for the longterm memory classes
+    template <class InstanceT>
     class EntitySnapshotBase : public MemoryItem
     {
     public:
         struct Statistics
         {
             long recordedInstances = 0;
-
         };
 
     public:
-
         using MemoryItem::MemoryItem;
 
         /// return the full sub-ltm as a wm::EntitySnapshot with only references
         /// the ltm may be huge, use with caution
-        void loadAllReferences(armem::wm::EntitySnapshot& e) const
+        void
+        loadAllReferences(armem::wm::EntitySnapshot& e) const
         {
             _loadAllReferences(e);
         }
 
         /// convert the references of the input into a wm::Memory
-        void resolve(armem::wm::EntitySnapshot& e) const
+        void
+        resolve(armem::wm::EntitySnapshot& e) const
         {
             _resolve(e);
         }
 
         /// encode the content of a wm::Memory and store
-        void store(const armem::wm::EntitySnapshot& e)
+        void
+        store(const armem::wm::EntitySnapshot& e)
         {
             _store(e);
         }
 
         /// statistics
-        void resetStatistics()
+        void
+        resetStatistics()
         {
             statistics.recordedInstances = 0;
         }
-        Statistics getStatistics() const
+
+        Statistics
+        getStatistics() const
         {
             return statistics;
         }
 
-        static std::string getLevelName();
+        static std::string
+        getLevelName()
+        {
+            return "LT-EntitySnapshot";
+        }
+
+        /// iterate over all Instance segments of this ltm
+        virtual bool forEachInstance(std::function<void(InstanceT&)> func) const = 0;
+
+        /// check if Instance segment exists
+        virtual bool hasInstance(const int) const = 0;
+
+        /// find Instance segment
+        virtual std::shared_ptr<InstanceT> findInstance(const int) const = 0;
 
     protected:
         virtual void _loadAllReferences(armem::wm::EntitySnapshot&) const = 0;
@@ -66,4 +85,4 @@ namespace armarx::armem::server::ltm
 
         Statistics statistics;
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryBase.cpp
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryBase.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/detail/MemoryBase.cpp
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryBase.h
similarity index 55%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/MemoryBase.h
index 1b32ee2c9fc10bdb476b36b7046f46fc8518e462..4ca25b8cb1944e345bf6c1f8c285b84c65ad648c 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/MemoryBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryBase.h
@@ -9,17 +9,17 @@
 #include "CoreSegmentBase.h"
 
 // ArmarX
-#include <ArmarXCore/core/time/TimeUtil.h>
+#include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/logging/LoggingUtil.h>
+#include <ArmarXCore/core/time.h>
 
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
-#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
 #include <RobotAPI/libraries/armem/core/operations.h>
+#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
-
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::detail
 {
     /// @brief Interface functions for the longterm memory classes
     template <class _CoreSegmentT>
@@ -35,38 +35,69 @@ namespace armarx::armem::server::ltm
     public:
         using CoreSegmentT = _CoreSegmentT;
 
-        MemoryBase(const MemoryID& id) :
-            MemoryItem(id)
+        MemoryBase(const std::string& exportName, const MemoryID& id) :
+            MemoryItem(exportName, id), enabled(false)
         {
         }
 
         /// initialize config
-        virtual void init()
+        void
+        configure()
         {
-            enabled = enabled_on_startup;
-            ARMARX_INFO << VAROUT(configuration_on_startup);
+            bool en = p.enabled_on_startup;
+            ARMARX_INFO << VAROUT(p.configuration_on_startup);
 
             try
             {
-                const auto j = nlohmann::json::parse(configuration_on_startup);
-                this->configure(j);
+                const auto j = nlohmann::json::parse(p.configuration_on_startup);
+
+                // Processors are shared. So we only need to configure the root
+                processors->configure(j);
+
+                this->_configure(j);
             }
-            catch(...)
+            catch (...)
             {
-                ARMARX_WARNING << "Failed to parse `" << configuration_on_startup << "`";
-                enabled = false;
+                ARMARX_WARNING << "Failed to parse `" << p.configuration_on_startup << "`";
+                en = false;
             }
+
+            if (en)
+            {
+                this->startRecording();
+            }
+        }
+
+        /// enable this LTM
+        void
+        enable()
+        {
+            ARMARX_INFO << "Enabling LTM " << id().str();
+            enabled = true;
+            this->_enable();
+        }
+
+        /// disable this LTM
+        void
+        disable()
+        {
+            ARMARX_INFO << "Disabling LTM " << id().str();
+            enabled = false;
+            this->_disable();
         }
 
         /// return the full ltm as a wm::Memory with only references
         /// the ltm may be huge, use with caution
-        armem::wm::Memory loadAllReferences()
+        armem::wm::Memory
+        loadAllReferences()
         {
             armem::wm::Memory ret;
             loadAllReferences(ret);
             return ret;
         }
-        void loadAllReferences(armem::wm::Memory& memory)
+
+        void
+        loadAllReferences(armem::wm::Memory& memory)
         {
             TIMING_START(LTM_Memory_LoadAll);
             _loadAllReferences(memory);
@@ -75,14 +106,16 @@ namespace armarx::armem::server::ltm
 
         /// return the full ltm as a wm::Memory and resolves the references
         /// the ltm may be huge, use with caution
-        armem::wm::Memory loadAllAndResolve()
+        armem::wm::Memory
+        loadAllAndResolve()
         {
             armem::wm::Memory ret;
             loadAllAndResolve(ret);
             return ret;
         }
 
-        void loadAllAndResolve(armem::wm::Memory& memory)
+        void
+        loadAllAndResolve(armem::wm::Memory& memory)
         {
             TIMING_START(LTM_Memory_LoadAllAndResolve);
             _loadAllReferences(memory);
@@ -91,7 +124,8 @@ namespace armarx::armem::server::ltm
         }
 
         /// convert the references of the input into a wm::Memory
-        void resolve(armem::wm::Memory& memory)
+        void
+        resolve(armem::wm::Memory& memory)
         {
             TIMING_START(LTM_Memory_Load);
             _resolve(memory);
@@ -99,14 +133,16 @@ namespace armarx::armem::server::ltm
         }
 
         /// append a wm::Memory instance to the ltm
-        void store(const armem::wm::Memory& memory)
+        void
+        store(const armem::wm::Memory& memory)
         {
             TIMING_START(LTM_Memory_Append);
             for (auto& f : processors->memFilters)
             {
-                if (f->enabled && !f->accept(memory))
+                if (!f->accept(memory))
                 {
-                    ARMARX_INFO << deactivateSpam() << "Ignoring to put a Memory into the LTM because it got filtered.";
+                    ARMARX_INFO << deactivateSpam()
+                                << "Ignoring to put a Memory into the LTM because it got filtered.";
                     return;
                 }
             }
@@ -115,7 +151,8 @@ namespace armarx::armem::server::ltm
         }
 
         /// append a wm::Memory instance to the ltm
-        void store(const armem::server::wm::Memory& serverMemory)
+        void
+        store(const armem::server::wm::Memory& serverMemory)
         {
             wm::Memory memory;
             memory.update(armem::toCommit(serverMemory));
@@ -125,74 +162,102 @@ namespace armarx::armem::server::ltm
         /// iterate over all core segments of this ltm
         virtual bool forEachCoreSegment(std::function<void(CoreSegmentT&)> func) const = 0;
 
+        /// check if core segment exists
+        virtual bool hasCoreSegment(const std::string&) const = 0;
+
         /// find core segment
-        virtual std::shared_ptr<CoreSegmentT> findCoreSegment(const std::string&) const = 0; // TODO make unique!!
+        virtual std::unique_ptr<CoreSegmentT> findCoreSegment(const std::string&) const = 0;
 
         /// default parameters. Implementation should use the configuration to configure
-        virtual void createPropertyDefinitions(PropertyDefinitionsPtr& defs, const std::string& prefix)
-        {
-            defs->optional(enabled_on_startup, prefix + "enabled");
-            defs->optional(configuration_on_startup, prefix + "configuration");
-            //processors->createPropertyDefinitions(defs, prefix);
-        }
-
-        /// configuration
-        virtual void configure(const nlohmann::json& config)
+        virtual void
+        createPropertyDefinitions(PropertyDefinitionsPtr& defs, const std::string& prefix)
         {
-            // Processors are shared. So we only need to configure the root
-            processors->configure(config);
+            defs->optional(p.enabled_on_startup, prefix + "enabled");
+            defs->optional(p.configuration_on_startup, prefix + "configuration");
         }
 
         /// enable/disable
-        void startRecording()
+        void
+        startRecording()
         {
             statistics.lastEnabled = armarx::core::time::DateTime::Now();
-            enabled = true;
+            enable();
         }
-        void stopRecording()
+
+        void
+        stopRecording()
         {
-            enabled = false;
+            disable();
         }
-        bool isRecording() const
+
+        bool
+        isRecording() const
         {
             return enabled;
         }
 
         /// statistics
-        virtual void resetStatistics()
+        virtual void
+        resetStatistics()
         {
             // enabled stays the same
             statistics.lastEnabled = armarx::core::time::DateTime::Invalid();
             statistics.recordedCoreSegments = 0;
         }
-        Statistics getStatistics() const
+
+        Statistics
+        getStatistics() const
         {
             return statistics;
         }
 
         /// get level name
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "LT-Memory";
         }
 
     protected:
+        /// configuration
+        virtual void
+        _configure(const nlohmann::json&)
+        {
+        }
+
+        virtual void
+        _enable()
+        {
+        }
+
+        virtual void
+        _disable()
+        {
+        }
+
+        virtual void
+        _setExportName(const std::string&)
+        {
+        }
+
         virtual void _loadAllReferences(armem::wm::Memory& memory) = 0;
         virtual void _resolve(armem::wm::Memory& memory) = 0;
         virtual void _store(const armem::wm::Memory& memory) = 0;
 
     public:
         // stuff for scenario parameters
-        bool enabled_on_startup = false;
-        std::string configuration_on_startup = "{}";
+        struct Properties
+        {
+            bool enabled_on_startup = false;
+            std::string configuration_on_startup =
+                "{\"SnapshotFrequencyFilter\": { \"WaitingTimeInMs\": 1000}, \"PngConverter\": {}}";
+        } p;
 
     protected:
         mutable std::recursive_mutex ltm_mutex;
 
-        Statistics statistics;
+        mutable Statistics statistics;
 
-    private:
         std::atomic_bool enabled = false;
-
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..99dfcfee345d5d2015baffa7ef389a0c6879b3f9
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.cpp
@@ -0,0 +1,53 @@
+#include "MemoryItem.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm::detail
+{
+    MemoryItem::MemoryItem(const std::string& exportName, const MemoryID& id) :
+        processors(std::make_shared<Processors>()), exportName(exportName), _id(id)
+    {
+    }
+
+    MemoryItem::MemoryItem(const std::string& exportName,
+                           const MemoryID& id,
+                           const std::shared_ptr<Processors>& p) :
+        processors(p), exportName(exportName), _id(id)
+    {
+    }
+
+    void
+    MemoryItem::setExportName(const std::string& id)
+    {
+        exportName = id;
+        _setExportName(id);
+    }
+
+    void
+    MemoryItem::setMemoryID(const MemoryID& id)
+    {
+        _id = id;
+        _setMemoryID(id);
+    }
+
+    MemoryID
+    MemoryItem::id() const
+    {
+        return _id;
+    }
+
+    std::string
+    MemoryItem::name() const
+    {
+        return _id.getLeafItem();
+    }
+
+    void
+    MemoryItem::setMemoryName(const std::string& memoryName)
+    {
+        _id.memoryName = memoryName;
+    }
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.h b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..bf212bb37f252afb3e848c8fe322d74a4b550b22
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/MemoryItem.h
@@ -0,0 +1,60 @@
+#pragma once
+
+#include <map>
+#include <mutex>
+#include <optional>
+#include <string>
+
+#include <RobotAPI/libraries/armem/server/ltm/processors/Processors.h>
+
+namespace armarx::armem::server::ltm::detail
+{
+    /// @brief Interface functions for the longterm memory classes
+    class MemoryItem
+    {
+    public:
+        MemoryItem(const std::string& exportName, const MemoryID&); // only used by memory
+        MemoryItem(const std::string& exportName,
+                   const MemoryID&,
+                   const std::shared_ptr<Processors>&); // used by all other segments
+        virtual ~MemoryItem() = default;
+
+        void setExportName(const std::string& n);
+        void setMemoryID(const MemoryID&);
+        void setMemoryName(const std::string& memoryName);
+
+        std::string
+        getExportName() const
+        {
+            return exportName;
+        }
+
+        MemoryID
+        getMemoryID() const
+        {
+            return id();
+        }
+
+        // aliases
+        MemoryID id() const;
+        std::string name() const;
+
+    protected:
+        virtual void
+        _setExportName(const std::string&)
+        {
+        }
+
+        virtual void
+        _setMemoryID(const MemoryID&)
+        {
+        }
+
+    protected:
+        std::shared_ptr<Processors> processors;
+
+    private:
+        std::string exportName = "MemoryExport";
+        MemoryID _id;
+    };
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/ProviderSegmentBase.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/ProviderSegmentBase.cpp
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/ProviderSegmentBase.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/detail/ProviderSegmentBase.cpp
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/ProviderSegmentBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/ProviderSegmentBase.h
similarity index 73%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/ProviderSegmentBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/ProviderSegmentBase.h
index c241d7889621f534991733baf82973e28428a641..65021cdbb9a7487dc20f2ea930cb7a37d109e8fc 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/ProviderSegmentBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/ProviderSegmentBase.h
@@ -2,16 +2,14 @@
 
 #include <functional>
 
-// BaseClass
-#include "MemoryItem.h"
-
-#include "EntityBase.h"
-
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
-#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 #include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+#include "EntityBase.h"
+#include "MemoryItem.h"
+
+namespace armarx::armem::server::ltm::detail
 {
     /// @brief Interface functions for the longterm memory classes
     template <class _EntityT>
@@ -21,7 +19,6 @@ namespace armarx::armem::server::ltm
         struct Statistics
         {
             long recordedEntities = 0;
-
         };
 
     public:
@@ -31,35 +28,35 @@ namespace armarx::armem::server::ltm
 
         /// return the full sub-ltm as a wm::ProviderSegment with only references
         /// the ltm may be huge, use with caution
-        void loadAllReferences(armem::wm::ProviderSegment& provSeg)
+        void
+        loadAllReferences(armem::wm::ProviderSegment& provSeg)
         {
             _loadAllReferences(provSeg);
         }
 
         /// convert the references of the input into a wm::Memory
-        void resolve(armem::wm::ProviderSegment& provSeg)
+        void
+        resolve(armem::wm::ProviderSegment& provSeg)
         {
             _resolve(provSeg);
         }
 
         /// encode the content of a wm::Memory and store
-        void store(const armem::wm::ProviderSegment& provSeg)
+        void
+        store(const armem::wm::ProviderSegment& provSeg)
         {
             _store(provSeg);
         }
 
-        /// store the type of the segment
-        void storeType(const armem::wm::ProviderSegment& coreSeg)
-        {
-            _storeType(coreSeg);
-        }
-
         /// statistics
-        void resetStatistics()
+        void
+        resetStatistics()
         {
             statistics.recordedEntities = 0;
         }
-        Statistics getStatistics() const
+
+        Statistics
+        getStatistics() const
         {
             return statistics;
         }
@@ -67,15 +64,20 @@ namespace armarx::armem::server::ltm
         /// iterate over all core segments of this ltm
         virtual bool forEachEntity(std::function<void(EntityT&)> func) const = 0;
 
+        /// check if entity segment exists
+        virtual bool hasEntity(const std::string&) const = 0;
+
         /// find entity segment
         virtual std::shared_ptr<EntityT> findEntity(const std::string&) const = 0;
 
-        aron::type::ObjectPtr aronType() const
+        aron::type::ObjectPtr
+        aronType() const
         {
             return nullptr;
         }
 
-        static std::string getLevelName()
+        static std::string
+        getLevelName()
         {
             return "LT-ProviderSegment";
         }
@@ -84,11 +86,10 @@ namespace armarx::armem::server::ltm
         virtual void _loadAllReferences(armem::wm::ProviderSegment&) = 0;
         virtual void _resolve(armem::wm::ProviderSegment&) = 0;
         virtual void _store(const armem::wm::ProviderSegment&) = 0;
-        virtual void _storeType(const armem::wm::ProviderSegment&) = 0;
 
     protected:
         mutable std::recursive_mutex ltm_mutex;
 
         Statistics statistics;
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..80982baf62c2bd7e20e0e7960deac373831c9614
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.cpp
@@ -0,0 +1,7 @@
+#include "BufferedMemoryMixin.h"
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+
+
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.h
similarity index 53%
rename from source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.h
rename to source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.h
index 1104da67e9c19488daa3cc4d508a4355095d1704..0bbf62f24ab3dd9427a9854bfadf8fe048c98bb1 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/BufferedMemoryMixin.h
@@ -1,64 +1,84 @@
 #pragma once
 
-#include "MemoryBase.h"
+#include <SimoxUtility/json.h>
 
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 
-namespace armarx::armem::server::ltm
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm::detail::mixin
 {
     template <class _CoreSegmentT>
-    class BufferedMemoryBase : public MemoryBase<_CoreSegmentT>
+    class BufferedMemoryMixin
     {
-        using Base = MemoryBase<_CoreSegmentT>;
 
     public:
-        BufferedMemoryBase(const MemoryID& id) :
-            Base(id),
-            buffer(std::make_shared<armem::wm::Memory>(id)),
-            to_store(std::make_shared<armem::wm::Memory>(id))
+        BufferedMemoryMixin(const MemoryID& id) :
+            buffer(std::make_unique<armem::wm::Memory>(id)),
+            to_store(std::make_unique<armem::wm::Memory>(id))
         {
         }
 
-        virtual ~BufferedMemoryBase() = default;
+        virtual ~BufferedMemoryMixin() = default;
 
-        void setMemoryID(const MemoryID& id) override
+        void
+        directlyStore(const armem::wm::Memory& memory)
         {
-            ARMARX_CHECK_NOT_EMPTY(id.memoryName) << " The full id was: " << id.str();
+            std::lock_guard l(storeMutex);
+
+            TIMING_START(LTM_Memory_DirectlyStore);
+            _directlyStore(memory);
+            TIMING_END_STREAM(LTM_Memory_DirectlyStore, ARMARX_DEBUG);
+        }
 
-            Base::setMemoryID(id.getMemoryID());
+    protected:
+        void
+        setMixinMemoryID(const MemoryID& id)
+        {
+            ARMARX_CHECK_NOT_EMPTY(id.memoryName) << " The full id was: " << id.str();
 
             buffer->id() = id.getMemoryID();
             to_store->id() = id.getMemoryID();
         }
 
-        armem::wm::Memory getBuffer() const
+        void
+        start()
         {
-            std::lock_guard l(bufferMutex);
-            return *buffer;
+            // create task if not already exists
+            if (!task)
+            {
+                int waitingTimeMs = 1000.f / storeFrequency;
+                task = new armarx::PeriodicTask<BufferedMemoryMixin>(
+                    this, &BufferedMemoryMixin::storeBuffer, waitingTimeMs);
+                task->start();
+            }
         }
 
-        void directlyStore(const armem::wm::Memory& memory)
+        void
+        stop()
         {
-            TIMING_START(LTM_Memory_DirectlyStore);
-            for (auto& f : this->processors->memFilters)
+            if (task)
             {
-                if (!f->accept(memory))
-                {
-                    ARMARX_WARNING << deactivateSpam() << "Ignoring to commit a Memory into the LTM because the full commit got filtered.";
-                    return;
-                }
+                task->stop();
+                task = nullptr;
             }
-            _directlyStore(memory);
-            TIMING_END_STREAM(LTM_Memory_DirectlyStore, ARMARX_DEBUG);
         }
 
-        void storeBuffer()
+        armem::wm::Memory
+        getBuffer() const
+        {
+            std::lock_guard l(bufferMutex);
+            return *buffer;
+        }
+
+        void
+        storeBuffer()
         {
             std::lock_guard l(storeMutex);
             {
                 std::lock_guard l(bufferMutex);
-                to_store = buffer;
-                buffer = std::make_shared<armem::wm::Memory>(this->id());
+                to_store = std::move(buffer);
+                buffer = std::make_unique<armem::wm::Memory>(to_store->id());
             }
 
             if (to_store->empty())
@@ -71,30 +91,22 @@ namespace armarx::armem::server::ltm
         }
 
         /// configuration
-        void configure(const nlohmann::json& json) override
+        void
+        configureMixin(const nlohmann::json& json)
         {
-            Base::configure(json);
-            if (json.find("BufferedMemoryBase.storeFrequency") != json.end())
+            if (json.find("BufferedMemory.storeFrequency") != json.end())
             {
-                storeFrequency = json.at("BufferedMemoryBase.storeFrequency");
+                storeFrequency = json.at("BufferedMemory.storeFrequency");
             }
         }
 
-    protected:
         virtual void _directlyStore(const armem::wm::Memory& memory) = 0;
 
-        void _store(const armem::wm::Memory& memory) override
+        void
+        addToBuffer(const armem::wm::Memory& memory)
         {
             std::lock_guard l(bufferMutex);
             buffer->append(memory);
-
-            // create task if not already exists
-            if (!task)
-            {
-                int waitingTimeMs = 1000.f / storeFrequency;
-                task = new armarx::PeriodicTask<BufferedMemoryBase>(this, &BufferedMemoryBase::storeBuffer, waitingTimeMs);
-                task->start();
-            }
         }
 
     protected:
@@ -102,18 +114,18 @@ namespace armarx::armem::server::ltm
         /// The to-put-to-ltm buffer (contains data in plain text)
         /// This buffer may still be filtered (e.g. snapshot filters).
         /// This means that it is not guaranteed that all data in the buffer will be stored in the ltm
-        std::shared_ptr<armem::wm::Memory> buffer;
-        std::shared_ptr<armem::wm::Memory> to_store;
-
-        /// The periodic'task to store the content of the buffer to the ltm
-        typename armarx::PeriodicTask<BufferedMemoryBase>::pointer_type task = nullptr;
+        std::unique_ptr<armem::wm::Memory> buffer;
+        std::unique_ptr<armem::wm::Memory> to_store;
 
         /// The frequency (Hz) to store data to the ltm
         float storeFrequency = 10;
 
-        /// a mutex to access the buffer object
-        mutable std::mutex bufferMutex;
-        mutable std::mutex storeMutex;
+    private:
+        /// The periodic'task to store the content of the buffer to the ltm
+        typename armarx::PeriodicTask<BufferedMemoryMixin>::pointer_type task = nullptr;
 
+        /// a mutex to access the buffer object
+        mutable std::recursive_mutex bufferMutex;
+        mutable std::recursive_mutex storeMutex;
     };
-} // namespace armarx::armem::server::ltm
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..50083aa97e06f4da65d15fa0a417df476e41bb41
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.cpp
@@ -0,0 +1,6 @@
+#include "CachedMemoryMixin.h"
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.h
new file mode 100644
index 0000000000000000000000000000000000000000..250484f07c95132a1de7b579cf6aac8b580b0cd4
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/CachedMemoryMixin.h
@@ -0,0 +1,98 @@
+#pragma once
+
+#include <SimoxUtility/json.h>
+
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+    template <class _CoreSegmentT>
+    class CachedMemoryMixin
+    {
+    public:
+        CachedMemoryMixin(const MemoryID& id) : cache(std::make_unique<armem::wm::Memory>(id))
+        {
+        }
+
+    protected:
+        armem::wm::Memory
+        getCache() const
+        {
+            std::lock_guard l(this->cache_mutex);
+            return *cache;
+        }
+
+        /// configuration
+        void
+        configureMixin(const nlohmann::json& json)
+        {
+            // TODO: Max cache size
+        }
+
+        void
+        setMixinMemoryID(const MemoryID& id)
+        {
+            ARMARX_CHECK_NOT_EMPTY(id.memoryName) << " The full id was: " << id.str();
+
+            cache->id() = id.getMemoryID();
+        }
+
+        void
+        addToCache(const armem::wm::Memory& memory)
+        {
+            std::lock_guard l(cache_mutex);
+            cache->append(memory);
+        }
+
+        bool
+        cacheHasCoreSegment(const std::string& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasCoreSegment(n);
+        }
+
+        bool
+        cacheHasCoreSegment(const MemoryID& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasCoreSegment(n);
+        }
+
+        bool
+        cacheHasProviderSegment(const MemoryID& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasProviderSegment(n);
+        }
+
+        bool
+        cacheHasEntity(const MemoryID& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasEntity(n);
+        }
+
+        bool
+        cacheHasEntitySnapshot(const MemoryID& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasSnapshot(n);
+        }
+
+        bool
+        cacheHasEntityInstance(const MemoryID& n) const
+        {
+            std::lock_guard l(cache_mutex);
+            return cache->hasInstance(n);
+        }
+
+
+    protected:
+        std::unique_ptr<armem::wm::Memory> cache;
+
+    private:
+        mutable std::recursive_mutex cache_mutex;
+    };
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8ceaf84eb19deaa0db3efdd5595179ed8d4bcbd4
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.cpp
@@ -0,0 +1,137 @@
+// Header
+#include "DiskStorageMixin.h"
+
+// STD/STL
+#include <algorithm>
+#include <fstream>
+#include <iostream>
+
+// Simox
+#include <SimoxUtility/algorithm/string.h>
+
+// ArmarX
+#include <ArmarXCore/core/exceptions/LocalException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/time/TimeUtil.h>
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+    DiskMemoryItemMixin::DiskMemoryItemMixin(const Path& memoryParentPath,
+                                             const std::string& exportName,
+                                             const armem::MemoryID& id) :
+        memoryBasePath(memoryParentPath), exportName(exportName), _id(id)
+    {
+    }
+
+    void
+    DiskMemoryItemMixin::setMemoryBasePath(const Path& n)
+    {
+        memoryBasePath = n;
+    }
+
+    void
+    DiskMemoryItemMixin::setMixinExportName(const std::string& n)
+    {
+        exportName = n;
+    }
+
+    void
+    DiskMemoryItemMixin::setMixinMemoryID(const MemoryID& n)
+    {
+        ARMARX_CHECK_NOT_EMPTY(_id.memoryName) << " The full id was: " << _id.str();
+
+        _id = n;
+    }
+
+    void
+    DiskMemoryItemMixin::configureMixin(const nlohmann::json& json)
+    {
+        if (json.find("DiskMemory.memoryParentPath") != json.end())
+        {
+            memoryBasePath = Path(json.at("DiskMemory.memoryParentPath"));
+        }
+    }
+
+    Path
+    DiskMemoryItemMixin::getMemoryBasePath() const
+    {
+        return memoryBasePath;
+    }
+
+    Path
+    DiskMemoryItemMixin::getFullPath() const
+    {
+        auto p = getMemoryBasePath() / exportName;
+        return util::fs::toPath(p, _id);
+    }
+
+    bool
+    DiskMemoryItemMixin::memoryBasePathExists() const
+    {
+        return util::fs::directoryExists(getMemoryBasePath());
+    }
+
+    bool
+    DiskMemoryItemMixin::fullPathExists() const
+    {
+        auto p = getFullPath();
+        return util::fs::directoryExists(p);
+    }
+
+    bool
+    DiskMemoryItemMixin::fileExists(const std::string& filename) const
+    {
+        auto p = getFullPath() / filename;
+        return util::fs::fileExists(p);
+    }
+
+    void
+    DiskMemoryItemMixin::ensureMemoryBasePathExists(bool createIfNotExistent) const
+    {
+        util::fs::ensureDirectoryExists(getMemoryBasePath(), createIfNotExistent);
+    }
+
+    void
+    DiskMemoryItemMixin::ensureFullPathExists(bool createIfNotExistent) const
+    {
+        auto p = getFullPath();
+        util::fs::ensureDirectoryExists(p, createIfNotExistent);
+    }
+
+    void
+    DiskMemoryItemMixin::ensureFileExists(const std::string& filename,
+                                          bool createIfNotExistent) const
+    {
+        auto p = getFullPath() / filename;
+        util::fs::ensureFileExists(p, createIfNotExistent);
+    }
+
+    void
+    DiskMemoryItemMixin::writeDataToFile(const std::string& filename,
+                                         const std::vector<unsigned char>& data) const
+    {
+        auto p = getFullPath() / filename;
+        util::fs::writeDataToFile(p, data);
+    }
+
+    std::vector<unsigned char>
+    DiskMemoryItemMixin::readDataFromFile(const std::string& filename) const
+    {
+        auto p = getFullPath() / filename;
+        return util::fs::readDataFromFile(p);
+    }
+
+    std::vector<Path>
+    DiskMemoryItemMixin::getAllDirectories() const
+    {
+        auto p = getFullPath();
+        return util::fs::getAllDirectories(p);
+    }
+
+    std::vector<Path>
+    DiskMemoryItemMixin::getAllFiles() const
+    {
+        auto p = getFullPath();
+        return util::fs::getAllFiles(p);
+    }
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.h
new file mode 100644
index 0000000000000000000000000000000000000000..b9550d4117a0c06675b3788e3c0065c040677fd3
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/DiskStorageMixin.h
@@ -0,0 +1,73 @@
+#pragma once
+
+#include <filesystem>
+#include <map>
+#include <string>
+
+#include <SimoxUtility/json.h>
+
+#include <ArmarXCore/core/services/tasks/PeriodicTask.h>
+
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+
+#include "util/filesystem.h"
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+    using Path = std::filesystem::path;
+
+    class DiskMemoryItemMixin
+    {
+    public:
+        DiskMemoryItemMixin() = default;
+        DiskMemoryItemMixin(const Path& memoryParentPath,
+                            const std::string& exportName,
+                            const armem::MemoryID& id);
+        virtual ~DiskMemoryItemMixin() = default;
+
+        Path getMemoryBasePath() const;
+        Path getFullPath() const;
+
+        // Filesystem interaction
+        bool memoryBasePathExists() const;
+        bool fullPathExists() const;
+        bool fileExists(const std::string& filename) const;
+
+        void ensureMemoryBasePathExists(bool createIfNotExistent = false) const;
+        void ensureFullPathExists(bool createIfNotExistent = false) const;
+        void ensureFileExists(const std::string& filename, bool createIfNotExistent = false) const;
+
+        void writeDataToFile(const std::string& filename,
+                             const std::vector<unsigned char>& data) const;
+
+        std::vector<unsigned char> readDataFromFile(const std::string& filename) const;
+        std::vector<Path> getAllDirectories() const;
+        std::vector<Path> getAllFiles() const;
+
+
+    protected:
+        // setter
+        void setMixinMemoryID(const MemoryID& n);
+        void setMemoryBasePath(const std::filesystem::path& n);
+        void setMixinExportName(const std::string& n);
+
+        /// configuration
+        void configureMixin(const nlohmann::json& json);
+
+    public:
+        static const int DEPTH_TO_DATA_FILES =
+            7; // from memory folder = 1 (cseg) + 1 (pseg) + 1 (ent) + 3 (snap) + 1 (inst)
+
+    protected:
+        static const constexpr char* TYPE_FILENAME = "type.aron";
+        static const constexpr char* DATA_FILENAME = "data.aron";
+        static const constexpr char* METADATA_FILENAME = "metadata.aron";
+
+        static const constexpr char* MEMORY_EXPORT_SUFFIX = "_";
+
+    private:
+        std::filesystem::path memoryBasePath;
+        std::string exportName;
+        armem::MemoryID _id;
+    };
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..dd29022893ab55f818a9e12c93f1fe37b515caf2
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.cpp
@@ -0,0 +1,459 @@
+#include "MongoDBStorageMixin.h"
+
+#include <SimoxUtility/algorithm/string.h>
+
+#include <ArmarXCore/core/exceptions/LocalException.h>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <ArmarXCore/core/logging/Logging.h>
+
+#include "util/filesystem.h"
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+    std::unique_ptr<mongocxx::instance> MongoDBStorageMixin::MongoCXXInstance = nullptr;
+    std::atomic_bool MongoDBStorageMixin::MongoCXXInitialized = false;
+    std::recursive_mutex MongoDBStorageMixin::MongoCXXConnectionPoolMutex;
+    std::map<std::string, std::unique_ptr<mongocxx::pool>>
+        MongoDBStorageMixin::MongoCXXConnectionPool = {};
+
+    void
+    MongoDBSettings::initializeFromArmarXConfig()
+    {
+        std::filesystem::path armarx_config_home = std::string(getenv("ARMARX_USER_CONFIG_DIR"));
+        if (!util::fs::directoryExists(armarx_config_home))
+        {
+            ARMARX_WARNING << ("Could not find an ArmarX Config folder. Tried: '" +
+                               armarx_config_home.string() +
+                               "' (from ARMARX_USER_CONFIG_DIR). If not set via scenario params "
+                               "this means that LTM is disabled.");
+            return;
+        }
+
+        std::ifstream cFile(armarx_config_home / "default.cfg");
+        if (cFile.is_open())
+        {
+            std::string line;
+            while (getline(cFile, line))
+            {
+                line.erase(std::remove_if(line.begin(), line.end(), isspace), line.end());
+                if (line.empty() || line[0] == '#')
+                {
+                    continue;
+                }
+                auto delimiterPos = line.find("=");
+                const auto name = simox::alg::to_lower(line.substr(0, delimiterPos));
+                const auto value = line.substr(delimiterPos + 1);
+                if (host.empty() && name == "armarx.mongohost")
+                {
+                    host = value;
+                }
+                if (port == 0 && name == "armarx.mongoport")
+                {
+                    port = (unsigned int)std::stoi(value);
+                }
+                if (user.empty() && name == "armarx.mongouser")
+                {
+                    user = value;
+                }
+                if (password.empty() && name == "armarx.mongopassword")
+                {
+                    password = value;
+                }
+            }
+        }
+    }
+
+    bool
+    MongoDBSettings::isSet() const
+    {
+        // we always need a host and a port
+        return !host.empty() and port != 0;
+    }
+
+    std::string
+    MongoDBSettings::baseUri() const
+    {
+        std::stringstream ss;
+        ss << "mongodb://";
+
+        if (!user.empty())
+        {
+            ss << user;
+            if (!password.empty())
+            {
+                ss << ":" << password;
+            }
+            ss << "@";
+        }
+        ss << host;
+        return ss.str();
+    }
+
+    std::string
+    MongoDBSettings::key() const
+    {
+        // TODO: What happens if a connection exists and you would like to open another one with a different user (e.g. that sees different things)?
+        return "mongodb://" + host + ":" + std::to_string(port);
+    }
+
+    std::string
+    MongoDBSettings::uri() const
+    {
+        return baseUri() + ":" + std::to_string(port) +
+               "/?minPoolSize=" + std::to_string(minPoolSize) +
+               "&maxPoolSize=" + std::to_string(maxPoolSize);
+    }
+
+    std::string
+    MongoDBSettings::toString() const
+    {
+        return uri();
+    }
+
+    MongoDBStorageMixin::MongoDBStorageMixin(const MongoDBSettings& settings,
+                                             const std::string& en,
+                                             const armem::MemoryID& id) :
+        settings(settings), exportName(en), _id(id)
+    {
+    }
+
+    void
+    MongoDBStorageMixin::setHost(const std::string& n)
+    {
+        settings.host = n;
+    }
+
+    void
+    MongoDBStorageMixin::setPort(const unsigned int n)
+    {
+        settings.port = n;
+    }
+
+    void
+    MongoDBStorageMixin::setUser(const std::string& n)
+    {
+        settings.user = n;
+    }
+
+    void
+    MongoDBStorageMixin::setPassword(const std::string& n)
+    {
+        settings.password = n;
+    }
+
+    void
+    MongoDBStorageMixin::connect() const
+    {
+        std::lock_guard l(MongoCXXConnectionPoolMutex);
+        if (!MongoCXXInitialized.exchange(true))
+        {
+            ARMARX_IMPORTANT << "INITIALIZE MONGODB";
+            MongoCXXInstance =
+                std::make_unique<mongocxx::instance>(); // This should be done only once.
+        }
+
+        const auto key = settings.key();
+        const auto uri = settings.uri();
+        auto it = MongoCXXConnectionPool.find(key);
+        if (it == MongoCXXConnectionPool.end())
+        {
+            ARMARX_INFO << "Establishing new connection to: " << uri << " from id: " << _id.str();
+            mongocxx::uri u(uri);
+            auto pool = std::make_unique<mongocxx::pool>(u);
+            MongoCXXConnectionPool.emplace(settings.key(), std::move(pool));
+        }
+    }
+
+    mongocxx::pool*
+    MongoDBStorageMixin::getPool(bool tryToConnect) const
+    {
+        std::lock_guard l(MongoCXXConnectionPoolMutex);
+        const auto key = settings.key();
+        auto it = MongoCXXConnectionPool.find(key);
+        if (it == MongoCXXConnectionPool.end())
+        {
+            if (tryToConnect)
+            {
+                // try to establish a connection and try again
+                connect();
+                return getPool(false);
+            }
+            return nullptr;
+        }
+        else
+        {
+            return it->second.get();
+        }
+    }
+
+    mongocxx::pool*
+    MongoDBStorageMixin::ensurePool() const
+    {
+        std::lock_guard l(MongoCXXConnectionPoolMutex);
+        auto pool = getPool();
+        if (pool)
+        {
+            return pool;
+        }
+        else
+        {
+            throw armarx::LocalException("Pool could not be ensured...");
+        }
+    }
+
+    void
+    MongoDBStorageMixin::start()
+    {
+        // ensure a connection is made if not done already
+        connect();
+    }
+
+    void
+    MongoDBStorageMixin::stop()
+    {
+    }
+
+    bool
+    MongoDBStorageMixin::connected() const
+    {
+        std::lock_guard l(MongoCXXConnectionPoolMutex);
+
+        try
+        {
+            auto client = ensurePool()->acquire();
+            auto admin = client->database("admin");
+            auto result = admin.run_command(bsoncxx::builder::basic::make_document(
+                bsoncxx::builder::basic::kvp("isMaster", 1)));
+            return true;
+        }
+        catch (const std::exception& xcp)
+        {
+            return false;
+        }
+        return false; // should never happen
+    }
+
+    std::string
+    MongoDBStorageMixin::getDocumentName() const
+    {
+        return util::mongodb::toDocumentID(_id);
+    }
+
+    std::string
+    MongoDBStorageMixin::getCollectionName() const
+    {
+        return util::mongodb::toCollectionName(_id);
+    }
+
+    std::string
+    MongoDBStorageMixin::getPreviousCollectionName() const
+    {
+        ARMARX_CHECK(!_id.memoryName.empty() and !_id.coreSegmentName.empty());
+        return util::mongodb::toCollectionName(_id.removeLeafItem());
+    }
+
+    std::string
+    MongoDBStorageMixin::getDatabaseName() const
+    {
+        return exportName;
+    }
+
+    std::optional<mongocxx::database>
+    MongoDBStorageMixin::databaseExists() const
+    {
+        auto client = this->ensurePool()->acquire();
+        return util::mongodb::databaseExists(*client, getDatabaseName());
+    }
+
+    std::optional<mongocxx::collection>
+    MongoDBStorageMixin::collectionExists() const
+    {
+        auto db = databaseExists();
+        if (!db)
+        {
+            return std::nullopt;
+        }
+
+        return util::mongodb::collectionExists(*db, getCollectionName());
+    }
+
+    std::optional<mongocxx::collection>
+    MongoDBStorageMixin::previousCollectionExists() const
+    {
+        auto db = databaseExists();
+        if (!db)
+        {
+            return std::nullopt;
+        }
+
+        return util::mongodb::collectionExists(*db, getPreviousCollectionName());
+    }
+
+    std::optional<nlohmann::json>
+    MongoDBStorageMixin::documentExists() const
+    {
+        return documentExists(getDocumentName());
+    }
+
+    std::optional<nlohmann::json>
+    MongoDBStorageMixin::documentExists(const std::string& id) const
+    {
+        auto coll = collectionExists();
+        if (!coll)
+        {
+            return std::nullopt;
+        }
+
+        nlohmann::json query;
+        query[ID] = getDocumentName();
+        return util::mongodb::documentExists(*coll, query);
+    }
+
+    mongocxx::database
+    MongoDBStorageMixin::ensureDatabaseExists(bool createIfNotExistent)
+    {
+        auto client = this->ensurePool()->acquire();
+        return util::mongodb::ensureDatabaseExists(*client, getDatabaseName(), createIfNotExistent);
+    }
+
+    mongocxx::collection
+    MongoDBStorageMixin::ensureCollectionExists(bool createIfNotExistent)
+    {
+        auto db = ensureDatabaseExists(createIfNotExistent);
+        return util::mongodb::ensureCollectionExists(db, getCollectionName(), createIfNotExistent);
+    }
+
+    mongocxx::collection
+    MongoDBStorageMixin::ensurePreviousCollectionExists(bool createIfNotExistent)
+    {
+        auto db = ensureDatabaseExists(createIfNotExistent);
+        return util::mongodb::ensureCollectionExists(
+            db, getPreviousCollectionName(), createIfNotExistent);
+    }
+
+    nlohmann::json
+    MongoDBStorageMixin::ensureDocumentExists(bool createIfNotExistent)
+    {
+        return ensureDocumentExists(getDocumentName(), createIfNotExistent);
+    }
+
+    nlohmann::json
+    MongoDBStorageMixin::ensureDocumentExists(const std::string& id, bool createIfNotExistent)
+    {
+        auto coll = ensureCollectionExists(createIfNotExistent);
+
+        nlohmann::json query;
+        query[ID] = getDocumentName();
+        return util::mongodb::ensureDocumentExists(coll, query, createIfNotExistent);
+    }
+
+    void
+    MongoDBStorageMixin::writeDataToDocument(const std::string& id, const nlohmann::json& data)
+    {
+        auto coll = ensureCollectionExists(true);
+
+        nlohmann::json query;
+        query[ID] = getDocumentName();
+
+        nlohmann::json update;
+        update[DATA] = data;
+        util::mongodb::writeDataToDocument(coll, query, update);
+    }
+
+    void
+    MongoDBStorageMixin::writeForeignKeyToPreviousDocument()
+    {
+        auto coll = ensurePreviousCollectionExists(true);
+
+        nlohmann::json query;
+        query[ID] = _id.str();
+
+        nlohmann::json update;
+        update[FOREIGN_KEY] = getCollectionName();
+        util::mongodb::writeDataToDocument(coll, query, update);
+    }
+
+    void
+    MongoDBStorageMixin::writeForeignKeyToPreviousDocument(const nlohmann::json& type)
+    {
+        auto coll = ensurePreviousCollectionExists(true);
+
+        nlohmann::json query;
+        query[ID] = _id.str();
+
+        nlohmann::json update;
+        update[FOREIGN_KEY] = getCollectionName();
+        update[TYPE] = type;
+
+        util::mongodb::writeDataToDocument(coll, query, update);
+    }
+
+    nlohmann::json
+    MongoDBStorageMixin::readDataFromDocument(const std::string& id) const
+    {
+        auto coll = collectionExists();
+        if (!coll)
+        {
+            // What to do here?
+            return {};
+        }
+
+        if (!documentExists())
+        {
+            // What to do here?
+            return {};
+        }
+
+        auto query =
+            nlohmann::json::parse(std::string("{\"") + ID + "\": " + getDocumentName() + "}");
+        return util::mongodb::readDataFromDocument(*coll, query);
+    }
+
+    void
+    MongoDBStorageMixin::writeDataToDocument(const nlohmann::json& data)
+    {
+        writeDataToDocument(getDocumentName(), data);
+    }
+
+    nlohmann::json
+    MongoDBStorageMixin::readDataFromDocument() const
+    {
+        return readDataFromDocument(getDocumentName());
+    }
+
+    std::vector<nlohmann::json>
+    MongoDBStorageMixin::getAllDocuments() const
+    {
+        auto coll = collectionExists();
+        if (!coll)
+        {
+            return {};
+        }
+        return util::mongodb::getAllDocuments(*coll);
+    }
+
+    MongoDBSettings
+    MongoDBStorageMixin::getSettings() const
+    {
+        return settings;
+    }
+
+    void
+    MongoDBStorageMixin::setMixinMemoryID(const MemoryID& n)
+    {
+        ARMARX_CHECK_NOT_EMPTY(_id.memoryName) << " The full id was: " << _id.str();
+
+        _id = n;
+    }
+
+    void
+    MongoDBStorageMixin::setMixinExportName(const std::string& n)
+    {
+        exportName = n;
+    }
+
+    void
+    MongoDBStorageMixin::configureMixin(const nlohmann::json& json)
+    {
+    }
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.h
new file mode 100644
index 0000000000000000000000000000000000000000..ff605b45193947abf4f4aa53a2ed28f941dccc24
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/MongoDBStorageMixin.h
@@ -0,0 +1,125 @@
+#pragma once
+
+#include <atomic>
+#include <fstream>
+#include <map>
+#include <memory>
+#include <mutex>
+#include <sstream>
+#include <string>
+
+#include "util/mongodb.h"
+
+namespace armarx::armem::server::ltm::detail::mixin
+{
+    class MongoDBSettings
+    {
+    public:
+        std::string host = "";
+        unsigned int port = 0;
+        std::string user = "";
+        std::string password = "";
+        int minPoolSize = 5;
+        int maxPoolSize = 100;
+
+    public:
+        MongoDBSettings()
+        {
+            initializeFromArmarXConfig();
+        };
+
+        /// Fills missing fields from armarx config file
+        void initializeFromArmarXConfig();
+
+        bool isSet() const;
+
+        std::string baseUri() const;
+
+        std::string key() const;
+
+        std::string uri() const;
+
+        std::string toString() const;
+    };
+
+    class MongoDBStorageMixin
+    {
+    public:
+        MongoDBStorageMixin() = default;
+        MongoDBStorageMixin(const MongoDBSettings& settings,
+                            const std::string& exportName,
+                            const armem::MemoryID& id);
+
+        MongoDBSettings getSettings() const;
+
+        std::string getDocumentName() const;
+        std::string getCollectionName() const;
+        std::string getPreviousCollectionName() const;
+        std::string getDatabaseName() const;
+
+        std::optional<mongocxx::database> databaseExists() const;
+        std::optional<mongocxx::collection> collectionExists() const;
+        std::optional<mongocxx::collection> previousCollectionExists() const;
+        std::optional<nlohmann::json> documentExists() const;
+        std::optional<nlohmann::json> documentExists(const std::string& id) const;
+
+        mongocxx::database ensureDatabaseExists(bool createIfNotExistent = false);
+        mongocxx::collection ensureCollectionExists(bool createIfNotExistent = false);
+        mongocxx::collection ensurePreviousCollectionExists(bool createIfNotExistent = false);
+        nlohmann::json ensureDocumentExists(bool createIfNotExistent = false);
+        nlohmann::json ensureDocumentExists(const std::string& id,
+                                            bool createIfNotExistent = false);
+
+        void writeForeignKeyToPreviousDocument();
+        void writeForeignKeyToPreviousDocument(const nlohmann::json& type);
+
+        void writeDataToDocument(const nlohmann::json& data);
+        nlohmann::json readDataFromDocument() const;
+
+        void writeDataToDocument(const std::string& id, const nlohmann::json& data);
+        nlohmann::json readDataFromDocument(const std::string& id) const;
+
+        std::vector<nlohmann::json> getAllDocuments() const;
+
+    protected:
+        void connect() const;
+        bool connected() const;
+
+        /// setter
+        void setMixinMemoryID(const armem::MemoryID&);
+        void setMixinExportName(const std::string& n);
+        void setHost(const std::string&);
+        void setPort(const unsigned int);
+        void setUser(const std::string&);
+        void setPassword(const std::string&);
+
+        /// start
+        void start();
+        void stop();
+
+        /// configuration
+        void configureMixin(const nlohmann::json& json);
+
+    private:
+        mongocxx::pool* getPool(bool tryToConnect = true) const;
+        mongocxx::pool* ensurePool() const;
+
+    protected:
+        static const constexpr char* ID = "_id";
+        static const constexpr char* FOREIGN_KEY = "_foreign_key";
+        static const constexpr char* TYPE = "_type";
+        static const constexpr char* DATA = "_data";
+        static const constexpr char* METADATA = "_metadata";
+
+    private:
+        MongoDBSettings settings;
+        std::string exportName;
+        armem::MemoryID _id;
+
+        static std::unique_ptr<mongocxx::instance> MongoCXXInstance;
+        static std::atomic_bool MongoCXXInitialized;
+        static std::recursive_mutex MongoCXXConnectionPoolMutex;
+        static std::map<std::string, std::unique_ptr<mongocxx::pool>> MongoCXXConnectionPool;
+    };
+
+} // namespace armarx::armem::server::ltm::detail::mixin
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0b1f29b70126a7efdd303690e3cc111ba668a5ff
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.cpp
@@ -0,0 +1,226 @@
+#include "filesystem.h"
+
+#include <fstream>
+#include <iostream>
+
+#include <SimoxUtility/algorithm/string.h>
+
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+
+namespace armarx::armem::server::ltm ::util::fs
+{
+
+    namespace detail
+    {
+        std::string
+        escapeName(const std::string& segmentName)
+        {
+            std::string ret = segmentName;
+            //simox::alg::replace_all(ret, Prefix, PrefixEscaped);
+            for (const auto& [s, r] : EscapeTable)
+            {
+                ret = simox::alg::replace_all(ret, s, r);
+            }
+            return ret;
+        }
+
+        std::string
+        unescapeName(const std::string& escapedName)
+        {
+            std::string ret = escapedName;
+            for (
+                const auto& [s, r] :
+                EscapeTable) // Here we assume that noone uses the replaced char usually in the segment name... TODO
+            {
+                ret = simox::alg::replace_all(ret, r, s);
+            }
+            return ret;
+        }
+
+        std::string
+        toDayString(const Time& t)
+        {
+            return t.toDateString();
+        }
+
+        std::string
+        toSecondsString(const Time& t)
+        {
+            return std::to_string(t.toSecondsSinceEpoch());
+        }
+
+        bool
+        isNumberString(const std::string& s)
+        {
+            for (char const& ch : s)
+            {
+                if (std::isdigit(ch) == 0)
+                {
+                    return false;
+                }
+            }
+            return true;
+        }
+
+        bool
+        isDateString(const std::string& s)
+        {
+            auto split = simox::alg::split(s, "-");
+            if (split.size() != 3)
+            {
+                return false;
+            }
+
+            return isNumberString(split[0]) && isNumberString(split[1]) && isNumberString(split[2]);
+        }
+    } // namespace detail
+
+    std::filesystem::path
+    toPath(const std::filesystem::path& base, const armem::MemoryID& id)
+    {
+        ARMARX_CHECK(id.isWellDefined());
+
+        std::filesystem::path p = base;
+        if (id.hasMemoryName())
+        {
+            p /= detail::escapeName(id.memoryName);
+        }
+        if (id.hasCoreSegmentName())
+        {
+            p /= detail::escapeName(id.coreSegmentName);
+        }
+        if (id.hasProviderSegmentName())
+        {
+            p /= detail::escapeName(id.providerSegmentName);
+        }
+        if (id.hasEntityName())
+        {
+            p /= detail::escapeName(id.entityName);
+        }
+        if (id.hasTimestamp())
+        {
+            p /= detail::toDayString(id.timestamp);
+            p /= detail::toSecondsString(id.timestamp);
+            p /= id.timestampStr();
+        }
+        if (id.hasInstanceIndex())
+        {
+            p /= id.instanceIndexStr();
+        }
+
+        return p;
+    }
+
+    bool
+    directoryExists(const std::filesystem::path& p)
+    {
+        return std::filesystem::exists(p) and std::filesystem::is_directory(p);
+    }
+
+    bool
+    fileExists(const std::filesystem::path& p)
+    {
+        return std::filesystem::exists(p) && std::filesystem::is_regular_file(p);
+    }
+
+    void
+    ensureDirectoryExists(const std::filesystem::path& p, bool createIfNotExistent)
+    {
+        if (!directoryExists(p))
+        {
+            if (createIfNotExistent)
+            {
+                std::filesystem::create_directories(p);
+            }
+            else
+            {
+                throw armarx::LocalException("Directory existence cannot be ensured: " +
+                                             p.string());
+            }
+        }
+    }
+
+    void
+    ensureFileExists(const std::filesystem::path& p, bool createIfNotExistent)
+    {
+        ensureDirectoryExists(p.parent_path(), createIfNotExistent);
+        if (!fileExists(p))
+        {
+            if (createIfNotExistent)
+            {
+                std::string content = "";
+                writeDataToFile(p, {content.begin(), content.end()});
+            }
+            else
+            {
+                // not found
+                throw armarx::LocalException("Could not find file: " + p.string());
+            }
+        }
+    }
+
+    void
+    writeDataToFile(const std::filesystem::path& p, const std::vector<unsigned char>& data)
+    {
+        std::ofstream dataofs;
+        dataofs.open(p);
+        if (!dataofs)
+        {
+            throw armarx::LocalException("Could not write data to filesystem file '" + p.string() +
+                                         "'. Skipping this file.");
+        }
+        dataofs.write(reinterpret_cast<const char*>(data.data()), data.size());
+        dataofs.close();
+    }
+
+    std::vector<unsigned char>
+    readDataFromFile(const std::filesystem::path& p)
+    {
+        std::ifstream dataifs(p);
+        std::vector<unsigned char> datafilecontent((std::istreambuf_iterator<char>(dataifs)),
+                                                   (std::istreambuf_iterator<char>()));
+        dataifs.close();
+        return datafilecontent;
+    }
+
+    std::vector<std::filesystem::path>
+    getAllDirectories(const std::filesystem::path& p)
+    {
+        std::vector<std::filesystem::path> ret;
+        for (const auto& subdir : std::filesystem::directory_iterator(p))
+        {
+            std::filesystem::path subdirPath = subdir.path();
+            if (std::filesystem::is_directory(subdirPath))
+            {
+                ret.push_back(subdirPath);
+            }
+        }
+        std::sort(ret.begin(),
+                  ret.end(),
+                  [](const std::filesystem::path& a, const std::filesystem::path& b) -> bool
+                  { return a.string() > b.string(); });
+        return ret;
+    }
+
+    std::vector<std::filesystem::path>
+    getAllFiles(const std::filesystem::path& p)
+    {
+        std::vector<std::filesystem::path> ret;
+        for (const auto& subdir : std::filesystem::directory_iterator(p))
+        {
+            std::filesystem::path subdirPath = subdir.path();
+            if (std::filesystem::is_regular_file(subdirPath))
+            {
+                ret.push_back(subdirPath);
+            }
+        }
+        std::sort(ret.begin(),
+                  ret.end(),
+                  [](const std::filesystem::path& a, const std::filesystem::path& b) -> bool
+                  { return a.string() > b.string(); });
+        return ret;
+    }
+} // namespace armarx::armem::server::ltm::util::fs
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.h
new file mode 100644
index 0000000000000000000000000000000000000000..9b5b778cc7ee6b7466685537eebd07b5dfe08326
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/filesystem.h
@@ -0,0 +1,47 @@
+#pragma once
+
+#include <filesystem>
+#include <map>
+#include <string>
+#include <vector>
+
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+
+namespace armarx::armem::server::ltm::util::fs
+{
+    namespace detail
+    {
+        inline const std::map<std::string, std::string> EscapeTable = {{"/", "|"}};
+
+        std::string escapeName(const std::string& segmentName);
+
+        std::string unescapeName(const std::string& escapedName);
+
+        std::string toDayString(const Time& t);
+
+        std::string toSecondsString(const Time& t);
+
+        bool isNumberString(const std::string& s);
+
+        bool isDateString(const std::string& s);
+    } // namespace detail
+
+    std::filesystem::path toPath(const std::filesystem::path& base, const armem::MemoryID& id);
+
+    bool directoryExists(const std::filesystem::path& p);
+
+    bool fileExists(const std::filesystem::path& p);
+
+    void ensureDirectoryExists(const std::filesystem::path& p, bool createIfNotExistent = false);
+
+    void ensureFileExists(const std::filesystem::path& p, bool createIfNotExistent = false);
+
+    void writeDataToFile(const std::filesystem::path& p, const std::vector<unsigned char>& data);
+
+    std::vector<unsigned char> readDataFromFile(const std::filesystem::path& p);
+
+    std::vector<std::filesystem::path> getAllDirectories(const std::filesystem::path& p);
+
+    std::vector<std::filesystem::path> getAllFiles(const std::filesystem::path& p);
+
+} // namespace armarx::armem::server::ltm::util::fs
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.cpp b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e1024a0f6333dd1919f9cf2dd7f66336b293b906
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.cpp
@@ -0,0 +1,251 @@
+#include "mongodb.h"
+
+// Simox
+#include <SimoxUtility/json.h>
+
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/core/wm/aron_conversions.h>
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+namespace armarx::armem::server::ltm::util::mongodb
+{
+    namespace bbuilder = bsoncxx::builder;
+    namespace bdoc = bsoncxx::document;
+
+    namespace detail
+    {
+        std::string
+        escapeName(const std::string& segmentName)
+        {
+            std::string ret = segmentName;
+            //simox::alg::replace_all(ret, Prefix, PrefixEscaped);
+            for (const auto& [s, r] : EscapeTable)
+            {
+                ret = simox::alg::replace_all(ret, s, r);
+            }
+            return ret;
+        }
+
+        std::string
+        unescapeName(const std::string& escapedName)
+        {
+            std::string ret = escapedName;
+            for (
+                const auto& [s, r] :
+                EscapeTable) // Here we assume that noone uses the replaced char usually in the segment name... TODO
+            {
+                ret = simox::alg::replace_all(ret, r, s);
+            }
+            return ret;
+        }
+
+        bool
+        insert(mongocxx::collection& coll, const nlohmann::json& value)
+        {
+            std::string v = value.dump();
+            auto q = bsoncxx::from_json(v);
+            auto res = coll.insert_one(q.view());
+
+            return (bool)res;
+        }
+
+        std::optional<nlohmann::json>
+        contains(mongocxx::collection& coll, const nlohmann::json& value)
+        {
+            // check mongodb
+            std::string v = value.dump();
+            auto q = bsoncxx::from_json(v);
+            auto res = coll.find_one(q.view());
+            if (res)
+            {
+                return nlohmann::json::parse(bsoncxx::to_json(*res));
+            }
+            return std::nullopt;
+        }
+
+        bool
+        update(mongocxx::collection& coll,
+               const nlohmann::json& query,
+               const nlohmann::json& update)
+        {
+            // check mongodb
+            auto q = bsoncxx::from_json(query.dump());
+            auto udoc = bsoncxx::from_json(update.dump());
+            auto u = bbuilder::basic::make_document(bbuilder::basic::kvp("$set", udoc));
+
+            auto res = coll.update_one(q.view(), u.view());
+
+            return (bool)res;
+        }
+    } // namespace detail
+
+    std::optional<mongocxx::database>
+    databaseExists(mongocxx::client& client, const std::string& databaseName)
+    {
+        //auto names = client.list_databases();
+        //if (auto it = std::find(names.begin(), names.end(), databaseName); it != names.end())
+        //{
+        //    return client[databaseName];
+        //}
+        return std::nullopt;
+    }
+
+    mongocxx::database
+    ensureDatabaseExists(mongocxx::client& client,
+                         const std::string& databaseName,
+                         bool createIfNotExistent)
+    {
+        auto db = databaseExists(client, databaseName);
+        if (!db)
+        {
+            if (!createIfNotExistent)
+            {
+                throw armarx::LocalException("Database existence can not be ensured: " +
+                                             databaseName);
+            }
+        }
+        return client[databaseName];
+    }
+
+    std::optional<mongocxx::collection>
+    collectionExists(mongocxx::database& db, const std::string& collectionName)
+    {
+        if (db.has_collection(collectionName))
+        {
+            return db[collectionName];
+        }
+        return std::nullopt;
+    }
+
+    mongocxx::collection
+    ensureCollectionExists(mongocxx::database& db,
+                           const std::string& collectionName,
+                           bool createIfNotExistent)
+    {
+        auto coll = collectionExists(db, collectionName);
+        if (!coll)
+        {
+            if (!createIfNotExistent)
+            {
+                throw armarx::LocalException("Collection existence can not be ensured: " +
+                                             collectionName);
+            }
+        }
+        return db[collectionName];
+    }
+
+    std::string
+    toDocumentID(const armem::MemoryID& id)
+    {
+        if (id.hasTimestamp())
+        {
+            return id.timestampStr();
+        }
+
+        // fallback
+        throw armarx::LocalException("Called toDocumentName() on non-snapshot id: " + id.str());
+    }
+
+    std::string
+    toCollectionName(const armem::MemoryID& id)
+    {
+        ARMARX_CHECK(id.isWellDefined());
+        std::stringstream ss;
+        if (id.hasMemoryName())
+        {
+            ss << detail::escapeName(id.memoryName);
+        }
+        if (id.hasCoreSegmentName())
+        {
+            ss << "." << detail::escapeName(id.coreSegmentName);
+        }
+        if (id.hasProviderSegmentName())
+        {
+            ss << "." << detail::escapeName(id.providerSegmentName);
+        }
+        if (id.hasEntityName())
+        {
+            ss << "." << detail::escapeName(id.entityName);
+        }
+
+        return ss.str();
+    }
+
+    std::optional<nlohmann::json>
+    documentExists(mongocxx::collection& collection, const nlohmann::json& json)
+    {
+        return detail::contains(collection, json);
+    }
+
+    nlohmann::json
+    ensureDocumentExists(mongocxx::collection& collection,
+                         const nlohmann::json& json,
+                         bool createIfNotExistent)
+    {
+        auto op = documentExists(collection, json);
+        if (!op)
+        {
+            if (!createIfNotExistent)
+            {
+                throw armarx::LocalException("Document existence can not be ensured: " +
+                                             json.dump());
+            }
+        }
+
+        if (!op)
+        {
+            detail::insert(collection, json);
+        }
+
+        auto find = detail::contains(collection, json);
+        if (!find)
+        {
+            throw armarx::LocalException(
+                "Even after creating the docuemnt it wasnt found.. error: " + json.dump());
+        }
+        return *find;
+    }
+
+    nlohmann::json
+    readDataFromDocument(mongocxx::collection& collection, const nlohmann::json& json)
+    {
+        auto doc = detail::contains(collection, json);
+
+        ARMARX_CHECK((bool)doc) << " Could not find document matching: " << json.dump()
+                                << " in collection " << collection.name();
+
+        return *doc;
+    }
+
+    void
+    writeDataToDocument(mongocxx::collection& collection,
+                        const nlohmann::json& query,
+                        const nlohmann::json& update)
+    {
+        if (documentExists(collection, query))
+        {
+            detail::update(collection, query, update);
+        }
+        else
+        {
+            nlohmann::json full;
+            full.update(query);
+            full.update(update);
+            detail::insert(collection, full);
+        }
+    }
+
+    std::vector<nlohmann::json>
+    getAllDocuments(mongocxx::collection& collection)
+    {
+        std::vector<nlohmann::json> ret;
+        mongocxx::cursor cursor = collection.find({});
+        for (const auto& doc : cursor)
+        {
+            ret.push_back(
+                nlohmann::json::parse(bsoncxx::to_json(doc, bsoncxx::ExtendedJsonMode::k_relaxed)));
+        }
+        return ret;
+    }
+
+} // namespace armarx::armem::server::ltm::util::mongodb
diff --git a/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.h b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.h
new file mode 100644
index 0000000000000000000000000000000000000000..9908e6c5b7f379be2ab7207a28610183c87395f5
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/detail/mixins/util/mongodb.h
@@ -0,0 +1,74 @@
+#pragma once
+
+#include <map>
+#include <memory>
+#include <string>
+
+#include <SimoxUtility/json.h>
+
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+
+#include <bsoncxx/builder/stream/array.hpp>
+#include <bsoncxx/builder/stream/document.hpp>
+#include <bsoncxx/builder/stream/helpers.hpp>
+#include <bsoncxx/json.hpp>
+#include <mongocxx/client.hpp>
+#include <mongocxx/instance.hpp>
+#include <mongocxx/pool.hpp>
+#include <mongocxx/stdx.hpp>
+#include <mongocxx/uri.hpp>
+
+namespace armarx::armem::server::ltm::util::mongodb
+{
+
+    namespace detail
+    {
+        inline const std::map<std::string, std::string> EscapeTable = {{"/", "|"}};
+
+        std::string escapeName(const std::string& segmentName);
+
+        std::string unescapeName(const std::string& escapedName);
+
+        bool insert(mongocxx::collection& coll, const nlohmann::json& value);
+
+        std::optional<nlohmann::json> contains(mongocxx::collection& coll,
+                                               const nlohmann::json& value);
+
+        bool update(mongocxx::collection& coll,
+                    const nlohmann::json& query,
+                    const std::string& vkey,
+                    const nlohmann::json& vdata);
+    } // namespace detail
+
+    std::string toDocumentID(const armem::MemoryID&);
+    std::string toCollectionName(const armem::MemoryID&);
+
+    std::optional<mongocxx::database> databaseExists(mongocxx::client&,
+                                                     const std::string& databaseName);
+    mongocxx::database ensureDatabaseExists(mongocxx::client&,
+                                            const std::string& databaseName,
+                                            bool createIfNotExistent);
+
+    std::optional<mongocxx::collection> collectionExists(mongocxx::database&,
+                                                         const std::string& collectionName);
+    mongocxx::collection ensureCollectionExists(mongocxx::database&,
+                                                const std::string& collectionName,
+                                                bool createIfNotExistent);
+
+    std::optional<nlohmann::json> documentExists(mongocxx::collection& collection,
+                                                 const nlohmann::json& query);
+
+    nlohmann::json ensureDocumentExists(mongocxx::collection& collection,
+                                        const nlohmann::json& query,
+                                        bool createIfNotExistent = false);
+
+    nlohmann::json readDataFromDocument(mongocxx::collection& collection,
+                                        const nlohmann::json& query);
+
+    void writeDataToDocument(mongocxx::collection& collection,
+                             const nlohmann::json& query,
+                             const nlohmann::json& data);
+
+    std::vector<nlohmann::json> getAllDocuments(mongocxx::collection& collection);
+
+} // namespace armarx::armem::server::ltm::util::mongodb
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.cpp
deleted file mode 100644
index a6a7aa48e28f697254755e857df6c7c70ceb01e3..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.cpp
+++ /dev/null
@@ -1,166 +0,0 @@
-#include "CoreSegment.h"
-
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-
-
-namespace armarx::armem::server::ltm::disk
-{
-    CoreSegment::CoreSegment(const std::filesystem::path& p, const MemoryID& id /* UNESCAPED */, const std::shared_ptr<Processors>& filters, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e) :
-        CoreSegmentBase(id, filters),
-        DiskMemoryItem(p, EscapeSegmentName(id.memoryName), std::filesystem::path(EscapeSegmentName(id.coreSegmentName))),
-        currentMode(mode),
-        currentExport(e)
-    {
-    }
-
-    bool CoreSegment::forEachProviderSegment(std::function<void(ProviderSegment&)> func) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return false;
-        }
-
-        for (const auto& subdirName : util::getAllDirectories(mPath, relPath))
-        {
-            std::string segmentName = UnescapeSegmentName(subdirName);
-            ProviderSegment c(memoryParentPath, id().withProviderSegmentName(segmentName), processors, currentMode, currentExport);
-            func(c);
-        }
-        return true;
-    }
-
-    std::shared_ptr<ProviderSegment> CoreSegment::findProviderSegment(const std::string& providerSegmentName) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return nullptr;
-        }
-
-        auto c = std::make_shared<ProviderSegment>(memoryParentPath, id().withProviderSegmentName(providerSegmentName), processors, currentMode, currentExport);
-        if (!util::checkIfFolderExists(mPath, c->getRelativePathForMode(currentMode)))
-        {
-            return nullptr;
-        }
-
-        return c;
-    }
-
-    void CoreSegment::_loadAllReferences(armem::wm::CoreSegment& e)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        e.id() = id();
-
-        auto& conv = processors->defaultTypeConverter;
-        auto relTPath = relPath / (constantes::TYPE_FILENAME + conv.suffix);
-
-        if (util::checkIfFileExists(mPath, relTPath))
-        {
-            auto typeFileContent = util::readDataFromFile(mPath, relTPath);
-            auto typeAron = conv.convert(typeFileContent, "");
-            e.aronType() = aron::type::Object::DynamicCastAndCheck(typeAron);
-        }
-
-        forEachProviderSegment([&e](auto& x) {
-            armem::wm::ProviderSegment s;
-            x.loadAllReferences(s);
-            e.addProviderSegment(s);
-        });
-    }
-
-    void CoreSegment::_resolve(armem::wm::CoreSegment& c)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        c.forEachProviderSegment([&](auto& e)
-        {
-            ProviderSegment c(memoryParentPath, id().withProviderSegmentName(e.id().providerSegmentName), processors, currentMode, currentExport);
-            if (util::checkIfFolderExists(mPath, c.getRelativePathForMode(currentMode)))
-            {
-                c.resolve(e);
-            }
-        });
-    }
-
-    void CoreSegment::_store(const armem::wm::CoreSegment& c)
-    {
-        auto currentMaxExport = currentExport;
-        auto encodingModeOfPast = currentMode;
-
-        if (id().coreSegmentName.empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << c.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().coreSegmentName = c.id().coreSegmentName;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        c.forEachProviderSegment([&](const auto& prov)
-        {
-            ProviderSegment c(memoryParentPath, id().withProviderSegmentName(prov.id().providerSegmentName), processors, encodingModeOfPast, currentMaxExport);
-            util::ensureFolderExists(defaultMPath, c.getRelativePathForMode(defaultMode), true);
-
-            statistics.recordedProviderSegments++;
-
-            c.storeType(prov);
-            c.store(prov);
-        });
-    }
-
-    void CoreSegment::_storeType(const armem::wm::CoreSegment& c)
-    {
-        if (id().coreSegmentName.empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << c.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().coreSegmentName = c.id().coreSegmentName;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        if(c.hasAronType())
-        {
-            auto& conv = processors->defaultTypeConverter;
-
-            auto [vec, modeSuffix] = conv.convert(c.aronType());
-            ARMARX_CHECK_EMPTY(modeSuffix);
-            std::filesystem::path relTypePath = defaultRelPath / (constantes::TYPE_FILENAME + conv.suffix);
-            util::writeDataToFileRepeated(defaultMPath, relTypePath, vec);
-        }
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.h b/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.h
deleted file mode 100644
index 78ff8be3f12d35eeebbed370cc04559b37a57822..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/CoreSegment.h
+++ /dev/null
@@ -1,36 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-// Base Class
-#include "../base/detail/CoreSegmentBase.h"
-#include "detail/DiskStorage.h"
-
-#include "ProviderSegment.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    class CoreSegment :
-            public CoreSegmentBase<ProviderSegment>,
-            public DiskMemoryItem
-    {
-    public:
-
-        CoreSegment(const std::filesystem::path& parentPath, const MemoryID& id, const std::shared_ptr<Processors>& p, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e);
-
-        bool forEachProviderSegment(std::function<void(ProviderSegment&)> func) const override;
-
-        std::shared_ptr<ProviderSegment> findProviderSegment(const std::string&) const override;
-
-    protected:
-        void _loadAllReferences(armem::wm::CoreSegment&) override;
-        void _resolve(armem::wm::CoreSegment&) override;
-        void _store(const armem::wm::CoreSegment&) override;
-        void _storeType(const armem::wm::CoreSegment&) override;
-
-    private:
-        MemoryEncodingMode currentMode;
-        unsigned long currentExport;
-    };
-
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.cpp
deleted file mode 100644
index ea5ad1757f2d71e955d41a80a416a2c10474feb7..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.cpp
+++ /dev/null
@@ -1,372 +0,0 @@
-// Header
-#include "Entity.h"
-
-// ArmarX
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-
-#include <RobotAPI/libraries/armem/core/base/detail/negative_index_semantics.h>
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-
-#include "../base/filter/frequencyFilter/FrequencyFilter.h"
-
-
-namespace armarx::armem::server::ltm::disk
-{
-    Entity::Entity(const std::filesystem::path& p, const MemoryID& id, const std::shared_ptr<Processors>& filters, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e) :
-        EntityBase(id, filters),
-        DiskMemoryItem(p, EscapeSegmentName(id.memoryName), std::filesystem::path(EscapeSegmentName(id.coreSegmentName)) / EscapeSegmentName(id.providerSegmentName) / EscapeSegmentName(id.entityName)),
-        currentMode(mode),
-        currentExport(e)
-    {
-    }
-
-    bool Entity::forEachSnapshot(std::function<void(EntitySnapshot&)> func) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return false;
-        }
-
-        for (const auto& hName : util::getAllDirectories(mPath, relPath))
-        {
-            if (!util::isNumber(hName))
-            {
-                ARMARX_WARNING << "Found a non-timestamp folder inside an entity '" << id().str() << "' with name '" << hName << "'. " <<
-                                  "Ignoring this folder, however this is a bad situation.";
-                continue;
-            }
-
-            // check if this is already a microsec folder (legacy export support)
-            //if (std::stol(secName) > 1647524607 /* the time in us the new export was implemented */)
-            //{
-            //    EntitySnapshot c(memoryParentPath, id().withTimestamp(timeFromStringMicroSeconds(secName)), processors, currentMode, currentExport);
-            //    func(c);
-            //    continue;
-            //}
-
-            auto hRelPath = relPath / hName;
-            for (const auto& secName : util::getAllDirectories(mPath, hRelPath))
-            {
-                if (!util::isNumber(secName))
-                {
-                    ARMARX_WARNING << "Found a non-timestamp folder inside an entity '" << id().str() << "' with name '" << secName << "'. " <<
-                                      "Ignoring this folder, however this is a bad situation.";
-                    continue;
-                }
-
-                auto secRelPath = hRelPath / secName;
-                for (const auto& usecName : util::getAllDirectories(mPath, secRelPath))
-                {
-                    if (!util::isNumber(usecName))
-                    {
-                        ARMARX_WARNING << "Found a non-timestamp folder inside an entity '" << id().str() << "' with name '" << usecName << "'. " <<
-                                          "Ignoring this folder, however this is a bad situation.";
-                        continue;
-                    }
-
-
-                    EntitySnapshot c(memoryParentPath, id().withTimestamp(timeFromStringMicroSeconds(usecName)), processors, currentMode, currentExport);
-                    func(c);
-                }
-            }
-        }
-        return true;
-    }
-
-    bool Entity::forEachSnapshotInIndexRange(long first, long last, std::function<void(EntitySnapshot&)> func) const
-    {
-        //ARMARX_WARNING << "PLEASE NOTE THAT QUERYING THE LTM INDEX WISE MAY BE BUGGY BECAUSE THE FILESYSTEM ITERATOR IS UNSORTED!";
-
-        if (first < 0 or last < 0)
-        {
-            // We need to know what the size of the memory is... May be slow
-            unsigned long size = 0;
-            auto f = [&](EntitySnapshot& e)
-            {
-                size++;
-            };
-            forEachSnapshot(std::move(f));
-
-            first = armarx::armem::base::detail::negativeIndexSemantics(first, size);
-            last = armarx::armem::base::detail::negativeIndexSemantics(last, size);
-        }
-
-        long checked = 0;
-        auto f = [&](EntitySnapshot& e)
-        {
-            if (checked >= first && checked <= last)
-            {
-                func(e);
-            }
-            checked++;
-        };
-
-        return forEachSnapshot(std::move(f));
-    }
-
-    bool Entity::forEachSnapshotInTimeRange(const Time& min, const Time& max, std::function<void(EntitySnapshot&)> func) const
-    {
-        auto f = [&](EntitySnapshot& e)
-        {
-            auto ts = e.id().timestamp;
-            if (ts >= min && ts <= max)
-            {
-                func(e);
-            }
-        };
-
-        return forEachSnapshot(std::move(f));
-    }
-
-    bool Entity::forEachSnapshotBeforeOrAt(const Time& time, std::function<void(EntitySnapshot&)> func) const
-    {
-        auto f = [&](EntitySnapshot& e)
-        {
-            auto ts = e.id().timestamp;
-            if (ts <= time)
-            {
-                func(e);
-            }
-        };
-
-        return forEachSnapshot(std::move(f));
-    }
-
-    bool Entity::forEachSnapshotBefore(const Time& time, std::function<void(EntitySnapshot&)> func) const
-    {
-        auto f = [&](EntitySnapshot& e)
-        {
-            auto ts = e.id().timestamp;
-            if (ts < time)
-            {
-                func(e);
-            }
-        };
-
-        return forEachSnapshot(std::move(f));
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findSnapshot(const Time& n) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return nullptr;
-        }
-
-        auto c = std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(n), processors, currentMode, currentExport);
-        if (!util::checkIfFolderExists(mPath, c->getRelativePathForMode(currentMode)))
-        {
-            return nullptr;
-        }
-
-        return c;
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findLatestSnapshot() const
-    {
-        Time bestMatch = Time::Invalid();
-        auto f = [&](EntitySnapshot& e) {
-            auto ts = e.id().timestamp;
-            if (ts > bestMatch)
-            {
-                bestMatch = ts;
-            }
-        };
-
-        forEachSnapshot(std::move(f));
-
-        if (bestMatch == Time::Invalid())
-        {
-            return nullptr;
-        }
-
-        return std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(bestMatch), processors, currentMode, currentExport);
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findLatestSnapshotBefore(const Time& time) const
-    {
-        Time bestMatch = Time::Invalid();
-        auto f = [&](EntitySnapshot& e) {
-            auto ts = e.id().timestamp;
-            if (ts < time && ts > bestMatch)
-            {
-                bestMatch = ts;
-            }
-        };
-
-        forEachSnapshot(std::move(f));
-
-        if (bestMatch == Time::Invalid())
-        {
-            return nullptr;
-        }
-
-        return std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(bestMatch), processors, currentMode, currentExport);
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findLatestSnapshotBeforeOrAt(const Time& time) const
-    {
-        Time bestMatch = Time::Invalid();
-        auto f = [&](EntitySnapshot& e) {
-            auto ts = e.id().timestamp;
-            if (ts <= time && ts > bestMatch)
-            {
-                bestMatch = ts;
-            }
-        };
-
-        forEachSnapshot(std::move(f));
-
-        if (bestMatch == Time::Invalid())
-        {
-            return nullptr;
-        }
-
-        return std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(bestMatch), processors, currentMode, currentExport);
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findFirstSnapshotAfter(const Time& time) const
-    {
-        Time bestMatch { Duration::MicroSeconds(std::numeric_limits<long>::max()) };
-        auto f = [&](EntitySnapshot& e)
-        {
-            auto ts = e.id().timestamp;
-            if (ts > time && ts < bestMatch)
-            {
-                bestMatch = ts;
-            }
-        };
-
-        forEachSnapshot(std::move(f));
-
-        if (bestMatch == Time(Duration::MicroSeconds(std::numeric_limits<long>::max())))
-        {
-            return nullptr;
-        }
-
-        return std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(bestMatch), processors, currentMode, currentExport);
-    }
-
-    std::shared_ptr<EntitySnapshot> Entity::findFirstSnapshotAfterOrAt(const Time& time) const
-    {
-        Time bestMatch { Duration::MicroSeconds(std::numeric_limits<long>::max()) };
-        auto f = [&](EntitySnapshot& e)
-        {
-            auto ts = e.id().timestamp;
-            if (ts >= time && ts < bestMatch)
-            {
-                bestMatch = ts;
-            }
-        };
-
-        forEachSnapshot(std::move(f));
-
-        if (bestMatch == Time(Duration::MicroSeconds(std::numeric_limits<long>::max())))
-        {
-            return nullptr;
-        }
-
-        return std::make_shared<EntitySnapshot>(memoryParentPath, id().withTimestamp(bestMatch), processors, currentMode, currentExport);
-    }
-
-    void Entity::_loadAllReferences(armem::wm::Entity& e)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        e.id() = id();
-
-        forEachSnapshot([&e](auto& x)
-        {
-            if (!e.hasSnapshot(x.id().timestamp)) // we only load the references if the snapshot is not existant
-            {
-                armem::wm::EntitySnapshot s;
-                x.loadAllReferences(s);
-                e.addSnapshot(s);
-            }
-        });
-    }
-
-    void Entity::_resolve(armem::wm::Entity& p)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        p.forEachSnapshot([&](auto& e)
-        {
-            EntitySnapshot c(memoryParentPath, id().withTimestamp(e.id().timestamp), processors, currentMode, currentExport);
-            if (util::checkIfFolderExists(mPath, c.getRelativePathForMode(currentMode)))
-            {
-                c.resolve(e);
-            }
-        });
-    }
-
-    void Entity::_store(const armem::wm::Entity& c)
-    {
-        if (id().entityName.empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << c.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().entityName = c.id().entityName;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        c.forEachSnapshot([&](const auto& snap)
-        {
-            auto currentMaxExport = currentExport;
-            auto encodingModeOfPast = currentMode;
-
-            for (unsigned long i = 0; i < currentMaxExport; ++i)
-            {
-                MemoryEncodingMode mode = i == 0 ? defaultMode : encodingModeOfPast;
-                auto mPath = getMemoryBasePathForMode(mode, i);
-
-                EntitySnapshot c(memoryParentPath, id().withTimestamp(snap.id().timestamp), processors, mode, i);
-                if (util::checkIfFolderExists(mPath, c.getRelativePathForMode(mode)))
-                {
-                    ARMARX_INFO << deactivateSpam() << "Ignoring to put an EntitiySnapshot into the LTM because the timestamp already existed (we assume snapshots are const and do not change outside the ltm).";
-                    return;
-                }
-            }
-
-            for (auto& f : processors->snapFilters)
-            {
-                if (f->enabled && !f->accept(snap))
-                {
-                    ARMARX_INFO << deactivateSpam() << "Ignoring to put an EntitiySnapshot into the LTM because it got filtered.";
-                    return;
-                }
-            }
-
-            EntitySnapshot c(memoryParentPath, id().withTimestamp(snap.id().timestamp), processors, encodingModeOfPast, currentMaxExport);
-            util::ensureFolderExists(defaultMPath, c.getRelativePathForMode(defaultMode));
-
-            statistics.recordedSnapshots++;
-
-            c.store(snap);
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.h b/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.h
deleted file mode 100644
index 3d98ef1bf8abe315e005a110ad6fa807f373d7ba..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/Entity.h
+++ /dev/null
@@ -1,44 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-// Base Class
-#include "../base/detail/EntityBase.h"
-#include "detail/DiskStorage.h"
-
-#include "EntitySnapshot.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    /// @brief A memory storing data in mongodb (needs 'armarx memory start' to start the mongod instance)
-    class Entity :
-            public EntityBase<EntitySnapshot>,
-            public DiskMemoryItem
-    {
-    public:
-        Entity(const std::filesystem::path& parentPath, const MemoryID& id, const std::shared_ptr<Processors>& p, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e);
-
-        bool forEachSnapshot(std::function<void(EntitySnapshot&)> func) const override;
-        bool forEachSnapshotInIndexRange(long first, long last, std::function<void(EntitySnapshot&)> func) const override;
-        bool forEachSnapshotInTimeRange(const Time& min, const Time& max, std::function<void(EntitySnapshot&)> func) const override;
-        bool forEachSnapshotBeforeOrAt(const Time& time, std::function<void(EntitySnapshot&)> func) const override;
-        bool forEachSnapshotBefore(const Time& time, std::function<void(EntitySnapshot&)> func) const override;
-
-        std::shared_ptr<EntitySnapshot> findSnapshot(const Time&) const override;
-        std::shared_ptr<EntitySnapshot> findLatestSnapshot() const override;
-        std::shared_ptr<EntitySnapshot> findLatestSnapshotBefore(const Time& time) const override;
-        std::shared_ptr<EntitySnapshot> findLatestSnapshotBeforeOrAt(const Time& time) const override;
-        std::shared_ptr<EntitySnapshot> findFirstSnapshotAfter(const Time& time) const override;
-        std::shared_ptr<EntitySnapshot> findFirstSnapshotAfterOrAt(const Time& time) const override;
-
-    protected:
-        void _loadAllReferences(armem::wm::Entity&) override;
-        void _resolve(armem::wm::Entity&) override;
-        void _store(const armem::wm::Entity&) override;
-
-    private:
-        MemoryEncodingMode currentMode;
-        unsigned long currentExport;
-    };
-
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.cpp
deleted file mode 100644
index aea0141b662e58a1dda66b261ccec875bcdf0768..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.cpp
+++ /dev/null
@@ -1,229 +0,0 @@
-// Header
-#include "EntitySnapshot.h"
-
-// STD / STL
-#include <iostream>
-#include <fstream>
-
-// ArmarX
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
-
-namespace armarx::armem::server::ltm::disk
-{
-    EntitySnapshot::EntitySnapshot(const std::filesystem::path& p, const MemoryID& id /* UNESCAPED */, const std::shared_ptr<Processors>& filters, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e) :
-        EntitySnapshotBase(id, filters),
-        DiskMemoryItem(p, EscapeSegmentName(id.memoryName),
-                       std::filesystem::path(EscapeSegmentName(id.coreSegmentName))
-                       / EscapeSegmentName(id.providerSegmentName)
-                       / EscapeSegmentName(id.entityName)
-                       / std::to_string(id.timestamp.toSecondsSinceEpoch() / 3600 /* hours */)
-                       / std::to_string(id.timestamp.toSecondsSinceEpoch()) /* seconds */ / id.timestampStr()),
-        currentMode(mode),
-        currentExport(e)
-    {
-    }
-
-    void EntitySnapshot::_loadAllReferences(armem::wm::EntitySnapshot& e) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        e.id() = id();
-
-        for (unsigned int i = 0; i < 1000; ++i) // 1000 is max size for instances in a single timestamp
-        {
-            std::filesystem::path relIPath = relPath / std::to_string(i) / "";
-            if (!util::checkIfFolderExists(mPath, relIPath))
-            {
-                break;
-            }
-
-            // add instance. Do not set data, since we only return references
-            e.addInstance();
-        }
-    }
-
-    void EntitySnapshot::_resolve(armem::wm::EntitySnapshot& e) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        auto& dictConverter = processors->defaultObjectConverter;
-
-        // Get data from disk
-        for (unsigned int i = 0; i < e.size(); ++i)
-        {
-            std::filesystem::path relIPath = relPath / std::to_string(i) / "";
-            if (util::checkIfFolderExists(mPath, relIPath))
-            {
-                std::string dataFilename = (constantes::DATA_FILENAME + dictConverter.suffix);
-                std::string metadataFilename = (constantes::METADATA_FILENAME + dictConverter.suffix);
-                std::filesystem::path relDataPath = relIPath / dataFilename;
-                std::filesystem::path relMetadataPath = relIPath / metadataFilename;
-
-                auto& ins = e.getInstance(i);
-                aron::data::DictPtr datadict = nullptr;
-                aron::data::DictPtr metadatadict = nullptr;
-
-                // get list of all files. This ensures that we only have to call fs::exists once for each file
-                auto allFilesInIndexFolder = util::getAllFiles(mPath, relIPath);
-
-                if (std::find(allFilesInIndexFolder.begin(), allFilesInIndexFolder.end(), dataFilename) != allFilesInIndexFolder.end())
-                {
-                    //ARMARX_INFO << "Convert data for entity " << id();
-                    auto datafilecontent = util::readDataFromFile(mPath, relDataPath);
-                    auto dataaron = dictConverter.convert(datafilecontent, {}, "");
-                    datadict = aron::data::Dict::DynamicCastAndCheck(dataaron);
-
-                    // check for special members TODO: only allowed for direct children?
-                    for (const auto& [key, m] : datadict->getElements())
-                    {
-                        for (auto& [t, f] : processors->converters)
-                        {
-                            for (const auto& filename : allFilesInIndexFolder) // iterate over all files and search for matching ones
-                            {
-                                if (simox::alg::starts_with(filename, key) and simox::alg::ends_with(filename, f->suffix))
-                                {
-                                    std::filesystem::path relMemberPath = relIPath / filename;
-                                    std::string mode = simox::alg::remove_suffix(simox::alg::remove_prefix(filename, key), f->suffix);
-
-                                    auto memberfilecontent = util::readDataFromFile(mPath, relMemberPath);
-                                    auto memberaron = f->convert(memberfilecontent, armarx::aron::Path(datadict->getPath(), std::vector<std::string>{key}), mode);
-                                    datadict->setElement(key, memberaron);
-                                    break;
-                                }
-                            }
-                        }
-                    }
-                }
-                else
-                {
-                    ARMARX_ERROR << "Could not find the data file '" << relDataPath.string() << "'. Continuing without data.";
-                }
-
-                //ARMARX_INFO << "Convert metadata for entity " << id();
-                if (std::find(allFilesInIndexFolder.begin(), allFilesInIndexFolder.end(), metadataFilename) != allFilesInIndexFolder.end())
-                {
-                    auto metadatafilecontent = util::readDataFromFile(mPath, relMetadataPath);
-                    auto metadataaron = dictConverter.convert(metadatafilecontent, {}, "");
-                    metadatadict = aron::data::Dict::DynamicCastAndCheck(metadataaron);
-                }
-                else
-                {
-                    ARMARX_ERROR << "Could not find the metadata file '" << relMetadataPath.string() << "'. Continuing without metadata.";
-                }
-
-                from_aron(metadatadict, datadict, ins);
-            }
-            else
-            {
-                ARMARX_WARNING << "Could not find the index segment folder for segment '" << e.id().str() << "'.";
-            }
-        }
-    }
-
-    void EntitySnapshot::_store(const armem::wm::EntitySnapshot& e)
-    {
-        //auto currentMaxExport = currentExport;
-        //auto encodingModeOfPast = currentMode;
-
-        if (id().timestampStr().empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << e.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().timestamp = e.id().timestamp;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto& dictConverter = processors->defaultObjectConverter;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        for (unsigned int i = 0; i < e.size(); ++i)
-        {
-            std::filesystem::path defaultRelIPath = defaultRelPath / std::to_string(i) / "";
-
-            // For performance reasons we skip to check whether the index folder already exists somewhere.
-            // We already check if the ts exists on entity level.
-
-            if (!util::checkIfFolderExists(defaultMPath, defaultRelIPath))
-            {
-                util::ensureFolderExists(defaultMPath, defaultRelIPath);
-
-                std::filesystem::path relDataPath = defaultRelIPath / (constantes::DATA_FILENAME + dictConverter.suffix);
-                std::filesystem::path relMetadataPath = defaultRelIPath / (constantes::METADATA_FILENAME + dictConverter.suffix);
-
-                auto& ins = e.getInstance(i);
-
-                // data
-                auto dataAron = std::make_shared<aron::data::Dict>();
-                auto metadataAron = std::make_shared<aron::data::Dict>();
-                to_aron(metadataAron, dataAron, ins);
-
-                // check special members for special extractions
-                for (auto& x : processors->extractors)
-                {
-                    if (!x->enabled) continue;
-
-                    const auto& t = x->identifier;
-
-                    Converter* conv = nullptr; // find suitable converter
-                    for (const auto& [ct, c] : processors->converters)
-                    {
-                        if (!c->enabled) continue;
-                        if (t != ct) continue;
-                        conv = c;
-                    }
-
-                    if (conv)
-                    {
-                        auto dataExt = x->extract(dataAron);
-
-                        for (const auto& [memberName, var] : dataExt.extraction)
-                        {
-                            ARMARX_CHECK_NOT_NULL(var);
-
-                            auto [memberDataVec, memberDataModeSuffix] = conv->convert(var);
-                            std::filesystem::path relMemberPath = defaultRelIPath / (memberName + memberDataModeSuffix + conv->suffix);
-
-                            util::writeDataToFileRepeated(defaultMPath, relMemberPath, memberDataVec);
-                        }
-
-                        dataAron = dataExt.dataWithoutExtraction;
-                    }
-                    // else we could not convert the extracted data so it makes no sense to extract it at all...
-                }
-
-                // convert dict and metadata
-                auto [dataVec, dataVecModeSuffix] = dictConverter.convert(dataAron);
-                auto [metadataVec, metadataVecModeSuffix] = dictConverter.convert(metadataAron);
-                ARMARX_CHECK_EMPTY(dataVecModeSuffix);
-                ARMARX_CHECK_EMPTY(metadataVecModeSuffix);
-
-                statistics.recordedInstances++;
-
-                util::writeDataToFileRepeated(defaultMPath, relDataPath, dataVec);
-                util::writeDataToFileRepeated(defaultMPath, relMetadataPath, metadataVec);
-            }
-            // Ignore if the full index already exists. Actually this should not happen since the existence of the ts folder is checked on entity level
-        }
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.h b/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.h
deleted file mode 100644
index aa72ea3e12e82e7f5787af2649b09a9cc29f0109..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/EntitySnapshot.h
+++ /dev/null
@@ -1,29 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-// Base Class
-#include "../base/detail/EntitySnapshotBase.h"
-#include "detail/DiskStorage.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-
-    class EntitySnapshot :
-            public EntitySnapshotBase,
-            public DiskMemoryItem
-    {
-    public:
-        EntitySnapshot(const std::filesystem::path& parentPath, const MemoryID& id, const std::shared_ptr<Processors>& p, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e);
-
-    protected:
-        void _loadAllReferences(armem::wm::EntitySnapshot&) const override;
-        void _resolve(armem::wm::EntitySnapshot&) const override;
-        void _store(const armem::wm::EntitySnapshot&) override;
-
-    private:
-        MemoryEncodingMode currentMode;
-        unsigned long currentExport;
-    };
-
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.cpp
deleted file mode 100644
index 31f5bd8106a32172540db9692b166cdd7fb9d858..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.cpp
+++ /dev/null
@@ -1,221 +0,0 @@
-#include "Memory.h"
-
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-
-namespace armarx::armem::server::ltm::disk
-{
-    void Memory::configure(const nlohmann::json& json)
-    {
-        Base::configure(json);
-        if (json.find("Memory.memoryParentPath") != json.end())
-        {
-            memoryParentPath = std::filesystem::path(json.at("Memory.memoryParentPath"));
-        }
-        if (json.find("Memory.sizeToCompressDataInMegaBytes") != json.end())
-        {
-            sizeToCompressDataInMegaBytes = json.at("Memory.sizeToCompressDataInMegaBytes");
-        }
-    }
-
-    Memory::Memory() :
-        Memory(std::filesystem::path("/tmp/MemoryExport"), "Test")
-    {
-    }
-
-    Memory::Memory(const std::filesystem::path& p, const std::string& memoryName /* UNESCAPED */, const MemoryEncodingMode defaultEncodingMode) :
-        Base(MemoryID(memoryName, "")),
-        DiskMemoryItem(p, EscapeSegmentName(memoryName), ""),
-        defaultExportEncodingMode(defaultEncodingMode)
-    {
-    }
-
-    void Memory::setMemoryID(const MemoryID &id)
-    {
-        Base::setMemoryID(id);
-        escapedMemoryName = EscapeSegmentName(id.memoryName);
-    }
-    void Memory::setMemoryID(const MemoryID& id, const std::string& componentNameFallback)
-    {
-        MemoryID _id = id;
-        if (id.memoryName.empty())
-        {
-            ARMARX_WARNING << "ATTENTION: A memory id passed to some LTM is empty. Either you used the wrong setter (always use setMemoryName(..) before onInitComponent()) or you emptied the scenario parameter. Using a the component name as fallback.";
-            _id.memoryName = componentNameFallback;
-        }
-
-        setMemoryID(_id);
-    }
-
-    void Memory::init()
-    {
-        Base::init();
-
-        // Discover how many exports already exists
-        for (unsigned long i = 1; i < 10000; ++i)
-        {
-            std::filesystem::path exportPath = getMemoryBasePathForMode(defaultExportEncodingMode, i);
-            if (!std::filesystem::exists(exportPath))
-            {
-                break;
-            }
-            maxExportIndex = i;
-        }
-    }
-
-    bool Memory::forEachCoreSegment(std::function<void(CoreSegment&)> func) const
-    {
-        for (unsigned long i = 0; i <= maxExportIndex; ++i)
-        {
-            MemoryEncodingMode mode = i == 0 ? MemoryEncodingMode::FILESYSTEM : defaultExportEncodingMode;
-            auto mPath = getMemoryBasePathForMode(mode, i);
-
-            if (util::checkIfBasePathExists(mPath))
-            {
-                for (const auto& subdirName : util::getAllDirectories(mPath, getRelativePathForMode(mode)))
-                {
-                    std::string segmentName = UnescapeSegmentName(subdirName);
-                    CoreSegment c(memoryParentPath, id().withCoreSegmentName(segmentName), processors, mode, i);
-                    func(c);
-                }
-            }
-        }
-
-        return true;
-    }
-
-    std::shared_ptr<CoreSegment> Memory::findCoreSegment(const std::string& coreSegmentName) const
-    {
-        for (unsigned long i = 0; i <= maxExportIndex; ++i)
-        {
-            MemoryEncodingMode mode = i == 0 ? MemoryEncodingMode::FILESYSTEM : defaultExportEncodingMode;
-
-            auto mPath = getMemoryBasePathForMode(mode, i);
-            if (!util::checkIfBasePathExists(mPath))
-            {
-                continue;
-            }
-
-            auto c = std::make_shared<CoreSegment>(memoryParentPath, id().withCoreSegmentName(coreSegmentName), processors, mode, i);
-            if (!util::checkIfFolderExists(mPath, c->getRelativePathForMode(mode)))
-            {
-                continue;
-            }
-
-            return c;
-        }
-        return nullptr;
-    }
-
-    void Memory::_loadAllReferences(armem::wm::Memory& m)
-    {
-        m.id() = id();
-
-        forEachCoreSegment([&m](auto& x) {
-            armem::wm::CoreSegment s;
-            x.loadAllReferences(s);
-            m.addCoreSegment(s);
-        });
-    }
-
-    void Memory::_resolve(armem::wm::Memory& m)
-    {
-        std::lock_guard l(ltm_mutex); // we cannot load a memory multiple times simultaneously
-
-        for (unsigned long i = 0; i <= maxExportIndex; ++i)
-        {
-            MemoryEncodingMode mode = i == 0 ? MemoryEncodingMode::FILESYSTEM : defaultExportEncodingMode;
-
-            auto mPath = getMemoryBasePathForMode(mode, i);
-            if (!util::checkIfBasePathExists(mPath))
-            {
-                continue;
-            }
-
-            m.forEachCoreSegment([&](auto& e)
-            {
-                CoreSegment c(memoryParentPath, id().withCoreSegmentName(e.id().coreSegmentName), processors, mode, i);
-                if (util::checkIfFolderExists(mPath, c.getRelativePathForMode(mode)))
-                {
-                    c.resolve(e);
-                }
-            });
-        }
-    }
-
-    void Memory::_directlyStore(const armem::wm::Memory& memory)
-    {
-        std::lock_guard l(ltm_mutex); // we cannot store a memory multiple times simultaneously
-
-        MemoryEncodingMode defaultMode = MemoryEncodingMode::FILESYSTEM;
-        MemoryEncodingMode encodeModeOfPast = defaultExportEncodingMode;
-        // Storage will always be in filesystem mode!
-        // Somehow, minizip was not able to write data to images. It always created a folder named xyz.png without any data in it...
-        // Another problem is that storing data directly in compressed format will require a lot of time when the compressed file is big (>20MB)
-
-        if (id().memoryName.empty())
-        {
-            ARMARX_WARNING << "During storage of memory '" << memory.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            setMemoryID(memory.id());
-        }
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-
-        // Check if we have to compress the memory!
-        // See above mentioned issues with directly compressing the data. Therefore we store data in plain text and compress from time to time
-        // using system calls. Also increase the index of all old exports
-        auto size = filesystem::util::getSizeOfDirectory(defaultMPath);
-        //std::cout << "Current maxExportIndex is: " << maxExportIndex << std::endl;
-        if (size >= (sizeToCompressDataInMegaBytes * 1024 * 1024))
-        {
-            ARMARX_INFO << "Compressen of memory " + id().memoryName + " needed because the size of last export is " + std::to_string(size / 1024.f / 1024.f) + " (>= " + std::to_string(sizeToCompressDataInMegaBytes) + ")";
-
-            // increase index of old memories
-            for (unsigned long i = maxExportIndex; i >= 1; --i)
-            {
-                ARMARX_INFO << "Increasing the index of old compressed memory " + id().memoryName + " (" + std::to_string(i) + " to " + std::to_string(i+1) + ")";
-                auto exportPath = getMemoryBasePathForMode(encodeModeOfPast, i);
-                auto newExportPath = getMemoryBasePathForMode(encodeModeOfPast, i+1);
-                std::string moveCommand = "mv " + exportPath.string() + " " + newExportPath.string();
-                //std::cout << "Exec command: " << moveCommand << std::endl;
-                int ret = system(moveCommand.c_str());
-                (void) ret;
-            }
-
-            // zip away current export
-            ARMARX_INFO << "Compressing the last export of " + id().memoryName;
-            auto newExportPath = getMemoryBasePathForMode(encodeModeOfPast, 1); // 1 will be the new export
-            std::string zipCommand = "cd " + memoryParentPath.string() + " && zip -r " + newExportPath.string() + " " + escapedMemoryName;
-            //std::cout << "Exec command: " << zipCommand << std::endl;
-            int ret = system(zipCommand.c_str());
-            (void) ret;
-
-            // remove unzipped memory export
-            ARMARX_INFO << "Removing the last export of " + id().memoryName;
-            std::string rmCommand = "rm -r " + defaultMPath.string();
-            ret = system(rmCommand.c_str());
-            (void) ret;
-
-            maxExportIndex++;
-        }
-
-        util::ensureBasePathExists(defaultMPath, true); // create if not exists
-
-        memory.forEachCoreSegment([&](const auto& core)
-        {
-            CoreSegment c(memoryParentPath, id().withCoreSegmentName(core.id().coreSegmentName), processors, encodeModeOfPast, 0 /* how far to look back in past on enity level. For full lookup use maxExportIndex. */);
-            util::ensureFolderExists(defaultMPath, c.getRelativePathForMode(defaultMode), true); // create subfolder
-
-            statistics.recordedCoreSegments++;
-
-            // 1. store type
-            c.storeType(core);
-
-            // 2. store data
-            c.store(core);
-        });
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.h b/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.h
index afd3a09004eea72c406ebfea844ffa80b257fc84..2e9ec475d751139f6e6a9b509726f5334a5f39cb 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/disk/Memory.h
@@ -1,48 +1,10 @@
-#pragma once
-
-#include <filesystem>
-
-// Base Class
-#include <RobotAPI/libraries/armem/server/ltm/base/detail/BufferedMemoryBase.h>
-#include "detail/DiskStorage.h"
+// LEGACY INCLUDE
 
-// Segmnet Type
-#include "CoreSegment.h"
+#pragma once
 
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
 
-namespace armarx::armem::server::ltm::disk
+namespace armarx::armem::server::ltm
 {
-    /// @brief A memory storing data in mongodb (needs 'armarx memory start' to start the mongod instance)
-    class Memory :
-            public BufferedMemoryBase<CoreSegment>,
-            public DiskMemoryItem
-    {
-    public:
-        using Base = BufferedMemoryBase<CoreSegment>;
-
-        Memory();
-        Memory(const std::filesystem::path&, const std::string&, const MemoryEncodingMode defaultEncodingMode = MemoryEncodingMode::MINIZIP);
-
-        void init() final;
-        void setMemoryID(const MemoryID& id) final;
-        void setMemoryID(const MemoryID& id, const std::string& fallback);
-
-        void configure(const nlohmann::json& config) final;
-
-        bool forEachCoreSegment(std::function<void(CoreSegment&)> func) const final;
-        std::shared_ptr<CoreSegment> findCoreSegment(const std::string& coreSegmentName) const final;
-
-    protected:
-        void _loadAllReferences(armem::wm::Memory&) final;
-        void _resolve(armem::wm::Memory&) final;
-        void _directlyStore(const armem::wm::Memory&) final;
-
-    private:
-        MemoryEncodingMode defaultExportEncodingMode = MemoryEncodingMode::MINIZIP;
-        unsigned long maxExportIndex = 0;
-        unsigned long sizeToCompressDataInMegaBytes = long(1) * 1024; // 1GB
 
-    public:
-        static const int DEPTH_TO_DATA_FILES = 7; // from memory folder = 1 (cseg) + 1 (pseg) + 1 (ent) + 3 (snap) + 1 (inst)
-    };
-} // namespace armarx::armem::server::ltm::disk
+}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.cpp
deleted file mode 100644
index 631461f464f25977fddbb518c9332bc51e273ce9..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.cpp
+++ /dev/null
@@ -1,167 +0,0 @@
-// Header
-#include "ProviderSegment.h"
-
-// ArmarX
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
-
-
-namespace armarx::armem::server::ltm::disk
-{
-    ProviderSegment::ProviderSegment(const std::filesystem::path& p, const MemoryID& id /* UNESCAPED */, const std::shared_ptr<Processors>& filters, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e) :
-        ProviderSegmentBase(id, filters),
-        DiskMemoryItem(p, EscapeSegmentName(id.memoryName), std::filesystem::path(EscapeSegmentName(id.coreSegmentName)) / EscapeSegmentName(id.providerSegmentName)),
-        currentMode(mode),
-        currentExport(e)
-    {
-    }
-
-    bool ProviderSegment::forEachEntity(std::function<void(Entity&)> func) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return false;
-        }
-
-        for (const auto& subdirName : util::getAllDirectories(mPath, relPath))
-        {
-            std::string segmentName = UnescapeSegmentName(subdirName);
-            Entity c(memoryParentPath, id().withEntityName(segmentName), processors, currentMode, currentExport);
-            func(c);
-        }
-        return true;
-    }
-
-    std::shared_ptr<Entity> ProviderSegment::findEntity(const std::string& entityName) const
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return nullptr;
-        }
-
-        auto c = std::make_shared<Entity>(memoryParentPath, id().withEntityName(entityName), processors, currentMode, currentExport);
-        if (!util::checkIfFolderExists(mPath, c->getRelativePathForMode(currentMode)))
-        {
-            return nullptr;
-        }
-
-        return c;
-    }
-
-    void ProviderSegment::_loadAllReferences(armem::wm::ProviderSegment& e)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        e.id() = id();
-
-        auto& conv = processors->defaultTypeConverter;
-        auto relTPath = relPath / (constantes::TYPE_FILENAME + conv.suffix);
-
-        if (util::checkIfFileExists(mPath, relTPath))
-        {
-            auto typeFileContent = util::readDataFromFile(mPath, relTPath);
-            auto typeAron = conv.convert(typeFileContent, "");
-            e.aronType() = aron::type::Object::DynamicCastAndCheck(typeAron);
-        }
-
-        forEachEntity([&e](auto& x) {
-            armem::wm::Entity s;
-            x.loadAllReferences(s);
-            e.addEntity(s);
-        });
-    }
-
-    void ProviderSegment::_resolve(armem::wm::ProviderSegment& p)
-    {
-        auto mPath = getMemoryBasePathForMode(currentMode, currentExport);
-        auto relPath = getRelativePathForMode(currentMode);
-        if (!util::checkIfBasePathExists(mPath) || !util::checkIfFolderExists(mPath, relPath))
-        {
-            return;
-        }
-
-        p.forEachEntity([&](auto& e)
-        {
-            Entity c(memoryParentPath, id().withEntityName(e.id().entityName), processors, currentMode, currentExport);
-            if (util::checkIfFolderExists(mPath, c.getRelativePathForMode(currentMode)))
-            {
-                c.resolve(e);
-            }
-        });
-    }
-
-    void ProviderSegment::_store(const armem::wm::ProviderSegment& p)
-    {
-        auto currentMaxExport = currentExport;
-        auto encodingModeOfPast = currentMode;
-
-        if (id().providerSegmentName.empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << p.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().providerSegmentName = p.id().providerSegmentName;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        p.forEachEntity([&](const auto& e)
-        {
-            Entity c(memoryParentPath, id().withEntityName(e.id().entityName), processors, encodingModeOfPast, currentMaxExport);
-            util::ensureFolderExists(defaultMPath, c.getRelativePathForMode(defaultMode), true);
-
-            statistics.recordedEntities++;
-
-            c.store(e);
-        });
-    }
-
-    void ProviderSegment::_storeType(const armem::wm::ProviderSegment& p)
-    {
-        if (id().providerSegmentName.empty())
-        {
-            ARMARX_WARNING << "During storage of segment '" << p.id().str() << "' I noticed that the corresponding LTM has no id set. " <<
-                              "I set the id of the LTM to the same name, however this should not happen!";
-            id().providerSegmentName = p.id().providerSegmentName;
-        }
-
-        auto defaultMode = MemoryEncodingMode::FILESYSTEM;
-
-        auto defaultMPath = getMemoryBasePathForMode(defaultMode, 0);
-        auto defaultRelPath = getRelativePathForMode(defaultMode);
-        if (!util::checkIfFolderExists(defaultMPath, defaultRelPath))
-        {
-            ARMARX_WARNING << "The segment folder for segment '"+id().str()+"'was not created. I will create the folder by myself, however it seems like there is a bug in the ltm pipeline.";
-            util::ensureFolderExists(defaultMPath, defaultRelPath, true);
-        }
-
-        if(p.hasAronType())
-        {
-            auto& conv = processors->defaultTypeConverter;
-
-            auto [vec, modeSuffix] = conv.convert(p.aronType());
-            ARMARX_CHECK_EMPTY(modeSuffix);
-            std::filesystem::path relTypePath = defaultRelPath / (constantes::TYPE_FILENAME + conv.suffix);
-            util::writeDataToFileRepeated(defaultMPath, relTypePath, vec);
-        }
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.h b/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.h
deleted file mode 100644
index dfa7c42714310a042dc344c043794eca4536ea00..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/ProviderSegment.h
+++ /dev/null
@@ -1,35 +0,0 @@
-#pragma once
-
-#include <filesystem>
-
-// Base Class
-#include "../base/detail/ProviderSegmentBase.h"
-#include "detail/DiskStorage.h"
-
-#include "Entity.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    class ProviderSegment :
-            public ProviderSegmentBase<Entity>,
-            public DiskMemoryItem
-    {
-    public:
-        ProviderSegment(const std::filesystem::path& parentPath, const MemoryID& id, const std::shared_ptr<Processors>& p, const DiskMemoryItem::MemoryEncodingMode mode, const unsigned long e);
-
-        bool forEachEntity(std::function<void(Entity&)> func) const override;
-
-        std::shared_ptr<Entity> findEntity(const std::string&) const override;
-
-    protected:
-        void _loadAllReferences(armem::wm::ProviderSegment&) override;
-        void _resolve(armem::wm::ProviderSegment&) override;
-        void _store(const armem::wm::ProviderSegment&) override;
-        void _storeType(const armem::wm::ProviderSegment&) override;
-
-    private:
-        MemoryEncodingMode currentMode;
-        unsigned long currentExport;
-    };
-
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.cpp
deleted file mode 100644
index 284f289842b88c888195ac4ac8f5d48a196e9a66..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.cpp
+++ /dev/null
@@ -1,79 +0,0 @@
-// Header
-#include "DiskStorage.h"
-
-// Simox
-#include <SimoxUtility/algorithm/string.h>
-
-// ArmarX
-#include <ArmarXCore/core/time/TimeUtil.h>
-#include <ArmarXCore/core/logging/Logging.h>
-#include <ArmarXCore/core/exceptions/LocalException.h>
-
-namespace armarx::armem::server::ltm::disk
-{
-    //const std::string DiskMemoryItem::Prefix = "_";
-    //const std::string DiskMemoryItem::PrefixEscaped = "__";
-
-    const std::string DiskMemoryItem::MEMORY_EXPORT_SUFFIX = "_";
-    const std::map<std::string, std::string> DiskMemoryItem::EscapeTable = {
-        {"/", "|"}
-    };
-
-    DiskMemoryItem::DiskMemoryItem(const std::filesystem::path& memoryParentPath, const std::string& memoryName, const std::filesystem::path relativePath) :
-        memoryParentPath(memoryParentPath),
-        escapedMemoryName(memoryName),
-        relativeSegmentPath(relativePath)
-    {
-    }
-
-    std::filesystem::path DiskMemoryItem::getMemoryBasePathForMode(const MemoryEncodingMode m, const unsigned long e) const
-    {
-        std::string escapedMemoryNameSuffixed = escapedMemoryName;
-        if (e > 0)
-        {
-            escapedMemoryNameSuffixed = escapedMemoryName + MEMORY_EXPORT_SUFFIX + std::to_string(e);
-        }
-
-        switch(m)
-        {
-        case MemoryEncodingMode::FILESYSTEM:
-            return memoryParentPath / escapedMemoryNameSuffixed;
-        case MemoryEncodingMode::MINIZIP:
-            return memoryParentPath / (escapedMemoryNameSuffixed + minizip::util::MINIZIP_SUFFIX);
-        }
-        return "";
-    }
-
-    std::filesystem::path DiskMemoryItem::getRelativePathForMode(const MemoryEncodingMode m) const
-    {
-        switch(m)  // ensure a tailing "/"
-        {
-        case MemoryEncodingMode::FILESYSTEM:
-            return relativeSegmentPath / "";
-        case MemoryEncodingMode::MINIZIP:
-            return std::filesystem::path(escapedMemoryName) / relativeSegmentPath / "";
-        }
-        return "";
-    }
-
-    std::string DiskMemoryItem::EscapeSegmentName(const std::string& segmentName)
-    {
-        std::string ret = segmentName;
-        //simox::alg::replace_all(ret, Prefix, PrefixEscaped);
-        for (const auto& [s, r] : EscapeTable)
-        {
-            ret = simox::alg::replace_all(ret, s, r);
-        }
-        return ret;
-    }
-
-    std::string DiskMemoryItem::UnescapeSegmentName(const std::string& escapedName)
-    {
-        std::string ret = escapedName;
-        for (const auto& [s, r] : EscapeTable) // Here we assume that noone uses the replaced char usually in the segment name... TODO
-        {
-            ret = simox::alg::replace_all(ret, r, s);
-        }
-        return ret;
-    }
-}
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.h b/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.h
deleted file mode 100644
index e4bc43b0b173908bdcc471b4033145cf5fdfd63a..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/DiskStorage.h
+++ /dev/null
@@ -1,42 +0,0 @@
-#pragma once
-
-#include <filesystem>
-#include <map>
-#include <string>
-
-// util
-#include "util/util.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    class DiskMemoryItem
-    {
-    public:
-        enum class MemoryEncodingMode
-        {
-            FILESYSTEM = 0,
-            MINIZIP = 1
-        };
-
-        DiskMemoryItem() = default;
-        DiskMemoryItem(const std::filesystem::path& memoryParentPath, const std::string& escapedMemoryName, const std::filesystem::path relativePath);
-        virtual ~DiskMemoryItem() = default;
-
-        std::filesystem::path getMemoryBasePathForMode(const MemoryEncodingMode m, const unsigned long e) const;
-        std::filesystem::path getRelativePathForMode(const MemoryEncodingMode m) const;
-
-    protected:
-        static std::string EscapeSegmentName(const std::string& segmentName);
-        static std::string UnescapeSegmentName(const std::string& escapedName);
-
-    protected:
-        //static const std::string PREFIX;
-        //static const std::string PREFIX_ESCAPED;
-        static const std::string MEMORY_EXPORT_SUFFIX;
-        static const std::map<std::string, std::string> EscapeTable;
-
-        std::filesystem::path memoryParentPath;
-        std::string escapedMemoryName;
-        std::filesystem::path relativeSegmentPath;
-    };
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.cpp b/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.cpp
deleted file mode 100644
index 2995afc21cba2caa75e5dc093398b900bb81e819..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.cpp
+++ /dev/null
@@ -1,276 +0,0 @@
-#include "minizip_util.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    namespace minizip::util
-    {
-        bool checkZipFile(const std::filesystem::path& pathToZip)
-        {
-            bool ret = false;
-            zipFile z = NULL;
-            if (std::filesystem::exists(pathToZip))
-            {
-                if (std::filesystem::is_regular_file(pathToZip) && pathToZip.extension() == MINIZIP_SUFFIX)
-                {
-                    z = zipOpen64(pathToZip.string().c_str(), APPEND_STATUS_ADDINZIP);
-                    ret = (bool) z;
-                    zipClose(z, NULL);
-                }
-            }
-            return ret;
-        }
-
-        zipFile ensureZipFile(const std::filesystem::path& pathToZip, bool createIfNotExistent)
-        {
-            zipFile z = NULL;
-            if (!checkZipFile(pathToZip))
-            {
-                if (createIfNotExistent)
-                {
-                    z = zipOpen64(pathToZip.string().c_str(), APPEND_STATUS_CREATE);
-                }
-                else
-                {
-                    throw error::ArMemError("Could not find zip file: " + pathToZip.string());
-                }
-            }
-            else
-            {
-                z = zipOpen64(pathToZip.string().c_str(), APPEND_STATUS_ADDINZIP);
-            }
-
-            if (!z)
-            {
-                throw error::ArMemError("Unknown error occured during opening zip file: " + pathToZip.string());
-            }
-            return z;
-        }
-
-        unzFile getUnzFile(const std::filesystem::path& pathToZip)
-        {
-            unzFile z = NULL;
-            if (std::filesystem::exists(pathToZip))
-            {
-                if (std::filesystem::is_regular_file(pathToZip) && pathToZip.extension() == MINIZIP_SUFFIX)
-                {
-                    z = unzOpen64(pathToZip.string().c_str());
-                }
-                else
-                {
-                    throw error::ArMemError("Existing file is not a zip file: " + pathToZip.string());
-                }
-            }
-
-            // if z is NULL then the zip file might be empty
-
-            return z;
-        }
-
-        bool checkIfElementInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p)
-        {
-            if (!checkZipFile(pathToZip)) return false;
-            auto uzf = getUnzFile(pathToZip);
-
-            bool ret = (unzLocateFile(uzf, p.string().c_str(), MINIZIP_CASE_SENSITIVITY) == UNZ_OK);
-
-            unzClose(uzf);
-            return ret;
-        }
-
-        void ensureElementInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p, bool createIfNotExistent)
-        {
-            auto zf = ensureZipFile(pathToZip, createIfNotExistent);
-            auto uzf = getUnzFile(pathToZip);
-
-            if (auto r = unzLocateFile(uzf, p.string().c_str(), MINIZIP_CASE_SENSITIVITY); r != UNZ_OK)
-            {
-                if (createIfNotExistent)
-                {
-                    zip_fileinfo zfi;
-                    zipOpenNewFileInZip64(zf, p.string().c_str(), &zfi, NULL, 0, NULL, 0, NULL, Z_DEFLATED, Z_DEFAULT_COMPRESSION, 1);
-                    zipCloseFileInZip(zf);
-                }
-                else
-                {
-                    unzClose(uzf);
-                    zipClose(zf, NULL);
-                    throw error::ArMemError("Could not find element '" + p.string() + "' in zip file: " + pathToZip.string());
-                }
-            }
-            // else folder exists
-
-            unzClose(uzf);
-            zipClose(zf, NULL);
-        }
-
-        void ensureFolderInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p, bool createIfNotExistent)
-        {
-            if (!p.filename().empty())
-            {
-                throw error::ArMemError("The specified path is not a folder (it needs tailing /): " + p.string());
-            }
-
-            ensureElementInZipExists(pathToZip, p, createIfNotExistent);
-        }
-
-        void ensureFileInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p)
-        {
-            if (p.filename().empty())
-            {
-                throw error::ArMemError("The specified path is not a file (it needs a filename): " + p.string());
-            }
-
-            ensureElementInZipExists(pathToZip, p, true);
-        }
-
-        bool checkIfFolderInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p)
-        {
-            if (!p.filename().empty())
-            {
-                throw error::ArMemError("The specified path is not a folder (it needs tailing /): " + p.string());
-            }
-
-            return checkIfElementInZipExists(pathToZip, p);
-        }
-
-        bool checkIfFileInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p)
-        {
-            if (p.filename().empty())
-            {
-                throw error::ArMemError("The specified path is not a file (it needs a filename): " + p.string());
-            }
-
-            return checkIfElementInZipExists(pathToZip, p);
-        }
-
-        void writeDataInFileInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path& p, const std::vector<unsigned char>& data)
-        {
-            auto zf = ensureZipFile(pathToZip);
-
-            zip_fileinfo zfi;
-            if(zipOpenNewFileInZip64(zf, p.string().c_str(), &zfi, NULL, 0, NULL, 0, NULL, Z_DEFLATED, Z_DEFAULT_COMPRESSION, 1) == Z_OK)
-            {
-                if(zipWriteInFileInZip(zf, data.data(), data.size()) != Z_OK)
-                {
-                    throw error::ArMemError("Could not write a file '"+p.string()+"' to zip '" + pathToZip.string() + "'.");
-                }
-            }
-            else
-            {
-                throw error::ArMemError("Could not add a new file '"+p.string()+"' to zip '" + pathToZip.string() + "'.");
-            }
-            zipCloseFileInZip(zf);
-            zipClose(zf, NULL);
-        }
-
-        std::vector<unsigned char> readDataFromFileInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path& p)
-        {
-            auto uzf = getUnzFile(pathToZip);
-            if (unzLocateFile(uzf, p.string().c_str(), MINIZIP_CASE_SENSITIVITY) == UNZ_OK) // set current file
-            {
-                // File located
-                unz_file_info uzfi;
-                if (unzGetCurrentFileInfo(uzf, &uzfi, NULL, 0, NULL, 0, NULL, 0) == UNZ_OK)
-                {
-                    std::vector<unsigned char> data(uzfi.uncompressed_size);
-
-                    if (unzOpenCurrentFile(uzf) == UNZ_OK) // open current file
-                    {
-                        if (unzReadCurrentFile(uzf, data.data(), uzfi.uncompressed_size) == UNZ_OK) // read file in buffer
-                        {
-                            unzCloseCurrentFile(uzf);
-                            unzClose(uzf);
-                            return data;
-                        }
-                    }
-                }
-            }
-            unzClose(uzf);
-            throw error::ArMemError("Could not read data from zip file '" + pathToZip.string() + "' and internal path '" + p.string() + "'.");
-        }
-
-        std::vector<std::string> getAllDirectoriesInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path p)
-        {
-            std::vector<std::string> ret;
-
-            unzFile uzf = getUnzFile(pathToZip);
-            if (unzLocateFile(uzf, p.string().c_str(), MINIZIP_CASE_SENSITIVITY) == UNZ_OK) // set current file
-            {
-                while(unzGoToNextFile(uzf) == UNZ_OK)
-                {
-                    unz_file_info uzfi;
-                    unzGetCurrentFileInfo(uzf, &uzfi, NULL, 0, NULL, 0, NULL, 0); // get file info
-                    std::vector<char> filenameVec(uzfi.size_filename);
-                    unzGetCurrentFileInfo(uzf, NULL, filenameVec.data(), uzfi.size_filename, NULL, 0, NULL, 0); // get file name
-                    std::string filename(filenameVec.begin(), filenameVec.end());
-
-                    auto pString = p.string();
-                    if (!simox::alg::starts_with(filename, pString))
-                    {
-                        // we moved out of the folder. Abort
-                        break;
-                    }
-
-                    std::string filenameWithoutPrefix = simox::alg::remove_prefix(filename, pString);
-
-                    if (!simox::alg::ends_with(filenameWithoutPrefix, "/"))
-                    {
-                        // this is not a directory
-                        continue;
-                    }
-
-                    if (simox::alg::count(filenameWithoutPrefix, "/") != 1)
-                    {
-                        // we are in a subfolder of the subfolder
-                        continue;
-                    }
-
-                    ret.push_back(filenameWithoutPrefix);
-                }
-            }
-            return ret;
-        }
-
-        std::vector<std::string> getAllFilesInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path p)
-        {
-            std::vector<std::string> ret;
-
-            unzFile uzf = getUnzFile(pathToZip);
-            if (unzLocateFile(uzf, p.string().c_str(), MINIZIP_CASE_SENSITIVITY) == UNZ_OK) // set current file
-            {
-                while(unzGoToNextFile(uzf) == UNZ_OK)
-                {
-                    unz_file_info uzfi;
-                    unzGetCurrentFileInfo(uzf, &uzfi, NULL, 0, NULL, 0, NULL, 0); // get file info
-                    std::vector<char> filenameVec(uzfi.size_filename);
-                    unzGetCurrentFileInfo(uzf, NULL, filenameVec.data(), uzfi.size_filename, NULL, 0, NULL, 0); // get file name
-                    std::string filename(filenameVec.begin(), filenameVec.end());
-
-                    auto pString = p.string();
-                    if (!simox::alg::starts_with(filename, pString))
-                    {
-                        // we moved out of the folder. Abort
-                        break;
-                    }
-
-                    std::string filenameWithoutPrefix = simox::alg::remove_prefix(filename, pString);
-
-                    if (simox::alg::ends_with(filenameWithoutPrefix, "/"))
-                    {
-                        // this is a directory
-                        continue;
-                    }
-
-                    if (simox::alg::count(filenameWithoutPrefix, "/") != 1)
-                    {
-                        // we are in a subfolder of the subfolder
-                        continue;
-                    }
-
-                    ret.push_back(filenameWithoutPrefix);
-                }
-            }
-            return ret;
-        }
-    }
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.h b/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.h
deleted file mode 100644
index 99ebab93572afd50cccb194c1aa827635a6c585d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/minizip_util.h
+++ /dev/null
@@ -1,47 +0,0 @@
-#pragma once
-
-// STD / STL
-#include <filesystem>
-#include <iostream>
-
-#include <minizip/zip.h>
-#include <minizip/unzip.h>
-
-#include <SimoxUtility/algorithm/string.h>
-
-#include "../../../../../core/error.h"
-
-namespace armarx::armem::server::ltm::disk
-{
-    namespace minizip::util
-    {
-        const std::string MINIZIP_SUFFIX = ".zip";
-        const int MINIZIP_CASE_SENSITIVITY = 1;
-
-        bool checkZipFile(const std::filesystem::path& pathToZip);
-
-        zipFile ensureZipFile(const std::filesystem::path& pathToZip, bool createIfNotExistent = true);
-
-        unzFile getUnzFile(const std::filesystem::path& pathToZip);
-
-        bool checkIfElementInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p);
-
-        void ensureElementInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p, bool createIfNotExistent = true);
-
-        void ensureFolderInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p, bool createIfNotExistent = true);
-
-        void ensureFileInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p);
-
-        bool checkIfFolderInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p);
-
-        bool checkIfFileInZipExists(const std::filesystem::path& pathToZip, const std::filesystem::path& p);
-
-        void writeDataInFileInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path& p, const std::vector<unsigned char>& data);
-
-        std::vector<unsigned char> readDataFromFileInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path& p);
-
-        std::vector<std::string> getAllDirectoriesInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path p);
-
-        std::vector<std::string> getAllFilesInZipFile(const std::filesystem::path& pathToZip, const std::filesystem::path p);
-    }
-} // namespace armarx::armem::server::ltm::disk
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/filesystem_util.cpp b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/filesystem_util.cpp
similarity index 96%
rename from source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/filesystem_util.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/filesystem_util.cpp
index 1a40e26a04923bccb123b4b07f00ab9be190efa9..d3b307eab0c5bb8cc9b8487d7429fc46ab2a76a6 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/filesystem_util.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/filesystem_util.cpp
@@ -118,4 +118,5 @@ namespace armarx::armem::server::ltm::disk
             return ret;
         }
     }
-} // namespace armarx::armem::server::ltm::disk
+} // namespace armarx::armem::server::ltm::diskfile:///home/fabian/code/armarx/RobotAPI/source/RobotAPI/libraries/armem/server/ltm/legacy/util/util.h
+
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/filesystem_util.h b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/filesystem_util.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/filesystem_util.h
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/filesystem_util.h
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/forgetter/Forgetter.cpp b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/minizip_util.cpp
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/forgetter/Forgetter.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/minizip_util.cpp
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/forgetter/Forgetter.h b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/minizip_util.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/forgetter/Forgetter.h
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/minizip_util.h
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/util.cpp b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/util.cpp
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/util.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/util.cpp
diff --git a/source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/util.h b/source/RobotAPI/libraries/armem/server/ltm/legacy/util/util.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/disk/detail/util/util.h
rename to source/RobotAPI/libraries/armem/server/ltm/legacy/util/util.h
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2b4f5afa549ab239b91d05ceafe3e49e13c2b36d
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.cpp
@@ -0,0 +1,35 @@
+#include "Processors.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+
+#include "converter/data/image/exr/ExrConverter.h"
+#include "converter/data/image/png/PngConverter.h"
+#include "extractor/imageExtractor/DepthImageExtractor.h"
+#include "extractor/imageExtractor/ImageExtractor.h"
+#include "filter/equalityFilter/EqualityFilter.h"
+#include "filter/frequencyFilter/FrequencyFilter.h"
+
+namespace armarx::armem::server::ltm
+{
+    void
+    Processors::configure(const nlohmann::json& config)
+    {
+        // Filters:
+        if (config.contains(processor::filter::SnapshotFrequencyFilter::NAME))
+        {
+            ARMARX_IMPORTANT << "ADDING SNAPSHOT FILTER";
+            auto f = std::make_unique<processor::filter::SnapshotFrequencyFilter>();
+            f->configure(config[processor::filter::SnapshotFrequencyFilter::NAME]);
+            snapFilters.push_back(std::move(f));
+        }
+
+        // Converters
+        if (config.contains(processor::converter::data::image::PngConverter::NAME))
+        {
+            ARMARX_IMPORTANT << "ADDING IMG CONVERTER";
+            auto f = std::make_unique<processor::converter::data::image::PngConverter>();
+            f->configure(config[processor::converter::data::image::PngConverter::NAME]);
+            converters.push_back(std::move(f));
+        }
+    }
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.h b/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.h
new file mode 100644
index 0000000000000000000000000000000000000000..0f4186a2c872f30d6ef1bb9b3ce7652232e0c669
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/Processors.h
@@ -0,0 +1,43 @@
+#pragma once
+
+#include <map>
+#include <mutex>
+#include <optional>
+#include <string>
+
+#include <RobotAPI/libraries/armem/core/MemoryID.h>
+
+#include "converter/data/Converter.h"
+#include "converter/data/object/json/JsonConverter.h"
+#include "converter/type/object/json/JsonConverter.h"
+#include "extractor/Extractor.h"
+#include "filter/Filter.h"
+
+namespace armarx::armem::server::ltm
+{
+    /// all necessary classes to filter and convert an entry of the ltm to some other format(s)
+    class Processors
+    {
+    public:
+        Processors() = default;
+
+        void configure(const nlohmann::json& config);
+
+    public:
+        // Unique Memory Filters
+        std::vector<std::unique_ptr<processor::MemoryFilter>> memFilters;
+
+        // Unique Snapshot filters
+        std::vector<std::unique_ptr<processor::SnapshotFilter>> snapFilters;
+
+        // Special Extractors
+        std::vector<std::unique_ptr<processor::Extractor>> extractors;
+
+        // Special Converters
+        std::vector<std::unique_ptr<processor::DataConverter>> converters;
+
+        // Default converters
+        processor::converter::data::object::JsonConverter defaultObjectConverter;
+        processor::converter::type::object::JsonConverter defaultTypeConverter;
+    };
+} // namespace armarx::armem::server::ltm
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..f32e7fc341ec3ea9ea9d395cc737af4c3b5989ee
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.cpp
@@ -0,0 +1,9 @@
+#include "Converter.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    void
+    DataConverter::configure(const nlohmann::json& json)
+    {
+    }
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.h
new file mode 100644
index 0000000000000000000000000000000000000000..b5e4eee857c0873d8c66c83f7bdbc2faf672d13a
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/Converter.h
@@ -0,0 +1,56 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+
+// Simox
+#include <SimoxUtility/json.h>
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+#include "../../extractor/Extractor.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    class DataConverter
+    {
+    public:
+        enum class ConverterType
+        {
+            Str,
+            Binary
+        };
+
+        struct ConversionResult
+        {
+            std::vector<unsigned char> data;
+            std::string suffix;
+        };
+
+        DataConverter(const ConverterType t,
+                      const std::string& id,
+                      const std::string& s,
+                      const aron::type::Descriptor c,
+                      std::unique_ptr<Extractor>&& ex) :
+            type(t), identifier(id), suffix(s), convertsType(c), extractor(std::move(ex))
+        {
+        }
+
+        virtual ~DataConverter() = default;
+
+        virtual ConversionResult convert(const aron::data::VariantPtr& data) = 0;
+        virtual aron::data::VariantPtr convert(const ConversionResult&,
+                                               const armarx::aron::Path& p) = 0;
+
+        virtual void configure(const nlohmann::json& json);
+
+    public:
+        const ConverterType type;
+        const std::string identifier;
+        const std::string suffix;
+        const aron::type::Descriptor convertsType;
+
+        const std::unique_ptr<Extractor> extractor;
+    };
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b3975f36dd82d57b6a2adb43ae9f826bc8acb372
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.cpp
@@ -0,0 +1,24 @@
+#include "Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data
+{
+    void
+    ImageConverter::configure(const nlohmann::json& json)
+    {
+    }
+
+    ImageConverter::ConversionResult
+    ImageConverter::convert(const aron::data::VariantPtr& data)
+    {
+        auto d = aron::data::NDArray::DynamicCastAndCheck(data);
+        return _convert(d);
+    }
+
+    aron::data::VariantPtr
+    ImageConverter::convert(const ConversionResult& data, const armarx::aron::Path& p)
+    {
+        auto d = _convert(data, p);
+        return d;
+    }
+
+} // namespace armarx::armem::server::ltm::processor::converter::data
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.h
new file mode 100644
index 0000000000000000000000000000000000000000..9daec4a624b8a4bd35aee44fb9639014f122a044
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/Converter.h
@@ -0,0 +1,40 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+
+// BaseClass
+#include "../Converter.h"
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
+
+#include "../../../extractor/imageExtractor/ImageExtractor.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data
+{
+    class ImageConverter : public DataConverter
+    {
+    public:
+        ImageConverter(const ConverterType t,
+                       const std::string& id,
+                       const std::string& s,
+                       std::unique_ptr<Extractor>&& ex) :
+            DataConverter(t, id, s, aron::type::Descriptor::IMAGE, std::move(ex))
+        {
+        }
+
+        virtual ~ImageConverter() = default;
+
+        ConversionResult convert(const aron::data::VariantPtr& data) final;
+        aron::data::VariantPtr convert(const ConversionResult& data,
+                                       const armarx::aron::Path& p) final;
+
+        void configure(const nlohmann::json& json) override;
+
+    protected:
+        virtual ConversionResult _convert(const aron::data::NDArrayPtr& data) = 0;
+        virtual aron::data::NDArrayPtr _convert(const ConversionResult& data,
+                                                const armarx::aron::Path& p) = 0;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..f55138796815ead0f27af90bbf9a4d8fc6e9c089
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.cpp
@@ -0,0 +1,34 @@
+#include "ExrConverter.h"
+
+// ArmarX
+#include <opencv2/imgcodecs.hpp>
+#include <opencv2/imgproc.hpp>
+#include <opencv2/opencv.hpp>
+
+#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
+
+namespace armarx::armem::server::ltm::processor::converter::data::image
+{
+    ExrConverter::ConversionResult
+    ExrConverter::_convert(const aron::data::NDArrayPtr& data)
+    {
+        ARMARX_CHECK_NOT_NULL(data);
+
+        auto img = aron::data::converter::AronOpenCVConverter::ConvertToMat(data);
+        std::vector<unsigned char> buffer;
+
+        auto shape = data->getShape(); // we know from the extraction that the shape has 3 elements
+        ARMARX_CHECK_EQUAL(shape.size(), 3);
+        ARMARX_CHECK_EQUAL(shape[2], 4);
+
+        cv::imencode(".exr", img, buffer);
+        return {buffer, ""};
+    }
+
+    aron::data::NDArrayPtr
+    ExrConverter::_convert(const ConversionResult& data, const armarx::aron::Path& p)
+    {
+        cv::Mat img = cv::imdecode(data.data, cv::IMREAD_ANYDEPTH);
+        return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
+    }
+} // namespace armarx::armem::server::ltm::processor::converter::data::image
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce9cc7ab220fd794442b69c4b826b647122d022e
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/exr/ExrConverter.h
@@ -0,0 +1,25 @@
+#pragma once
+
+// Base Class
+#include "../../../../extractor/imageExtractor/DepthImageExtractor.h"
+#include "../Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data::image
+{
+    class ExrConverter : public ImageConverter
+    {
+    public:
+        ExrConverter() :
+            ImageConverter(ConverterType::Binary,
+                           "depthimage",
+                           ".exr",
+                           std::make_unique<extractor::DepthImageExtractor>())
+        {
+        }
+
+    protected:
+        ConversionResult _convert(const aron::data::NDArrayPtr& data) final;
+        aron::data::NDArrayPtr _convert(const ConversionResult& data,
+                                        const armarx::aron::Path& p) final;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data::image
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b9d4a92d4514075c72d9f70948ab9d39a7428d65
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.cpp
@@ -0,0 +1,67 @@
+#include "PngConverter.h"
+
+// ArmarX
+#include <opencv2/imgcodecs.hpp>
+#include <opencv2/imgproc.hpp>
+#include <opencv2/opencv.hpp>
+
+#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
+
+namespace armarx::armem::server::ltm::processor::converter::data::image
+{
+    void
+    PngConverter::configure(const nlohmann::json& json)
+    {
+    }
+
+    PngConverter::ConversionResult
+    PngConverter::_convert(const aron::data::NDArrayPtr& data)
+    {
+        ARMARX_CHECK_NOT_NULL(data);
+
+        auto img = aron::data::converter::AronOpenCVConverter::ConvertToMat(data);
+        std::vector<unsigned char> buffer;
+
+
+        auto shape = data->getShape(); // we know from the extraction that the shape has 3 elements
+        ARMARX_CHECK_EQUAL(shape.size(), 3);
+
+        if (shape[2] == 3) // its probably a rgb image
+        {
+            cv::cvtColor(img, img, CV_RGB2BGR);
+            cv::imencode(suffix, img, buffer);
+            return {buffer, ".rgb"};
+        }
+
+        if (shape[2] == 1) // its probably a grayscale image
+        {
+            cv::imencode(suffix, img, buffer);
+            return {buffer, ".gs"};
+        }
+
+        // try to export without conversion
+        cv::imencode(suffix, img, buffer);
+        return {buffer, ""};
+    }
+
+    aron::data::NDArrayPtr
+    PngConverter::_convert(const ConversionResult& data, const armarx::aron::Path& p)
+    {
+        if (data.suffix == ".rgb")
+        {
+            cv::Mat img = cv::imdecode(data.data, cv::IMREAD_COLOR);
+            cv::cvtColor(img, img, CV_BGR2RGB);
+            return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
+        }
+
+        if (data.suffix == ".gs")
+        {
+            cv::Mat img = cv::imdecode(data.data, cv::IMREAD_GRAYSCALE);
+            return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
+        }
+
+        // try to load without conversion
+        cv::Mat img = cv::imdecode(data.data, cv::IMREAD_ANYCOLOR);
+        return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
+    }
+} // namespace armarx::armem::server::ltm::processor::converter::data::image
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..8fb622d281147068c2c01d4902258867ce3545e3
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/image/png/PngConverter.h
@@ -0,0 +1,29 @@
+#pragma once
+
+// Base Class
+#include "../../../../extractor/imageExtractor/ImageExtractor.h"
+#include "../Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data::image
+{
+    class PngConverter : public ImageConverter
+    {
+    public:
+        static const constexpr char* NAME = "PngConverter";
+
+        PngConverter() :
+            ImageConverter(ConverterType::Binary,
+                           "image",
+                           ".png",
+                           std::make_unique<extractor::ImageExtractor>())
+        {
+        }
+
+        void configure(const nlohmann::json& json) override;
+
+    protected:
+        ConversionResult _convert(const aron::data::NDArrayPtr& data) final;
+        aron::data::NDArrayPtr _convert(const ConversionResult& data,
+                                        const armarx::aron::Path& p) final;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data::image
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c710675a99277631478ff97ccae0147ad5c025b7
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.cpp
@@ -0,0 +1,20 @@
+#include "Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data
+{
+
+    ObjectConverter::ConversionResult
+    ObjectConverter::convert(const aron::data::VariantPtr& data)
+    {
+        auto d = aron::data::Dict::DynamicCastAndCheck(data);
+        return _convert(d);
+    }
+
+    aron::data::VariantPtr
+    ObjectConverter::convert(const ConversionResult& data, const armarx::aron::Path& p)
+    {
+        auto d = _convert(data, p);
+        return d;
+    }
+
+} // namespace armarx::armem::server::ltm::processor::converter::data
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.h
new file mode 100644
index 0000000000000000000000000000000000000000..9b46ad4341fd464bfca5e90a9416925b13c7b86d
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/Converter.h
@@ -0,0 +1,33 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+
+// BaseClass
+#include "../Converter.h"
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+namespace armarx::armem::server::ltm::processor::converter::data
+{
+    class ObjectConverter : public DataConverter
+    {
+    public:
+        ObjectConverter(const ConverterType t, const std::string& id, const std::string& s) :
+            DataConverter(t, id, s, aron::type::Descriptor::OBJECT, nullptr)
+        {
+        }
+
+        virtual ~ObjectConverter() = default;
+
+        ConversionResult convert(const aron::data::VariantPtr& data) final;
+        aron::data::VariantPtr convert(const ConversionResult& data,
+                                       const armarx::aron::Path& p) final;
+
+    protected:
+        virtual ConversionResult _convert(const aron::data::DictPtr& data) = 0;
+        virtual aron::data::DictPtr _convert(const ConversionResult& data,
+                                             const armarx::aron::Path& p) = 0;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.cpp
similarity index 53%
rename from source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.cpp
index 4155808d3c7dc5818bfb48112a6e77f41a74b681..010fd1406996c3b44aa873e31e89934352483e85 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/converter/object/bson/BsonConverter.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.cpp
@@ -1,16 +1,17 @@
 #include "BsonConverter.h"
 
-#include <bsoncxx/json.hpp>
-#include <bsoncxx/builder/stream/helpers.hpp>
-#include <bsoncxx/builder/stream/document.hpp>
 #include <bsoncxx/builder/stream/array.hpp>
+#include <bsoncxx/builder/stream/document.hpp>
+#include <bsoncxx/builder/stream/helpers.hpp>
+#include <bsoncxx/json.hpp>
 
-namespace armarx::armem::server::ltm::converter::object
+namespace armarx::armem::server::ltm::processor::converter::data::object
 {
     namespace bsoncxxbuilder = bsoncxx::builder::stream;
     namespace bsoncxxdoc = bsoncxx::document;
 
-    std::pair<std::vector<unsigned char>, std::string> BsonConverter::_convert(const aron::data::DictPtr& data)
+    BsonConverter::ConversionResult
+    BsonConverter::_convert(const aron::data::DictPtr& data)
     {
         auto [jsonVec, str] = jsonConverter.convert(data);
         std::string json(jsonVec.begin(), jsonVec.end());
@@ -21,16 +22,21 @@ namespace armarx::armem::server::ltm::converter::object
         {
             std::memcpy(bson.data(), view.data(), view.length());
         }
-        return std::make_pair(bson, str);
+        return {bson, str};
     }
 
-    aron::data::DictPtr BsonConverter::_convert(const std::vector<unsigned char>& data, const armarx::aron::Path& p, const std::string& m)
+    aron::data::DictPtr
+    BsonConverter::_convert(const ConversionResult& data, const armarx::aron::Path& p)
     {
-        bsoncxx::document::view view(data.data(), data.size());
+        bsoncxx::document::view view(data.data.data(), data.data.size());
         nlohmann::json json = bsoncxx::to_json(view);
-        std::string str = json.dump(2);
-        std::vector<unsigned char> jsonVec(str.begin(), str.end());
-        auto v = jsonConverter.convert(jsonVec, p, m);
+        std::string str = json.dump();
+
+        ConversionResult j;
+        j.data = std::vector<unsigned char>(str.begin(), str.end());
+        j.suffix = data.suffix;
+
+        auto v = jsonConverter.convert(j, p);
         return aron::data::Dict::DynamicCast(v);
     }
-}
+} // namespace armarx::armem::server::ltm::processor::converter::data::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..d0f18daddeb5fd5a23ddbc10cca9dfc2d42182e5
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/bson/BsonConverter.h
@@ -0,0 +1,29 @@
+#pragma once
+
+// Base Class
+#include "../Converter.h"
+
+// ArmarX
+#include "../json/JsonConverter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::data::object
+{
+    class BsonConverter;
+    using BsonConverterPtr = std::shared_ptr<BsonConverter>;
+
+    class BsonConverter : public ObjectConverter
+    {
+    public:
+        BsonConverter() : ObjectConverter(ConverterType::Binary, "dict", ".bson")
+        {
+        }
+
+    protected:
+        ConversionResult _convert(const aron::data::DictPtr& data) final;
+        aron::data::DictPtr _convert(const ConversionResult& data,
+                                     const armarx::aron::Path& p) final;
+
+    private:
+        JsonConverter jsonConverter;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c22eebc62497ebed29ef5da5645d622a805606d2
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.cpp
@@ -0,0 +1,26 @@
+#include "JsonConverter.h"
+
+#include <ArmarXCore/core/logging/Logging.h>
+
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+namespace armarx::armem::server::ltm::processor::converter::data::object
+{
+    JsonConverter::ConversionResult
+    JsonConverter::_convert(const aron::data::DictPtr& data)
+    {
+        nlohmann::json j =
+            aron::data::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
+        auto str = j.dump(2);
+        return {std::vector<unsigned char>(str.begin(), str.end()), ""};
+    }
+
+    aron::data::DictPtr
+    JsonConverter::_convert(const ConversionResult& data, const armarx::aron::Path& p)
+    {
+        std::string str(data.data.begin(), data.data.end());
+        nlohmann::json j = nlohmann::json::parse(str);
+        return aron::data::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(j,
+                                                                                               p);
+    }
+} // namespace armarx::armem::server::ltm::processor::converter::data::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..dff7d4dfbc0aaa4033cc08831b43a2ff4e7d4912
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/data/object/json/JsonConverter.h
@@ -0,0 +1,23 @@
+#pragma once
+
+// Base Class
+#include "../Converter.h"
+
+// Simox
+#include <SimoxUtility/json.h>
+
+namespace armarx::armem::server::ltm::processor::converter::data::object
+{
+    class JsonConverter : public ObjectConverter
+    {
+    public:
+        JsonConverter() : ObjectConverter(ConverterType::Str, "dict", ".json")
+        {
+        }
+
+    protected:
+        ConversionResult _convert(const aron::data::DictPtr& data) final;
+        aron::data::DictPtr _convert(const ConversionResult& data,
+                                     const armarx::aron::Path& p) final;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::data::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..be24f0e4076e54807192e51fbfe5dc35a9a47155
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.cpp
@@ -0,0 +1,9 @@
+#include "Converter.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    void
+    TypeConverter::configure(const nlohmann::json& json)
+    {
+    }
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.h
new file mode 100644
index 0000000000000000000000000000000000000000..cc9cab4d83e8a03c51d22f80740464744f6499f1
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/Converter.h
@@ -0,0 +1,35 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+
+// Simox
+#include <SimoxUtility/json.h>
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
+
+#include "../../extractor/Extractor.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    class TypeConverter
+    {
+    public:
+        TypeConverter(const std::string& id, const std::string& s) : identifier(id), suffix(s)
+        {
+        }
+
+        virtual ~TypeConverter() = default;
+
+        virtual std::pair<std::vector<unsigned char>, std::string>
+        convert(const aron::type::ObjectPtr& data) = 0;
+        virtual aron::type::ObjectPtr convert(const std::vector<unsigned char>& data,
+                                              const std::string&) = 0;
+        virtual void configure(const nlohmann::json& json);
+
+    public:
+        const std::string identifier;
+        const std::string suffix;
+    };
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..64a74c17e2e35cb738d0a5a46b44ecc97b7b5d82
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.cpp
@@ -0,0 +1,5 @@
+#include "Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::type
+{
+} // namespace armarx::armem::server::ltm::processor::converter::type
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.h
new file mode 100644
index 0000000000000000000000000000000000000000..959af6cdfe7c5760b4afecfd1ab8ba1e2a0b2569
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/Converter.h
@@ -0,0 +1,23 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+
+// Simox
+#include <SimoxUtility/json.h>
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/type/variant/container/Object.h>
+
+#include "../Converter.h"
+
+namespace armarx::armem::server::ltm::processor::converter::type
+{
+    class ObjectConverter : public TypeConverter
+    {
+    public:
+        ObjectConverter(const std::string& id, const std::string& s) : TypeConverter(id, s)
+        {
+        }
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::type
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..dbea5198d6be6d08bddacc7023c6c75d0f3f63a2
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.cpp
@@ -0,0 +1,24 @@
+#include "JsonConverter.h"
+
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+namespace armarx::armem::server::ltm::processor::converter::type::object
+{
+    std::pair<std::vector<unsigned char>, std::string>
+    JsonConverter::convert(const aron::type::ObjectPtr& data)
+    {
+        nlohmann::json j =
+            aron::type::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
+        auto str = j.dump(2);
+        return std::make_pair(std::vector<unsigned char>(str.begin(), str.end()), "");
+    }
+
+    aron::type::ObjectPtr
+    JsonConverter::convert(const std::vector<unsigned char>& data, const std::string&)
+    {
+        std::string str(data.begin(), data.end());
+        nlohmann::json j = nlohmann::json::parse(str);
+        return aron::type::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONTypeObject(
+            j);
+    }
+} // namespace armarx::armem::server::ltm::processor::converter::type::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..886192287c98ab2241e45e1a416be910304f6bf8
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/converter/type/object/json/JsonConverter.h
@@ -0,0 +1,23 @@
+#pragma once
+
+// Base Class
+#include "../Converter.h"
+
+// Simox
+#include <SimoxUtility/json.h>
+
+namespace armarx::armem::server::ltm::processor::converter::type::object
+{
+    class JsonConverter : public ObjectConverter
+    {
+    public:
+        JsonConverter() : ObjectConverter("dict", ".json")
+        {
+        }
+
+        std::pair<std::vector<unsigned char>, std::string>
+        convert(const aron::type::ObjectPtr& data) final;
+        aron::type::ObjectPtr convert(const std::vector<unsigned char>& data,
+                                      const std::string&) final;
+    };
+} // namespace armarx::armem::server::ltm::processor::converter::type::object
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..6fab07ccc648b821d4cc4e6d32e1735221fad074
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.cpp
@@ -0,0 +1,9 @@
+#include "Extractor.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    void
+    Extractor::configure(const nlohmann::json& json)
+    {
+    }
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.h b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.h
similarity index 57%
rename from source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.h
index 0fd5ca5adc0f82010d1a4f0ac85cc836301bac4f..aff91989a3f02c226aa6751c546158ef258ed698 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/Extractor.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/Extractor.h
@@ -3,29 +3,34 @@
 // STD/STL
 #include <memory>
 
+// Simox
+#include <SimoxUtility/json.h>
+
 // ArmarX
-#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
+#include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::processor
 {
     class Extractor
     {
     public:
-        struct Extraction
+        struct ExtractionResult
         {
             aron::data::DictPtr dataWithoutExtraction;
             std::map<std::string, aron::data::VariantPtr> extraction;
         };
 
-        Extractor(const aron::type::Descriptor t, const std::string& id) : extractsType(t), identifier(id) {};
+        Extractor(const aron::type::Descriptor t, const std::string& id) :
+            extractsType(t), identifier(id){};
         virtual ~Extractor() = default;
 
-        virtual Extraction extract(aron::data::DictPtr& data) = 0;
-        virtual aron::data::DictPtr merge(Extraction& encoding) = 0;
+        virtual ExtractionResult extract(aron::data::DictPtr& data) = 0;
+        virtual aron::data::DictPtr merge(ExtractionResult& encoding) = 0;
+
+        virtual void configure(const nlohmann::json& json);
 
         const aron::type::Descriptor extractsType;
         const std::string identifier;
-        bool enabled = false;
     };
-}
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.cpp
similarity index 84%
rename from source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.cpp
index e0b4c1c6a59c48f9dc144239d4023eb85370b347..2222482857e3148659f3c00bdb978aa0e3125381 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.cpp
@@ -1,7 +1,7 @@
 #include "DepthImageExtractor.h"
 
 
-namespace armarx::armem::server::ltm::extractor
+namespace armarx::armem::server::ltm::processor::extractor
 {
     void DepthImageExtractorVisitor::visitDictOnEnter(Input& data)
     {
@@ -28,20 +28,20 @@ namespace armarx::armem::server::ltm::extractor
         // A member is null. Simply ignore...
     }
 
-    Extractor::Extraction DepthImageExtractor::extract(aron::data::DictPtr& data)
+    Extractor::ExtractionResult DepthImageExtractor::extract(aron::data::DictPtr& data)
     {
         DepthImageExtractorVisitor visitor;
         aron::data::VariantPtr var = std::static_pointer_cast<aron::data::Variant>(data);
         aron::data::VariantPtr p;
         aron::data::visitRecursive(visitor, var);
 
-        Extraction encoding;
+        ExtractionResult encoding;
         encoding.dataWithoutExtraction = data;
         encoding.extraction = visitor.depthImages;
         return encoding;
     }
 
-    aron::data::DictPtr DepthImageExtractor::merge(Extraction& encoding)
+    aron::data::DictPtr DepthImageExtractor::merge(ExtractionResult& encoding)
     {
         return encoding.dataWithoutExtraction;
     }
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.h b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.h
similarity index 57%
rename from source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.h
index f7857c267f560159bce9d3e82aa230b103baf864..92d7f3fdfd9557d9dc696def70b5eb921b37c5ac 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/DepthImageExtractor.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/DepthImageExtractor.h
@@ -1,11 +1,11 @@
 #pragma once
 
 // Base Class
-#include "../Extractor.h"
-
 #include <RobotAPI/libraries/aron/core/data/visitor/variant/VariantVisitor.h>
 
-namespace armarx::armem::server::ltm::extractor
+#include "../Extractor.h"
+
+namespace armarx::armem::server::ltm::processor::extractor
 {
     class DepthImageExtractorVisitor : public aron::data::RecursiveVariantVisitor
     {
@@ -19,13 +19,9 @@ namespace armarx::armem::server::ltm::extractor
     class DepthImageExtractor : public Extractor
     {
     public:
-        DepthImageExtractor() :
-            Extractor(aron::type::Descriptor::IMAGE, "depthimage")
-        {
-            enabled = true;
-        };
+        DepthImageExtractor() : Extractor(aron::type::Descriptor::IMAGE, "depthimage"){};
 
-        virtual Extraction extract(aron::data::DictPtr& data) override;
-        virtual aron::data::DictPtr merge(Extraction& encoding) override;
+        ExtractionResult extract(aron::data::DictPtr& data) override;
+        aron::data::DictPtr merge(ExtractionResult& encoding) override;
     };
-}
+} // namespace armarx::armem::server::ltm::processor::extractor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.cpp
similarity index 58%
rename from source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.cpp
index 767de1c5c2cb6ffc54ba90d421fbd95a03819197..b1fd4650973c0aaebd97c08fb32a533672756fa3 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.cpp
@@ -1,9 +1,9 @@
 #include "ImageExtractor.h"
 
-
-namespace armarx::armem::server::ltm::extractor
+namespace armarx::armem::server::ltm::processor::extractor
 {
-    void ImageExtractorVisitor::visitDictOnEnter(Input& data)
+    void
+    ImageExtractorVisitor::visitDictOnEnter(Input& data)
     {
         ARMARX_CHECK_NOT_NULL(data);
 
@@ -14,7 +14,10 @@ namespace armarx::armem::server::ltm::extractor
             {
                 auto ndarray = aron::data::NDArray::DynamicCastAndCheck(child);
                 auto shape = ndarray->getShape();
-                if (shape.size() == 3 && (shape[2] == 3 || shape[2] == 1 /* 3 channel color or grayscale */) && std::accumulate(std::begin(shape), std::end(shape), 1, std::multiplies<int>()) > 200) // must be big enough to assume an image (instead of 4x4x4 poses)
+                if (shape.size() == 3 &&
+                    (shape[2] == 3 || shape[2] == 1 /* 3 channel color or grayscale */) &&
+                    std::accumulate(std::begin(shape), std::end(shape), 1, std::multiplies<int>()) >
+                        200) // must be big enough to assume an image (instead of 4x4x4 poses)
                 {
                     images[key] = ndarray;
                     dict->setElement(key, nullptr);
@@ -23,26 +26,29 @@ namespace armarx::armem::server::ltm::extractor
         }
     }
 
-    void ImageExtractorVisitor::visitUnknown(Input&)
+    void
+    ImageExtractorVisitor::visitUnknown(Input&)
     {
         // A member is null. Simply ignore...
     }
 
-    Extractor::Extraction ImageExtractor::extract(aron::data::DictPtr& data)
+    Extractor::ExtractionResult
+    ImageExtractor::extract(aron::data::DictPtr& data)
     {
         ImageExtractorVisitor visitor;
         aron::data::VariantPtr var = std::static_pointer_cast<aron::data::Variant>(data);
         aron::data::VariantPtr p;
         aron::data::visitRecursive(visitor, var);
 
-        Extraction encoding;
+        ExtractionResult encoding;
         encoding.dataWithoutExtraction = data;
         encoding.extraction = visitor.images;
         return encoding;
     }
 
-    aron::data::DictPtr ImageExtractor::merge(Extraction& encoding)
+    aron::data::DictPtr
+    ImageExtractor::merge(ExtractionResult& encoding)
     {
         return encoding.dataWithoutExtraction;
     }
-}
+} // namespace armarx::armem::server::ltm::extractor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.h b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.h
similarity index 57%
rename from source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.h
index c8ef9669dea0e8d45ff0b7a100b276aa6c106b98..63381f62108ae68253a9fb9352a15e1d9c1e9d66 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/extractor/imageExtractor/ImageExtractor.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/extractor/imageExtractor/ImageExtractor.h
@@ -1,11 +1,11 @@
 #pragma once
 
 // Base Class
-#include "../Extractor.h"
-
 #include <RobotAPI/libraries/aron/core/data/visitor/variant/VariantVisitor.h>
 
-namespace armarx::armem::server::ltm::extractor
+#include "../Extractor.h"
+
+namespace armarx::armem::server::ltm::processor::extractor
 {
     class ImageExtractorVisitor : public aron::data::RecursiveVariantVisitor
     {
@@ -19,13 +19,9 @@ namespace armarx::armem::server::ltm::extractor
     class ImageExtractor : public Extractor
     {
     public:
-        ImageExtractor() :
-            Extractor(aron::type::Descriptor::IMAGE, "image")
-        {
-            enabled = true;
-        };
+        ImageExtractor() : Extractor(aron::type::Descriptor::IMAGE, "image"){};
 
-        virtual Extraction extract(aron::data::DictPtr& data) override;
-        virtual aron::data::DictPtr merge(Extraction& encoding) override;
+        ExtractionResult extract(aron::data::DictPtr& data) override;
+        aron::data::DictPtr merge(ExtractionResult& encoding) override;
     };
-}
+} // namespace armarx::armem::server::ltm::processor::extractor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..c4c53c68888b5fe576572ef8166f9a20807d27ba
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.cpp
@@ -0,0 +1,14 @@
+#include "Filter.h"
+
+namespace armarx::armem::server::ltm::processor
+{
+    void
+    MemoryFilter::configure(const nlohmann::json& json)
+    {
+    }
+
+    void
+    SnapshotFilter::configure(const nlohmann::json& json)
+    {
+    }
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.h
similarity index 68%
rename from source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.h
index e75969bfa50b86379b1a0db47ab99c9f533ddc05..9d84c0a0ffdd976b54deb4585279d28161223da6 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/Filter.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/Filter.h
@@ -3,11 +3,14 @@
 // STD/STL
 #include <memory>
 
+// Simox
+#include <SimoxUtility/json.h>
+
 // ArmarX
 #include <RobotAPI/libraries/armem/core/MemoryID.h>
 #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
 
-namespace armarx::armem::server::ltm
+namespace armarx::armem::server::ltm::processor
 {
     class MemoryFilter
     {
@@ -16,8 +19,7 @@ namespace armarx::armem::server::ltm
         virtual ~MemoryFilter() = default;
 
         virtual bool accept(const armem::wm::Memory& e) = 0;
-
-        bool enabled = false;
+        virtual void configure(const nlohmann::json& json);
     };
 
     class SnapshotFilter
@@ -27,7 +29,6 @@ namespace armarx::armem::server::ltm
         virtual ~SnapshotFilter() = default;
 
         virtual bool accept(const armem::wm::EntitySnapshot& e) = 0;
-
-        bool enabled = false;
+        virtual void configure(const nlohmann::json& json);
     };
-}
+} // namespace armarx::armem::server::ltm::processor
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..92c8bb26ecf818492401e938b1c95cecb17519e1
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.cpp
@@ -0,0 +1,51 @@
+#include "EqualityFilter.h"
+
+#include <IceUtil/Time.h>
+
+namespace armarx::armem::server::ltm::processor::filter
+{
+    bool
+    SnapshotSimilarityFilter::accept(const armem::wm::EntitySnapshot& e)
+    {
+        auto entityID = e.id().getEntityID();
+        auto genMs = e.time().toMilliSecondsSinceEpoch();
+
+        long lastMs = 0;
+        std::vector<aron::data::DictPtr> lastData;
+        if (timestampLastCommitInMs.count(entityID) > 0)
+        {
+            lastData = dataLastCommit.at(entityID);
+            lastMs = timestampLastCommitInMs.at(entityID);
+        }
+
+
+        bool accept = false;
+        std::vector<aron::data::DictPtr> genData;
+        for (unsigned int i = 0; i != e.size(); ++i)
+        {
+            const auto& d = e.getInstance(i).data();
+            genData.push_back(d);
+
+            if (lastMs == 0 ||
+                e.size() != lastData.size()) // nothing stored yet or we cannot compare
+            {
+                accept = true;
+                break;
+            }
+
+            const auto& el = lastData.at(i);
+            if ((!d and el) || (d and !el) || (d && el && !(*d == *el))) // data unequal?
+            {
+                accept = true;
+                break;
+            }
+        }
+
+        if (!accept)
+            return false;
+
+        dataLastCommit[entityID] = genData;
+        timestampLastCommitInMs[entityID] = genMs;
+        return true;
+    }
+} // namespace armarx::armem::server::ltm::filter
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.h
similarity index 56%
rename from source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.h
index 1ad630b4fb4add2cd318b6b3e8cdf5eddd52e5fa..203b1fe3fa87108b144c604a59ebf46e58ab350f 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/equalityFilter/EqualityFilter.h
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/equalityFilter/EqualityFilter.h
@@ -1,7 +1,7 @@
 #pragma once
 
-#include <vector>
 #include <map>
+#include <vector>
 
 // Base Class
 #include "../Filter.h"
@@ -9,21 +9,22 @@
 // Aron
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
-namespace armarx::armem::server::ltm::filter
+namespace armarx::armem::server::ltm::processor::filter
 {
-    class SnapshotEqualityFilter :
-            public SnapshotFilter
+    class SnapshotSimilarityFilter : public SnapshotFilter
     {
     public:
-        SnapshotEqualityFilter() = default;
+        static const constexpr char* NAME = "SnapshotSimilarityFilter";
+
+        SnapshotSimilarityFilter() = default;
 
         virtual bool accept(const armem::wm::EntitySnapshot& e) override;
 
     public:
-        int maxWaitingTimeInMs = -1;
+        // TODO link aron/similarity
 
     private:
         std::map<MemoryID, std::vector<aron::data::DictPtr>> dataLastCommit;
         std::map<MemoryID, long> timestampLastCommitInMs;
     };
-}
+} // namespace armarx::armem::server::ltm::processor::filter
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.cpp
similarity index 59%
rename from source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.cpp
index a98aab7f756e42be8d995401964170e64c83e537..56c7250c37988efd1b5fc824aec8aabd2e040a17 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/filter/frequencyFilter/FrequencyFilter.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.cpp
@@ -2,9 +2,10 @@
 
 #include <IceUtil/Time.h>
 
-namespace armarx::armem::server::ltm::filter
+namespace armarx::armem::server::ltm::processor::filter
 {
-    bool MemoryFrequencyFilter::accept(const armem::wm::Memory& e)
+    bool
+    MemoryFrequencyFilter::accept(const armem::wm::Memory& e)
     {
         auto now = armem::Time::Now().toMilliSecondsSinceEpoch();
         if (waitingTimeInMs < 0 || (now - timestampLastCommitInMs) > waitingTimeInMs)
@@ -15,7 +16,17 @@ namespace armarx::armem::server::ltm::filter
         return false;
     }
 
-    bool SnapshotFrequencyFilter::accept(const armem::wm::EntitySnapshot& e)
+    void
+    MemoryFrequencyFilter::configure(const nlohmann::json& json)
+    {
+        if (json.find(PARAM_WAITING_TIME) != json.end())
+        {
+            waitingTimeInMs = json.at(PARAM_WAITING_TIME);
+        }
+    }
+
+    bool
+    SnapshotFrequencyFilter::accept(const armem::wm::EntitySnapshot& e)
     {
         auto entityID = e.id().getEntityID();
         auto genMs = e.time().toMilliSecondsSinceEpoch();
@@ -36,4 +47,13 @@ namespace armarx::armem::server::ltm::filter
         }
         return false;
     }
-}
+
+    void
+    SnapshotFrequencyFilter::configure(const nlohmann::json& json)
+    {
+        if (json.find(PARAM_WAITING_TIME) != json.end())
+        {
+            waitingTimeInMs = json.at(PARAM_WAITING_TIME);
+        }
+    }
+} // namespace armarx::armem::server::ltm::processor::filter
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.h
new file mode 100644
index 0000000000000000000000000000000000000000..00ba1e9db0162d4d866a359c920008838ad5e279
--- /dev/null
+++ b/source/RobotAPI/libraries/armem/server/ltm/processors/filter/frequencyFilter/FrequencyFilter.h
@@ -0,0 +1,45 @@
+#pragma once
+
+#include <map>
+
+// Base Class
+#include "../Filter.h"
+
+namespace armarx::armem::server::ltm::processor::filter
+{
+    class MemoryFrequencyFilter : public MemoryFilter
+    {
+    public:
+        static const constexpr char* NAME = "MemoryFrequencyFilter";
+        static const constexpr char* PARAM_WAITING_TIME = "WaitingTimeInMs";
+
+        MemoryFrequencyFilter() = default;
+
+        virtual bool accept(const armem::wm::Memory& e) override;
+        void configure(const nlohmann::json& json) override;
+
+    public:
+        int waitingTimeInMs = -1;
+
+    private:
+        long timestampLastCommitInMs = 0;
+    };
+
+    class SnapshotFrequencyFilter : public SnapshotFilter
+    {
+    public:
+        static const constexpr char* NAME = "SnapshotFrequencyFilter";
+        static const constexpr char* PARAM_WAITING_TIME = "WaitingTimeInMs";
+
+        SnapshotFrequencyFilter() = default;
+
+        virtual bool accept(const armem::wm::EntitySnapshot& e) override;
+        void configure(const nlohmann::json& json) override;
+
+    public:
+        int waitingTimeInMs = -1;
+
+    private:
+        std::map<MemoryID, long> timestampLastCommitInMs;
+    };
+} // namespace armarx::armem::server::ltm::processor::filter
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/forgetter/LRUForgetter/LRUForgetter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/Forgetter.cpp
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/forgetter/LRUForgetter/LRUForgetter.cpp
rename to source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/Forgetter.cpp
diff --git a/source/RobotAPI/libraries/armem/server/ltm/base/forgetter/LRUForgetter/LRUForgetter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/Forgetter.h
similarity index 100%
rename from source/RobotAPI/libraries/armem/server/ltm/base/forgetter/LRUForgetter/LRUForgetter.h
rename to source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/Forgetter.h
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/LRUForgetter/LRUForgetter.cpp b/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/LRUForgetter/LRUForgetter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/LRUForgetter/LRUForgetter.h b/source/RobotAPI/libraries/armem/server/ltm/processors/forgetter/LRUForgetter/LRUForgetter.h
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp b/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp
index b8b422bff746b435a1503b84af330bca5c66e524..d379cf033d76392d07417b0345aa09a3cca900bf 100644
--- a/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp
+++ b/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp
@@ -1,20 +1,18 @@
 #include "Plugin.h"
-#include "ArmarXCore/util/CPPUtility/trace.h"
-
-#include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/client/util/MemoryListener.h>
-#include <RobotAPI/libraries/armem/client/plugins/Plugin.h>
 
+#include "ArmarXCore/util/CPPUtility/trace.h"
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <RobotAPI/libraries/armem/client/plugins/Plugin.h>
+#include <RobotAPI/libraries/armem/client/util/MemoryListener.h>
+#include <RobotAPI/libraries/armem/core/error.h>
 
 namespace armarx::armem::server::plugins
 {
 
     Plugin::~Plugin() = default;
 
-
     Plugin::Plugin(ManagedIceObject& parent, std::string prefix) :
         armarx::ComponentPlugin(parent, prefix)
     {
@@ -24,8 +22,8 @@ namespace armarx::armem::server::plugins
         addPluginDependency(clientPlugin);
     }
 
-
-    void Plugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties)
+    void
+    Plugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties)
     {
         const std::string prefix = "mem.";
 
@@ -39,36 +37,45 @@ namespace armarx::armem::server::plugins
         // also add scenario param to overwrite the chosen name
         if (not properties->hasDefinition(prefix + "MemoryName"))
         {
-            properties->optional(workingMemory.name(), prefix + "MemoryName", "Name of this memory server.");
+            properties->optional(
+                workingMemory.name(), prefix + "MemoryName", "Name of this memory server.");
         }
 
         // stuff for ltm
         longtermMemory.createPropertyDefinitions(properties, prefix + "ltm.");
     }
 
-
-    void Plugin::preOnInitComponent()
+    void
+    Plugin::preOnInitComponent()
     {
         ARMARX_TRACE;
-        memoryTopicName = client::util::MemoryListener::MakeMemoryTopicName(MemoryID(workingMemory.name()));
+        memoryTopicName =
+            client::util::MemoryListener::MakeMemoryTopicName(MemoryID(workingMemory.name()));
         parent().offeringTopic(memoryTopicName);
     }
 
-
-    void Plugin::postOnInitComponent()
+    void
+    Plugin::postOnInitComponent()
     {
         Component& parent = this->parent<Component>();
 
         // activate LTM
         ARMARX_TRACE;
-        longtermMemory.setMemoryID(workingMemory.id(), parent.getName());
-        longtermMemory.init();
+        if (not workingMemory.id().memoryName.empty())
+        {
+            longtermMemory.setMemoryID(workingMemory.id());
+        }
+        else
+        {
+            longtermMemory.setMemoryID(MemoryID(parent.getDefaultName(), ""));
+        }
+        longtermMemory.configure();
 
         initialized = true;
     }
 
-
-    void Plugin::postOnConnectComponent()
+    void
+    Plugin::postOnConnectComponent()
     {
         Component& parent = this->parent<Component>();
 
@@ -83,8 +90,8 @@ namespace armarx::armem::server::plugins
         connected = true;
     }
 
-
-    void Plugin::preOnDisconnectComponent()
+    void
+    Plugin::preOnDisconnectComponent()
     {
         if (clientPlugin->isMemoryNameSystemEnabled() and clientPlugin->getMemoryNameSystemClient())
         {
@@ -92,19 +99,20 @@ namespace armarx::armem::server::plugins
         }
     }
 
-
-    void Plugin::setMemoryName(const std::string& memoryName)
+    void
+    Plugin::setMemoryName(const std::string& memoryName)
     {
         if (initialized)
         {
-            ARMARX_WARNING << "Please set the memory name before initializing the component. Otherwise the WM and LTM may have different names";
+            ARMARX_WARNING << "Please set the memory name before initializing the component. "
+                              "Otherwise the WM and LTM may have different names";
         }
 
         workingMemory.name() = memoryName;
     }
 
-
-    mns::dto::RegisterServerResult Plugin::registerServer(armarx::Component& parent)
+    mns::dto::RegisterServerResult
+    Plugin::registerServer(armarx::Component& parent)
     {
         ARMARX_TRACE;
 
@@ -120,7 +128,8 @@ namespace armarx::armem::server::plugins
         {
             clientPlugin->getMemoryNameSystemClient().registerServer(id, server);
             result.success = true;
-            ARMARX_DEBUG << "Registered memory server for " << id << " in the Memory Name System (MNS).";
+            ARMARX_DEBUG << "Registered memory server for " << id
+                         << " in the Memory Name System (MNS).";
         }
         catch (const armem::error::ServerRegistrationOrRemovalFailed& e)
         {
@@ -131,8 +140,8 @@ namespace armarx::armem::server::plugins
         return result;
     }
 
-
-    mns::dto::RemoveServerResult Plugin::removeServer()
+    mns::dto::RemoveServerResult
+    Plugin::removeServer()
     {
         MemoryID id = MemoryID().withMemoryName(workingMemory.name());
 
@@ -141,7 +150,8 @@ namespace armarx::armem::server::plugins
         {
             clientPlugin->getMemoryNameSystemClient().removeServer(id);
             result.success = true;
-            ARMARX_DEBUG << "Removed memory server for " << id << " from the Memory Name System (MNS).";
+            ARMARX_DEBUG << "Removed memory server for " << id
+                         << " from the Memory Name System (MNS).";
         }
         catch (const armem::error::ServerRegistrationOrRemovalFailed& e)
         {
@@ -158,4 +168,4 @@ namespace armarx::armem::server::plugins
         return result;
     }
 
-}
+} // namespace armarx::armem::server::plugins
diff --git a/source/RobotAPI/libraries/armem/server/plugins/Plugin.h b/source/RobotAPI/libraries/armem/server/plugins/Plugin.h
index aa6afd8171ff50cf43b955ff145a4770cf8f24b7..e37c5e093232af4aae66114703a7debb8f122ba4 100644
--- a/source/RobotAPI/libraries/armem/server/plugins/Plugin.h
+++ b/source/RobotAPI/libraries/armem/server/plugins/Plugin.h
@@ -1,19 +1,17 @@
 #pragma once
 
-#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
-
-#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
+#include <ArmarXCore/core/ComponentPlugin.h>
 
 #include <RobotAPI/interface/armem/client/MemoryListenerInterface.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
-
-#include <ArmarXCore/core/ComponentPlugin.h>
-
+#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
+#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h>
 
 namespace armarx
 {
     class Component;
 }
+
 namespace armarx::armem::client::plugins
 {
     class Plugin;
@@ -22,11 +20,9 @@ namespace armarx::armem::client::plugins
 namespace armarx::armem::server::plugins
 {
 
-    class Plugin :
-        public armarx::ComponentPlugin
+    class Plugin : public armarx::ComponentPlugin
     {
     public:
-
         Plugin(ManagedIceObject& parent, std::string prefix);
         virtual ~Plugin() override;
 
@@ -40,13 +36,11 @@ namespace armarx::armem::server::plugins
 
 
     public:
-
         /// Set the name of the wm and the ltm
         void setMemoryName(const std::string& memoryName);
 
 
     protected:
-
         /**
          * @brief Register the parent component in the MNS.
          *
@@ -62,16 +56,14 @@ namespace armarx::armem::server::plugins
         mns::dto::RemoveServerResult removeServer();
 
 
-
     public:
-
         // Working Memory
 
         /// The actual memory.
         server::wm::Memory workingMemory;
 
         /// Helps connecting `memory` to ice. Used to handle Ice callbacks.
-        MemoryToIceAdapter iceAdapter { &workingMemory, &longtermMemory};
+        MemoryToIceAdapter iceAdapter{&workingMemory, &longtermMemory};
 
 
         // Working Memory Updates (publishing)
@@ -85,18 +77,16 @@ namespace armarx::armem::server::plugins
         // Long-Term Memory
 
         /// A manager class for the ltm. It internally holds a normal wm instance as a cache.
-        server::ltm::disk::Memory longtermMemory;
+        server::ltm::Memory longtermMemory;
 
 
     private:
-
         client::plugins::Plugin* clientPlugin = nullptr;
 
         std::atomic_bool initialized = false;
         std::atomic_bool connected = false;
-
     };
-}
+} // namespace armarx::armem::server::plugins
 
 namespace armarx::armem::server
 {
diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp
index 299e8242ee540df8c5397d86a03a7cae2d1a0eb8..0578214ecb8270828d6de3a9d7764c945c170311 100644
--- a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp
+++ b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp
@@ -1,14 +1,13 @@
 #include "ReadWritePluginUser.h"
-#include "Plugin.h"
-
-#include <RobotAPI/libraries/armem/core/error.h>
-#include <RobotAPI/libraries/armem/core/Prediction.h>
-#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <RobotAPI/libraries/armem/core/Prediction.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 
+#include "Plugin.h"
 
 namespace armarx::armem::server::plugins
 {
@@ -18,126 +17,133 @@ namespace armarx::armem::server::plugins
         addPlugin(plugin);
     }
 
-
     ReadWritePluginUser::~ReadWritePluginUser()
     {
     }
 
-
-    void ReadWritePluginUser::setMemoryName(const std::string& memoryName)
+    void
+    ReadWritePluginUser::setMemoryName(const std::string& memoryName)
     {
         plugin->setMemoryName(memoryName);
     }
 
-
     // WRITING
-    data::AddSegmentsResult ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, const Ice::Current&)
+    data::AddSegmentsResult
+    ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, const Ice::Current&)
     {
         ARMARX_TRACE;
         bool addCoreSegmentOnUsage = false;
         return addSegments(input, addCoreSegmentOnUsage);
     }
 
-    data::AddSegmentsResult ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments)
+    data::AddSegmentsResult
+    ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments)
     {
         ARMARX_TRACE;
         data::AddSegmentsResult result = iceAdapter().addSegments(input, addCoreSegments);
         return result;
     }
 
-
-    data::CommitResult ReadWritePluginUser::commit(const data::Commit& commitIce, const Ice::Current&)
+    data::CommitResult
+    ReadWritePluginUser::commit(const data::Commit& commitIce, const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().commit(commitIce);
     }
 
-
     // READING
-    armem::query::data::Result ReadWritePluginUser::query(const armem::query::data::Input& input, const Ice::Current&)
+    armem::query::data::Result
+    ReadWritePluginUser::query(const armem::query::data::Input& input, const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().query(input);
     }
 
-    structure::data::GetServerStructureResult ReadWritePluginUser::getServerStructure(const Ice::Current&)
+    structure::data::GetServerStructureResult
+    ReadWritePluginUser::getServerStructure(const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().getServerStructure();
     }
 
-
     // LTM STORING AND RECORDING
-    dto::DirectlyStoreResult ReadWritePluginUser::directlyStore(const dto::DirectlyStoreInput& input, const Ice::Current&)
+    dto::DirectlyStoreResult
+    ReadWritePluginUser::directlyStore(const dto::DirectlyStoreInput& input, const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().directlyStore(input);
     }
 
-    dto::StartRecordResult ReadWritePluginUser::startRecord(const dto::StartRecordInput& startRecordInput, const Ice::Current&)
+    dto::StartRecordResult
+    ReadWritePluginUser::startRecord(const dto::StartRecordInput& startRecordInput,
+                                     const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().startRecord(startRecordInput);
     }
 
-    dto::StopRecordResult ReadWritePluginUser::stopRecord(const Ice::Current&)
+    dto::StopRecordResult
+    ReadWritePluginUser::stopRecord(const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().stopRecord();
     }
 
-    dto::RecordStatusResult ReadWritePluginUser::getRecordStatus(const Ice::Current&)
+    dto::RecordStatusResult
+    ReadWritePluginUser::getRecordStatus(const Ice::Current&)
     {
         ARMARX_TRACE;
         return iceAdapter().getRecordStatus();
     }
 
-
-    Plugin& ReadWritePluginUser::memoryServerPlugin()
+    Plugin&
+    ReadWritePluginUser::memoryServerPlugin()
     {
         return *plugin;
     }
 
-
-    wm::Memory& ReadWritePluginUser::workingMemory()
+    wm::Memory&
+    ReadWritePluginUser::workingMemory()
     {
         return plugin->workingMemory;
     }
 
-
-    MemoryToIceAdapter& ReadWritePluginUser::iceAdapter()
+    MemoryToIceAdapter&
+    ReadWritePluginUser::iceAdapter()
     {
         return plugin->iceAdapter;
     }
 
-
-    ltm::disk::Memory& ReadWritePluginUser::longtermMemory()
+    ltm::Memory&
+    ReadWritePluginUser::longtermMemory()
     {
         return plugin->longtermMemory;
     }
 
     // ACTIONS
-    armem::actions::GetActionsOutputSeq ReadWritePluginUser::getActions(
-            const armem::actions::GetActionsInputSeq& inputs, const ::Ice::Current&  /*unused*/)
+    armem::actions::GetActionsOutputSeq
+    ReadWritePluginUser::getActions(const armem::actions::GetActionsInputSeq& inputs,
+                                    const ::Ice::Current& /*unused*/)
     {
         return getActions(inputs);
     }
 
-    armem::actions::GetActionsOutputSeq ReadWritePluginUser::getActions(
-            const armem::actions::GetActionsInputSeq& inputs)
+    armem::actions::GetActionsOutputSeq
+    ReadWritePluginUser::getActions(const armem::actions::GetActionsInputSeq& inputs)
     {
-        (void) inputs;
+        (void)inputs;
         return {};
     }
 
-    armem::actions::ExecuteActionOutputSeq ReadWritePluginUser::executeActions(
-            const armem::actions::ExecuteActionInputSeq& inputs, const ::Ice::Current& /*unused*/)
+    armem::actions::ExecuteActionOutputSeq
+    ReadWritePluginUser::executeActions(const armem::actions::ExecuteActionInputSeq& inputs,
+                                        const ::Ice::Current& /*unused*/)
     {
         return executeActions(inputs);
     }
 
-    armem::actions::ExecuteActionOutputSeq ReadWritePluginUser::executeActions(
-            const armem::actions::ExecuteActionInputSeq& inputs)
+    armem::actions::ExecuteActionOutputSeq
+    ReadWritePluginUser::executeActions(const armem::actions::ExecuteActionInputSeq& inputs)
     {
         return {};
     }
diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h
index 3c29eb693b49df92b1fe82fcd84f416ed4152141..89dcb3239cc6a62275dbd744732f4a262474d447 100644
--- a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h
+++ b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h
@@ -1,32 +1,28 @@
 #pragma once
 
-#include <RobotAPI/libraries/armem/server/forward_declarations.h>
+#include <ArmarXCore/core/ManagedIceObject.h>
 
+#include <RobotAPI/interface/armem/server/MemoryInterface.h>
 #include <RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h>
 #include <RobotAPI/libraries/armem/core/actions.h>
-#include <RobotAPI/interface/armem/server/MemoryInterface.h>
-
-#include <ArmarXCore/core/ManagedIceObject.h>
-
+#include <RobotAPI/libraries/armem/server/forward_declarations.h>
 
 namespace armarx::armem::server::plugins
 {
 
     class Plugin;
 
-
     /**
      * @brief Base class of memory server components.
      *
      * Implements the server ice interfaces using the ice adapter of the plugin.
      */
     class ReadWritePluginUser :
-        virtual public ManagedIceObject
-        , virtual public MemoryInterface
-        , virtual public client::plugins::ListeningPluginUser
+        virtual public ManagedIceObject,
+        virtual public MemoryInterface,
+        virtual public client::plugins::ListeningPluginUser
     {
     public:
-
         ReadWritePluginUser();
         virtual ~ReadWritePluginUser() override;
 
@@ -35,61 +31,78 @@ namespace armarx::armem::server::plugins
 
 
         // WritingInterface interface
-        virtual data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, const Ice::Current& = Ice::emptyCurrent) override;
-        data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, bool addCoreSegments);
+        virtual data::AddSegmentsResult
+        addSegments(const data::AddSegmentsInput& input,
+                    const Ice::Current& = Ice::emptyCurrent) override;
+        data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input,
+                                            bool addCoreSegments);
 
-        virtual data::CommitResult commit(const data::Commit& commit, const Ice::Current& = Ice::emptyCurrent) override;
+        virtual data::CommitResult commit(const data::Commit& commit,
+                                          const Ice::Current& = Ice::emptyCurrent) override;
 
 
         // ReadingInterface interface
-        virtual armem::query::data::Result query(const armem::query::data::Input& input, const Ice::Current& = Ice::emptyCurrent) override;
-        virtual armem::structure::data::GetServerStructureResult getServerStructure(const Ice::Current& = Ice::emptyCurrent) override;
+        virtual armem::query::data::Result query(const armem::query::data::Input& input,
+                                                 const Ice::Current& = Ice::emptyCurrent) override;
+        virtual armem::structure::data::GetServerStructureResult
+        getServerStructure(const Ice::Current& = Ice::emptyCurrent) override;
 
 
         // StoringInterface interface
-        virtual dto::DirectlyStoreResult directlyStore(const dto::DirectlyStoreInput&, const Ice::Current& = Ice::emptyCurrent) override;
-        virtual dto::StartRecordResult startRecord(const dto::StartRecordInput& startRecordInput, const Ice::Current& = Ice::emptyCurrent) override;
+        virtual dto::DirectlyStoreResult
+        directlyStore(const dto::DirectlyStoreInput&,
+                      const Ice::Current& = Ice::emptyCurrent) override;
+        virtual dto::StartRecordResult
+        startRecord(const dto::StartRecordInput& startRecordInput,
+                    const Ice::Current& = Ice::emptyCurrent) override;
         virtual dto::StopRecordResult stopRecord(const Ice::Current& = Ice::emptyCurrent) override;
-        virtual dto::RecordStatusResult getRecordStatus(const Ice::Current& = Ice::emptyCurrent) override;
+        virtual dto::RecordStatusResult
+        getRecordStatus(const Ice::Current& = Ice::emptyCurrent) override;
 
         // ActionsInterface interface
-        virtual armem::actions::GetActionsOutputSeq getActions(const armem::actions::GetActionsInputSeq& inputs);
-        virtual armem::actions::ExecuteActionOutputSeq executeActions(const armem::actions::ExecuteActionInputSeq& inputs);
-
-        virtual armem::actions::GetActionsOutputSeq getActions(const armem::actions::GetActionsInputSeq& inputs, const ::Ice::Current&) override;
-        virtual armem::actions::ExecuteActionOutputSeq executeActions(const armem::actions::ExecuteActionInputSeq& inputs, const ::Ice::Current&) override;
+        virtual armem::actions::GetActionsOutputSeq
+        getActions(const armem::actions::GetActionsInputSeq& inputs);
+        virtual armem::actions::ExecuteActionOutputSeq
+        executeActions(const armem::actions::ExecuteActionInputSeq& inputs);
+
+        virtual armem::actions::GetActionsOutputSeq
+        getActions(const armem::actions::GetActionsInputSeq& inputs,
+                   const ::Ice::Current&) override;
+        virtual armem::actions::ExecuteActionOutputSeq
+        executeActions(const armem::actions::ExecuteActionInputSeq& inputs,
+                       const ::Ice::Current&) override;
 
         // PredictingInterface interface
-        virtual armem::prediction::data::PredictionResultSeq predict(const armem::prediction::data::PredictionRequestSeq& requests);
+        virtual armem::prediction::data::PredictionResultSeq
+        predict(const armem::prediction::data::PredictionRequestSeq& requests);
 
         // Unless you need very unusual behavior from this method for your memory server,
         // it is better to set the available prediction engines in the memory itself
         // and let it handle the requests than to override this.
         virtual armem::prediction::data::EngineSupportMap getAvailableEngines();
 
-        virtual armem::prediction::data::PredictionResultSeq predict(const armem::prediction::data::PredictionRequestSeq& requests, const ::Ice::Current&) override;
-        virtual armem::prediction::data::EngineSupportMap getAvailableEngines(const ::Ice::Current&) override;
+        virtual armem::prediction::data::PredictionResultSeq
+        predict(const armem::prediction::data::PredictionRequestSeq& requests,
+                const ::Ice::Current&) override;
+        virtual armem::prediction::data::EngineSupportMap
+        getAvailableEngines(const ::Ice::Current&) override;
 
     public:
-
         Plugin& memoryServerPlugin();
 
         server::wm::Memory& workingMemory();
         MemoryToIceAdapter& iceAdapter();
 
-        server::ltm::disk::Memory& longtermMemory();
+        server::ltm::Memory& longtermMemory();
 
 
     private:
-
         plugins::Plugin* plugin = nullptr;
-
     };
 
-}
+} // namespace armarx::armem::server::plugins
 
 namespace armarx::armem::server
 {
     using plugins::ReadWritePluginUser;
 }
-
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h b/source/RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h
index f569e986a57832def5e1343f20da9f0b007d664f..aa7349eadafcbafd40472ba2b19adf21041cd5ce 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h
@@ -1,35 +1,37 @@
 #pragma once
 
-#include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h>
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
 #include <RobotAPI/libraries/armem/server/query_proc/base.h>
 
-#include "../detail/MemoryQueryProcessorBase.h"
 #include "../detail/CoreSegmentQueryProcessorBase.h"
-#include "../detail/ProviderSegmentQueryProcessorBase.h"
 #include "../detail/EntityQueryProcessorBase.h"
+#include "../detail/MemoryQueryProcessorBase.h"
+#include "../detail/ProviderSegmentQueryProcessorBase.h"
 
-namespace armarx::armem::server::query_proc::ltm_server::disk
+namespace armarx::armem::server::query_proc::ltm_server
 {
     class EntityQueryProcessor :
-        public ltm::detail::EntityQueryProcessorBase<armem::server::ltm::disk::Entity, armem::wm::Entity>
+        public ltm::detail::EntityQueryProcessorBase<armem::server::ltm::Entity, armem::wm::Entity>
     {
     protected:
-
-        using Base = ltm::detail::EntityQueryProcessorBase<armem::server::ltm::disk::Entity, armem::wm::Entity>;
+        using Base =
+            ltm::detail::EntityQueryProcessorBase<armem::server::ltm::Entity, armem::wm::Entity>;
 
 
     public:
-
         using Base::process;
-
     };
 
     class ProviderSegmentQueryProcessor :
-        public ltm::detail::ProviderSegmentQueryProcessorBase<armem::server::ltm::disk::ProviderSegment, armem::wm::ProviderSegment, EntityQueryProcessor>
+        public ltm::detail::ProviderSegmentQueryProcessorBase<armem::server::ltm::ProviderSegment,
+                                                              armem::wm::ProviderSegment,
+                                                              EntityQueryProcessor>
     {
     protected:
-
-        using Base = ltm::detail::ProviderSegmentQueryProcessorBase<armem::server::ltm::disk::ProviderSegment, armem::wm::ProviderSegment, EntityQueryProcessor>;
+        using Base =
+            ltm::detail::ProviderSegmentQueryProcessorBase<armem::server::ltm::ProviderSegment,
+                                                           armem::wm::ProviderSegment,
+                                                           EntityQueryProcessor>;
 
 
     public:
@@ -37,11 +39,14 @@ namespace armarx::armem::server::query_proc::ltm_server::disk
     };
 
     class CoreSegmentQueryProcessor :
-        public ltm::detail::CoreSegmentQueryProcessorBase<armem::server::ltm::disk::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor>
+        public ltm::detail::CoreSegmentQueryProcessorBase<armem::server::ltm::CoreSegment,
+                                                          armem::wm::CoreSegment,
+                                                          ProviderSegmentQueryProcessor>
     {
     protected:
-
-        using Base = ltm::detail::CoreSegmentQueryProcessorBase<armem::server::ltm::disk::CoreSegment, armem::wm::CoreSegment, ProviderSegmentQueryProcessor>;
+        using Base = ltm::detail::CoreSegmentQueryProcessorBase<armem::server::ltm::CoreSegment,
+                                                                armem::wm::CoreSegment,
+                                                                ProviderSegmentQueryProcessor>;
 
 
     public:
@@ -49,14 +54,17 @@ namespace armarx::armem::server::query_proc::ltm_server::disk
     };
 
     class MemoryQueryProcessor :
-        public ltm::detail::MemoryQueryProcessorBase<armem::server::ltm::disk::Memory, armem::wm::Memory, CoreSegmentQueryProcessor>
+        public ltm::detail::MemoryQueryProcessorBase<armem::server::ltm::Memory,
+                                                     armem::wm::Memory,
+                                                     CoreSegmentQueryProcessor>
     {
     protected:
-
-        using Base = ltm::detail::MemoryQueryProcessorBase<armem::server::ltm::disk::Memory, armem::wm::Memory, CoreSegmentQueryProcessor>;
+        using Base = ltm::detail::MemoryQueryProcessorBase<armem::server::ltm::Memory,
+                                                           armem::wm::Memory,
+                                                           CoreSegmentQueryProcessor>;
 
     public:
         using Base::process;
     };
 
-}
+} // namespace armarx::armem::server::query_proc::ltm_server
diff --git a/source/RobotAPI/libraries/armem/server/test/ArMemLTMBenchmark.cpp b/source/RobotAPI/libraries/armem/server/test/ArMemLTMBenchmark.cpp
index ecf13ddc3a54c6000ae7e9d6abcbfa32bec84057..d2bbeb2f8d1ec31e4b69beacd1e30a3994d00752 100644
--- a/source/RobotAPI/libraries/armem/server/test/ArMemLTMBenchmark.cpp
+++ b/source/RobotAPI/libraries/armem/server/test/ArMemLTMBenchmark.cpp
@@ -24,19 +24,17 @@
 
 #define ARMARX_BOOST_TEST
 
+#include <filesystem>
+#include <iostream>
+
+#include <ArmarXCore/core/time/StopWatch.h>
+
 #include <RobotAPI/Test.h>
-#include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/type/variant/All.h>
 
-#include <ArmarXCore/core/time/StopWatch.h>
-
-
-#include <filesystem>
-#include <iostream>
-
 namespace armem = armarx::armem;
 namespace aron = armarx::aron;
 namespace fs = std::filesystem;
@@ -51,12 +49,14 @@ namespace ArMemLTMBenchmark
         {
             clearStoragePath();
         }
+
         ~Fixture()
         {
             //clearStoragePath();
         }
 
-        void clearStoragePath()
+        void
+        clearStoragePath()
         {
             if (fs::exists(storagePath))
             {
@@ -66,9 +66,13 @@ namespace ArMemLTMBenchmark
             BOOST_REQUIRE(!fs::exists(storagePath));
         }
 
-        void storeElementNTimes(const std::string& memoryName, const aron::data::DictPtr& dict, int waitingTimeMs, int n)
+        void
+        storeElementNTimes(const std::string& memoryName,
+                           const aron::data::DictPtr& dict,
+                           int waitingTimeMs,
+                           int n)
         {
-            armem::server::ltm::disk::Memory ltm(storagePath, memoryName);
+            armem::server::ltm::Memory ltm(storagePath, "MemoryExport", memoryName);
 
             armem::wm::Memory wm(memoryName);
             auto& core = wm.addCoreSegment("CoreS");
@@ -85,29 +89,25 @@ namespace ArMemLTMBenchmark
                 auto cloned = aron::data::Dict::DynamicCastAndCheck(dict->clone());
                 ins.data() = cloned;
 
-                ltm.store(wm);
-                ltm.storeBuffer();
-
+                ltm.directlyStore(wm);
                 usleep(waitingTimeMs * 1000.0);
             }
         }
     };
-}
+} // namespace ArMemLTMBenchmark
 
 BOOST_FIXTURE_TEST_SUITE(ArMemLTMBenchmark, Fixture)
 
-
 BOOST_AUTO_TEST_CASE(test_memory_export__single_image_benchmark)
 {
     auto data = std::make_shared<aron::data::Dict>();
 
     std::vector<int> dimensions = {720, 1280, 3};
     std::string type = "16";
-    std::vector<unsigned char> d(720*1280*3, 255);
+    std::vector<unsigned char> d(720 * 1280 * 3, 255);
     data->addElement("image", std::make_shared<aron::data::NDArray>(dimensions, type, d));
 
     storeElementNTimes("SingleImageBenchmark", data, 100, 2);
 }
 
 BOOST_AUTO_TEST_SUITE_END()
-
diff --git a/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp b/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
index fd326aa038d122cb76a26ad34825dcab4f85b933..db6c68b2d4c6142ef3e7716b1d80245b02b93734 100644
--- a/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
+++ b/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
@@ -25,24 +25,23 @@
 #define ARMARX_BOOST_TEST
 
 #include <RobotAPI/Test.h>
-#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
 #include <RobotAPI/libraries/armem/core/error.h>
-
+#include <RobotAPI/libraries/armem/core/wm/ice_conversions.h>
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/type/variant/All.h>
 
-#include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h>
-
 //#include "../core/io/diskWriter/NlohmannJSON/NlohmannJSONDiskWriter.h"
 
 // TODO: REMOVE ME!!
+#include <filesystem>
+#include <iostream>
+
+#include <VirtualRobot/Import/SimoxXMLFactory.h>
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/Import/SimoxXMLFactory.h>
-#include <RobotAPI/libraries/armem_objects/aron/ObjectInstance.aron.generated.h>
 
-#include <filesystem>
-#include <iostream>
+#include <RobotAPI/libraries/armem_objects/aron/ObjectInstance.aron.generated.h>
 
 namespace armem = armarx::armem;
 namespace aron = armarx::aron;
@@ -59,12 +58,14 @@ namespace ArMemLTMTest
             clearStoragePath();
             assureStoragePath();
         }
+
         ~Fixture()
         {
             //clearStoragePath();
         }
 
-        void assureStoragePath()
+        void
+        assureStoragePath()
         {
             if (!fs::is_directory(storagePath))
             {
@@ -74,7 +75,8 @@ namespace ArMemLTMTest
             BOOST_REQUIRE(fs::exists(storagePath) && fs::is_directory(storagePath));
         }
 
-        void clearStoragePath()
+        void
+        clearStoragePath()
         {
             if (fs::exists(storagePath))
             {
@@ -84,13 +86,12 @@ namespace ArMemLTMTest
             BOOST_REQUIRE(!fs::exists(storagePath));
         }
 
-
-        static armem::wm::Memory setupMemoryWithType(
-            const std::string& memoryName,
-            const aron::type::ObjectPtr& t1,
-            const aron::type::ObjectPtr& t2,
-            unsigned int numSnapshots,
-            unsigned int numInstances)
+        static armem::wm::Memory
+        setupMemoryWithType(const std::string& memoryName,
+                            const aron::type::ObjectPtr& t1,
+                            const aron::type::ObjectPtr& t2,
+                            unsigned int numSnapshots,
+                            unsigned int numInstances)
         {
             /*aron::Randomizer r;
 
@@ -134,7 +135,8 @@ namespace ArMemLTMTest
         }
 
         template <class TypeNavigatorT>
-        aron::type::ObjectPtr makeType(const std::string& memberPrefix, int numMembers = 4)
+        aron::type::ObjectPtr
+        makeType(const std::string& memberPrefix, int numMembers = 4)
         {
             /*aron::type::ObjectPtr t = std::make_shared<aron::type::Object>(aron::Path());
             t->setObjectName("TestObjectType1");
@@ -149,7 +151,8 @@ namespace ArMemLTMTest
         }
 
         template <class TypeNavigatorT>
-        void run(const std::string& memoryName, const std::string& memberNamePrefix)
+        void
+        run(const std::string& memoryName, const std::string& memberNamePrefix)
         {
             /*aron::typenavigator::ObjectNavigatorPtr t = makeType<TypeNavigatorT>(memberNamePrefix);
             armem::Memory memory = setupMemoryWithType(memoryName, t, nullptr, 15, 1);
@@ -177,11 +180,10 @@ namespace ArMemLTMTest
             BOOST_CHECK_EQUAL(memory.equalsDeep(memory2), true);*/
         }
     };
-}
+} // namespace ArMemLTMTest
 
 BOOST_FIXTURE_TEST_SUITE(ArMemLTMTest, Fixture)
 
-
 BOOST_AUTO_TEST_CASE(test_memory_export__easy_int_setup)
 {
     run<aron::type::Int>("TestMemory_IntSetup", "theInt");
@@ -216,40 +218,45 @@ BOOST_AUTO_TEST_CASE(test_memory_export__easy_fabian_setup)
 {
     std::filesystem::path memoryExport = "/home/fabian/repos/projects/ltmtools/data/sim_2022_09_15";
 
-    armem::server::ltm::disk::Memory ltm(memoryExport, "Object");
+    armem::server::ltm::Memory ltm(memoryExport, "MemoryExportTest", "Object");
     auto ltm_c_seg = ltm.findCoreSegment("Instance");
 
-    ltm_c_seg->forEachProviderSegment([](const armem::server::ltm::disk::ProviderSegment& ltm_p_seg){
-        ltm_p_seg.forEachEntity([](const armem::server::ltm::disk::Entity& ltm_e){
-            ltm_e.forEachSnapshot([](const armem::server::ltm::disk::EntitySnapshot& ltm_snapshot){
-                armem::wm::EntitySnapshot s;
-                ltm_snapshot.loadAllReferences(s);
-                ltm_snapshot.resolve(s);
-
-                auto i = s.getInstance(0);
-                auto data = i.data();
+    ltm_c_seg->forEachProviderSegment(
+        [](const armem::server::ltm::ProviderSegment& ltm_p_seg)
+        {
+            ltm_p_seg.forEachEntity(
+                [](const armem::server::ltm::Entity& ltm_e)
+                {
+                    ltm_e.forEachSnapshot(
+                        [](const armem::server::ltm::EntitySnapshot& ltm_snapshot)
+                        {
+                            armem::wm::EntitySnapshot s;
+                            ltm_snapshot.loadAllReferences(s);
+                            ltm_snapshot.resolve(s);
 
+                            auto i = s.getInstance(0);
+                            auto data = i.data();
 
 
-                auto p = data->getElement("pose");
-                auto p2 = armarx::aron::data::Dict::DynamicCastAndCheck(p);
+                            auto p = data->getElement("pose");
+                            auto p2 = armarx::aron::data::Dict::DynamicCastAndCheck(p);
 
-                armarx::objpose::arondto::ObjectPose px;
-                px.fromAron(p2);
+                            armarx::objpose::arondto::ObjectPose px;
+                            px.fromAron(p2);
 
-                auto a = p2->getElement("attachment");
-                auto a2 = armarx::aron::data::Dict::DynamicCastAndCheck(a);
+                            auto a = p2->getElement("attachment");
+                            auto a2 = armarx::aron::data::Dict::DynamicCastAndCheck(a);
 
-                armarx::objpose::arondto::ObjectAttachmentInfo ax;
-                ax.fromAron(a2);
+                            armarx::objpose::arondto::ObjectAttachmentInfo ax;
+                            ax.fromAron(a2);
 
-                if (ax.agentName != "")
-                {
-                    ARMARX_INFO << (ax.poseInFrame);
-                }
-            });
+                            if (ax.agentName != "")
+                            {
+                                ARMARX_INFO << (ax.poseInFrame);
+                            }
+                        });
+                });
         });
-    });
 
 
     //auto ltm_p_seg = ltm_c_seg->findProviderSegment("Armar3");
@@ -263,8 +270,6 @@ BOOST_AUTO_TEST_CASE(test_memory_export__easy_fabian_setup)
 
     //e.forEachSnapshot(f);
     //auto wm = ltm.loadAllAndResolve();
-
-
 }
 
 /*
@@ -315,4 +320,3 @@ BOOST_AUTO_TEST_CASE(test_memory_export__easy_rainer_setup)
 
 
 BOOST_AUTO_TEST_SUITE_END()
-
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
index 4fdda00748d1201e84181c80e3054938c0143348..42c849af0e391fc525b98950a4cfec1f542ea225 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
+++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
@@ -17,13 +17,12 @@
 #include <SimoxUtility/algorithm/get_map_keys_values.h>
 
 #include <ArmarXCore/core/ManagedIceObject.h>
+#include <ArmarXCore/core/ice_conversions/ice_conversions_templates.h>
 #include <ArmarXCore/core/time/TimeUtil.h>
 #include <ArmarXCore/observers/variant/Variant.h>
-#include <ArmarXCore/core/ice_conversions/ice_conversions_templates.h>
 
 #include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
 
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
 #include <RobotAPI/interface/armem/actions.h>
 #include <RobotAPI/interface/armem/memory.h>
 #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h>
@@ -35,7 +34,7 @@
 #include <RobotAPI/libraries/armem_gui/gui_utils.h>
 #include <RobotAPI/libraries/armem_gui/instance/AronDataView.h>
 #include <RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedJSONConverter.h>
-
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
 
 namespace armarx::armem::gui
 {
@@ -82,7 +81,7 @@ namespace armarx::armem::gui
             {
                 std::stringstream sstream;
                 sstream << "Predictions are not available for memory '" << entityID.memoryName
-                   << "'.";
+                        << "'.";
                 this->statusLabel->setText(QString::fromStdString(sstream.str()));
                 return {};
             }
@@ -97,8 +96,7 @@ namespace armarx::armem::gui
             catch (const Ice::LocalException& e)
             {
                 std::stringstream sstream;
-                sstream << "Could not get prediction engines and type from memory: "
-                        << e.what();
+                sstream << "Could not get prediction engines and type from memory: " << e.what();
                 this->statusLabel->setText(QString::fromStdString(sstream.str()));
                 return {nullptr, {}};
             }
@@ -114,8 +112,7 @@ namespace armarx::armem::gui
             }
             return PredictionWidget::EntityInfo{
                 .type = entityType,
-                .engines = armem::accumulateEntriesContainingID(predictionEngines, entityID)
-            };
+                .engines = armem::accumulateEntriesContainingID(predictionEngines, entityID)};
         };
         memoryGroup = new armem::gui::MemoryGroupBox(std::move(retrieveEntityInfo));
 
@@ -153,9 +150,18 @@ namespace armarx::armem::gui
         connect(periodicUpdateTimer, &QTimer::timeout, this, &This::updateListOfActiveMemories);
         connect(periodicUpdateTimer, &QTimer::timeout, this, &This::processQueryResults);
 
-        connect(memoryGroup->queryWidget(), &armem::gui::QueryWidget::storeInLTM, this, &This::queryAndStoreInLTM);
-        connect(memoryGroup->queryWidget(), &armem::gui::QueryWidget::startRecording, this, &This::startLTMRecording);
-        connect(memoryGroup->queryWidget(), &armem::gui::QueryWidget::stopRecording, this, &This::stopLTMRecording);
+        connect(memoryGroup->queryWidget(),
+                &armem::gui::QueryWidget::storeInLTM,
+                this,
+                &This::queryAndStoreInLTM);
+        connect(memoryGroup->queryWidget(),
+                &armem::gui::QueryWidget::startRecording,
+                this,
+                &This::startLTMRecording);
+        connect(memoryGroup->queryWidget(),
+                &armem::gui::QueryWidget::stopRecording,
+                this,
+                &This::stopLTMRecording);
 
         connect(memoryGroup->predictionWidget(),
                 &armem::gui::PredictionWidget::makePrediction,
@@ -192,14 +198,12 @@ namespace armarx::armem::gui
                 &This::showActionsMenu);
     }
 
-
     void
     MemoryViewer::setLogTag(const std::string& _tag) // Leading _ silences a warning
     {
         Logging::setTag(_tag);
     }
 
-
     void
     MemoryViewer::onInit(ManagedIceObject& component)
     {
@@ -216,7 +220,6 @@ namespace armarx::armem::gui
         emit initialized();
     }
 
-
     void
     MemoryViewer::onConnect(ManagedIceObject& component)
     {
@@ -242,7 +245,6 @@ namespace armarx::armem::gui
         emit connected();
     }
 
-
     void
     MemoryViewer::onDisconnect(ManagedIceObject&)
     {
@@ -254,7 +256,8 @@ namespace armarx::armem::gui
         emit disconnected();
     }
 
-    void MemoryViewer::startPeriodicUpdateTimer()
+    void
+    MemoryViewer::startPeriodicUpdateTimer()
     {
         periodicUpdateTimer->start();
     }
@@ -266,8 +269,8 @@ namespace armarx::armem::gui
         if (it == memoryData.end())
         {
             std::stringstream ss;
-            ss << "Memory name '" << memoryName
-               << "' is unknown. Known are: " << simox::alg::join(simox::alg::get_keys(memoryData), ", ");
+            ss << "Memory name '" << memoryName << "' is unknown. Known are: "
+               << simox::alg::join(simox::alg::get_keys(memoryData), ", ");
             statusLabel->setText(QString::fromStdString(ss.str()));
             return nullptr;
         }
@@ -282,7 +285,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::queryAndStoreInLTM()
     {
@@ -292,7 +294,8 @@ namespace armarx::armem::gui
         for (auto& [name, reader] : memoryReaders)
         {
             // skip if memory should not be queried
-            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) == enabledMemories.end())
+            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) ==
+                enabledMemories.end())
             {
                 continue;
             }
@@ -325,7 +328,8 @@ namespace armarx::armem::gui
         for (auto& [name, reader] : memoryReaders)
         {
             // skip if memory should not be queried
-            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) == enabledMemories.end())
+            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) ==
+                enabledMemories.end())
             {
                 continue;
             }
@@ -345,7 +349,8 @@ namespace armarx::armem::gui
         for (auto& [name, reader] : memoryReaders)
         {
             // skip if memory should not be queried
-            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) == enabledMemories.end())
+            if (std::find(enabledMemories.begin(), enabledMemories.end(), name) ==
+                enabledMemories.end())
             {
                 continue;
             }
@@ -355,7 +360,8 @@ namespace armarx::armem::gui
         TIMING_END_STREAM(MemoryStopRecording, ARMARX_VERBOSE);
     }
 
-    void MemoryViewer::commit()
+    void
+    MemoryViewer::commit()
     {
 
         TIMING_START(Commit);
@@ -370,7 +376,8 @@ namespace armarx::armem::gui
 
         if (!memId.hasEntityName())
         {
-            ARMARX_WARNING << "The entered MemoryID '" << memoryIDStr << "' does not contain an entity.";
+            ARMARX_WARNING << "The entered MemoryID '" << memoryIDStr
+                           << "' does not contain an entity.";
         }
         else
         {
@@ -378,11 +385,14 @@ namespace armarx::armem::gui
             nlohmann::json json = nlohmann::json::parse(aronJSONStr);
 
             // ToDo: multiple objects
-            auto aron = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(json);
+            auto aron =
+                aron::data::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(
+                    json);
 
             if (const auto& it = memoryWriters.find(memId.memoryName); it == memoryWriters.end())
             {
-                ARMARX_WARNING << "No memory with name '" << memId.memoryName << "' available for commit.";
+                ARMARX_WARNING << "No memory with name '" << memId.memoryName
+                               << "' available for commit.";
             }
             else
             {
@@ -399,7 +409,6 @@ namespace armarx::armem::gui
         TIMING_END_STREAM(Commit, ARMARX_VERBOSE);
     }
 
-
     void
     MemoryViewer::storeOnDisk(QString directory)
     {
@@ -413,7 +422,6 @@ namespace armarx::armem::gui
         TIMING_END_STREAM(MemoryExport, ARMARX_VERBOSE)
     }
 
-
     void
     MemoryViewer::loadFromDisk(QString directory)
     {
@@ -433,7 +441,8 @@ namespace armarx::armem::gui
             }
             else
             {
-                ARMARX_INFO << "No memory with name '" << name << "' available for commit. Create new virtual memory.";
+                ARMARX_INFO << "No memory with name '" << name
+                            << "' available for commit. Create new virtual memory.";
 
                 // Please note: Here we assume that a memory server with the same name does not exist.
                 // I think this assumption is ok, since nobody should use filepaths as memory name.
@@ -450,14 +459,12 @@ namespace armarx::armem::gui
         emit memoryDataChanged();
     }
 
-
     void
     MemoryViewer::startQueries()
     {
         startDueQueries();
     }
 
-
     void
     MemoryViewer::processQueryResults()
     {
@@ -470,7 +477,6 @@ namespace armarx::armem::gui
         updateStatusLabel(errorCount);
     }
 
-
     void
     MemoryViewer::updateStatusLabel(int errorCount)
     {
@@ -488,7 +494,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::startDueQueries()
     {
@@ -502,7 +507,8 @@ namespace armarx::armem::gui
         for (const auto& pair : memoryReaders)
         {
             // skip if memory should not be queried
-            if (std::find(enabledMemories.begin(), enabledMemories.end(), pair.first) == enabledMemories.end())
+            if (std::find(enabledMemories.begin(), enabledMemories.end(), pair.first) ==
+                enabledMemories.end())
             {
                 continue;
             }
@@ -518,18 +524,18 @@ namespace armarx::armem::gui
 
             // You could pass the query function itself to async here,
             // but that caused severe template headaches when I tried it.
-            runningQueries[name] = std::async(std::launch::async,
-                   [reader, input, recursionDepth, this]()
-                   {
-                       // Can't resolve MemoryLinks without data
-                       return recursionDepth == 0 || input.dataMode == armem::query::DataMode::NoData
-                                  ? reader.query(input.toIce())
-                                  : reader.query(input.toIce(), mns, recursionDepth);
-                   });
+            runningQueries[name] = std::async(
+                std::launch::async,
+                [reader, input, recursionDepth, this]()
+                {
+                    // Can't resolve MemoryLinks without data
+                    return recursionDepth == 0 || input.dataMode == armem::query::DataMode::NoData
+                               ? reader.query(input.toIce())
+                               : reader.query(input.toIce(), mns, recursionDepth);
+                });
         }
     }
 
-
     std::map<std::string, client::QueryResult>
     MemoryViewer::collectQueryResults()
     {
@@ -581,9 +587,9 @@ namespace armarx::armem::gui
         return results;
     }
 
-
     void
-    MemoryViewer::applyQueryResults(const std::map<std::string, client::QueryResult>& results, int* outErrorCount)
+    MemoryViewer::applyQueryResults(const std::map<std::string, client::QueryResult>& results,
+                                    int* outErrorCount)
     {
         TIMING_START(tProcessQueryResults)
         for (const auto& [name, result] : results)
@@ -594,7 +600,8 @@ namespace armarx::armem::gui
             }
             else
             {
-                ARMARX_WARNING << "Querying memory server '" << name << "' produced an error: \n" << result.errorMessage;
+                ARMARX_WARNING << "Querying memory server '" << name << "' produced an error: \n"
+                               << result.errorMessage;
                 if (outErrorCount)
                 {
                     outErrorCount++;
@@ -621,7 +628,8 @@ namespace armarx::armem::gui
             }
 
             // Drop all entries that are not enabled by user (which means that there is no query result)
-            if (std::find(enabledMemories.begin(), enabledMemories.end(), it->first) == enabledMemories.end())
+            if (std::find(enabledMemories.begin(), enabledMemories.end(), it->first) ==
+                enabledMemories.end())
             {
                 if (memoryGroup->queryWidget()->dropDisabledMemories())
                 {
@@ -651,7 +659,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::updateInstanceTree(const armem::MemoryID& selectedID)
     {
@@ -702,7 +709,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::resolveMemoryID(const MemoryID& id)
     {
@@ -773,7 +779,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::updateListOfActiveMemories()
     {
@@ -787,7 +792,10 @@ namespace armarx::armem::gui
                 std::vector<std::string> activeMemoryNames;
 
                 // add all active memories to update list
-                std::transform(memoryReaders.begin(), memoryReaders.end(), std::back_inserter(activeMemoryNames), [](const auto& p){return p.first;});
+                std::transform(memoryReaders.begin(),
+                               memoryReaders.end(),
+                               std::back_inserter(activeMemoryNames),
+                               [](const auto& p) { return p.first; });
 
                 TIMING_START(GuiUpdateAvailableMemories);
                 memoryGroup->queryWidget()->update(activeMemoryNames);
@@ -801,11 +809,12 @@ namespace armarx::armem::gui
         }
         else
         {
-            ARMARX_VERBOSE << deactivateSpam() << "MNS not ready yet. Skip update of available memories in query widget.";
+            ARMARX_VERBOSE
+                << deactivateSpam()
+                << "MNS not ready yet. Skip update of available memories in query widget.";
         }
     }
 
-
     void
     MemoryViewer::updateMemoryTree()
     {
@@ -825,9 +834,10 @@ namespace armarx::armem::gui
         {
             try
             {
-                debugObserver->setDebugDatafield(Logging::tag.tagName,
-                                                 "GUI Update [ms]",
-                                                 new Variant(GuiUpdateMemoryTree.toMilliSecondsDouble()));
+                debugObserver->setDebugDatafield(
+                    Logging::tag.tagName,
+                    "GUI Update [ms]",
+                    new Variant(GuiUpdateMemoryTree.toMilliSecondsDouble()));
             }
             catch (const Ice::Exception&)
             {
@@ -836,7 +846,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::showActionsMenu(const MemoryID& memoryID,
                                   QWidget* parent,
@@ -865,8 +874,7 @@ namespace armarx::armem::gui
         catch (const error::CouldNotResolveMemoryServer& e)
         {
             statusLabel->setText(
-                    QString::fromStdString(
-                        e.makeMsg(memoryID, "Could not resolve memory server.")));
+                QString::fromStdString(e.makeMsg(memoryID, "Could not resolve memory server.")));
             showMenu();
             return;
         }
@@ -874,8 +882,7 @@ namespace armarx::armem::gui
         if (!prx.actions)
         {
             std::stringstream ss;
-            ss << "Memory server " << memoryID
-               << " does not support actions or is offline.";
+            ss << "Memory server " << memoryID << " does not support actions or is offline.";
             statusLabel->setText(QString::fromStdString(ss.str()));
             showMenu();
             return;
@@ -909,7 +916,7 @@ namespace armarx::armem::gui
                 try
                 {
                     result = prx.actions->executeActions(
-                            {{armarx::toIce<armem::data::MemoryID>(memoryID), path}});
+                        {{armarx::toIce<armem::data::MemoryID>(memoryID), path}});
                 }
                 catch (const Ice::LocalException& e)
                 {
@@ -942,7 +949,6 @@ namespace armarx::armem::gui
         }
     }
 
-
     void
     MemoryViewer::makePrediction(const MemoryID& entityID,
                                  const aron::type::ObjectPtr& entityType,
@@ -952,9 +958,7 @@ namespace armarx::armem::gui
 
         std::stringstream errorStream;
         auto showError = [this, &errorStream]()
-        {
-            statusLabel->setText(QString::fromStdString(errorStream.str()));
-        };
+        { statusLabel->setText(QString::fromStdString(errorStream.str())); };
 
         if (!entityID.hasEntityName() || entityID.hasGap())
         {
@@ -1004,11 +1008,9 @@ namespace armarx::armem::gui
         view->update(result.prediction, entityType);
     }
 
-
     const static std::string CONFIG_KEY_MEMORY = "MemoryViewer.MemoryNameSystem";
     const static std::string CONFIG_KEY_DEBUG_OBSERVER = "MemoryViewer.DebugObserverName";
 
-
     void
     MemoryViewer::loadSettings(QSettings* settings)
     {
@@ -1020,6 +1022,7 @@ namespace armarx::armem::gui
                 .toString()
                 .toStdString();
     }
+
     void
     MemoryViewer::saveSettings(QSettings* settings)
     {
@@ -1029,7 +1032,6 @@ namespace armarx::armem::gui
                            QString::fromStdString(debugObserverName));
     }
 
-
     void
     MemoryViewer::writeConfigDialog(SimpleConfigDialog* dialog)
     {
@@ -1038,6 +1040,7 @@ namespace armarx::armem::gui
         dialog->addProxyFinder<armarx::DebugObserverInterfacePrx>(
             {CONFIG_KEY_DEBUG_OBSERVER, "Debug Observer", "DebugObserver"});
     }
+
     void
     MemoryViewer::readConfigDialog(SimpleConfigDialog* dialog)
     {
diff --git a/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp
index a490d63436a484cee322d167a02675710c695260..cb828b64fdb412ce6e7faa30def48e91867173b0 100644
--- a/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp
+++ b/source/RobotAPI/libraries/armem_gui/disk/ControlWidget.cpp
@@ -1,19 +1,17 @@
 #include "ControlWidget.h"
 
-#include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h>
-#include <RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h>
-
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+#include <cmath>
+#include <filesystem>
 
-#include <QHBoxLayout>
-#include <QSpacerItem>
 #include <QFileDialog>
+#include <QHBoxLayout>
 #include <QPushButton>
+#include <QSpacerItem>
 
-#include <filesystem>
-
-#include <cmath>
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <RobotAPI/libraries/armem/server/ltm/Memory.h>
+#include <RobotAPI/libraries/armem/server/query_proc/ltm/disk/ltm.h>
 
 namespace armarx::armem::gui::disk
 {
@@ -28,7 +26,7 @@ namespace armarx::armem::gui::disk
         _storeOnDiskButton->setIcon(QIcon(":/icons/document-save.svg"));
 
         // Allow horizontal shrinking of buttons
-        std::vector<QPushButton*> buttons { _storeOnDiskButton, _loadFromDiskButton };
+        std::vector<QPushButton*> buttons{_storeOnDiskButton, _loadFromDiskButton};
         for (QPushButton* button : buttons)
         {
             button->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::Fixed);
@@ -48,46 +46,47 @@ namespace armarx::armem::gui::disk
 
         // Connections
 
-        connect(_loadFromDiskButton, &QPushButton::pressed, [this]()
-        {
-            QString directory = chooseDirectoryDialog();
-            if (directory.size() > 0)
-            {
-                emit requestedLoadFromDisk(directory);
-            }
-        });
-        connect(_storeOnDiskButton, &QPushButton::pressed, [this]()
-        {
-            QString directory = chooseDirectoryDialog();
-            if (directory.size() > 0)
-            {
-                emit requestedStoreOnDisk(directory);
-            }
-        });
+        connect(_loadFromDiskButton,
+                &QPushButton::pressed,
+                [this]()
+                {
+                    QString directory = chooseDirectoryDialog();
+                    if (directory.size() > 0)
+                    {
+                        emit requestedLoadFromDisk(directory);
+                    }
+                });
+        connect(_storeOnDiskButton,
+                &QPushButton::pressed,
+                [this]()
+                {
+                    QString directory = chooseDirectoryDialog();
+                    if (directory.size() > 0)
+                    {
+                        emit requestedStoreOnDisk(directory);
+                    }
+                });
     }
 
-
-    static
-    const std::string&
+    static const std::string&
     handleSingular(int num, const std::string& singular, const std::string& plural)
     {
         return num == 1 ? singular : plural;
     }
 
-
     void
-    ControlWidget::storeOnDisk(
-        QString directory,
-        const std::vector<wm::Memory> memoryData,
-        std::string* outStatus)
+    ControlWidget::storeOnDisk(QString directory,
+                               const std::vector<wm::Memory> memoryData,
+                               std::string* outStatus)
     {
         std::filesystem::path path(directory.toUtf8().constData());
-        ARMARX_CHECK_POSITIVE(path.string().size());  // An empty path indicates an error.
+        ARMARX_CHECK_POSITIVE(path.string().size()); // An empty path indicates an error.
 
         std::stringstream status;
         if (std::filesystem::is_regular_file(path))
         {
-            status << "Could not export memories contents to " << path << ": Cannot overwrite existing file.";
+            status << "Could not export memories contents to " << path
+                   << ": Cannot overwrite existing file.";
         }
         else
         {
@@ -97,17 +96,19 @@ namespace armarx::armem::gui::disk
                 std::string name = data.id().memoryName;
                 if (std::filesystem::is_regular_file(path / name))
                 {
-                    status << "Could not export memory '" << name << "' to " << path << ": Cannot overwrite existing file.\n";
+                    status << "Could not export memory '" << name << "' to " << path
+                           << ": Cannot overwrite existing file.\n";
                 }
                 else
                 {
-                    armem::server::ltm::disk::Memory memory(path, name);
+                    armem::server::ltm::Memory memory(path, "MemoryExport", name);
                     memory.directlyStore(data);
 
                     numStored++;
                 }
             }
-            status << "Exported " << numStored << " " << handleSingular(numStored, "memory", "memories") << " to " << path << ".";
+            status << "Exported " << numStored << " "
+                   << handleSingular(numStored, "memory", "memories") << " to " << path << ".";
         }
 
         if (outStatus)
@@ -116,18 +117,17 @@ namespace armarx::armem::gui::disk
         }
     }
 
-
     std::map<std::filesystem::path, wm::Memory>
-    ControlWidget::loadFromDisk(
-        QString directory,
-        const armem::client::QueryInput& _queryInput,
-        std::string* outStatus)
+    ControlWidget::loadFromDisk(QString directory,
+                                const armem::client::QueryInput& _queryInput,
+                                std::string* outStatus)
     {
         std::filesystem::path path(directory.toUtf8().constData());
 
         std::map<std::filesystem::path, wm::Memory> memoryData;
 
-        auto setStatus = [&](const std::string& s){
+        auto setStatus = [&](const std::string& s)
+        {
             if (outStatus)
             {
                 *outStatus = s;
@@ -136,28 +136,33 @@ namespace armarx::armem::gui::disk
 
         if (not std::filesystem::is_directory(path))
         {
-            setStatus("Could not import a memory from " + path.string() + ". It is not a directory. Skipping import.");
+            setStatus("Could not import a memory from " + path.string() +
+                      ". It is not a directory. Skipping import.");
             return memoryData;
         }
 
         // Find out whether this is a single memory or a collection of memories by searching
         // for a data.aron.* or metadata.aron.* file at depth 5 (if 6 then it is collection of memories)
         bool isSingleMemory = false;
-        for (auto i = std::filesystem::recursive_directory_iterator(path); i != std::filesystem::recursive_directory_iterator(); ++i)
+        for (auto i = std::filesystem::recursive_directory_iterator(path);
+             i != std::filesystem::recursive_directory_iterator();
+             ++i)
         {
-            if (i.depth() > armem::server::ltm::disk::Memory::DEPTH_TO_DATA_FILES + 2)
+            if (i.depth() > armem::server::ltm::Memory::DEPTH_TO_DATA_FILES + 2)
             {
                 // After some depth we stop searching to not freeze GUI too long
-                setStatus("Could not import a memory from " + path.string() + ". Data files were not found until max-depth 7. Skipping import.");
+                setStatus("Could not import a memory from " + path.string() +
+                          ". Data files were not found until max-depth 7. Skipping import.");
                 return memoryData;
             }
 
             auto& dir = *i;
 
             // if one matches it is enough to check
-            if (std::filesystem::is_regular_file(dir.path()) && simox::alg::starts_with(dir.path().filename(), "data.aron"))
+            if (std::filesystem::is_regular_file(dir.path()) &&
+                simox::alg::starts_with(dir.path().filename(), "data.aron"))
             {
-                isSingleMemory = (i.depth() == armem::server::ltm::disk::Memory::DEPTH_TO_DATA_FILES);
+                isSingleMemory = (i.depth() == armem::server::ltm::Memory::DEPTH_TO_DATA_FILES);
                 break;
             }
         }
@@ -169,11 +174,13 @@ namespace armarx::armem::gui::disk
         // const query::data::Input queryIce = queryInput.toIce();
 
         int numLoaded = 0;
-        auto loadMemory = [&](const std::filesystem::path& p) {
+        auto loadMemory = [&](const std::filesystem::path& p)
+        {
             if (std::filesystem::is_directory(p))
             {
-                armem::server::ltm::disk::Memory ltm(p.parent_path(), p.filename());
-                armem::wm::Memory memory = ltm.loadAllAndResolve(); // load list of references and load data
+                armem::server::ltm::Memory ltm(p.parent_path(), "MemoryExport", p.filename());
+                armem::wm::Memory memory =
+                    ltm.loadAllAndResolve(); // load list of references and load data
                 memoryData[p] = memory;
 
                 numLoaded++;
@@ -193,20 +200,21 @@ namespace armarx::armem::gui::disk
             }
         }
 
-        setStatus("Loaded " + std::to_string(numLoaded) + " " + handleSingular(numLoaded, "memory", "memories") + " from " + path.string() + ".");
+        setStatus("Loaded " + std::to_string(numLoaded) + " " +
+                  handleSingular(numLoaded, "memory", "memories") + " from " + path.string() + ".");
         return memoryData;
     }
 
-
-    QString ControlWidget::chooseDirectoryDialog()
+    QString
+    ControlWidget::chooseDirectoryDialog()
     {
-        _latestDirectory = QFileDialog::getExistingDirectory(this, "Open query result",
+        _latestDirectory = QFileDialog::getExistingDirectory(this,
+                                                             "Open query result",
                                                              _latestDirectory,
-                                                             QFileDialog::ShowDirsOnly
-                                                             | QFileDialog::DontResolveSymlinks);
+                                                             QFileDialog::ShowDirsOnly |
+                                                                 QFileDialog::DontResolveSymlinks);
 
         return _latestDirectory;
     }
 
-}
-
+} // namespace armarx::armem::gui::disk
diff --git a/source/RobotAPI/libraries/armem_gui/instance/DataView.cpp b/source/RobotAPI/libraries/armem_gui/instance/DataView.cpp
index f4d5f79cabb89ecbf0a0e5c50c8975af6e14010d..ecb8cecf7eb72d285e071217db47f0174ffd16f2 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/DataView.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/DataView.cpp
@@ -55,8 +55,10 @@ namespace armarx::armem::gui::instance
         tree->addTopLevelItem(treeItemData);
         treeItemData->setExpanded(true);
         tree->setContextMenuPolicy(Qt::CustomContextMenu);
-        connect(
-            tree, &QTreeWidget::customContextMenuRequested, this, &DataView::prepareTreeContextMenu);
+        connect(tree,
+                &QTreeWidget::customContextMenuRequested,
+                this,
+                &DataView::prepareTreeContextMenu);
     }
 
     void
@@ -322,7 +324,7 @@ namespace armarx::armem::gui::instance
                     try
                     {
                         nlohmann::json json =
-                            aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(
+                            aron::data::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(
                                 element);
                         QClipboard* clipboard = QApplication::clipboard();
                         clipboard->setText(QString::fromStdString(json.dump(2)));
@@ -570,7 +572,6 @@ namespace armarx::armem::gui::instance
         return image;
     }
 
-
     void
     DataView::updateImageView(const aron::data::DictPtr& data)
     {
@@ -691,7 +692,6 @@ namespace armarx::armem::gui::instance
         }
     }
 
-
     DataView::ImageView::ImageView() :
         cmap(simox::color::cmaps::plasma().reversed()), limitsHistoryMaxSize(32)
     {
diff --git a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp
index 6b7e2a77a2a606cd111091a850157600d1efd892..6e2e92a7cea71f53f2eb16f4ea369f53176f7079 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp
@@ -1,85 +1,92 @@
 #include "TypedDataDisplayVisitor.h"
 
-#include <iomanip>      // std::setprecision
+#include <iomanip> // std::setprecision
 
 #include <SimoxUtility/algorithm/string.h>
 #include <SimoxUtility/math/pose/pose.h>
 
 #include <ArmarXCore/core/logging/Logging.h>
 
-#include <RobotAPI/libraries/aron/core/data/variant/All.h>
-#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
 
 #include "DataDisplayVisitor.h"
 
-
 namespace armarx::aron
 {
 
-    std::string TypedDataDisplayVisitor::getValue(const type::VariantPtr& type, const data::VariantPtr& data)
+    std::string
+    TypedDataDisplayVisitor::getValue(const type::VariantPtr& type, const data::VariantPtr& data)
     {
         TypedDataDisplayVisitor v;
         data::visit(v, data, type);
         return v.value.str();
     }
 
-
     TypedDataDisplayVisitor::TypedDataDisplayVisitor() :
-        coeffSep("  "),
-        eigenIof(Eigen::StreamPrecision, 0, coeffSep, "\n", "", "", "", "")
+        coeffSep("  "), eigenIof(Eigen::StreamPrecision, 0, coeffSep, "\n", "", "", "", "")
     {
     }
 
-
-    void TypedDataDisplayVisitor::visitDict(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitDict(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitObject(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitObject(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitList(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitList(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitTuple(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitTuple(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitBool(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitBool(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitDouble(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitDouble(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         setStreamPrecision();
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitFloat(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitFloat(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         setStreamPrecision();
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitInt(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitInt(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitLong(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitLong(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitString(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitString(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
@@ -93,23 +100,29 @@ namespace armarx::aron
 
 
     template <typename ScalarT>
-    void TypedDataDisplayVisitor::processMatrix(const type::Matrix& type, const data::NDArray& data)
+    void
+    TypedDataDisplayVisitor::processMatrix(const type::Matrix& type, const data::NDArray& data)
     {
-        Eigen::Map<Eigen::Matrix<ScalarT, Eigen::Dynamic, Eigen::Dynamic>> m(reinterpret_cast<ScalarT*>(data.getData()), type.getRows(), type.getCols());
+        Eigen::Map<Eigen::Matrix<ScalarT, Eigen::Dynamic, Eigen::Dynamic>> m(
+            reinterpret_cast<ScalarT*>(data.getData()), type.getRows(), type.getCols());
         value << m.format(eigenIof);
     }
 
-    void TypedDataDisplayVisitor::processQuaternion(const data::NDArray& data)
+    void
+    TypedDataDisplayVisitor::processQuaternion(const data::NDArray& data)
     {
-        const Eigen::Quaternionf quat = aron::converter::AronEigenConverter::ConvertToQuaternionf(data);
+        const Eigen::Quaternionf quat =
+            aron::data::converter::AronEigenConverter::ConvertToQuaternionf(data);
         setStreamPrecision();
-        value << quat.w() << coeffSep << "|" << coeffSep << quat.x() << coeffSep << quat.y() << coeffSep << quat.z();
+        value << quat.w() << coeffSep << "|" << coeffSep << quat.x() << coeffSep << quat.y()
+              << coeffSep << quat.z();
     }
 
-    void TypedDataDisplayVisitor::processPose(const type::Matrix&, const data::NDArray& d)
+    void
+    TypedDataDisplayVisitor::processPose(const type::Matrix&, const data::NDArray& d)
     {
         const Eigen::IOFormat eigenIof(Eigen::StreamPrecision, 0, " ", "\n", "( ", " )", "", "");
-        const std::string cdot = "\u00B7";  // center dot: https://unicode-table.com/de/00B7/
+        const std::string cdot = "\u00B7"; // center dot: https://unicode-table.com/de/00B7/
 
         auto getLines = [&](auto&& mat)
         {
@@ -121,7 +134,8 @@ namespace armarx::aron
             return lines;
         };
 
-        const Eigen::Matrix4f pose = aron::converter::AronEigenConverter::ConvertToMatrix4f(d);
+        const Eigen::Matrix4f pose =
+            aron::data::converter::AronEigenConverter::ConvertToMatrix4f(d);
         const std::vector<std::string> r = getLines(simox::math::orientation(pose));
         const std::vector<std::string> t = getLines(simox::math::position(pose));
 
@@ -133,14 +147,16 @@ namespace armarx::aron
         value << simox::alg::join(lines, "\n");
     }
 
-    void TypedDataDisplayVisitor::processPosition(const type::Matrix&, const data::NDArray& d)
+    void
+    TypedDataDisplayVisitor::processPosition(const type::Matrix&, const data::NDArray& d)
     {
-        const Eigen::Vector3f pos = aron::converter::AronEigenConverter::ConvertToVector3f(d);
+        const Eigen::Vector3f pos = aron::data::converter::AronEigenConverter::ConvertToVector3f(d);
         setStreamPrecision();
         value << pos.format(eigenIof);
     }
 
-    void TypedDataDisplayVisitor::visitMatrix(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitMatrix(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         auto t = *type::Matrix::DynamicCastAndCheck(type);
         auto d = *data::NDArray::DynamicCastAndCheck(data);
@@ -166,32 +182,38 @@ namespace armarx::aron
         }
     }
 
-    void TypedDataDisplayVisitor::visitQuaternion(const data::VariantPtr& data, const type::VariantPtr&)
+    void
+    TypedDataDisplayVisitor::visitQuaternion(const data::VariantPtr& data, const type::VariantPtr&)
     {
         auto d = *data::NDArray::DynamicCastAndCheck(data);
         processQuaternion(d);
     }
 
-    void TypedDataDisplayVisitor::visitImage(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitImage(const data::VariantPtr& data, const type::VariantPtr& type)
     {
         // aron::typenavigator::ImagePixelType pixelType = ImageNavigator::pixelTypeFromName(data.getType());
         //value << DataDisplayVisitor::getValue(data) << " pixel type: " << data.getType()";
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::visitPointCloud(const data::VariantPtr& data, const type::VariantPtr& type)
+    void
+    TypedDataDisplayVisitor::visitPointCloud(const data::VariantPtr& data,
+                                             const type::VariantPtr& type)
     {
         value << DataDisplayVisitor::getValue(data);
     }
 
-    void TypedDataDisplayVisitor::setStreamPrecision()
+    void
+    TypedDataDisplayVisitor::setStreamPrecision()
     {
         setStreamPrecision(value);
     }
 
-    void TypedDataDisplayVisitor::setStreamPrecision(std::ostream& os)
+    void
+    TypedDataDisplayVisitor::setStreamPrecision(std::ostream& os)
     {
         os << std::setprecision(2) << std::fixed;
     }
 
-}
+} // namespace armarx::aron
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedDataVisitor.cpp b/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedDataVisitor.cpp
index c37bff2f8acdc57ff57b691344bd7f78f70435ed..43c4cb1eccef4ce1cf5a4e73c60f3ce7378c8d09 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedDataVisitor.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedDataVisitor.cpp
@@ -1,15 +1,14 @@
 #include "TreeTypedDataVisitor.h"
 
-#include <iomanip>      // std::setprecision
+#include <iomanip> // std::setprecision
 
 #include <SimoxUtility/algorithm/string.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
-#include <RobotAPI/libraries/aron/core/Exception.h>
-#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
 #include <RobotAPI/libraries/armem/core.h>
-
+#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
+#include <RobotAPI/libraries/aron/core/Exception.h>
 
 namespace armarx::armem::gui::instance
 {
@@ -22,14 +21,17 @@ namespace armarx::armem::gui::instance
         ss << armem::toDateTimeMilliSeconds(time);
     }*/
 
-    void TreeTypedDataVisitor::streamValueText(const aron::data::NDArray& data, const aron::type::Matrix& type, std::stringstream& ss) const
+    void
+    TreeTypedDataVisitor::streamValueText(const aron::data::NDArray& data,
+                                          const aron::type::Matrix& type,
+                                          std::stringstream& ss) const
     {
         auto shape = data.getShape();
 
         // TODO: Remove hardcoded stuff
         if (shape.size() == 3)
         {
-            if (shape[0] == 3 && shape [1] == 1 && shape[2] == 4)
+            if (shape[0] == 3 && shape[1] == 1 && shape[2] == 4)
             {
                 streamPositionText(data, type, ss);
                 return;
@@ -50,28 +52,42 @@ namespace armarx::armem::gui::instance
         TreeDataVisitorBase::streamValueText(data, ss); // fallback
     }
 
-    void TreeTypedDataVisitor::streamPoseText(const aron::data::NDArray& data, const aron::type::Matrix& type, std::stringstream& ss) const
+    void
+    TreeTypedDataVisitor::streamPoseText(const aron::data::NDArray& data,
+                                         const aron::type::Matrix& type,
+                                         std::stringstream& ss) const
     {
-        (void) type;
-        const Eigen::Matrix4f pose = aron::converter::AronEigenConverter::ConvertToMatrix4f(data);
+        (void)type;
+        const Eigen::Matrix4f pose =
+            aron::data::converter::AronEigenConverter::ConvertToMatrix4f(data);
         ss << std::setprecision(2) << std::fixed;
-        ss << pose.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, coeffSep, "\n", "", "", "", ""));
+        ss << pose.format(
+            Eigen::IOFormat(Eigen::StreamPrecision, 0, coeffSep, "\n", "", "", "", ""));
     }
 
-    void TreeTypedDataVisitor::streamPositionText(const aron::data::NDArray& data, const aron::type::Matrix& type, std::stringstream& ss) const
+    void
+    TreeTypedDataVisitor::streamPositionText(const aron::data::NDArray& data,
+                                             const aron::type::Matrix& type,
+                                             std::stringstream& ss) const
     {
-        (void) type;
-        const Eigen::Vector3f pos = aron::converter::AronEigenConverter::ConvertToVector3f(data);
+        (void)type;
+        const Eigen::Vector3f pos =
+            aron::data::converter::AronEigenConverter::ConvertToVector3f(data);
         ss << std::setprecision(2) << std::fixed;
         ss << pos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, "", coeffSep, "", "", "", ""));
     }
 
-    void TreeTypedDataVisitor::streamOrientationText(const aron::data::NDArray& data, const aron::type::Matrix& type, std::stringstream& ss) const
+    void
+    TreeTypedDataVisitor::streamOrientationText(const aron::data::NDArray& data,
+                                                const aron::type::Matrix& type,
+                                                std::stringstream& ss) const
     {
-        (void) type;
-        const Eigen::Quaternionf quat = aron::converter::AronEigenConverter::ConvertToQuaternionf(data);
+        (void)type;
+        const Eigen::Quaternionf quat =
+            aron::data::converter::AronEigenConverter::ConvertToQuaternionf(data);
         ss << std::setprecision(2) << std::fixed;
-        ss << quat.w() << coeffSep << "|" << coeffSep << quat.x() << coeffSep << quat.y() << coeffSep << quat.z();
+        ss << quat.w() << coeffSep << "|" << coeffSep << quat.x() << coeffSep << quat.y()
+           << coeffSep << quat.z();
     }
 
-}
+} // namespace armarx::armem::gui::instance
diff --git a/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedJSONConverter.cpp b/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedJSONConverter.cpp
index d3f214b6f038581d93b55ce8e9d7e6145620c82e..c36d567350b3050ed49e7d362dfcaf2f63f3a643 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedJSONConverter.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/tree_visitors/TreeTypedJSONConverter.cpp
@@ -165,7 +165,7 @@ namespace armarx::armem::gui::instance
         const std::string key = elementData->getPath().getLastElement();
         auto nd = *aron::data::NDArray::DynamicCastAndCheck(elementData);
         nlohmann::json obj;
-        Eigen::to_json(obj, aron::converter::AronEigenConverter::ConvertToQuaternionf(nd));
+        Eigen::to_json(obj, aron::data::converter::AronEigenConverter::ConvertToQuaternionf(nd));
         insertIntoJSON(key, obj);
     }
 
diff --git a/source/RobotAPI/libraries/armem_laser_scans/CMakeLists.txt b/source/RobotAPI/libraries/armem_laser_scans/CMakeLists.txt
index 1d452ddcb4d41e37379cf21364bd914e59e328c5..f40102f3bb1c12ea9d6884e58d4115f25634737b 100644
--- a/source/RobotAPI/libraries/armem_laser_scans/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_laser_scans/CMakeLists.txt
@@ -11,6 +11,7 @@ armarx_add_library(
         RobotAPI::Core
         RobotAPI::armem
         aroncommon
+        aronvectorconverter
         armem_robot_state
         armem_robot
         # System / External
diff --git a/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.cpp b/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.cpp
index aaa39472e70e3152feee0f306aca66b81d3f7343..4cc4a87d2f003633f99b365f5b068b53efc2ac33 100644
--- a/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.cpp
+++ b/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.cpp
@@ -8,7 +8,6 @@
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
 #include <RobotAPI/libraries/armem_laser_scans/aron/LaserScan.aron.generated.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
-#include <RobotAPI/libraries/aron/converter/common/Converter.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
 #include "types.h"
diff --git a/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.h b/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.h
index 931cda8c82013b0d2ad9060bd39be4273e9fce51..6c6761b521128684a89cae3c085b9060d0a2a7e5 100644
--- a/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.h
+++ b/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.h
@@ -24,8 +24,8 @@
 #include <RobotAPI/interface/units/LaserScannerUnit.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem_laser_scans/types.h>
-#include <RobotAPI/libraries/aron/converter/common/VectorConverter.h>
 #include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
+#include <RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
 namespace armarx::armem::laser_scans
@@ -49,7 +49,7 @@ namespace armarx::armem::laser_scans
     auto
     fromAron(const aron::data::NDArrayPtr& navigator)
     {
-        return aron::converter::AronVectorConverter::ConvertToVector<T>(navigator);
+        return aron::data::converter::AronVectorConverter::ConvertToVector<T>(navigator);
     }
 
     void fromAron(const arondto::LaserScanStamped& aronLaserScan, LaserScanStamped& laserScan);
@@ -63,7 +63,7 @@ namespace armarx::armem::laser_scans
     inline aron::data::NDArrayPtr
     toAron(const LaserScan& laserScan)
     {
-        using aron::converter::AronVectorConverter;
+        using aron::data::converter::AronVectorConverter;
         return AronVectorConverter::ConvertFromVector(laserScan);
     }
 
diff --git a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h
index 4900004e06517e824053b4ed080de02c42aeb3a2..0a517497c617db0773adc21851adb791835fe2b3 100644
--- a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h
+++ b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h
@@ -34,6 +34,7 @@
 
 // The object pose provider. As long as the provider is not connected to armem we need the second proxy
 #include <RobotAPI/interface/objectpose/ObjectPoseProvider.h>
+#include <RobotAPI/interface/objectpose/ObjectPoseStorageInterface.h>
 
 namespace armarx::armem::obj::instance
 {
@@ -172,6 +173,7 @@ namespace armarx::armem::obj::instance
         const std::string propertyPrefix = "mem.obj.instance.";
 
         armem::client::MemoryNameSystem& memoryNameSystem;
+        objpose::ObjectPoseStorageInterfacePrx objPoseStorage;
         objpose::ObjectPoseProviderPrx objPoseProvider;
 
         armem::client::Reader memoryReader;
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
index b0726c001d978f7f98e5517e69248c6a9b4fd47f..03da4c2061d786b22fd1f126d9e8c2983e28faec 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
@@ -1317,7 +1317,13 @@ namespace armarx::armem::server::obj::instance
 
             if (robot)
             {
-                ARMARX_CHECK(reader->synchronizeRobot(*robot, Clock::Now()));
+                bool synchronized = reader->synchronizeRobot(*robot, Clock::Now());
+                if (not synchronized)
+                {
+                    ARMARX_INFO << "The robot '" << robotName << "' could be loaded, but not"
+                                << " synchronized successfully (e.g., the global localization could be missing). "
+                                << "Make sure to synchronize it before use if necessary.";
+                }
                 // Store robot if valid.
                 loaded.emplace(robotName, robot);
             }
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.h b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.h
index a9cddc6b2afd5258271f5718b4f1c82d0dd6a995..ee1274fab20cadb62231bc7fdd685c408104e705 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.h
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.h
@@ -47,9 +47,9 @@ namespace armarx::armem::robot_state
         RobotReader(armem::client::MemoryNameSystem& memoryNameSystem);
         virtual ~RobotReader() = default;
 
-        void connect();
+        virtual void connect();
 
-        void registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def);
+        virtual void registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def);
 
         [[nodiscard]] bool synchronize(robot::Robot& obj, const armem::Time& timestamp) override;
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
index 225e048864e69a7c349b9e53163d41ed1e0eef6b..76fa10a4c0186acecdb969ec69af75d97975708f 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
@@ -13,42 +13,37 @@
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include <ArmarXCore/core/time/Clock.h>
 
-
 namespace armarx::armem::robot_state
 {
 
     VirtualRobotReader::VirtualRobotReader(armem::client::MemoryNameSystem& memoryNameSystem) :
-        RobotReader(memoryNameSystem)
+            RobotReader(memoryNameSystem)
     {
     }
 
-    void
-    VirtualRobotReader::connect()
+    void VirtualRobotReader::connect()
     {
         RobotReader::connect();
     }
 
     // TODO(fabian.reister): register property defs
-    void
-    VirtualRobotReader::registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def)
+    void VirtualRobotReader::registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def)
     {
         RobotReader::registerPropertyDefinitions(def);
     }
 
-    bool
-    VirtualRobotReader::synchronizeRobot(VirtualRobot::Robot& robot, const armem::Time& timestamp)
+    bool VirtualRobotReader::synchronizeRobot(VirtualRobot::Robot& robot, const armem::Time& timestamp)
     {
         // const static auto packages = armarx::CMakePackageFinder::FindAllArmarXSourcePackages();
         // const auto package = armarx::ArmarXDataPath::getProject(packages, robot.getFilename());
 
-        const robot::RobotDescription robotDescription{
-            .name = robot.getName(), .xml = PackagePath{"", ""}};
+        const robot::RobotDescription robotDescription{.name = robot.getName(), .xml = PackagePath{"", ""}};
 
         const auto robotState = queryState(robotDescription, timestamp);
         if (not robotState)
         {
-            ARMARX_VERBOSE << "Querying robot state failed for robot `" << robot.getName() << "` "
-                           << "(type `"<< robot.getType() << "`)!";
+            ARMARX_VERBOSE << deactivateSpam(5) << "Querying robot state failed for robot `" << robot.getName() << "` "
+                           << "(type `" << robot.getType() << "`)!";
             return false;
         }
 
@@ -58,18 +53,15 @@ namespace armarx::armem::robot_state
         return true;
     }
 
-    VirtualRobot::RobotPtr
-    VirtualRobotReader::getRobot(const std::string& name,
-                                 const armem::Time& timestamp,
-                                 const VirtualRobot::RobotIO::RobotDescription& loadMode)
+    VirtualRobot::RobotPtr VirtualRobotReader::getRobot(const std::string& name, const armem::Time& timestamp,
+                                                        const VirtualRobot::RobotIO::RobotDescription& loadMode)
     {
-        ARMARX_INFO << deactivateSpam(60)
-                    << "Querying robot description for robot '" << name << "'";
+        ARMARX_VERBOSE << deactivateSpam(60) << "Querying robot description for robot '" << name << "'";
         const auto description = queryDescription(name, timestamp);
 
         if (not description)
         {
-            ARMARX_VERBOSE << "The description of robot `" << name << "` is not a available!";
+            ARMARX_VERBOSE << deactivateSpam(5) << "The description of robot `" << name << "` is not a available!";
 
             return nullptr;
         }
@@ -77,8 +69,8 @@ namespace armarx::armem::robot_state
         const std::string xmlFilename = description->xml.toSystemPath();
         ARMARX_CHECK(std::filesystem::exists(xmlFilename)) << xmlFilename;
 
-        ARMARX_INFO << "Loading (virtual) robot '" << description->name << "' from XML file '"
-                        << xmlFilename << "'";
+        ARMARX_VERBOSE << deactivateSpam(5) << "Loading (virtual) robot '" << description->name << "' from XML file '"
+                       << xmlFilename << "'";
 
         auto robot = VirtualRobot::RobotIO::loadRobot(xmlFilename, loadMode);
         ARMARX_CHECK_NOT_NULL(robot) << "Could not load robot from file `" << xmlFilename << "`";
@@ -88,34 +80,24 @@ namespace armarx::armem::robot_state
         return robot;
     }
 
-
-    VirtualRobot::RobotPtr
-    VirtualRobotReader::getSynchronizedRobot(
-            const std::string& name,
-            const VirtualRobot::BaseIO::RobotDescription& loadMode,
-            bool blocking)
+    VirtualRobot::RobotPtr VirtualRobotReader::getSynchronizedRobot(const std::string& name,
+                                                                    const VirtualRobot::BaseIO::RobotDescription& loadMode,
+                                                                    bool blocking)
     {
         return _getSynchronizedRobot(name, armem::Time::Invalid(), loadMode, blocking);
     }
 
-
     VirtualRobot::RobotPtr
-    VirtualRobotReader::getSynchronizedRobot(
-        const std::string& name,
-        const armem::Time& timestamp,
-        const VirtualRobot::RobotIO::RobotDescription& loadMode,
-        const bool blocking)
+    VirtualRobotReader::getSynchronizedRobot(const std::string& name, const armem::Time& timestamp,
+                                             const VirtualRobot::RobotIO::RobotDescription& loadMode,
+                                             const bool blocking)
     {
         return _getSynchronizedRobot(name, timestamp, loadMode, blocking);
     }
 
-
-    VirtualRobot::RobotPtr
-    VirtualRobotReader::_getSynchronizedRobot(
-            const std::string& name,
-            const Time& timestamp,
-            const VirtualRobot::BaseIO::RobotDescription& loadMode,
-            bool blocking)
+    VirtualRobot::RobotPtr VirtualRobotReader::_getSynchronizedRobot(const std::string& name, const Time& timestamp,
+                                                                     const VirtualRobot::BaseIO::RobotDescription& loadMode,
+                                                                     bool blocking)
     {
         while (blocking)
         {
@@ -127,11 +109,11 @@ namespace armarx::armem::robot_state
                 return robot;
             }
 
-            ARMARX_INFO << "Retrying to query robot after failure";
+            ARMARX_VERBOSE << deactivateSpam(5) << "Retrying to query robot after failure";
             Clock::WaitFor(sleepAfterFailure);
         }
 
-        ARMARX_VERBOSE << "Failed to get synchronized robot `" << name << "`";
+        ARMARX_VERBOSE << deactivateSpam(5) << "Failed to get synchronized robot `" << name << "`";
         return nullptr;
     }
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
index ab30cbc1317d98f802dc24cbe5d844da02b038e9..3de8fbe8b49c453a79a7cafbcf7904713f4d756f 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
@@ -43,8 +43,8 @@ namespace armarx::armem::robot_state
         VirtualRobotReader(armem::client::MemoryNameSystem& memoryNameSystem);
         ~VirtualRobotReader() override = default;
 
-        void connect();
-        void registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def);
+        void connect() override;
+        void registerPropertyDefinitions(::armarx::PropertyDefinitionsPtr& def) override;
 
         [[nodiscard]] bool synchronizeRobot(VirtualRobot::Robot& robot,
                                             const armem::Time& timestamp);
diff --git a/source/RobotAPI/libraries/armem_skills/CMakeLists.txt b/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
index f0d624155b4f8e7abadd86f158c445ca4484d49e..5dea7fd336d310010fdd6a15be653b6c5cdeba46 100644
--- a/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
@@ -13,7 +13,7 @@ armarx_add_library(
         RobotAPI::armem_server
         RobotAPI::skills
         aronjsonconverter
-        aroncommonconverter
+        arondatatypeconverter
     SOURCES  
         ./aron_conversions.cpp
 
diff --git a/source/RobotAPI/libraries/armem_skills/server/segment/ExecutableSkillLibrarySegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/ExecutableSkillLibrarySegment.cpp
index 1a342fe0cde09bd59821bb93374025cd8866e782..89e7e1c92af94e46c2493a5c18825c94b0551ac7 100644
--- a/source/RobotAPI/libraries/armem_skills/server/segment/ExecutableSkillLibrarySegment.cpp
+++ b/source/RobotAPI/libraries/armem_skills/server/segment/ExecutableSkillLibrarySegment.cpp
@@ -1,31 +1,36 @@
 #include "ExecutableSkillLibrarySegment.h"
 
-#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 #include <SimoxUtility/algorithm/string.h>
 
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
-#include <RobotAPI/libraries/aron/converter/common/DatatypeConverter.h>
-
+#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
 #include <RobotAPI/libraries/armem_skills/aron/Skill.aron.generated.h>
+#include <RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h>
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
 
 namespace armarx::skills::segment
 {
-    ExecutableSkillLibraryCoreSegment::ExecutableSkillLibraryCoreSegment(armem::server::MemoryToIceAdapter& iceMemory):
+    ExecutableSkillLibraryCoreSegment::ExecutableSkillLibraryCoreSegment(
+        armem::server::MemoryToIceAdapter& iceMemory) :
         Base(iceMemory, CoreSegmentName, skills::arondto::SkillDescription::ToAronType())
     {
     }
 
-    void ExecutableSkillLibraryCoreSegment::defineProperties(PropertyDefinitionsPtr defs, const std::string &prefix)
+    void
+    ExecutableSkillLibraryCoreSegment::defineProperties(PropertyDefinitionsPtr defs,
+                                                        const std::string& prefix)
     {
         // No properties! (meaning no name and no max size)
     }
 
-    void ExecutableSkillLibraryCoreSegment::init()
+    void
+    ExecutableSkillLibraryCoreSegment::init()
     {
         Base::init();
     }
 
-    void ExecutableSkillLibraryCoreSegment::addSkillProvider(const skills::manager::dto::ProviderInfo& info)
+    void
+    ExecutableSkillLibraryCoreSegment::addSkillProvider(
+        const skills::manager::dto::ProviderInfo& info)
     {
         // add skills
         auto skills = info.providedSkills;
@@ -45,7 +50,7 @@ namespace armarx::skills::segment
             {
                 auto t = aron::type::Object::FromAronObjectDTO(desc.acceptedType);
 
-                aron::converter::DatatypeConverter c;
+                aron::type::converter::AronDatatypeConverterVisitor c;
                 aron::type::visit(c, t);
 
                 skillDescription.acceptedType = aron::data::Dict::DynamicCastAndCheck(c.latest);
@@ -65,10 +70,11 @@ namespace armarx::skills::segment
         }
     }
 
-    void ExecutableSkillLibraryCoreSegment::removeSkillProvider(const std::string& providerName)
+    void
+    ExecutableSkillLibraryCoreSegment::removeSkillProvider(const std::string& providerName)
     {
         skills.erase(providerName);
 
         // TODO also add info about removed provider to memory?
     }
-}
+} // namespace armarx::skills::segment
diff --git a/source/RobotAPI/libraries/armem_vision/CMakeLists.txt b/source/RobotAPI/libraries/armem_vision/CMakeLists.txt
index e59ec79249df593a76633d3ba3c27d3ac5262617..74a2ece78b8db2462731d6460836387d143cf514 100644
--- a/source/RobotAPI/libraries/armem_vision/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_vision/CMakeLists.txt
@@ -11,6 +11,7 @@ armarx_add_library(
         RobotAPI::Core
         RobotAPI::armem
         aroncommon
+        aronvectorconverter
         # System / External
         Eigen3::Eigen
         armem_laser_scans
diff --git a/source/RobotAPI/libraries/armem_vision/aron_conversions.cpp b/source/RobotAPI/libraries/armem_vision/aron_conversions.cpp
index f15cc62479df42c420c839312dd9e2777ce514bf..7051c186ac290a3e71fe3cbb435d1b9ab09b997d 100644
--- a/source/RobotAPI/libraries/armem_vision/aron_conversions.cpp
+++ b/source/RobotAPI/libraries/armem_vision/aron_conversions.cpp
@@ -6,7 +6,6 @@
 
 #include <RobotAPI/libraries/armem/core/aron_conversions.h>
 #include <RobotAPI/libraries/aron/common/aron_conversions.h>
-#include <RobotAPI/libraries/aron/converter/common/Converter.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
 #include "types.h"
diff --git a/source/RobotAPI/libraries/armem_vision/aron_conversions.h b/source/RobotAPI/libraries/armem_vision/aron_conversions.h
index e2d8c1c454aaf10ec09ea5eea5c0b252c7d337e7..f6f1a53225698f2617559073db3f19c3351b1dd1 100644
--- a/source/RobotAPI/libraries/armem_vision/aron_conversions.h
+++ b/source/RobotAPI/libraries/armem_vision/aron_conversions.h
@@ -24,8 +24,8 @@
 #include <RobotAPI/libraries/armem/core/Time.h>
 #include <RobotAPI/libraries/armem_vision/aron/OccupancyGrid.aron.generated.h>
 #include <RobotAPI/libraries/armem_vision/types.h>
-#include <RobotAPI/libraries/aron/converter/common/VectorConverter.h>
 #include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
+#include <RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
 namespace armarx::armem::vision
@@ -38,7 +38,7 @@ namespace armarx::armem::vision
     inline aron::data::NDArrayPtr
     toAron(const OccupancyGrid::Grid& grid)
     {
-        return aron::converter::AronEigenConverter::ConvertFromArray(grid);
+        return aron::data::converter::AronEigenConverter::ConvertFromArray(grid);
     }
 
 } // namespace armarx::armem::vision
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 a98495d192583b101299c8b6b0b365f569427a38..b3f93dd6878789db4b104cb7ed4d7fc36c0878ee 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Reader.cpp
@@ -6,11 +6,10 @@
 #include <map>
 #include <optional>
 #include <ostream>
+#include <type_traits>
 #include <utility>
 #include <vector>
 
-#include <type_traits>
-
 // ICE
 #include <IceUtil/Handle.h>
 #include <IceUtil/Time.h>
@@ -25,10 +24,10 @@
 #include <ArmarXCore/core/logging/Logging.h>
 
 // RobotAPI Interfaces
-#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>
+#include <RobotAPI/libraries/aron/converter/eigen/EigenConverter.h>
 
 // RobotAPI Aron
 #include <RobotAPI/libraries/armem_vision/aron/OccupancyGrid.aron.generated.h>
@@ -49,7 +48,8 @@ namespace armarx::armem::vision::occupancy_grid::client
 {
     Reader::~Reader() = default;
 
-    armarx::armem::client::query::Builder Reader::buildQuery(const Query& query) const
+    armarx::armem::client::query::Builder
+    Reader::buildQuery(const Query& query) const
     {
         armarx::armem::client::query::Builder qb;
 
@@ -63,35 +63,35 @@ namespace armarx::armem::vision::occupancy_grid::client
 
         return qb;
     }
-    
-    std::string Reader::propertyPrefix() const 
+
+    std::string
+    Reader::propertyPrefix() const
     {
         return "mem.vision.occupancy_grid.";
     }
-    
-    armarx::armem::client::util::SimpleReaderBase::Properties Reader::defaultProperties() const 
+
+    armarx::armem::client::util::SimpleReaderBase::Properties
+    Reader::defaultProperties() const
     {
-        return 
-        {
-            .memoryName = "Vision",
-            .coreSegmentName = "OccupancyGrid"
-        };
+        return {.memoryName = "Vision", .coreSegmentName = "OccupancyGrid"};
     }
 
-    OccupancyGrid asOccupancyGrid(const wm::ProviderSegment& providerSegment)
+    OccupancyGrid
+    asOccupancyGrid(const wm::ProviderSegment& providerSegment)
     {
         ARMARX_CHECK(not providerSegment.empty()) << "No entities";
         ARMARX_CHECK(providerSegment.size() == 1) << "There should be only one entity!";
 
         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";
+        providerSegment.forEachEntity(
+            [&entityInstance](const wm::Entity& entity)
+            {
+                const auto& entitySnapshot = entity.getLatestSnapshot();
+                ARMARX_CHECK(not entitySnapshot.empty()) << "No entity snapshot instances";
 
-            entityInstance = &entitySnapshot.getInstance(0);
-            return false;
-        });
+                entityInstance = &entitySnapshot.getInstance(0);
+                return false;
+            });
         ARMARX_CHECK_NOT_NULL(entityInstance);
 
         const auto aronDto = tryCast<arondto::OccupancyGrid>(*entityInstance);
@@ -101,66 +101,63 @@ namespace armarx::armem::vision::occupancy_grid::client
         fromAron(*aronDto, occupancyGrid);
 
         // direct access to grid data
-        const auto ndArrayNavigator = aron::data::NDArray::DynamicCast(
-                                          entityInstance->data()->getElement("grid"));
+        const auto ndArrayNavigator =
+            aron::data::NDArray::DynamicCast(entityInstance->data()->getElement("grid"));
         ARMARX_CHECK_NOT_NULL(ndArrayNavigator);
 
-        occupancyGrid.grid = aron::converter::AronEigenConverter::ConvertToArray<float>(*ndArrayNavigator);
+        occupancyGrid.grid =
+            aron::data::converter::AronEigenConverter::ConvertToArray<float>(*ndArrayNavigator);
 
         return occupancyGrid;
     }
 
-    Reader::Result Reader::query(const Query& query) const
+    Reader::Result
+    Reader::query(const Query& query) const
     {
         const auto qb = buildQuery(query);
 
         ARMARX_DEBUG << "[MappingDataReader] query ... ";
 
-        const armem::client::QueryResult qResult =
-            memoryReader().query(qb.buildQueryInput());
+        const armem::client::QueryResult qResult = memoryReader().query(qb.buildQueryInput());
 
         ARMARX_DEBUG << "[MappingDataReader] result: " << qResult;
 
         if (not qResult.success)
         {
-            ARMARX_WARNING << "Failed to query data from memory: "
-                           << qResult.errorMessage;
+            ARMARX_WARNING << "Failed to query data from memory: " << qResult.errorMessage;
             return {.occupancyGrid = std::nullopt,
-                    .status        = Result::Status::Error,
-                    .errorMessage  = qResult.errorMessage};
+                    .status = Result::Status::Error,
+                    .errorMessage = qResult.errorMessage};
         }
 
         const auto coreSegment = qResult.memory.getCoreSegment(properties().coreSegmentName);
 
-        if(not coreSegment.hasProviderSegment(query.providerName))
+        if (not coreSegment.hasProviderSegment(query.providerName))
         {
-            ARMARX_WARNING << "Provider segment `" << query.providerName << "` does not exist (yet).";
-            return
-            {
-                .occupancyGrid = std::nullopt,
-                .status = Result::Status::NoData
-            };
+            ARMARX_WARNING << "Provider segment `" << query.providerName
+                           << "` does not exist (yet).";
+            return {.occupancyGrid = std::nullopt, .status = Result::Status::NoData};
         }
 
-        const wm::ProviderSegment& providerSegment = coreSegment.getProviderSegment(query.providerName);
+        const wm::ProviderSegment& providerSegment =
+            coreSegment.getProviderSegment(query.providerName);
 
         if (providerSegment.empty())
         {
             ARMARX_WARNING << "No entities.";
             return {.occupancyGrid = std::nullopt,
-                    .status        = Result::Status::NoData,
-                    .errorMessage  = "No entities"};
+                    .status = Result::Status::NoData,
+                    .errorMessage = "No entities"};
         }
 
         try
         {
             const auto occupancyGrid = asOccupancyGrid(providerSegment);
-            return Result{.occupancyGrid = occupancyGrid,
-                          .status        = Result::Status::Success};
+            return Result{.occupancyGrid = occupancyGrid, .status = Result::Status::Success};
         }
         catch (...)
         {
-            return Result{.status       = Result::Status::Error,
+            return Result{.status = Result::Status::Error,
                           .errorMessage = GetHandledExceptionString()};
         }
     }
diff --git a/source/RobotAPI/libraries/aron/CMakeLists.txt b/source/RobotAPI/libraries/aron/CMakeLists.txt
index e1ccc8560ff75b018fbc958d0f1febf0512d9590..692784791b779d28035abc83adb5354033a4b335 100644
--- a/source/RobotAPI/libraries/aron/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/CMakeLists.txt
@@ -1,5 +1,7 @@
 add_subdirectory(core)
+add_subdirectory(common)
 add_subdirectory(converter)
+add_subdirectory(filter)
 add_subdirectory(codegeneration)
-add_subdirectory(common)
+add_subdirectory(similarity)
 add_subdirectory(test)
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
index d0bf18091c9fd3310b1d0d9de98ff7c6c259eff3..ce9389d138de2774555bb3c1b6bbc45b151d65cc 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
@@ -26,72 +26,89 @@
 
 #include <SimoxUtility/meta/type_name.h>
 
-
 namespace armarx::aron::codegenerator::cpp::generator
 {
-    const std::map<type::matrix::ElementType, std::tuple<std::string, int, std::string>> ElementType2Cpp =
-    {
-        // TODO: rename to float32 etc. but keep backward compability
-        {type::matrix::INT16, {"short", 2, "::armarx::aron::type::matrix::INT16"}},
-        {type::matrix::INT32, {"int", 4, "::armarx::aron::type::matrix::INT32"}},
-        {type::matrix::INT64, {"long", 8, "::armarx::aron::type::matrix::INT64"}},
-        {type::matrix::FLOAT32, {"float", 4, "::armarx::aron::type::matrix::FLOAT32"}},
-        {type::matrix::FLOAT64, {"double", 8, "::armarx::aron::type::matrix::FLOAT64"}}
-    };
+    const std::map<type::matrix::ElementType, std::tuple<std::string, int, std::string>>
+        ElementType2Cpp = {
+            // TODO: rename to float32 etc. but keep backward compability
+            {type::matrix::INT16, {"short", 2, "::armarx::aron::type::matrix::INT16"}},
+            {type::matrix::INT32, {"int", 4, "::armarx::aron::type::matrix::INT32"}},
+            {type::matrix::INT64, {"long", 8, "::armarx::aron::type::matrix::INT64"}},
+            {type::matrix::FLOAT32, {"float", 4, "::armarx::aron::type::matrix::FLOAT32"}},
+            {type::matrix::FLOAT64, {"double", 8, "::armarx::aron::type::matrix::FLOAT64"}}};
 
     // constructors
     Matrix::Matrix(const type::Matrix& n) :
         detail::NDArrayGenerator<type::Matrix, Matrix>(
-            "Eigen::Matrix<" + std::get<0>(ElementType2Cpp.at(n.getElementType())) + ", " + (n.getRows() == -1 ? "Eigen::Dynamic" : std::to_string(n.getRows())) + ", " + (n.getCols() == -1 ? "Eigen::Dynamic" : std::to_string(n.getCols())) + ">",
-            "Eigen::Matrix<" + std::get<0>(ElementType2Cpp.at(n.getElementType())) + ", " + (n.getRows() == -1 ? "Eigen::Dynamic" : std::to_string(n.getRows())) + ", " + (n.getCols() == -1 ? "Eigen::Dynamic" : std::to_string(n.getCols())) + ">",
+            "Eigen::Matrix<" + std::get<0>(ElementType2Cpp.at(n.getElementType())) + ", " +
+                (n.getRows() == -1 ? "Eigen::Dynamic" : std::to_string(n.getRows())) + ", " +
+                (n.getCols() == -1 ? "Eigen::Dynamic" : std::to_string(n.getCols())) + ">",
+            "Eigen::Matrix<" + std::get<0>(ElementType2Cpp.at(n.getElementType())) + ", " +
+                (n.getRows() == -1 ? "Eigen::Dynamic" : std::to_string(n.getRows())) + ", " +
+                (n.getCols() == -1 ? "Eigen::Dynamic" : std::to_string(n.getCols())) + ">",
             simox::meta::get_type_name<data::dto::NDArray>(),
-            simox::meta::get_type_name<type::dto::Matrix>(), n)
+            simox::meta::get_type_name<type::dto::Matrix>(),
+            n)
     {
     }
 
-    std::vector<std::string> Matrix::getRequiredIncludes() const
+    std::vector<std::string>
+    Matrix::getRequiredIncludes() const
     {
         return {"<Eigen/Core>"};
     }
 
-    CppBlockPtr Matrix::getResetSoftBlock(const std::string& cppAccessor) const
+    CppBlockPtr
+    Matrix::getResetSoftBlock(const std::string& cppAccessor) const
     {
         CppBlockPtr block_if_data = std::make_shared<CppBlock>();
         block_if_data->addLine(cppAccessor + nextEl() + "setZero();");
         return this->resolveMaybeResetSoftBlock(block_if_data, cppAccessor);
     }
 
-    CppBlockPtr Matrix::getWriteTypeBlock(const std::string& typeAccessor, const std::string& cppAccessor, const Path& p, std::string& variantAccessor) const
+    CppBlockPtr
+    Matrix::getWriteTypeBlock(const std::string& typeAccessor,
+                              const std::string& cppAccessor,
+                              const Path& p,
+                              std::string& variantAccessor) const
     {
         CppBlockPtr b = std::make_shared<CppBlock>();
         std::string escaped_accessor = EscapeAccessor(cppAccessor);
         variantAccessor = ARON_VARIANT_RETURN_ACCESSOR + "_" + escaped_accessor;
-        b->addLine("auto " + variantAccessor + " = " + ARON_WRITER_ACCESSOR + ".writeMatrix((int) " + std::to_string(type.getRows()) + ", " +
-                "(int) " + std::to_string(type.getCols()) + ", " +
-                std::get<2>(ElementType2Cpp.at(type.getElementType())) + ", " +
-                conversion::Maybe2CppString.at(type.getMaybe()) + ", " +
-                "armarx::aron::Path("+ARON_PATH_ACCESSOR+", {"+simox::alg::join(p.getPath(), ", ")+"})); // of " + cppAccessor);
+        b->addLine("auto " + variantAccessor + " = " + ARON_WRITER_ACCESSOR +
+                   ".writeMatrix((int) " + std::to_string(type.getRows()) + ", " + "(int) " +
+                   std::to_string(type.getCols()) + ", " +
+                   std::get<2>(ElementType2Cpp.at(type.getElementType())) + ", " +
+                   conversion::Maybe2CppString.at(type.getMaybe()) + ", " + "armarx::aron::Path(" +
+                   ARON_PATH_ACCESSOR + ", {" + simox::alg::join(p.getPath(), ", ") +
+                   "})); // of " + cppAccessor);
 
         return b;
     }
 
-    CppBlockPtr Matrix::getWriteBlock(const std::string& cppAccessor, const Path& p, std::string& variantAccessor) const
+    CppBlockPtr
+    Matrix::getWriteBlock(const std::string& cppAccessor,
+                          const Path& p,
+                          std::string& variantAccessor) const
     {
         CppBlockPtr block_if_data = std::make_shared<CppBlock>();
         std::string escaped_accessor = EscapeAccessor(cppAccessor);
         variantAccessor = ARON_VARIANT_RETURN_ACCESSOR + "_" + escaped_accessor;
 
-        block_if_data->addLine(variantAccessor + " = " + ARON_WRITER_ACCESSOR + ".writeNDArray({(int) " + cppAccessor + nextEl() + "rows(), "+
-                "(int) " + cppAccessor + nextEl() + "cols(), " +
-                std::to_string(std::get<1>(ElementType2Cpp.at(type.getElementType()))) + "}, "+
-                "\"" + std::get<0>(ElementType2Cpp.at(type.getElementType())) + "\", "+
-                "reinterpret_cast<const unsigned char*>(" + cppAccessor + nextEl() + "data()), " +
-                "armarx::aron::Path("+ARON_PATH_ACCESSOR+", {" + simox::alg::join(p.getPath(), ", ") + "})); // of " + cppAccessor);
+        block_if_data->addLine(
+            variantAccessor + " = " + ARON_WRITER_ACCESSOR + ".writeNDArray({(int) " + cppAccessor +
+            nextEl() + "rows(), " + "(int) " + cppAccessor + nextEl() + "cols(), " +
+            std::to_string(std::get<1>(ElementType2Cpp.at(type.getElementType()))) + "}, " + "\"" +
+            std::get<0>(ElementType2Cpp.at(type.getElementType())) + "\", " +
+            "reinterpret_cast<const unsigned char*>(" + cppAccessor + nextEl() + "data()), " +
+            "armarx::aron::Path(" + ARON_PATH_ACCESSOR + ", {" +
+            simox::alg::join(p.getPath(), ", ") + "})); // of " + cppAccessor);
 
         return resolveMaybeWriteBlock(block_if_data, cppAccessor);
     }
 
-    CppBlockPtr Matrix::getReadBlock(const std::string& cppAccessor, const std::string& variantAccessor) const
+    CppBlockPtr
+    Matrix::getReadBlock(const std::string& cppAccessor, const std::string& variantAccessor) const
     {
         CppBlockPtr block_if_data = std::make_shared<CppBlock>();
         std::string escaped_accessor = EscapeAccessor(cppAccessor);
@@ -103,35 +120,52 @@ namespace armarx::aron::codegenerator::cpp::generator
         block_if_data->addLine("std::vector<int> " + dims + ";");
         block_if_data->addLine("std::vector<unsigned char> " + data + ";");
 
-        block_if_data->addLine("" + ARON_READER_ACCESSOR + ".readNDArray("+variantAccessor+", "+dims+", "+type+", "+data+"); // of " + cppAccessor);
+        block_if_data->addLine("" + ARON_READER_ACCESSOR + ".readNDArray(" + variantAccessor +
+                               ", " + dims + ", " + type + ", " + data + "); // of " + cppAccessor);
 
-        if((this->type.getRows() == -1 or this->type.getRows() == Eigen::Dynamic) and this->type.getCols() != -1)
+        if ((this->type.getRows() == -1 or this->type.getRows() == Eigen::Dynamic) and
+            this->type.getCols() != -1)
         {
             block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + ".at(0));");
         }
 
-        if(this->type.getRows() != -1 and (this->type.getCols() == -1 or this->type.getCols() == Eigen::Dynamic))
+        if (this->type.getRows() != -1 and
+            (this->type.getCols() == -1 or this->type.getCols() == Eigen::Dynamic))
         {
             block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + ".at(1));");
         }
 
-        if((this->type.getRows() == -1 or this->type.getRows() == Eigen::Dynamic) and (this->type.getCols() == -1 or this->type.getCols() == Eigen::Dynamic))
+        if ((this->type.getRows() == -1 or this->type.getRows() == Eigen::Dynamic) and
+            (this->type.getCols() == -1 or this->type.getCols() == Eigen::Dynamic))
         {
-            block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + ".at(0), " + dims + ".at(1));");
+            block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + ".at(0), " + dims +
+                                   ".at(1));");
         }
 
-        block_if_data->addLine("ARMARX_CHECK_AND_THROW(" + cppAccessor + nextEl() + "rows() == " + dims + ".at(0) and " + cppAccessor + nextEl() + "cols() == " + dims + ".at(1), ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, \"Received wrong dimensions for member '"+cppAccessor+"'.\"));");
-        block_if_data->addLine("ARMARX_CHECK_AND_THROW(" + type + " == \"" + std::get<0>(ElementType2Cpp.at(this->type.getElementType())) + "\", ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, \"Received wrong type for member '"+cppAccessor+"'.\"));");
-
-        block_if_data->addLine("std::memcpy(reinterpret_cast<unsigned char*>(" + cppAccessor + nextEl() + "data()), "+data+".data(), "+data+".size());");
+        block_if_data->addLine("ARMARX_CHECK_AND_THROW(" + cppAccessor + nextEl() + "rows() == " +
+                               dims + ".at(0) and " + cppAccessor + nextEl() + "cols() == " + dims +
+                               ".at(1), ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, "
+                               "\"Received wrong dimensions for member '" +
+                               cppAccessor + "'.\"));");
+        block_if_data->addLine("//ARMARX_CHECK_AND_THROW(" + type + " == \"" +
+                               std::get<0>(ElementType2Cpp.at(this->type.getElementType())) +
+                               "\", ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, "
+                               "\"Received wrong type for member '" +
+                               cppAccessor + "'.\"));");
+
+        block_if_data->addLine("std::memcpy(reinterpret_cast<unsigned char*>(" + cppAccessor +
+                               nextEl() + "data()), " + data + ".data(), " + data + ".size());");
         return resolveMaybeReadBlock(block_if_data, cppAccessor, variantAccessor);
     }
 
-    CppBlockPtr Matrix::getEqualsBlock(const std::string& accessor, const std::string& otherInstanceAccessor) const
+    CppBlockPtr
+    Matrix::getEqualsBlock(const std::string& accessor,
+                           const std::string& otherInstanceAccessor) const
     {
         CppBlockPtr block_if_data = std::make_shared<CppBlock>();
-        block_if_data->addLine("if (not (" + accessor + nextEl() + "isApprox(" + resolveMaybeAccessor(otherInstanceAccessor) + ")))");
+        block_if_data->addLine("if (not (" + accessor + nextEl() + "isApprox(" +
+                               resolveMaybeAccessor(otherInstanceAccessor) + ")))");
         block_if_data->addLineAsBlock("return false;");
         return resolveMaybeEqualsBlock(block_if_data, accessor, otherInstanceAccessor);
     }
-}
+} // namespace armarx::aron::codegenerator::cpp::generator
diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions.h b/source/RobotAPI/libraries/aron/common/aron_conversions.h
index 84804124d7e82a042e89eb5720400e991fc8139d..95177ce57e2b6ab67e0e0e5e4f761646d2775302 100644
--- a/source/RobotAPI/libraries/aron/common/aron_conversions.h
+++ b/source/RobotAPI/libraries/aron/common/aron_conversions.h
@@ -1,5 +1,6 @@
 #pragma once
 
+#include <RobotAPI/libraries/aron/core/aron_conversions.h>
 #include "aron_conversions/armarx.h"
 #include "aron_conversions/simox.h"
 #include "aron_conversions/eigen.h"
diff --git a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
index e93d191b2f99b0eccb973a925a77ebdf674ffaee..d1c054832bef05c9062baa5ee04f5eef9d1494f5 100644
--- a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
@@ -1,21 +1,23 @@
-add_subdirectory(common)
 add_subdirectory(ivt)
 add_subdirectory(pcl)
 add_subdirectory(eigen)
 add_subdirectory(opencv)
 add_subdirectory(json)
+add_subdirectory(stdstl)
+add_subdirectory(datatype)
 
 
 add_library(AronConverter INTERFACE)
 
 target_link_libraries(AronConverter
     INTERFACE
-        RobotAPI::aron::converter::common    
         RobotAPI::aron::converter::ivt    
         RobotAPI::aron::converter::pcl    
         RobotAPI::aron::converter::eigen    
         RobotAPI::aron::converter::opencv
         RobotAPI::aron::converter::json
+        RobotAPI::aron::converter::stdstl
+        RobotAPI::aron::converter::datatype
 )
 
 add_library(aron::converter ALIAS AronConverter)
diff --git a/source/RobotAPI/libraries/aron/converter/binary/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/binary/CMakeLists.txt
deleted file mode 100644
index 7fa2684a23d3ef1e887a5f11b1c5aa83cbbe4b8f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/binary/CMakeLists.txt
+++ /dev/null
@@ -1,34 +0,0 @@
-set(LIB_NAME aronivtconverter)
-
-armarx_component_set_name("${LIB_NAME}")
-armarx_set_target("Library: ${LIB_NAME}")
-
-armarx_build_if(IVT_FOUND "IVT not available")
-armarx_build_if(OpenCV_FOUND "OpenCV not available")
-
-set(LIBS
-    aron 
-    ivt 
-    ivtopencv
-
-    ${IVT_LIBRARIES}
-)
-
-set(LIB_FILES
-    IVTConverter.cpp
-)
-
-set(LIB_HEADERS
-    IVTConverter.h
-)
-
-armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
-
-if(IVT_FOUND)
-    target_include_directories(aronivtconverter
-        SYSTEM PUBLIC 
-            ${IVT_INCLUDE_DIRS}
-    )
-endif()
-
-add_library(RobotAPI::aron::converter::ivt ALIAS aronivtconverter)
diff --git a/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.cpp b/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.cpp
deleted file mode 100644
index 999359d6b79ef56bbe7352263556ad71316e7384..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.cpp
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * This file is part of ArmarX.
- *
- * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
- * Karlsruhe Institute of Technology (KIT), all rights reserved.
- *
- * 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/>.
- *
- * @author     Fabian Peller-Konrad (fabian dot peller-konrad at kit dot edu)
- * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
- *             GNU General Public License
- */
-
-// STD/STL
-#include <numeric>
-
-// Header
-#include "IVTConverter.h"
-
-namespace armarx::aron::converter
-{
-    std::shared_ptr<CByteImage> AronIVTConverter::ConvertToCByteImage(const data::NDArrayPtr& nav)
-    {
-        ARMARX_CHECK_NOT_NULL(nav);
-
-        if (nav->getShape().size() != 3) // +1 for bytes per pixel
-        {
-            throw error::AronException(__PRETTY_FUNCTION__, "The size of an NDArray does not match.", nav->getPath());
-        }
-        auto dims = nav->getShape();
-
-        auto ret = std::make_shared<CByteImage>();
-        ret->Set(dims[0], dims[1], static_cast<CByteImage::ImageType>(std::stoi(nav->getType())));
-        memcpy(reinterpret_cast<unsigned char*>(ret->pixels), nav->getData(), std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()));
-        return ret;
-    }
-
-    data::NDArrayPtr ConvertFromCByteImage(const std::shared_ptr<CByteImage>& img)
-    {
-        // TODO:
-        return nullptr;
-    }
-}
diff --git a/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.h b/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.h
deleted file mode 100644
index 6d0c23d3b598c7dc55334c7181fa39885ee15ce4..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/binary/LTMVectorRepresentationConverter.h
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
-* 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/>.
-*
-* @author     Fabian Peller (fabian dot peller at kit dot edu)
-* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
-*             GNU General Public License
-*/
-
-#pragma once
-
-// STD/STL
-#include <memory>
-#include <string>
-
-// IVT
-#include <Image/ByteImage.h>
-
-// ArmarX
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-#include <RobotAPI/interface/aron.h>
-#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
-
-
-namespace armarx::aron::converter
-{
-    class AronIVTConverter
-    {
-        AronIVTConverter() = delete;
-    public:
-        static std::shared_ptr<CByteImage> ConvertToCByteImage(const data::NDArrayPtr&);
-        static data::NDArrayPtr ConvertFromCByteImage(const std::shared_ptr<CByteImage>&);
-    };
-}
diff --git a/source/RobotAPI/libraries/aron/converter/common/Converter.cpp b/source/RobotAPI/libraries/aron/converter/common/Converter.cpp
deleted file mode 100644
index c5161e17c00a2ab5dbe0d893a83ef29d46ac7da9..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/Converter.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "Converter.h"
\ No newline at end of file
diff --git a/source/RobotAPI/libraries/aron/converter/common/Converter.h b/source/RobotAPI/libraries/aron/converter/common/Converter.h
deleted file mode 100644
index f6e9959dfba18891807fad9579580375bf53382d..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/Converter.h
+++ /dev/null
@@ -1,71 +0,0 @@
-/*
- * 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/>.
- *
- * @author     Fabian Reister ( fabian dot reister at kit dot edu )
- * @date       2021
- * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
- *             GNU General Public License
- */
-
-#pragma once
-
-#include <algorithm>
-#include <vector>
-
-namespace armarx::aron
-{
-
-    /**
-     * @brief Converter function for vector of aron elements to plain cpp type
-     *
-     *  You have to provide a converter function for the element with the signature
-     *
-     *      PlainCppType fromAron(const AronType&)
-     *
-     * @tparam T the aron vector element
-     * @param v the vector of elements
-     * @return the vector of aron elements
-     */
-    template <typename T>
-    auto fromAron(const std::vector<T>& v) -> std::vector<decltype(fromAron(T()))>
-    {
-        std::vector<decltype(fromAron(T()))> r;
-        r.reserve(v.size());
-
-        std::transform(v.begin(), v.end(), std::back_inserter(r),
-                       [](const T & t)
-        {
-            return fromAron(t);
-        });
-
-        return r;
-    }
-
-
-    template <typename T> auto toAron(const std::vector<T>& v)
-    {
-        std::vector<decltype(toAron(T()))> r;
-        r.reserve(v.size());
-
-        std::transform(v.begin(), v.end(), std::back_inserter(r),
-                       [](const T & t)
-        {
-            return toAron(t);
-        });
-
-        return r;
-    }
-
-} // namespace armarx::aron
diff --git a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp
deleted file mode 100644
index 77743613df7297b67273debdbcb0c71c0d346dff..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp
+++ /dev/null
@@ -1,151 +0,0 @@
-#include "DatatypeConverter.h"
-
-namespace armarx::aron::converter
-{
-    void DatatypeConverter::visitAronVariant(const type::ObjectPtr& el)
-    {
-        auto dict = aron::make_dict(el->getPath());
-        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
-        dict->addElement(typeMemberName, type);
-
-        for (const auto& [key, child] : el->getMemberTypes())
-        {
-            DatatypeConverter converter;
-            aron::type::visit(converter, child);
-
-            dict->addElement(key, converter.latest);
-        }
-
-        latest = dict;
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::DictPtr& el)
-    {
-        auto dict = aron::make_dict(el->getPath());
-        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
-        dict->addElement(typeMemberName, type);
-
-        auto acceptedType = el->getAcceptedType();
-        DatatypeConverter converter;
-        aron::type::visit(converter, acceptedType);
-        dict->addElement(acceptedTypeMemberName, converter.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::ListPtr& el)
-    {
-        auto dict = aron::make_dict(el->getPath());
-        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
-        dict->addElement(typeMemberName, type);
-
-        auto acceptedType = el->getAcceptedType();
-        DatatypeConverter converter;
-        aron::type::visit(converter, acceptedType);
-        dict->addElement(acceptedTypeMemberName, converter.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::PairPtr& el)
-    {
-        auto dict = aron::make_dict(el->getPath());
-        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
-        dict->addElement(typeMemberName, type);
-
-        auto acceptedType1 = el->getFirstAcceptedType();
-        DatatypeConverter converter1;
-        aron::type::visit(converter1, acceptedType1);
-        dict->addElement(firstAcceptedTypeMemberName, converter1.latest);
-
-        auto acceptedType2 = el->getSecondAcceptedType();
-        DatatypeConverter converter2;
-        aron::type::visit(converter2, acceptedType2);
-        dict->addElement(secondAcceptedTypeMemberName, converter2.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::TuplePtr& el)
-    {
-        auto dict = aron::make_dict(el->getPath());
-        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
-        dict->addElement(typeMemberName, type);
-
-        int i = 0;
-        for (const auto& child : el->getAcceptedTypes())
-        {
-            DatatypeConverter converter;
-            aron::type::visit(converter, child);
-
-            dict->addElement(acceptedTypeMemberName + "_" + std::to_string(i++), converter.latest);
-        }
-
-        latest = dict;
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::MatrixPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::NDArrayPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::QuaternionPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::PointCloudPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::ImagePtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::IntEnumPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::IntPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::LongPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::FloatPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::DoublePtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::BoolPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::StringPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverter::visitAronVariant(const type::AnyObjectPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-}
diff --git a/source/RobotAPI/libraries/aron/converter/common/VectorConverter.cpp b/source/RobotAPI/libraries/aron/converter/common/VectorConverter.cpp
deleted file mode 100644
index 5f5406cc2be80d443623d0d406865b89279ad00e..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/VectorConverter.cpp
+++ /dev/null
@@ -1 +0,0 @@
-#include "VectorConverter.h"
\ No newline at end of file
diff --git a/source/RobotAPI/libraries/aron/converter/common/VectorConverter.h b/source/RobotAPI/libraries/aron/converter/common/VectorConverter.h
deleted file mode 100644
index 14b3ffc96765308ddc49fb684e69fb78b3fa5b5f..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/VectorConverter.h
+++ /dev/null
@@ -1,149 +0,0 @@
-/*
- * 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/>.
- *
- * @author     Fabian Reister ( fabian dot reister at kit dot edu )
- * @date       2021
- * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
- *             GNU General Public License
- */
-
-#pragma once
-
-// STD/STL
-#include <memory>
-#include <string>
-#include <numeric>
-
-// ArmarX
-#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
-
-#include <RobotAPI/interface/aron.h>
-#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
-
-
-namespace armarx::aron::converter
-{
-    class AronVectorConverter
-    {
-    private:
-        template<typename T>
-        static std::vector<T> convert_to_1d_vector(const unsigned char* data, const int elements, const int offset, const int size)
-        {
-            ARMARX_CHECK_NOT_NULL(data);
-            ARMARX_CHECK(elements * sizeof(T) == size);
-
-            std::vector<T> v(elements);
-            memcpy(v.data(), data, size);
-
-            return v;
-        }
-
-    public:
-        AronVectorConverter() = delete;
-
-        template<typename T>
-        static std::vector<std::vector<T>> ConvertTo2DVector(const data::NDArray& nav)
-        {
-            const auto& dims = nav.getShape();
-
-            if (dims.size() != 3)
-            {
-                throw error::AronException(__PRETTY_FUNCTION__, "The NDArray must have 3 dimensions.", nav.getPath());
-            }
-
-            if (dims.at(dims.size()-1) != sizeof(T))
-            {
-                throw error::AronException(__PRETTY_FUNCTION__, "Last dimension of the array has to match the element size.", nav.getPath());
-            }
-
-            const int one_row_size = dims.at(1) * dims.at(2);
-            std::vector<std::vector<T>> v(dims.at(0));
-            for (int i = 0; i < dims.at(0); i++)
-            {
-                v[i] = convert_to_1d_vector<T>(nav.getData(), dims.at(1), i * one_row_size, one_row_size);
-            }
-
-            return v;
-        }
-
-        template<typename T>
-        static std::vector<std::vector<T>> ConvertTo2DVector(const data::NDArrayPtr& nav)
-        {
-            ARMARX_CHECK_NOT_NULL(nav);
-
-            return ConvertTo2DVector<T>(*nav);
-        }
-
-        template<typename T>
-        static std::vector<T> ConvertTo1DVector(const data::NDArray& nav, const bool allowFlatten = false)
-        {
-            const auto& dims = nav.getShape();
-
-            if (!allowFlatten && dims.size() != 2)
-            {
-                throw error::AronException(__PRETTY_FUNCTION__, "The NDArray must have 2 dimensions.", nav.getPath());
-            }
-
-            if (dims.at(dims.size()-1) != sizeof(T))
-            {
-                throw error::AronException(__PRETTY_FUNCTION__, "Last dimension of the array has to match the element size.", nav.getPath());
-            }
-
-            ARMARX_CHECK(dims.size() >= 1);
-
-            const int elements = std::accumulate(std::begin(dims), std::prev(std::end(dims)), 1, std::multiplies<>());
-            const int all_size = std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<>());
-            std::vector<T> v = convert_to_1d_vector<T>(nav.getData(), elements, 0, all_size);
-            return v;
-        }
-
-        template<typename T>
-        static std::vector<T> ConvertTo1DVector(const data::NDArrayPtr& nav, const bool allowFlatten = false)
-        {
-            ARMARX_CHECK_NOT_NULL(nav);
-
-            return ConvertTo1DVector<T>(*nav, allowFlatten);
-        }
-
-        // alias
-        template<typename T>
-        static std::vector<T> ConvertToVector(const data::NDArrayPtr& nav, const bool allowFlatten = false)
-        {
-            return ConvertTo1DVector<T>(nav, allowFlatten);
-        }
-
-
-        // Attention: If a vector was flattened, the reconstruction is flattened as well!
-        template<typename T>
-        static data::NDArrayPtr ConvertFrom1DVector(const std::vector<T>& data)
-        {
-            data::NDArrayPtr ndArr(new data::NDArray);
-
-            ndArr->setShape({static_cast<int>(data.size()), sizeof(T)});
-            ndArr->setData(sizeof(T) * data.size(), reinterpret_cast <const unsigned char* >(data.data()));
-
-            return ndArr;
-        }
-
-        // alias
-        template<typename T>
-        static data::NDArrayPtr ConvertFromVector(const std::vector<T>& data)
-        {
-            return ConvertFrom1DVector<T>(data);
-        }
-
-    };
-
-}  // namespace armarx::aron::converter
diff --git a/source/RobotAPI/libraries/aron/converter/common/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
similarity index 52%
rename from source/RobotAPI/libraries/aron/converter/common/CMakeLists.txt
rename to source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
index fcc6342d5c779174e6322ff0c45bd9ca610758c2..2f77f156296882acce0f470fd1c06a584b57bbde 100644
--- a/source/RobotAPI/libraries/aron/converter/common/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
@@ -1,25 +1,26 @@
-set(LIB_NAME aroncommonconverter)
+set(LIB_NAME arondatatypeconverter)
 
 armarx_component_set_name("${LIB_NAME}")
 armarx_set_target("Library: ${LIB_NAME}")
 
 set(LIBS
     aron
+    aroncommon
 )
 
 set(LIB_FILES
-    Converter.cpp
-    VectorConverter.cpp
     DatatypeConverter.cpp
+    DatatypeConverterVisitor.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
-    Converter.h
-    VectorConverter.h
     DatatypeConverter.h
+    DatatypeConverterVisitor.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
 
 
-add_library(RobotAPI::aron::converter::common ALIAS aroncommonconverter)
+add_library(RobotAPI::aron::converter::datatype ALIAS arondatatypeconverter)
diff --git a/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.cpp b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a9ec3d64b1f3ff9338e8345717d3358a6e68e0b0
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.cpp
@@ -0,0 +1,15 @@
+#include "DatatypeConverter.h"
+
+#include "DatatypeConverterVisitor.h"
+
+namespace armarx::aron::type::converter
+{
+    data::VariantPtr
+    AronDatatypeConverter::ConvertToDatatype(const type::VariantPtr& el)
+    {
+        AronDatatypeConverterVisitor v;
+        aron::type::visit(v, el);
+
+        return v.latest;
+    }
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.h b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..cf3d50923ca535a46dc4516e1df38c1d7affac3e
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverter.h
@@ -0,0 +1,41 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller ( fabian dot peller at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <algorithm>
+#include <vector>
+
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/variant/forward_declarations.h>
+
+namespace armarx::aron::type::converter
+{
+
+    class AronDatatypeConverter
+    {
+    public:
+        AronDatatypeConverter() = delete;
+
+        static data::VariantPtr ConvertToDatatype(const type::VariantPtr&);
+    };
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.cpp b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0bd552b43c3886d2399f1056f527f49cc9fb5a8c
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.cpp
@@ -0,0 +1,170 @@
+#include "DatatypeConverterVisitor.h"
+
+namespace armarx::aron::type::converter
+{
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::ObjectPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {TYPE_MEMBER_NAME}));
+        dict->addElement(TYPE_MEMBER_NAME, type);
+
+        for (const auto& [key, child] : el->getMemberTypes())
+        {
+            AronDatatypeConverterVisitor converter;
+            aron::type::visit(converter, child);
+
+            dict->addElement(key, converter.latest);
+        }
+
+        latest = dict;
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::DictPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {TYPE_MEMBER_NAME}));
+        dict->addElement(TYPE_MEMBER_NAME, type);
+
+        auto acceptedType = el->getAcceptedType();
+        AronDatatypeConverterVisitor converter;
+        aron::type::visit(converter, acceptedType);
+        dict->addElement(ACCEPTED_TYPE_MEMBER_NAME, converter.latest);
+
+        latest = dict;
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::ListPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {TYPE_MEMBER_NAME}));
+        dict->addElement(TYPE_MEMBER_NAME, type);
+
+        auto acceptedType = el->getAcceptedType();
+        AronDatatypeConverterVisitor converter;
+        aron::type::visit(converter, acceptedType);
+        dict->addElement(ACCEPTED_TYPE_MEMBER_NAME, converter.latest);
+
+        latest = dict;
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::PairPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {TYPE_MEMBER_NAME}));
+        dict->addElement(TYPE_MEMBER_NAME, type);
+
+        auto acceptedType1 = el->getFirstAcceptedType();
+        AronDatatypeConverterVisitor converter1;
+        aron::type::visit(converter1, acceptedType1);
+        dict->addElement(FIRST_ACCEPTED_TYPE_MEMBER_NAME, converter1.latest);
+
+        auto acceptedType2 = el->getSecondAcceptedType();
+        AronDatatypeConverterVisitor converter2;
+        aron::type::visit(converter2, acceptedType2);
+        dict->addElement(SECOND_ACCEPTED_TYPE_MEMBER_NAME, converter2.latest);
+
+        latest = dict;
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::TuplePtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {TYPE_MEMBER_NAME}));
+        dict->addElement(TYPE_MEMBER_NAME, type);
+
+        int i = 0;
+        for (const auto& child : el->getAcceptedTypes())
+        {
+            AronDatatypeConverterVisitor converter;
+            aron::type::visit(converter, child);
+
+            dict->addElement(std::string(ACCEPTED_TYPE_MEMBER_NAME) + "_" + std::to_string(i++),
+                             converter.latest);
+        }
+
+        latest = dict;
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::MatrixPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::NDArrayPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::QuaternionPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::PointCloudPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::ImagePtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::IntEnumPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::IntPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::LongPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::FloatPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::DoublePtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::BoolPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::StringPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void
+    AronDatatypeConverterVisitor::visitAronVariant(const type::AnyObjectPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h
similarity index 80%
rename from source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
rename to source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h
index 34201b359d763ac81901135b475fd875714ab05c..7b2601ad17de4477c1aea12e10cc11c8e4a93ba1 100644
--- a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h
@@ -27,15 +27,15 @@
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h>
 
-namespace armarx::aron::converter
+namespace armarx::aron::type::converter
 {
-    class DatatypeConverter :
-        public aron::type::ConstVariantVisitor
+    class AronDatatypeConverterVisitor : public aron::type::ConstVariantVisitor
     {
-        const std::string typeMemberName = "_aron_type";
-        const std::string acceptedTypeMemberName = "_aron_accepted_type";
-        const std::string firstAcceptedTypeMemberName = "_aron_first_accepted_type";
-        const std::string secondAcceptedTypeMemberName = "_aron_second_accepted_type";
+        static const constexpr char* TYPE_MEMBER_NAME = "_aron_type";
+        static const constexpr char* ACCEPTED_TYPE_MEMBER_NAME = "_aron_accepted_type";
+        static const constexpr char* FIRST_ACCEPTED_TYPE_MEMBER_NAME = "_aron_first_accepted_type";
+        static const constexpr char* SECOND_ACCEPTED_TYPE_MEMBER_NAME =
+            "_aron_second_accepted_type";
 
         void visitAronVariant(const type::ObjectPtr&) override;
         void visitAronVariant(const type::DictPtr&) override;
@@ -59,4 +59,4 @@ namespace armarx::aron::converter
     public:
         aron::data::VariantPtr latest;
     };
-}
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..4b8623c29e66c2a8938ba06e2e2dd457f1002601
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.cpp
@@ -0,0 +1,17 @@
+
+#include "aron_conversions.h"
+
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+
+#include "DatatypeConverter.h"
+
+namespace armarx::aron::type::converter::datatype
+{
+    void
+    toAron(aron::data::VariantPtr& x, const aron::type::VariantPtr& t)
+    {
+        x = AronDatatypeConverter::ConvertToDatatype(t);
+    }
+
+} // namespace armarx::aron::type::converter::datatype
diff --git a/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..d3909e3af266aaf27122559c1904f70d98e26017
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/datatype/aron_conversions.h
@@ -0,0 +1,31 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller ( fabian dot peller at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <RobotAPI/libraries/aron/core/data/variant/forward_declarations.h>
+#include <RobotAPI/libraries/aron/core/type/variant/forward_declarations.h>
+
+namespace armarx::aron::type::converter::datatype
+{
+    void toAron(aron::data::VariantPtr&, const aron::type::VariantPtr&);
+
+} // namespace armarx::aron::type::converter::datatype
diff --git a/source/RobotAPI/libraries/aron/converter/eigen/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/eigen/CMakeLists.txt
index d4f9008ea45cfb34d3a6056e2155907060e672f0..1e3195c4b80c0ddf13336544b25ad3ef3a842fe0 100644
--- a/source/RobotAPI/libraries/aron/converter/eigen/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/eigen/CMakeLists.txt
@@ -13,10 +13,12 @@ set(LIBS
 
 set(LIB_FILES
     EigenConverter.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
     EigenConverter.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.cpp b/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.cpp
index a15a5ad9243cd05ae875fb2dec9c76927fa20508..d5663728ada285e9f5a081b02835a0f3666ef0b2 100644
--- a/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.cpp
+++ b/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.cpp
@@ -27,61 +27,85 @@
 // Header
 #include "EigenConverter.h"
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
-    Eigen::Quaternion<float> AronEigenConverter::ConvertToQuaternionf(const data::NDArrayPtr& n)
+    Eigen::Quaternion<float>
+    AronEigenConverter::ConvertToQuaternionf(const data::NDArrayPtr& n)
     {
         return ConvertToQuaternion<float>(n);
     }
-    Eigen::Quaternion<double> AronEigenConverter::ConvertToQuaterniond(const data::NDArrayPtr& n)
+
+    Eigen::Quaternion<double>
+    AronEigenConverter::ConvertToQuaterniond(const data::NDArrayPtr& n)
     {
         return ConvertToQuaternion<double>(n);
     }
-    Eigen::Vector3f AronEigenConverter::ConvertToVector3f(const data::NDArrayPtr& n)
+
+    Eigen::Vector3f
+    AronEigenConverter::ConvertToVector3f(const data::NDArrayPtr& n)
     {
         return ConvertToVector<float, 3>(n);
     }
-    Eigen::Vector3d AronEigenConverter::ConvertToVector3d(const data::NDArrayPtr& n)
+
+    Eigen::Vector3d
+    AronEigenConverter::ConvertToVector3d(const data::NDArrayPtr& n)
     {
         return ConvertToVector<double, 3>(n);
     }
-    Eigen::Matrix4f AronEigenConverter::ConvertToMatrix4f(const data::NDArrayPtr& n)
+
+    Eigen::Matrix4f
+    AronEigenConverter::ConvertToMatrix4f(const data::NDArrayPtr& n)
     {
         return ConvertToMatrix<float, 4, 4>(n);
     }
-    Eigen::Matrix4d AronEigenConverter::ConvertToMatrix4d(const data::NDArrayPtr& n)
+
+    Eigen::Matrix4d
+    AronEigenConverter::ConvertToMatrix4d(const data::NDArrayPtr& n)
     {
         return ConvertToMatrix<double, 4, 4>(n);
     }
 
-    Eigen::Quaternion<float> AronEigenConverter::ConvertToQuaternionf(const data::NDArray& n)
+    Eigen::Quaternion<float>
+    AronEigenConverter::ConvertToQuaternionf(const data::NDArray& n)
     {
         return ConvertToQuaternion<float>(n);
     }
-    Eigen::Quaternion<double> AronEigenConverter::ConvertToQuaterniond(const data::NDArray& n)
+
+    Eigen::Quaternion<double>
+    AronEigenConverter::ConvertToQuaterniond(const data::NDArray& n)
     {
         return ConvertToQuaternion<double>(n);
     }
-    Eigen::Vector3f AronEigenConverter::ConvertToVector3f(const data::NDArray& n)
+
+    Eigen::Vector3f
+    AronEigenConverter::ConvertToVector3f(const data::NDArray& n)
     {
         return ConvertToVector<float, 3>(n);
     }
-    Eigen::Vector3d AronEigenConverter::ConvertToVector3d(const data::NDArray& n)
+
+    Eigen::Vector3d
+    AronEigenConverter::ConvertToVector3d(const data::NDArray& n)
     {
         return ConvertToVector<double, 3>(n);
     }
-    Eigen::Matrix4f AronEigenConverter::ConvertToMatrix4f(const data::NDArray& n)
+
+    Eigen::Matrix4f
+    AronEigenConverter::ConvertToMatrix4f(const data::NDArray& n)
     {
         return ConvertToMatrix<float, 4, 4>(n);
     }
-    Eigen::Matrix4d AronEigenConverter::ConvertToMatrix4d(const data::NDArray& n)
+
+    Eigen::Matrix4d
+    AronEigenConverter::ConvertToMatrix4d(const data::NDArray& n)
     {
         return ConvertToMatrix<double, 4, 4>(n);
     }
 
-    void AronEigenConverter::checkDimensions(
-        const data::NDArray& nav, const std::vector<int>& expected,
-        const std::string& method, const std::string& caller)
+    void
+    AronEigenConverter::checkDimensions(const data::NDArray& nav,
+                                        const std::vector<int>& expected,
+                                        const std::string& method,
+                                        const std::string& caller)
     {
         if (nav.getShape() != expected)
         {
@@ -93,4 +117,4 @@ namespace armarx::aron::converter
             throw error::AronException(__PRETTY_FUNCTION__, ss.str(), nav.getPath());
         }
     }
-}
+} // namespace armarx::aron::data::converter
diff --git a/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.h b/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.h
index 9d83042a1ce7e0254c827350a87d515f05761665..79164ab84cea2848fd5737d301f30df6bdc0cf5d 100644
--- a/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/eigen/EigenConverter.h
@@ -22,21 +22,21 @@
 
 // STD/STL
 #include <memory>
-#include <string>
 #include <numeric>
+#include <string>
 
 // Eigen
-#include <Eigen/Geometry>
 #include <Eigen/Core>
+#include <Eigen/Geometry>
 
 
 // ArmarX
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
 #include <RobotAPI/interface/aron.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
-
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
     class AronEigenConverter
     {
@@ -58,16 +58,17 @@ namespace armarx::aron::converter
         static Eigen::Matrix4d ConvertToMatrix4d(const data::NDArrayPtr&);
         static Eigen::Matrix4d ConvertToMatrix4d(const data::NDArray&);
 
-
-        template<typename T>
-        static Eigen::Quaternion<T> ConvertToQuaternion(const data::NDArrayPtr& nav)
+        template <typename T>
+        static Eigen::Quaternion<T>
+        ConvertToQuaternion(const data::NDArrayPtr& nav)
         {
             ARMARX_CHECK_NOT_NULL(nav);
             return ConvertToQuaternion<T>(*nav);
         }
 
-        template<typename T>
-        static Eigen::Quaternion<T> ConvertToQuaternion(const data::NDArray& nav)
+        template <typename T>
+        static Eigen::Quaternion<T>
+        ConvertToQuaternion(const data::NDArray& nav)
         {
             checkDimensions(nav, {1, 4, sizeof(T)}, "ConvertToQuaternion");
             auto dims = nav.getShape();
@@ -76,17 +77,17 @@ namespace armarx::aron::converter
             return ret;
         }
 
-
-        template<typename T, int Size>
-        static Eigen::Matrix<T, Size, 1> ConvertToVector(const data::NDArrayPtr& nav)
+        template <typename T, int Size>
+        static Eigen::Matrix<T, Size, 1>
+        ConvertToVector(const data::NDArrayPtr& nav)
         {
             ARMARX_CHECK_NOT_NULL(nav);
             return ConvertToVector<T, Size>(*nav);
         }
 
-
-        template<typename T, int Size>
-        static Eigen::Matrix<T, Size, 1> ConvertToVector(const data::NDArray& nav)
+        template <typename T, int Size>
+        static Eigen::Matrix<T, Size, 1>
+        ConvertToVector(const data::NDArray& nav)
         {
             checkDimensions(nav, {Size, 1, sizeof(T)}, "ConvertToVector");
             auto dims = nav.getShape();
@@ -95,34 +96,32 @@ namespace armarx::aron::converter
             return ret;
         }
 
-
-        template<typename T, int Rows, int Cols>
-        static Eigen::Matrix<T, Rows, Cols> ConvertToMatrix(const data::NDArrayPtr& nav)
+        template <typename T, int Rows, int Cols>
+        static Eigen::Matrix<T, Rows, Cols>
+        ConvertToMatrix(const data::NDArrayPtr& nav)
         {
             ARMARX_CHECK_NOT_NULL(nav);
             return ConvertToMatrix<T, Rows, Cols>(*nav);
         }
 
-
-        template<typename T>
-        static Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> ConvertToDynamicMatrix(const data::NDArray& nav)
+        template <typename T>
+        static Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>
+        ConvertToDynamicMatrix(const data::NDArray& nav)
         {
             using MatrixT = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
 
             const auto dims = nav.getShape();
             ARMARX_CHECK_EQUAL(dims.size(), 2); // for now ...
 
-            Eigen::Map<MatrixT> map(
-                        reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1)
-            );
+            Eigen::Map<MatrixT> map(reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1));
             return map;
         }
 
-
-        template<typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
-        static Eigen::Matrix<T, Rows, Cols> ConvertToMatrix(const data::NDArray& nav)
+        template <typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
+        static Eigen::Matrix<T, Rows, Cols>
+        ConvertToMatrix(const data::NDArray& nav)
         {
-            if constexpr(Rows == Eigen::Dynamic and Cols == Eigen::Dynamic)
+            if constexpr (Rows == Eigen::Dynamic and Cols == Eigen::Dynamic)
             {
                 return ConvertToDynamicMatrix<T>(nav);
             }
@@ -135,60 +134,65 @@ namespace armarx::aron::converter
             }
         }
 
-        template<typename T>
-        static data::NDArrayPtr ConvertFromQuaternion(
-            const Eigen::Quaternion<T>& quat)
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFromQuaternion(const Eigen::Quaternion<T>& quat)
         {
             data::NDArrayPtr ndArr(new data::NDArray);
             ndArr->setShape({1, 4});
-            ndArr->setData(sizeof(T) * 4, reinterpret_cast <const unsigned char* >(quat.coeffs().data()));
+            ndArr->setData(sizeof(T) * 4,
+                           reinterpret_cast<const unsigned char*>(quat.coeffs().data()));
 
             return ndArr;
         }
 
-        template<typename T>
-        static data::NDArrayPtr ConvertFromMatrix(
-                const Eigen::Matrix < T, Eigen::Dynamic, Eigen::Dynamic >& mat)
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFromMatrix(const Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>& mat)
         {
             data::NDArrayPtr ndArr(new data::NDArray);
 
             ndArr->setShape({static_cast<int>(mat.rows()), static_cast<int>(mat.cols())});
-            ndArr->setData(sizeof(T) * mat.size(), reinterpret_cast <const unsigned char* >(mat.data()));
+            ndArr->setData(sizeof(T) * mat.size(),
+                           reinterpret_cast<const unsigned char*>(mat.data()));
 
             return ndArr;
         }
 
-        template<typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
-        static data::NDArrayPtr ConvertFromMatrix(
-            const Eigen::Matrix < T, Rows, Cols >& mat)
+        template <typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
+        static data::NDArrayPtr
+        ConvertFromMatrix(const Eigen::Matrix<T, Rows, Cols>& mat)
         {
             data::NDArrayPtr ndArr(new data::NDArray);
 
             ndArr->setShape({Rows, Cols});
-            ndArr->setData(sizeof(T) * mat.size(), reinterpret_cast <const unsigned char* >(mat.data()));
+            ndArr->setData(sizeof(T) * mat.size(),
+                           reinterpret_cast<const unsigned char*>(mat.data()));
 
             return ndArr;
         }
 
-
         // Eigen::Array
 
-        template<typename T>
-        static Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic> ConvertToDynamicArray(const data::NDArray& nav)
+        template <typename T>
+        static Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic>
+        ConvertToDynamicArray(const data::NDArray& nav)
         {
             const auto dims = nav.getShape();
             ARMARX_CHECK_EQUAL(dims.size(), 2);
 
             using ArrayT = Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic>;
 
-            ArrayT ret = Eigen::Map<ArrayT>(reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1));
+            ArrayT ret =
+                Eigen::Map<ArrayT>(reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1));
             return ret;
         }
 
-        template<typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
-        static Eigen::Array<T, Rows, Cols> ConvertToArray(const data::NDArray& nav)
+        template <typename T, int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
+        static Eigen::Array<T, Rows, Cols>
+        ConvertToArray(const data::NDArray& nav)
         {
-            if constexpr(Rows == Eigen::Dynamic and Cols == Eigen::Dynamic)
+            if constexpr (Rows == Eigen::Dynamic and Cols == Eigen::Dynamic)
             {
                 return ConvertToDynamicArray<T>(nav);
             }
@@ -196,31 +200,39 @@ namespace armarx::aron::converter
             checkDimensions(nav, {Rows, Cols, sizeof(T)}, "ConvertToMatrix");
             auto dims = nav.getShape();
 
-            Eigen::Map<Eigen::Array<T, Rows, Cols>> ret(reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1));
+            Eigen::Map<Eigen::Array<T, Rows, Cols>> ret(
+                reinterpret_cast<T*>(nav.getData()), dims.at(0), dims.at(1));
             return ret;
         }
 
-        template<typename T>
-        static data::NDArrayPtr ConvertFromArray(const Eigen::Array < T, Eigen::Dynamic, Eigen::Dynamic >& mat)
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFromArray(const Eigen::Array<T, Eigen::Dynamic, Eigen::Dynamic>& mat)
         {
             data::NDArrayPtr ndArr(new data::NDArray);
 
             ndArr->setShape({static_cast<int>(mat.rows()), static_cast<int>(mat.cols())});
-            ndArr->setData(sizeof(T) * mat.size(), reinterpret_cast <const unsigned char* >(mat.data()));
+            ndArr->setData(sizeof(T) * mat.size(),
+                           reinterpret_cast<const unsigned char*>(mat.data()));
 
             return ndArr;
         }
 
 
-
     private:
-
         /**
          * @throw `error::AronException` If `nav`'s dimensions do not match `expected`.
          */
-        static void checkDimensions(const data::NDArray& nav, const std::vector<int>& expected,
-                                    const std::string& method, const std::string& caller = "AronEigenConverter");
-
+        static void checkDimensions(const data::NDArray& nav,
+                                    const std::vector<int>& expected,
+                                    const std::string& method,
+                                    const std::string& caller = "AronEigenConverter");
     };
 
+} // namespace armarx::aron::data::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronEigenConverter = ::armarx::aron::data::converter::AronEigenConverter;
 }
diff --git a/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..7ff93ed618f42f262495c0d5e904e2377596b4c7
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.cpp
@@ -0,0 +1,5 @@
+#include "aron_conversions.h"
+
+namespace armarx::aron::data::converter::eigen
+{
+}
diff --git a/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..9fcbf00c219d6ed0c346444cbb3b975daa0f1ced
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/eigen/aron_conversions.h
@@ -0,0 +1,28 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller (fabian dot peller at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "EigenConverter.h"
+
+namespace armarx::aron::data::converter::eigen
+{
+    // No clear conversion possible. Use EigenConverter instead
+}
diff --git a/source/RobotAPI/libraries/aron/converter/ivt/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/ivt/CMakeLists.txt
index 7fa2684a23d3ef1e887a5f11b1c5aa83cbbe4b8f..700a3a7e57ca9ca77aff15830dfb1c7b15d3e287 100644
--- a/source/RobotAPI/libraries/aron/converter/ivt/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/ivt/CMakeLists.txt
@@ -16,10 +16,12 @@ set(LIBS
 
 set(LIB_FILES
     IVTConverter.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
     IVTConverter.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.cpp b/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.cpp
index 999359d6b79ef56bbe7352263556ad71316e7384..715fe6526fc51e7078c97b769c85ec61bd437907 100644
--- a/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.cpp
+++ b/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.cpp
@@ -27,27 +27,32 @@
 // Header
 #include "IVTConverter.h"
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
-    std::shared_ptr<CByteImage> AronIVTConverter::ConvertToCByteImage(const data::NDArrayPtr& nav)
+    std::shared_ptr<CByteImage>
+    AronIVTConverter::ConvertToCByteImage(const data::NDArrayPtr& nav)
     {
         ARMARX_CHECK_NOT_NULL(nav);
 
         if (nav->getShape().size() != 3) // +1 for bytes per pixel
         {
-            throw error::AronException(__PRETTY_FUNCTION__, "The size of an NDArray does not match.", nav->getPath());
+            throw error::AronException(
+                __PRETTY_FUNCTION__, "The size of an NDArray does not match.", nav->getPath());
         }
         auto dims = nav->getShape();
 
         auto ret = std::make_shared<CByteImage>();
         ret->Set(dims[0], dims[1], static_cast<CByteImage::ImageType>(std::stoi(nav->getType())));
-        memcpy(reinterpret_cast<unsigned char*>(ret->pixels), nav->getData(), std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()));
+        memcpy(reinterpret_cast<unsigned char*>(ret->pixels),
+               nav->getData(),
+               std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()));
         return ret;
     }
 
-    data::NDArrayPtr ConvertFromCByteImage(const std::shared_ptr<CByteImage>& img)
+    data::NDArrayPtr
+    ConvertFromCByteImage(const std::shared_ptr<CByteImage>& img)
     {
         // TODO:
         return nullptr;
     }
-}
+} // namespace armarx::aron::data::converter
diff --git a/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h b/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h
index 6d0c23d3b598c7dc55334c7181fa39885ee15ce4..b0fe1530645d8f3016afafeaf56f45d05d775107 100644
--- a/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h
@@ -29,17 +29,24 @@
 
 // ArmarX
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
 #include <RobotAPI/interface/aron.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
-
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
     class AronIVTConverter
     {
         AronIVTConverter() = delete;
+
     public:
         static std::shared_ptr<CByteImage> ConvertToCByteImage(const data::NDArrayPtr&);
         static data::NDArrayPtr ConvertFromCByteImage(const std::shared_ptr<CByteImage>&);
     };
+} // namespace armarx::aron::data::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronIVTConverter = ::armarx::aron::data::converter::AronIVTConverter;
 }
diff --git a/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..833348e61131d8ba7d227ce5bce5357b27c642db
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.cpp
@@ -0,0 +1,5 @@
+#include "aron_conversions.h"
+
+namespace armarx::aron::data::converter::ivt
+{
+}
diff --git a/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..790eeadeec47fcf7a4a5efbeee649f1cb9280a4a
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/ivt/aron_conversions.h
@@ -0,0 +1,28 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller (fabian dot peller at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "IVTConverter.h"
+
+namespace armarx::aron::data::converter::ivt
+{
+    // No clear conversion possible. Use EigenConverter instead
+}
diff --git a/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt
index d044d9dfedd3933df0293e5e0b04cf3dea09e162..01f16de4c83de33b20acf9b08c3a48cb82f40012 100644
--- a/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/json/CMakeLists.txt
@@ -10,10 +10,14 @@ set(LIBS
 
 set(LIB_FILES
     NLohmannJSONConverter.cpp
+    NLohmannJSONConverterVisitor.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
     NLohmannJSONConverter.h
+    NLohmannJSONConverterVisitor.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
index e083d47104d5c4747470d97b162028d7fee5a3a7..b4682df50a19597d8c0057b1cecd2b11978fae54 100644
--- a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
+++ b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.cpp
@@ -2,57 +2,81 @@
 
 #include <ArmarXCore/core/logging/Logging.h>
 
-namespace armarx::aron::converter
+#include "NLohmannJSONConverterVisitor.h"
+
+namespace armarx::aron::data::converter
 {
-    nlohmann::json AronNlohmannJSONConverter::ConvertToNlohmannJSON(const data::VariantPtr& aron)
+    nlohmann::json
+    AronNlohmannJSONConverter::ConvertToNlohmannJSON(const data::VariantPtr& aron)
     {
         nlohmann::json j;
         ConvertToNlohmannJSON(aron, j);
         return j;
     }
 
-    void AronNlohmannJSONConverter::ConvertToNlohmannJSON(const aron::data::VariantPtr& aron, nlohmann::json& j)
+    void
+    AronNlohmannJSONConverter::ConvertToNlohmannJSON(const aron::data::VariantPtr& aron,
+                                                     nlohmann::json& j)
     {
-        j = aron::data::readAndWrite<data::FromVariantConverter<data::writer::NlohmannJSONWriter>>(aron);
+        j = aron::data::readAndWrite<ToNLohmannJSONConverterVisitor>(aron);
     }
 
-    nlohmann::json AronNlohmannJSONConverter::ConvertToNlohmannJSON(const type::VariantPtr& aron)
+    data::DictPtr
+    AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(const nlohmann::json& j,
+                                                             const armarx::aron::Path& p)
     {
-        nlohmann::json j;
-        ConvertToNlohmannJSON(aron, j);
-        return j;
+        // TODO Switch case over json type and add other methods, e.g. for float, array, ...
+        // TODO add check if json is object_t
+        data::VariantPtr aron = std::make_shared<aron::data::Dict>(p);
+        ConvertFromNlohmannJSON(aron, j);
+        return data::Dict::DynamicCastAndCheck(aron);
     }
 
-    void AronNlohmannJSONConverter::ConvertToNlohmannJSON(const aron::type::VariantPtr& aron, nlohmann::json& j)
+    void
+    AronNlohmannJSONConverter::ConvertFromNlohmannJSON(
+        aron::data::VariantPtr& a,
+        const nlohmann::json& e,
+        const aron::type::VariantPtr& expectedStructure)
     {
-        j = aron::type::readAndWrite<type::FromVariantConverter<type::writer::NlohmannJSONWriter>>(aron);
+        a = aron::data::readAndWrite<FromNLohmannJSONConverterVisitor>(e);
+        ARMARX_CHECK_EXPRESSION(a->fullfillsType(expectedStructure));
     }
 
-    data::DictPtr AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(const nlohmann::json& j, const armarx::aron::Path& p)
+} // namespace armarx::aron::data::converter
+
+namespace armarx::aron::type::converter
+{
+
+    nlohmann::json
+    AronNlohmannJSONConverter::ConvertToNlohmannJSON(const type::VariantPtr& aron)
     {
-        // TODO Switch case over json type and add other methods, e.g. for float, array, ...
-        // TODO add check if json is object_t
-        data::VariantPtr aron = std::make_shared<aron::data::Dict>(p);
-        ConvertFromNlohmannJSON(aron, j);
-        return data::Dict::DynamicCastAndCheck(aron);
+        nlohmann::json j;
+        ConvertToNlohmannJSON(aron, j);
+        return j;
     }
 
-    type::ObjectPtr AronNlohmannJSONConverter::ConvertFromNlohmannJSONTypeObject(const nlohmann::json& j, const armarx::aron::Path& p)
+    void
+    AronNlohmannJSONConverter::ConvertToNlohmannJSON(const aron::type::VariantPtr& aron,
+                                                     nlohmann::json& j)
     {
-        type::ObjectPtr foo = std::make_shared<aron::type::Object>("foo"); // foo is just a placeholder
-        type::VariantPtr aron = std::make_shared<aron::type::Object>(*foo, p);
-        ConvertFromNlohmannJSON(aron, j);
-        return type::Object::DynamicCastAndCheck(aron);
+        j = aron::type::readAndWrite<ToNLohmannJSONConverterVisitor>(aron);
     }
 
-    void AronNlohmannJSONConverter::ConvertFromNlohmannJSON(aron::data::VariantPtr& a, const nlohmann::json& e, const aron::type::VariantPtr& expectedStructure)
+    type::ObjectPtr
+    AronNlohmannJSONConverter::ConvertFromNlohmannJSONTypeObject(const nlohmann::json& j,
+                                                                 const armarx::aron::Path& p)
     {
-        a = aron::data::readAndWrite<data::FromNlohmannJSONConverter<data::writer::VariantWriter>>(e);
-        ARMARX_CHECK_EXPRESSION(a->fullfillsType(expectedStructure));
+        type::ObjectPtr foo =
+            std::make_shared<aron::type::Object>("foo"); // foo is just a placeholder
+        type::VariantPtr aron = std::make_shared<aron::type::Object>(*foo, p);
+        ConvertFromNlohmannJSON(aron, j);
+        return type::Object::DynamicCastAndCheck(aron);
     }
 
-    void AronNlohmannJSONConverter::ConvertFromNlohmannJSON(aron::type::VariantPtr& a, const nlohmann::json& e)
+    void
+    AronNlohmannJSONConverter::ConvertFromNlohmannJSON(aron::type::VariantPtr& a,
+                                                       const nlohmann::json& e)
     {
-        a = aron::type::readAndWrite<type::FromNlohmannJSONConverter<type::writer::VariantWriter>>(e);
+        a = aron::type::readAndWrite<FromNLohmannJSONConverterVisitor>(e);
     }
-}
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h
index 0902ed0c3c133fcec75e0cf2502801f8fcce218a..1e9044cb3beea01195c87629e6464169ed392f43 100644
--- a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h
@@ -2,30 +2,28 @@
 
 // STD/STL
 #include <memory>
-#include <string>
 #include <numeric>
+#include <string>
 
 // Memory
-#include <RobotAPI/libraries/aron/core/data/variant/All.h>
-
-#include <RobotAPI/libraries/aron/core/data/converter/variant/VariantConverter.h>
 #include <RobotAPI/libraries/aron/core/data/converter/nlohmannJSON/NlohmannJSONConverter.h>
-#include <RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>
-#include <RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>
+#include <RobotAPI/libraries/aron/core/data/converter/variant/VariantConverter.h>
 #include <RobotAPI/libraries/aron/core/data/rw/reader/nlohmannJSON/NlohmannJSONReader.h>
+#include <RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>
 #include <RobotAPI/libraries/aron/core/data/rw/writer/nlohmannJSON/NlohmannJSONWriter.h>
-
-#include <RobotAPI/libraries/aron/core/type/converter/variant/VariantConverter.h>
+#include <RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/type/converter/nlohmannJSON/NlohmannJSONConverter.h>
-#include <RobotAPI/libraries/aron/core/type/rw/reader/variant/VariantReader.h>
-#include <RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>
+#include <RobotAPI/libraries/aron/core/type/converter/variant/VariantConverter.h>
 #include <RobotAPI/libraries/aron/core/type/rw/reader/nlohmannJSON/NlohmannJSONReader.h>
+#include <RobotAPI/libraries/aron/core/type/rw/reader/variant/VariantReader.h>
 #include <RobotAPI/libraries/aron/core/type/rw/writer/nlohmannJSON/NlohmannJSONWriter.h>
+#include <RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>
 
 // JSON
 #include <SimoxUtility/json/json.hpp>
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
     class AronNlohmannJSONConverter
     {
@@ -35,13 +33,32 @@ namespace armarx::aron::converter
         static nlohmann::json ConvertToNlohmannJSON(const data::VariantPtr&);
         static void ConvertToNlohmannJSON(const data::VariantPtr&, nlohmann::json&);
 
+        static data::DictPtr ConvertFromNlohmannJSONObject(const nlohmann::json&,
+                                                           const armarx::aron::Path& p = {});
+        static void ConvertFromNlohmannJSON(data::VariantPtr&,
+                                            const nlohmann::json&,
+                                            const aron::type::VariantPtr& = nullptr);
+    };
+} // namespace armarx::aron::data::converter
+
+namespace armarx::aron::type::converter
+{
+    class AronNlohmannJSONConverter
+    {
+    public:
+        AronNlohmannJSONConverter() = delete;
+
         static nlohmann::json ConvertToNlohmannJSON(const type::VariantPtr&);
         static void ConvertToNlohmannJSON(const type::VariantPtr&, nlohmann::json&);
 
-        static data::DictPtr ConvertFromNlohmannJSONObject(const nlohmann::json&, const armarx::aron::Path& p = {});
-        static void ConvertFromNlohmannJSON(data::VariantPtr&, const nlohmann::json&, const aron::type::VariantPtr& = nullptr);
-
-        static type::ObjectPtr ConvertFromNlohmannJSONTypeObject(const nlohmann::json& j, const armarx::aron::Path& p = {});
+        static type::ObjectPtr ConvertFromNlohmannJSONTypeObject(const nlohmann::json& j,
+                                                                 const armarx::aron::Path& p = {});
         static void ConvertFromNlohmannJSON(aron::type::VariantPtr& a, const nlohmann::json& e);
     };
+} // namespace armarx::aron::type::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronNlohmannJSONConverter = ::armarx::aron::data::converter::AronNlohmannJSONConverter;
 }
diff --git a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverterVisitor.cpp b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverterVisitor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverterVisitor.h b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverterVisitor.h
new file mode 100644
index 0000000000000000000000000000000000000000..86d14cea16a07fc191f66d40ea862428fb02166a
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/json/NLohmannJSONConverterVisitor.h
@@ -0,0 +1,42 @@
+#pragma once
+
+// STD/STL
+#include <memory>
+#include <numeric>
+#include <string>
+
+// Memory
+#include <RobotAPI/libraries/aron/core/data/converter/nlohmannJSON/NlohmannJSONConverter.h>
+#include <RobotAPI/libraries/aron/core/data/converter/variant/VariantConverter.h>
+#include <RobotAPI/libraries/aron/core/data/rw/reader/nlohmannJSON/NlohmannJSONReader.h>
+#include <RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>
+#include <RobotAPI/libraries/aron/core/data/rw/writer/nlohmannJSON/NlohmannJSONWriter.h>
+#include <RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/converter/nlohmannJSON/NlohmannJSONConverter.h>
+#include <RobotAPI/libraries/aron/core/type/converter/variant/VariantConverter.h>
+#include <RobotAPI/libraries/aron/core/type/rw/reader/nlohmannJSON/NlohmannJSONReader.h>
+#include <RobotAPI/libraries/aron/core/type/rw/reader/variant/VariantReader.h>
+#include <RobotAPI/libraries/aron/core/type/rw/writer/nlohmannJSON/NlohmannJSONWriter.h>
+#include <RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>
+
+// JSON
+#include <SimoxUtility/json/json.hpp>
+
+namespace armarx::aron::data::converter
+{
+    using ToNLohmannJSONConverterVisitor =
+        data::FromVariantConverter<data::writer::NlohmannJSONWriter>;
+
+    using FromNLohmannJSONConverterVisitor =
+        data::FromNlohmannJSONConverter<data::writer::VariantWriter>;
+} // namespace armarx::aron::data::converter
+
+namespace armarx::aron::type::converter
+{
+    using ToNLohmannJSONConverterVisitor =
+        type::FromVariantConverter<type::writer::NlohmannJSONWriter>;
+
+    using FromNLohmannJSONConverterVisitor =
+        type::FromNlohmannJSONConverter<type::writer::VariantWriter>;
+} // namespace armarx::aron::type::converter
diff --git a/source/RobotAPI/libraries/aron/converter/json/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/json/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/aron/converter/json/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/json/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/aron/converter/opencv/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/opencv/CMakeLists.txt
index 4a3eadd0caaec648db2a175f7a103b33b7a3acad..4b0beee06ab2829a1657e46d6f174c357dd5519f 100644
--- a/source/RobotAPI/libraries/aron/converter/opencv/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/opencv/CMakeLists.txt
@@ -14,10 +14,12 @@ set(LIBS
 
 set(LIB_FILES
     OpenCVConverter.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
     OpenCVConverter.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.cpp b/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.cpp
index d232500c20754beb3d2f212a79b6f16939812ef7..957003a9eb4770c896b14439f171f1dfbaa81c75 100644
--- a/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.cpp
+++ b/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.cpp
@@ -27,25 +27,29 @@
 // Header
 #include "OpenCVConverter.h"
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
-    cv::Mat AronOpenCVConverter::ConvertToMat(const data::NDArrayPtr& nav)
+    cv::Mat
+    AronOpenCVConverter::ConvertToMat(const data::NDArrayPtr& nav)
     {
         ARMARX_CHECK_NOT_NULL(nav);
 
         if (nav->getShape().size() < 3)
         {
-            throw error::AronException(__PRETTY_FUNCTION__, "The size of an NDArray does not match.", nav->getPath());
+            throw error::AronException(
+                __PRETTY_FUNCTION__, "The size of an NDArray does not match.", nav->getPath());
         }
         auto dims = nav->getShape();
 
-        cv::Mat ret(std::vector<int>({dims.begin(), std::prev(dims.end())}), std::stoi(nav->getType()));
+        cv::Mat ret(std::vector<int>({dims.begin(), std::prev(dims.end())}),
+                    std::stoi(nav->getType()));
         auto size = std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>());
         memcpy(reinterpret_cast<unsigned char*>(ret.data), nav->getData(), size);
         return ret;
     }
 
-    data::NDArrayPtr AronOpenCVConverter::ConvertFromMat(const cv::Mat& mat, const armarx::aron::Path& p)
+    data::NDArrayPtr
+    AronOpenCVConverter::ConvertFromMat(const cv::Mat& mat, const armarx::aron::Path& p)
     {
         std::vector<int> dims;
         for (int i = 0; i < mat.dims; ++i)
@@ -57,9 +61,9 @@ namespace armarx::aron::converter
         auto ret = std::make_shared<data::NDArray>(p);
         ret->setShape(dims);
         ret->setType(std::to_string(mat.type()));
-        ret->setData(std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()), reinterpret_cast<const unsigned char*>(mat.data));
+        ret->setData(std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()),
+                     reinterpret_cast<const unsigned char*>(mat.data));
 
         return ret;
     }
-}
-
+} // namespace armarx::aron::data::converter
diff --git a/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h b/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h
index fb4f21487b413272fc6b1b4cbb340cf819a8a5a7..9b3dcc79cb8a9c82c8e588b332a52d8e742e53f0 100644
--- a/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h
@@ -29,11 +29,11 @@
 
 // ArmarX
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
 #include <RobotAPI/interface/aron.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
-
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
     class AronOpenCVConverter
     {
@@ -44,4 +44,10 @@ namespace armarx::aron::converter
         static data::NDArrayPtr ConvertFromMat(const cv::Mat&, const armarx::aron::Path& = {});
     };
 
+} // namespace armarx::aron::data::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronOpenCVConverter = ::armarx::aron::data::converter::AronOpenCVConverter;
 }
diff --git a/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d59b782fae5ab7f1d0cc2f01a7944d31bb81c772
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.cpp
@@ -0,0 +1,5 @@
+#include "aron_conversions.h"
+
+namespace armarx::aron::data::converter::opencv
+{
+}
diff --git a/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..c8e0ee5aff793d9a1dbe8650ead78ca8baf7e72a
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/opencv/aron_conversions.h
@@ -0,0 +1,28 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller (fabian dot peller at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "OpenCVConverter.h"
+
+namespace armarx::aron::data::converter::opencv
+{
+    // No clear conversion possible. Use EigenConverter instead
+}
diff --git a/source/RobotAPI/libraries/aron/converter/pcl/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/pcl/CMakeLists.txt
index c14d50a5f6f91db9b36088845b63d14ed217a6a4..3f6386701ee5f585ae0ca740e51e57e68df495ec 100644
--- a/source/RobotAPI/libraries/aron/converter/pcl/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/pcl/CMakeLists.txt
@@ -13,10 +13,12 @@ set(LIBS
 
 set(LIB_FILES
     PCLConverter.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
     PCLConverter.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
diff --git a/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.cpp b/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.cpp
index 23dd2e4d38142a7cb03a9dbad16f0c7b5f728d07..e0878fe2061dbde7ff94330337b8b2e08b986783 100644
--- a/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.cpp
+++ b/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.cpp
@@ -27,7 +27,7 @@
 // Header
 #include "PCLConverter.h"
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
 
 }
diff --git a/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.h b/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.h
index 1b7c12294bee8846fd37c3ff7cbb8727f80eca11..77498aaf815ce7ae3f7736ac4831059bd2adcde2 100644
--- a/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/pcl/PCLConverter.h
@@ -22,8 +22,8 @@
 
 // STD/STL
 #include <memory>
-#include <string>
 #include <numeric>
+#include <string>
 
 // Eigen
 #include <pcl/point_cloud.h>
@@ -31,32 +31,44 @@
 
 // ArmarX
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
 #include <RobotAPI/interface/aron.h>
 #include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
 
-
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
     class AronPCLConverter
     {
         AronPCLConverter() = delete;
 
     public:
-        template<typename T>
-        static pcl::PointCloud<T> ConvertToPointClout(const data::NDArrayPtr& nav)
+        template <typename T>
+        static pcl::PointCloud<T>
+        ConvertToPointClout(const data::NDArrayPtr& nav)
         {
             ARMARX_CHECK_NOT_NULL(nav);
 
             if (nav->getShape().size() != 3) // +1 for bytes per pixel
             {
-                throw error::AronException("AronIVTConverter", "ConvertToCByteImage", "The size of an NDArray does not match.", nav->getPath());
+                throw error::AronException("AronIVTConverter",
+                                           "ConvertToCByteImage",
+                                           "The size of an NDArray does not match.",
+                                           nav->getPath());
             }
             auto dims = nav->getShape();
 
             pcl::PointCloud<T> ret(dims[0], dims[1]);
-            memcpy(reinterpret_cast<unsigned char*>(ret.points.data()), nav->getData(), std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()));
+            memcpy(reinterpret_cast<unsigned char*>(ret.points.data()),
+                   nav->getData(),
+                   std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()));
             return ret;
         }
     };
 
+} // namespace armarx::aron::data::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronPCLConverter = ::armarx::aron::data::converter::AronPCLConverter;
 }
diff --git a/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..bf63d615f87019b2cf552104fdaee83d7fc87649
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.cpp
@@ -0,0 +1,5 @@
+#include "aron_conversions.h"
+
+namespace armarx::aron::data::converter::pcl
+{
+}
diff --git a/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..0bf1b4e30d319dd96fd3e0e7ae5fd4111dd80b1f
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/pcl/aron_conversions.h
@@ -0,0 +1,28 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller (fabian dot peller at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "PCLConverter.h"
+
+namespace armarx::aron::data::converter::pcl
+{
+    // No clear conversion possible. Use EigenConverter instead
+}
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..707f8eeeeaef746cc40f2d17600591f362a8d31d
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt
@@ -0,0 +1,30 @@
+set(LIB_NAME aronstdstlconverter)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+set(LIBS
+    aron
+    aroncommon
+)
+
+set(LIB_FILES
+    StdVectorConverter.cpp
+    StdVectorConverterVisitor.cpp
+    aron_conversions.cpp
+)
+
+set(LIB_HEADERS
+    StdVectorConverter.h
+    StdVectorConverterVisitor.h
+    aron_conversions.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+# legacy alias
+add_library(aronvectorconverter ALIAS aronstdstlconverter)
+
+# namespace alias
+add_library(RobotAPI::aron::converter::stdstl ALIAS aronstdstlconverter)
+
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.cpp b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e0f2ae15265dc970c38957bdd9e77a823a86257c
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.cpp
@@ -0,0 +1 @@
+#include "StdVectorConverter.h"
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..2bc52d046af1186142195bcbc7223a848fa1ecd7
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h
@@ -0,0 +1,166 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+// STD/STL
+#include <memory>
+#include <numeric>
+#include <string>
+
+// ArmarX
+#include <ArmarXCore/core/exceptions/local/ExpressionException.h>
+
+#include <RobotAPI/interface/aron.h>
+#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
+
+namespace armarx::aron::data::converter
+{
+    class AronVectorConverter
+    {
+    private:
+        template <typename T>
+        static std::vector<T>
+        convert_to_1d_vector(const unsigned char* data, const int offset, const int size)
+        {
+            ARMARX_CHECK_NOT_NULL(data);
+            ARMARX_CHECK(size % sizeof(T) == 0);
+            int elements = size / sizeof(T);
+
+            std::vector<T> v(elements);
+            memcpy(v.data(), data + offset, size);
+
+            return v;
+        }
+
+    public:
+        AronVectorConverter() = delete;
+
+        template <typename T>
+        static std::vector<std::vector<T>>
+        ConvertTo2DVector(const data::NDArray& nav, int dim0size = -1)
+        {
+            const auto& dims = nav.getShape();
+
+            if (dims.size() == 0 || dim0size == 0)
+            {
+                return {};
+            }
+
+            if (dim0size == -1)
+            {
+                dim0size = dims.at(0);
+            }
+
+            const int fullDataByteSize = nav.getDataAsVector().size();
+
+            ARMARX_CHECK(fullDataByteSize % sizeof(T) == 0);
+            const int fullDataSize = fullDataByteSize / sizeof(T);
+
+            ARMARX_CHECK(fullDataSize % dim0size == 0);
+            const int dim1size = fullDataSize / dim0size;
+
+            const int oneRowByteSize = dim1size * sizeof(T);
+            std::vector<std::vector<T>> v(dims.at(0));
+            for (int i = 0; i < dim0size; i++)
+            {
+                v[i] = convert_to_1d_vector<T>(nav.getData(), i * oneRowByteSize, oneRowByteSize);
+            }
+
+            return v;
+        }
+
+        template <typename T>
+        static std::vector<std::vector<T>>
+        ConvertTo2DVector(const data::NDArrayPtr& nav)
+        {
+            ARMARX_CHECK_NOT_NULL(nav);
+
+            return ConvertTo2DVector<T>(*nav);
+        }
+
+        template <typename T>
+        static std::vector<T>
+        ConvertTo1DVector(const data::NDArray& nav)
+        {
+            const auto& dims = nav.getShape();
+
+            if (dims.size() == 0)
+            {
+                return {};
+            }
+
+            const int fullDataByteSize = nav.getDataAsVector().size();
+
+            ARMARX_CHECK(fullDataByteSize % sizeof(T) == 0);
+            const int dim0size = fullDataByteSize / sizeof(T);
+
+            const int oneRowByteSize = dim0size * sizeof(T);
+            std::vector<T> v = convert_to_1d_vector<T>(nav.getData(), 0, oneRowByteSize);
+            return v;
+        }
+
+        template <typename T>
+        static std::vector<T>
+        ConvertTo1DVector(const data::NDArrayPtr& nav)
+        {
+            ARMARX_CHECK_NOT_NULL(nav);
+
+            return ConvertTo1DVector<T>(*nav);
+        }
+
+        // alias
+        template <typename T>
+        static std::vector<T>
+        ConvertToVector(const data::NDArrayPtr& nav)
+        {
+            return ConvertTo1DVector<T>(nav);
+        }
+
+        // Attention: If a vector was flattened, the reconstruction is flattened as well!
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFrom1DVector(const std::vector<T>& data)
+        {
+            data::NDArrayPtr ndArr(new data::NDArray);
+
+            ndArr->setShape({static_cast<int>(data.size()), sizeof(T)});
+            ndArr->setData(sizeof(T) * data.size(),
+                           reinterpret_cast<const unsigned char*>(data.data()));
+
+            return ndArr;
+        }
+
+        // alias
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFromVector(const std::vector<T>& data)
+        {
+            return ConvertFrom1DVector<T>(data);
+        }
+    };
+} // namespace armarx::aron::data::converter
+
+// legacy
+namespace armarx::aron::converter
+{
+    using AronVectorConverter = ::armarx::aron::data::converter::AronVectorConverter;
+}
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..cfeb5a4f633320ed0ca98e7f43c91730eab206d2
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp
@@ -0,0 +1,6 @@
+#include "StdVectorConverterVisitor.h"
+
+namespace armarx::aron::data::converter
+{
+
+}
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h
new file mode 100644
index 0000000000000000000000000000000000000000..317e11d1537598dd699dd52118e9cffcbf6ea23b
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h
@@ -0,0 +1,167 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+// ArmarX
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/data/visitor/variant/VariantVisitor.h>
+
+#include "StdVectorConverter.h"
+
+namespace armarx::aron::data::converter
+{
+    namespace detail
+    {
+        template <typename T, size_t D>
+        struct multidimensional_vector
+        {
+            static_assert(D > 0, "matrix dimensions must be positive");
+            typedef std::vector<typename multidimensional_vector<T, D - 1>::type> type;
+        };
+
+        template <typename T>
+        struct multidimensional_vector<T, 1>
+        {
+            typedef std::vector<T> type;
+        };
+
+        template <typename T, size_t D>
+        class AronVectorConverterVisitorBase :
+            public armarx::aron::data::RecursiveConstVariantVisitor
+        {
+        public:
+            using VectorType = typename detail::multidimensional_vector<T, D>::type;
+            using Input = armarx::aron::data::RecursiveConstVariantVisitor::Input;
+
+            VectorType data;
+            std::map<std::string, int> memberInfo;
+
+        protected:
+            int currentIndex = 0;
+        };
+    } // namespace detail
+
+    template <typename T, size_t D>
+    class AronVectorConverterVisitor : public detail::AronVectorConverterVisitorBase<T, D>
+    {
+    };
+
+    template <>
+    class AronVectorConverterVisitor<float, 1> :
+        public detail::AronVectorConverterVisitorBase<float, 1>
+    {
+    public:
+        using T = float;
+
+        void
+        visitNDArray(Input& aron) override
+        {
+            auto ndarray = armarx::aron::data::NDArray::DynamicCastAndCheck(aron);
+
+            auto shape = ndarray->getShape();
+            memberInfo[ndarray->getPath().toString()] = currentIndex;
+
+            VectorType vec;
+            vec = AronVectorConverter::ConvertTo1DVector<T>(ndarray);
+            shape = {shape.empty() ? 0
+                                   : std::accumulate(std::begin(shape),
+                                                     std::prev(std::end(shape)),
+                                                     1,
+                                                     std::multiplies<int>())};
+            shape.push_back(sizeof(T));
+
+            data.insert(data.end(), vec.begin(), vec.end());
+            currentIndex += shape.at(0);
+        }
+
+        void
+        visitInt(Input& aron) override
+        {
+            auto a = armarx::aron::data::Int::DynamicCastAndCheck(aron);
+            memberInfo[a->getPath().toString()] = currentIndex;
+
+            data.push_back(T(a->getValue()));
+        }
+
+        void
+        visitLong(Input& aron) override
+        {
+            auto a = armarx::aron::data::Long::DynamicCastAndCheck(aron);
+            memberInfo[a->getPath().toString()] = currentIndex;
+
+            data.push_back(T(a->getValue()));
+        }
+
+        void
+        visitFloat(Input& aron) override
+        {
+            auto a = armarx::aron::data::Float::DynamicCastAndCheck(aron);
+            memberInfo[a->getPath().toString()] = currentIndex;
+
+            data.push_back(T(a->getValue()));
+        }
+
+        void
+        visitDouble(Input& aron) override
+        {
+            auto a = armarx::aron::data::Double::DynamicCastAndCheck(aron);
+            memberInfo[a->getPath().toString()] = currentIndex;
+
+            data.push_back(T(a->getValue()));
+        }
+
+        void
+        visitBool(Input& aron) override
+        {
+            auto a = armarx::aron::data::Bool::DynamicCastAndCheck(aron);
+            memberInfo[a->getPath().toString()] = currentIndex;
+
+            data.push_back(T(a->getValue()));
+        }
+    };
+
+    template <>
+    class AronVectorConverterVisitor<char, 2> :
+        public detail::AronVectorConverterVisitorBase<char, 2>
+    {
+    public:
+        using T = char;
+
+    public:
+        void
+        visitNDArray(Input& aron) override
+        {
+            auto ndarray = armarx::aron::data::NDArray::DynamicCastAndCheck(aron);
+
+            auto shape = ndarray->getShape();
+            memberInfo[ndarray->getPath().toString()] = currentIndex;
+
+            VectorType vec;
+            vec = AronVectorConverter::ConvertTo2DVector<T>(ndarray);
+            shape.push_back(1);
+
+            data.insert(data.end(), vec.begin(), vec.end());
+            currentIndex += shape.at(0);
+        }
+    };
+
+} // namespace armarx::aron::data::converter
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.cpp b/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..4f93debe1c2e2c3f0c6d2df35d8c813b510d1588
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.cpp
@@ -0,0 +1,5 @@
+#include "aron_conversions.h"
+
+namespace armarx::aron::data::converter::stdstl
+{
+}
diff --git a/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.h b/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.h
new file mode 100644
index 0000000000000000000000000000000000000000..3a9890a832443011d386b144c3ba52dcd68a6f85
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/aron_conversions.h
@@ -0,0 +1,28 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller (fabian dot peller at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "StdVectorConverter.h"
+
+namespace armarx::aron::data::converter::stdstl
+{
+    // No clear conversion possible. Use StdVectorConverter instead
+}
diff --git a/source/RobotAPI/libraries/aron/core/aron_conversions.h b/source/RobotAPI/libraries/aron/core/aron_conversions.h
index d27d6415877d4c15f9ddf36310e656590f8efd7e..9d067df7ed847624e6a6d07f9ececfe3669ee88d 100644
--- a/source/RobotAPI/libraries/aron/core/aron_conversions.h
+++ b/source/RobotAPI/libraries/aron/core/aron_conversions.h
@@ -5,6 +5,7 @@
 #include <optional>
 #include <type_traits>
 #include <vector>
+#include <algorithm>
 
 #include "Path.h"
 
@@ -414,4 +415,45 @@ namespace armarx
     {
         armarx::aron::toAron<DtoKeyT, DtoValueT, BoKeyT, BoValueT>(boMap);
     }
+
+    /**
+     * @brief Converter function for vector of aron elements to plain cpp type
+     *
+     *  You have to provide a converter function for the element with the signature
+     *
+     *      PlainCppType fromAron(const AronType&)
+     *
+     * @tparam T the aron vector element
+     * @param v the vector of elements
+     * @return the vector of aron elements
+     */
+    template <typename T>
+    auto fromAron(const std::vector<T>& v) -> std::vector<decltype(fromAron(T()))>
+    {
+        std::vector<decltype(fromAron(T()))> r;
+        r.reserve(v.size());
+
+        std::transform(v.begin(), v.end(), std::back_inserter(r),
+                       [](const T & t)
+        {
+            return fromAron(t);
+        });
+
+        return r;
+    }
+
+
+    template <typename T> auto toAron(const std::vector<T>& v)
+    {
+        std::vector<decltype(toAron(T()))> r;
+        r.reserve(v.size());
+
+        std::transform(v.begin(), v.end(), std::back_inserter(r),
+                       [](const T & t)
+        {
+            return toAron(t);
+        });
+
+        return r;
+    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/Variant.h b/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
index aee8c55fc02d07395e67ff7fd907a8fb5b207999..1fab338ab2df57c267c841ac9297c533632bc46a 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
@@ -115,7 +115,7 @@ namespace armarx::aron::data
 
         // virtual definitions
         /// get a pointer to a copy of this variant
-        virtual VariantPtr clone() const = 0;
+        virtual VariantPtr cloneAsVariant() const = 0;
 
         /// get the children of a data variant
         virtual std::vector<VariantPtr> getChildren() const = 0;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
index 593298a7df80e167b9525ce6280cebdbb132cd59..068fd1a85cebc436ca6c1330c59c6d88ba9f183c 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
@@ -84,7 +84,7 @@ namespace armarx::aron::data
         data::dto::NDArrayPtr toNDArrayDTO() const;
 
         // virtual implementations
-        virtual VariantPtr clone() const override
+        NDArrayPtr clone() const override
         {
             NDArrayPtr ret(new NDArray(getShape(), getType(), getDataAsVector(), getPath()));
             return ret;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
index 498e59ee2a058ffe61676ed5ff8cfe75fcf7cc30..5006a0c97a5b830f7d0998024ce2113d38af59a5 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
@@ -64,9 +64,9 @@ namespace armarx::aron::data
         std::vector<std::string> getAllKeys() const;
         std::string getAllKeysAsString() const;
 
-        void addElement(const std::string& key, const VariantPtr&);
+        void addElement(const std::string& key, const VariantPtr& = nullptr);
         bool hasElement(const std::string&) const;
-        void setElement(const std::string&, const VariantPtr&);
+        void setElement(const std::string&, const VariantPtr& = nullptr);
         VariantPtr getElement(const std::string&) const;
         std::map<std::string, VariantPtr> getElements() const;
 
@@ -75,12 +75,12 @@ namespace armarx::aron::data
         void clear();
 
         // virtual implementations        
-        VariantPtr clone() const override
+        DictPtr clone() const override
         {
             DictPtr ret(new Dict(getPath()));
             for (const auto& [key, val] : getElements())
             {
-                ret->addElement(key, val->clone());
+                ret->addElement(key, val->cloneAsVariant());
             }
             return ret;
         }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/List.h b/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
index 4ab656bfa2e11461ffb4914a2fc444f16c5ce6f8..142f42ee66940c6a5fa6d99a616d4845719234e2 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
@@ -73,12 +73,12 @@ namespace armarx::aron::data
         void clear();
 
         // virtual implementations
-        VariantPtr clone() const override
+        ListPtr clone() const override
         {
             ListPtr ret(new List(getPath()));
             for (const auto& val : getElements())
             {
-                ret->addElement(val->clone());
+                ret->addElement(val->cloneAsVariant());
             }
             return ret;
         }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h b/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
index ad4ad2eac47f0fdded2b6dbc3f9bfdc6b61c3226..3b36c6310386a27122ae7607e41a137fc6420833 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
@@ -41,6 +41,7 @@ namespace armarx::aron::data::detail
         public SpecializedVariantBase<AronDataT, DerivedT>
     {
     public:
+        using PointerType = std::shared_ptr<DerivedT>;
         using ValueType = ValueT;
 
     public:
@@ -80,9 +81,9 @@ namespace armarx::aron::data::detail
             throw error::AronException(__PRETTY_FUNCTION__, "Could not navigate through a non container navigator. The input path was: " + path.toString(), Variant::getPath());
         }
 
-        VariantPtr clone() const override
+        PointerType clone() const override
         {
-            typename DerivedT::PointerType ret(new DerivedT(getValue(), this->getPath()));
+            PointerType ret(new DerivedT(getValue(), this->getPath()));
             return ret;
         }
 
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/detail/SpecializedVariant.h b/source/RobotAPI/libraries/aron/core/data/variant/detail/SpecializedVariant.h
index 4ac67da09aa6efe678ddcbebb00bff8a5f5ac02c..d7e6e4a55cd9e96fed989b8a1a4f60e6a1c5d8b2 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/detail/SpecializedVariant.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/detail/SpecializedVariant.h
@@ -77,7 +77,15 @@ namespace armarx::aron::data::detail
         virtual bool operator==(const DerivedT&) const = 0;
         virtual bool operator==(const PointerType& other) const = 0;
 
+        // new interface methods
+        virtual PointerType clone() const = 0;
+
         // virtual implementations
+        VariantPtr cloneAsVariant() const override
+        {
+            return clone();
+        }
+
         data::dto::GenericDataPtr toAronDTO() const override
         {
             return aron;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h b/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
index a15811e6330d35b4d879202bf45859d5cc0e95ff..19d29c04e47f9af8e0a7dda2fdeee8d4799f6ce8 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
@@ -33,5 +33,4 @@ namespace armarx::aron::type
 
     using AnyObjectPtr = std::shared_ptr<class AnyObject>;
 
-}
-
+} // namespace armarx::aron::type
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h b/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
index 0a132de3166df5d582652f07295fa084ecc05c9b..c11d835fef9f95ca86f3556e9d8406633b86c5ca 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
@@ -34,7 +34,9 @@ namespace armarx::aron::type
      * @brief The visitRecursive function. Calls visitX of a RecursiveVisitorImplementation recursively. For more information please see Visitor.h
      */
     template <class RecursiveVisitorImplementation>
-    void visitRecursive(RecursiveVisitorImplementation& v, typename RecursiveVisitorImplementation::Input& t)
+    void
+    visitRecursive(RecursiveVisitorImplementation& v,
+                   typename RecursiveVisitorImplementation::Input& t)
     {
         auto descriptor = v.getDescriptor(t);
         switch (descriptor)
@@ -137,33 +139,37 @@ namespace armarx::aron::type
         virtual PairElements getPairAcceptedTypes(Input&) = 0;
         virtual TupleElements getTupleAcceptedTypes(Input&) = 0;
 
-        virtual void visitObjectOnEnter(Input&) {};
-        virtual void visitObjectOnExit(Input&) {};
-        virtual void visitDictOnEnter(Input&) {};
-        virtual void visitDictOnExit(Input&) {};
-        virtual void visitPairOnEnter(Input&) {};
-        virtual void visitPairOnExit(Input&) {};
-        virtual void visitTupleOnEnter(Input&) {};
-        virtual void visitTupleOnExit(Input&) {};
-        virtual void visitListOnEnter(Input&) {};
-        virtual void visitListOnExit(Input&) {};
+        virtual void visitObjectOnEnter(Input&){};
+        virtual void visitObjectOnExit(Input&){};
+        virtual void visitDictOnEnter(Input&){};
+        virtual void visitDictOnExit(Input&){};
+        virtual void visitPairOnEnter(Input&){};
+        virtual void visitPairOnExit(Input&){};
+        virtual void visitTupleOnEnter(Input&){};
+        virtual void visitTupleOnExit(Input&){};
+        virtual void visitListOnEnter(Input&){};
+        virtual void visitListOnExit(Input&){};
 
-        virtual void visitMatrix(Input&) {};
-        virtual void visitNDArray(Input&) {};
-        virtual void visitQuaternion(Input&) {};
-        virtual void visitImage(Input&) {};
-        virtual void visitPointCloud(Input&) {};
-        virtual void visitIntEnum(Input&) {};
-        virtual void visitInt(Input&) {};
-        virtual void visitLong(Input&) {};
-        virtual void visitFloat(Input&) {};
-        virtual void visitDouble(Input&) {};
-        virtual void visitBool(Input&) {};
-        virtual void visitString(Input&) {};
-        virtual void visitAnyObject(Input&) {};
-        virtual void visitUnknown(Input&) {
+        virtual void visitMatrix(Input&){};
+        virtual void visitNDArray(Input&){};
+        virtual void visitQuaternion(Input&){};
+        virtual void visitImage(Input&){};
+        virtual void visitPointCloud(Input&){};
+        virtual void visitIntEnum(Input&){};
+        virtual void visitInt(Input&){};
+        virtual void visitLong(Input&){};
+        virtual void visitFloat(Input&){};
+        virtual void visitDouble(Input&){};
+        virtual void visitBool(Input&){};
+        virtual void visitString(Input&){};
+        virtual void visitAnyObject(Input&){};
+
+        virtual void
+        visitUnknown(Input&)
+        {
             throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor.");
         }
+
         virtual ~RecursiveVisitor() = default;
     };
-}
+} // namespace armarx::aron::type
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
index 72e02863e6ca67aea5be0b20ed9999a091893292..fc2e8153ce86c9247c9d4ae1e781fe21e33c0c6f 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
@@ -31,7 +31,8 @@ namespace armarx::aron::type
     /****************************************************************************
      * VariantVisitor
      ***************************************************************************/
-    type::Descriptor ConstVariantVisitor::GetDescriptor(Input& n)
+    type::Descriptor
+    ConstVariantVisitor::GetDescriptor(Input& n)
     {
         if (!n)
         {
@@ -40,360 +41,575 @@ namespace armarx::aron::type
         return n->getDescriptor();
     }
 
-    type::Descriptor ConstVariantVisitor::getDescriptor(Input& n)
+    type::Descriptor
+    ConstVariantVisitor::getDescriptor(Input& n)
     {
         return GetDescriptor(n);
     }
 
-    void ConstVariantVisitor::visitObject(Input& i)
+    void
+    ConstVariantVisitor::visitObject(Input& i)
     {
         auto aron = type::Object::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitDict(Input& i)
+    void
+    ConstVariantVisitor::visitDict(Input& i)
     {
         auto aron = type::Dict::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitPair(Input& i)
+    void
+    ConstVariantVisitor::visitPair(Input& i)
     {
         auto aron = type::Pair::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitTuple(Input& i)
+    void
+    ConstVariantVisitor::visitTuple(Input& i)
     {
         auto aron = type::Tuple::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitList(Input& i)
+    void
+    ConstVariantVisitor::visitList(Input& i)
     {
         auto aron = type::List::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitMatrix(Input& i)
+    void
+    ConstVariantVisitor::visitMatrix(Input& i)
     {
         auto aron = type::Matrix::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitNDArray(Input& i)
+    void
+    ConstVariantVisitor::visitNDArray(Input& i)
     {
         auto aron = type::NDArray::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitQuaternion(Input & i)
+    void
+    ConstVariantVisitor::visitQuaternion(Input& i)
     {
         auto aron = type::Quaternion::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitImage(Input& i)
+    void
+    ConstVariantVisitor::visitImage(Input& i)
     {
         auto aron = type::Image::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitPointCloud(Input& i)
+    void
+    ConstVariantVisitor::visitPointCloud(Input& i)
     {
         auto aron = type::PointCloud::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitIntEnum(Input& i)
+    void
+    ConstVariantVisitor::visitIntEnum(Input& i)
     {
         auto aron = type::IntEnum::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitInt(Input& i)
+    void
+    ConstVariantVisitor::visitInt(Input& i)
     {
         auto aron = type::Int::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitLong(Input& i)
+    void
+    ConstVariantVisitor::visitLong(Input& i)
     {
         auto aron = type::Long::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitFloat(Input& i)
+    void
+    ConstVariantVisitor::visitFloat(Input& i)
     {
         auto aron = type::Float::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitDouble(Input& i)
+    void
+    ConstVariantVisitor::visitDouble(Input& i)
     {
         auto aron = type::Double::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitBool(Input& i)
+    void
+    ConstVariantVisitor::visitBool(Input& i)
     {
         auto aron = type::Bool::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitString(Input& i)
+    void
+    ConstVariantVisitor::visitString(Input& i)
     {
         auto aron = type::String::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitAnyObject(Input& i)
+    void
+    ConstVariantVisitor::visitAnyObject(Input& i)
     {
         auto aron = type::AnyObject::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void ConstVariantVisitor::visitAronVariant(const type::ObjectPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::DictPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::PairPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::TuplePtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::ListPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::NDArrayPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::MatrixPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::QuaternionPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::ImagePtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::PointCloudPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::IntEnumPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::IntPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::LongPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::FloatPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::DoublePtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::BoolPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::StringPtr&) {}
-    void ConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&) {}
+    void
+    ConstVariantVisitor::visitAronVariant(const type::ObjectPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::DictPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::PairPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::TuplePtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::ListPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::NDArrayPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::MatrixPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::QuaternionPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::ImagePtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::PointCloudPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::IntEnumPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::IntPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::LongPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::FloatPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::DoublePtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::BoolPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::StringPtr&)
+    {
+    }
+
+    void
+    ConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&)
+    {
+    }
 
     /****************************************************************************
      * RecursiveVariantVisitor
      ***************************************************************************/
-    type::Descriptor RecursiveConstVariantVisitor::getDescriptor(Input& n)
+    type::Descriptor
+    RecursiveConstVariantVisitor::getDescriptor(Input& n)
     {
         return ConstVariantVisitor::GetDescriptor(n);
     }
 
-    RecursiveConstVariantVisitor::ObjectElements RecursiveConstVariantVisitor::GetObjectAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::ObjectElements
+    RecursiveConstVariantVisitor::GetObjectAcceptedTypes(Input& t)
     {
         auto o = type::Object::DynamicCastAndCheck(t);
         return o->getMemberTypes();
     }
 
-    RecursiveConstVariantVisitor::ObjectElements RecursiveConstVariantVisitor::getObjectAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::ObjectElements
+    RecursiveConstVariantVisitor::getObjectAcceptedTypes(Input& t)
     {
         return GetObjectAcceptedTypes(t);
     }
 
-    RecursiveConstVariantVisitor::InputNonConst RecursiveConstVariantVisitor::GetDictAcceptedType(Input& t)
+    RecursiveConstVariantVisitor::InputNonConst
+    RecursiveConstVariantVisitor::GetDictAcceptedType(Input& t)
     {
         auto o = type::Dict::DynamicCastAndCheck(t);
         return o->getAcceptedType();
     }
 
-    RecursiveConstVariantVisitor::InputNonConst RecursiveConstVariantVisitor::getDictAcceptedType(Input& t)
+    RecursiveConstVariantVisitor::InputNonConst
+    RecursiveConstVariantVisitor::getDictAcceptedType(Input& t)
     {
         return GetDictAcceptedType(t);
     }
 
-    RecursiveConstVariantVisitor::InputNonConst RecursiveConstVariantVisitor::GetListAcceptedType(Input& t)
+    RecursiveConstVariantVisitor::InputNonConst
+    RecursiveConstVariantVisitor::GetListAcceptedType(Input& t)
     {
         auto o = type::List::DynamicCastAndCheck(t);
         return o->getAcceptedType();
     }
 
-    RecursiveConstVariantVisitor::InputNonConst RecursiveConstVariantVisitor::getListAcceptedType(Input& t)
+    RecursiveConstVariantVisitor::InputNonConst
+    RecursiveConstVariantVisitor::getListAcceptedType(Input& t)
     {
         return GetListAcceptedType(t);
     }
 
-    RecursiveConstVariantVisitor::PairElements RecursiveConstVariantVisitor::GetPairAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::PairElements
+    RecursiveConstVariantVisitor::GetPairAcceptedTypes(Input& t)
     {
         auto o = type::Pair::DynamicCastAndCheck(t);
         return o->getAcceptedTypes();
     }
 
-    RecursiveConstVariantVisitor::PairElements RecursiveConstVariantVisitor::getPairAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::PairElements
+    RecursiveConstVariantVisitor::getPairAcceptedTypes(Input& t)
     {
         return GetPairAcceptedTypes(t);
     }
 
-    RecursiveConstVariantVisitor::TupleElements RecursiveConstVariantVisitor::GetTupleAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::TupleElements
+    RecursiveConstVariantVisitor::GetTupleAcceptedTypes(Input& t)
     {
         auto o = type::Tuple::DynamicCastAndCheck(t);
         return o->getAcceptedTypes();
     }
 
-    RecursiveConstVariantVisitor::TupleElements RecursiveConstVariantVisitor::getTupleAcceptedTypes(Input& t)
+    RecursiveConstVariantVisitor::TupleElements
+    RecursiveConstVariantVisitor::getTupleAcceptedTypes(Input& t)
     {
         return GetTupleAcceptedTypes(t);
     }
 
-    void RecursiveConstVariantVisitor::visitObjectOnEnter(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitObjectOnEnter(Input& i)
     {
         auto aron = type::Object::DynamicCastAndCheck(i);
         visitAronVariantEnter(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitObjectOnExit(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitObjectOnExit(Input& i)
     {
         auto aron = type::Object::DynamicCastAndCheck(i);
         visitAronVariantExit(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitDictOnEnter(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitDictOnEnter(Input& i)
     {
         auto aron = type::Dict::DynamicCastAndCheck(i);
         visitAronVariantEnter(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitDictOnExit(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitDictOnExit(Input& i)
     {
         auto aron = type::Dict::DynamicCastAndCheck(i);
         visitAronVariantExit(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitPairOnEnter(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitPairOnEnter(Input& i)
     {
         auto aron = type::Pair::DynamicCastAndCheck(i);
         visitAronVariantEnter(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitPairOnExit(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitPairOnExit(Input& i)
     {
         auto aron = type::Pair::DynamicCastAndCheck(i);
         visitAronVariantExit(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitTupleOnEnter(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitTupleOnEnter(Input& i)
     {
         auto aron = type::Tuple::DynamicCastAndCheck(i);
         visitAronVariantEnter(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitTupleOnExit(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitTupleOnExit(Input& i)
     {
         auto aron = type::Tuple::DynamicCastAndCheck(i);
         visitAronVariantExit(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitListOnEnter(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitListOnEnter(Input& i)
     {
         auto aron = type::List::DynamicCastAndCheck(i);
         visitAronVariantEnter(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitListOnExit(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitListOnExit(Input& i)
     {
         auto aron = type::List::DynamicCastAndCheck(i);
         visitAronVariantExit(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitMatrix(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitMatrix(Input& i)
     {
         auto aron = type::Matrix::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitNDArray(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitNDArray(Input& i)
     {
         auto aron = type::NDArray::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitQuaternion(Input & i)
+    void
+    RecursiveConstVariantVisitor::visitQuaternion(Input& i)
     {
         auto aron = type::Quaternion::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitImage(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitImage(Input& i)
     {
         auto aron = type::Image::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitPointCloud(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitPointCloud(Input& i)
     {
         auto aron = type::PointCloud::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitIntEnum(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitIntEnum(Input& i)
     {
         auto aron = type::IntEnum::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitInt(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitInt(Input& i)
     {
         auto aron = type::Int::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitLong(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitLong(Input& i)
     {
         auto aron = type::Long::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitFloat(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitFloat(Input& i)
     {
         auto aron = type::Float::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitDouble(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitDouble(Input& i)
     {
         auto aron = type::Double::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitBool(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitBool(Input& i)
     {
         auto aron = type::Bool::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitString(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitString(Input& i)
     {
         auto aron = type::String::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitAnyObject(Input& i)
+    void
+    RecursiveConstVariantVisitor::visitAnyObject(Input& i)
     {
         auto aron = type::AnyObject::DynamicCastAndCheck(i);
         visitAronVariant(aron);
     }
 
-    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ObjectPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::ObjectPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::DictPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::DictPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::PairPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::PairPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::TuplePtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::TuplePtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ListPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::ListPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::NDArrayPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::MatrixPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::QuaternionPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::ImagePtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::PointCloudPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::IntEnumPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::IntPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::LongPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::FloatPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::DoublePtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::BoolPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::StringPtr&) {}
-    void RecursiveConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&) {}
-}
+    void
+    RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ObjectPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantExit(const type::ObjectPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantEnter(const type::DictPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantExit(const type::DictPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantEnter(const type::PairPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantExit(const type::PairPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantEnter(const type::TuplePtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantExit(const type::TuplePtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ListPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariantExit(const type::ListPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::NDArrayPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::MatrixPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::QuaternionPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::ImagePtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::PointCloudPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::IntEnumPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::IntPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::LongPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::FloatPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::DoublePtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::BoolPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::StringPtr&)
+    {
+    }
+
+    void
+    RecursiveConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&)
+    {
+    }
+} // namespace armarx::aron::type
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
index fccfae04aff6b10bca173d3b096001af51dd6782..0c9e0380f7021f32a36934694151b70531630e28 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
@@ -27,8 +27,8 @@
 #include <string>
 #include <vector>
 
-#include "../RecursiveVisitor.h"
 #include "../../variant/forward_declarations.h"
+#include "../RecursiveVisitor.h"
 
 namespace armarx::aron::type
 {
@@ -153,4 +153,4 @@ namespace armarx::aron::type
 
         virtual ~RecursiveConstVariantVisitor() = default;
     };
-}
+} // namespace armarx::aron::type
diff --git a/source/RobotAPI/libraries/aron/filter/CMakeLists.txt b/source/RobotAPI/libraries/aron/filter/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..7111da3687d6f4b8640bedfce30190237fe8c502
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/filter/CMakeLists.txt
@@ -0,0 +1,24 @@
+set(LIB_NAME aronfilter)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+set(LIBS
+    aron
+    aroncommon
+)
+
+set(LIB_FILES
+    data/WhitelistFilter.cpp
+    data/LambdaFilter.cpp
+)
+
+set(LIB_HEADERS
+    data/WhitelistFilter.h
+    data/LambdaFilter.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+
+add_library(RobotAPI::aron::filter ALIAS aronfilter)
diff --git a/source/RobotAPI/libraries/aron/filter/data/LambdaFilter.cpp b/source/RobotAPI/libraries/aron/filter/data/LambdaFilter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/aron/filter/data/LambdaFilter.h b/source/RobotAPI/libraries/aron/filter/data/LambdaFilter.h
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d3777a72b9615e066a110db208add1fa28738987
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp
@@ -0,0 +1,145 @@
+#include "WhitelistFilter.h"
+
+#include <SimoxUtility/algorithm/string.h>
+
+namespace armarx::aron::data::filter
+{
+    WhitelistFilter::WhitelistFilter(const std::vector<std::string>& whitelist,
+                                     const std::map<std::string, Normalization>& normalization) :
+        whitelist(whitelist), normalization(normalization)
+    {
+    }
+
+    bool
+    WhitelistFilter::pathInWhitelist(const aron::Path& p) const
+    {
+        for (const auto& w : whitelist)
+        {
+            if (simox::alg::starts_with(p.toString(), w))
+            {
+                return true;
+            }
+        }
+        return false;
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::ListPtr& aron)
+    {
+        auto l = aron::make_list(aron->getPath());
+        for (const auto& el : aron->getElements())
+        {
+            WhitelistFilter v(whitelist, normalization);
+            aron::data::visit(v, el);
+
+            if (v.data)
+            {
+                l->addElement(v.data);
+            }
+        }
+
+        if (l->getElements().size() || pathInWhitelist(aron->getPath()))
+        {
+            data = l;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::DictPtr& aron)
+    {
+        auto l = aron::make_dict(aron->getPath());
+        for (const auto& [k, el] : aron->getElements())
+        {
+            WhitelistFilter v(whitelist, normalization);
+            aron::data::visit(v, el);
+
+            if (v.data)
+            {
+                l->addElement(k, v.data);
+            }
+        }
+
+        if (l->getElements().size() || pathInWhitelist(aron->getPath()))
+        {
+            data = l;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::NDArrayPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            data = aron->clone();
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::IntPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            auto e = aron->clone();
+            int v = checkForNormalization(aron->getPath(), e->getValue());
+            e->setValue(v);
+            data = e;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::LongPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            auto e = aron->clone();
+            long v = checkForNormalization(aron->getPath(), e->getValue());
+            e->setValue(v);
+            data = e;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::FloatPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            auto e = aron->clone();
+            float v = checkForNormalization(aron->getPath(), e->getValue());
+            e->setValue(v);
+            data = e;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::DoublePtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            auto e = aron->clone();
+            double v = checkForNormalization(aron->getPath(), e->getValue());
+            e->setValue(v);
+            data = e;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::BoolPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            auto e = aron->clone();
+            bool v = checkForNormalization(aron->getPath(), e->getValue());
+            e->setValue(v);
+            data = e;
+        }
+    }
+
+    void
+    WhitelistFilter::visitAronVariant(const data::StringPtr& aron)
+    {
+        if (pathInWhitelist(aron->getPath()))
+        {
+            data = aron->clone();
+        }
+    }
+} // namespace armarx::aron::data::filter
diff --git a/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h
new file mode 100644
index 0000000000000000000000000000000000000000..aa43790e00befde0a269c932e6ebebafc0387d00
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h
@@ -0,0 +1,81 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller ( fabian dot peller at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <algorithm>
+#include <map>
+#include <vector>
+
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/data/visitor/variant/VariantVisitor.h>
+
+namespace armarx::aron::data::filter
+{
+    class WhitelistFilter : public aron::data::ConstVariantVisitor
+    {
+    public:
+        struct Normalization
+        {
+            float min;
+            float max;
+        };
+
+        WhitelistFilter(const std::vector<std::string>& whitelist,
+                        const std::map<std::string, Normalization>& normalization = {});
+
+        void visitAronVariant(const data::DictPtr&) override;
+        void visitAronVariant(const data::ListPtr&) override;
+        void visitAronVariant(const data::NDArrayPtr&) override;
+        void visitAronVariant(const data::IntPtr&) override;
+        void visitAronVariant(const data::LongPtr&) override;
+        void visitAronVariant(const data::FloatPtr&) override;
+        void visitAronVariant(const data::DoublePtr&) override;
+        void visitAronVariant(const data::BoolPtr&) override;
+        void visitAronVariant(const data::StringPtr&) override;
+
+    private:
+        bool pathInWhitelist(const aron::Path& p) const;
+
+        // normalization
+        template <class T>
+        T
+        checkForNormalization(const aron::Path& p, const T& t)
+        {
+            for (const auto& [n, v] : normalization)
+            {
+                if (simox::alg::starts_with(p.toString(), n))
+                {
+                    auto diff = v.max - v.min;
+                    auto norm = (t - v.min) / diff;
+                    return norm;
+                }
+            }
+            return t;
+        }
+
+        std::vector<std::string> whitelist;
+        std::map<std::string, Normalization> normalization;
+
+    public:
+        aron::data::VariantPtr data;
+    };
+} // namespace armarx::aron::data::filter
diff --git a/source/RobotAPI/libraries/aron/similarity/CMakeLists.txt b/source/RobotAPI/libraries/aron/similarity/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..92661f2d2ecd6994a9978e6c8d1b2aad2ffb7e9a
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/CMakeLists.txt
@@ -0,0 +1,2 @@
+#add_subdirectory(data/aron)
+#add_subdirectory(data/image)
diff --git a/source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt b/source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9f1fdc1bc8a727847e9614e2a5f142807cd969e8
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt
@@ -0,0 +1,22 @@
+set(LIB_NAME aronsimilarity)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+set(LIBS
+    aron
+    aroncommon
+)
+
+set(LIB_FILES
+    data/image/mse.cpp
+)
+
+set(LIB_HEADERS
+    data/image/mse.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+
+add_library(RobotAPI::aron::similarity ALIAS aronsimilarity)
diff --git a/source/RobotAPI/libraries/aron/similarity/data/graph/CMakeLists.txt b/source/RobotAPI/libraries/aron/similarity/data/graph/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9f1fdc1bc8a727847e9614e2a5f142807cd969e8
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/data/graph/CMakeLists.txt
@@ -0,0 +1,22 @@
+set(LIB_NAME aronsimilarity)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+set(LIBS
+    aron
+    aroncommon
+)
+
+set(LIB_FILES
+    data/image/mse.cpp
+)
+
+set(LIB_HEADERS
+    data/image/mse.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+
+add_library(RobotAPI::aron::similarity ALIAS aronsimilarity)
diff --git a/source/RobotAPI/libraries/aron/similarity/data/image/CMakeLists.txt b/source/RobotAPI/libraries/aron/similarity/data/image/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9f1fdc1bc8a727847e9614e2a5f142807cd969e8
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/data/image/CMakeLists.txt
@@ -0,0 +1,22 @@
+set(LIB_NAME aronsimilarity)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+set(LIBS
+    aron
+    aroncommon
+)
+
+set(LIB_FILES
+    data/image/mse.cpp
+)
+
+set(LIB_HEADERS
+    data/image/mse.h
+)
+
+armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
+
+
+add_library(RobotAPI::aron::similarity ALIAS aronsimilarity)
diff --git a/source/RobotAPI/libraries/aron/similarity/data/image/mse.cpp b/source/RobotAPI/libraries/aron/similarity/data/image/mse.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..0f26147604663e1e752fa8d7a8498faae480d9b3
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/data/image/mse.cpp
@@ -0,0 +1,12 @@
+#include "mse.h"
+
+#include <SimoxUtility/algorithm/string.h>
+
+namespace armarx::aron::similarity
+{
+    double
+    mse::compute_similarity(const aron::data::NDArrayPtr& p1, const aron::data::NDArrayPtr& p2)
+    {
+        return 0;
+    }
+} // namespace armarx::aron::similarity
diff --git a/source/RobotAPI/libraries/aron/similarity/data/image/mse.h b/source/RobotAPI/libraries/aron/similarity/data/image/mse.h
new file mode 100644
index 0000000000000000000000000000000000000000..461768d99d4624a5a5d92d82ed749845ceef94f1
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/similarity/data/image/mse.h
@@ -0,0 +1,33 @@
+/*
+ * 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/>.
+ *
+ * @author     Fabian Peller ( fabian dot peller at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <algorithm>
+#include <map>
+#include <vector>
+
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+
+namespace armarx::aron::similarity::mse
+{
+    double compute_similarity(const aron::data::NDArrayPtr& p1, const aron::data::NDArrayPtr& p2);
+}
diff --git a/source/RobotAPI/libraries/aron_component_config/RemoteGuiVisitors.cpp b/source/RobotAPI/libraries/aron_component_config/RemoteGuiVisitors.cpp
index fc6ed525f1ff9239f9eb4f3078e66203e0baa44d..89499311e289b0d50bdba2f29637e5b7dc2087d6 100644
--- a/source/RobotAPI/libraries/aron_component_config/RemoteGuiVisitors.cpp
+++ b/source/RobotAPI/libraries/aron_component_config/RemoteGuiVisitors.cpp
@@ -235,13 +235,13 @@ namespace armarx::aron::component_config
         if (cols == 4 && rows == 4)
         {
             // Poses
-            const auto& matrix = aron::converter::AronEigenConverter::ConvertToMatrix4f(data);
+            const auto& matrix = aron::data::converter::AronEigenConverter::ConvertToMatrix4f(data);
             group.addChild(RemoteGui::makePosRPYSpinBoxes(name).value(matrix).toolTip(name));
         }
         else if ((cols == 3 and rows == 1) or (rows == 3 and cols == 1))
         {
             // Positions
-            const auto& vector = aron::converter::AronEigenConverter::ConvertToVector3f(data);
+            const auto& vector = aron::data::converter::AronEigenConverter::ConvertToVector3f(data);
             group.addChild(RemoteGui::makeVector3fSpinBoxes(name).value(vector).toolTip(name));
         }
         group_hierarchy_.back()->addChild(group);
@@ -255,7 +255,7 @@ namespace armarx::aron::component_config
         auto data = data::NDArray::DynamicCastAndCheck(q);
         auto type = type::Quaternion::DynamicCast(t);
         const auto& quat = simox::math::quat_to_rpy(
-            aron::converter::AronEigenConverter::ConvertToQuaternionf(data));
+            aron::data::converter::AronEigenConverter::ConvertToQuaternionf(data));
         const auto& name = pathToName(q);
         auto group = RemoteGui::makeHBoxLayout(name + "_layout");
         group.addChild(RemoteGui::makeLabel(name + "_label").value(q->getPath().getLastElement()));
@@ -540,14 +540,14 @@ namespace armarx::aron::component_config
         if (cols == 4 && rows == 4)
         {
             auto gui_value = proxy_->getValue<Eigen::Matrix4f>(name);
-            auto config_value = converter::AronEigenConverter::ConvertToMatrix4f(value);
+            auto config_value = data::converter::AronEigenConverter::ConvertToMatrix4f(value);
 
             if (config_value != gui_value.get())
             {
                 if (proxy_->hasValueChanged(name))
                 {
                     auto variant =
-                        converter::AronEigenConverter::ConvertFromMatrix(gui_value.get());
+                        data::converter::AronEigenConverter::ConvertFromMatrix(gui_value.get());
                     value->setData(gui_value.get().size() * sizeof(float), variant->getData());
                 }
                 else
@@ -559,14 +559,14 @@ namespace armarx::aron::component_config
         else if ((cols == 3 and rows == 1) or (cols == 1 and rows == 3))
         {
             auto gui_value = proxy_->getValue<Eigen::Vector3f>(name);
-            auto config_value = converter::AronEigenConverter::ConvertToVector3f(value);
+            auto config_value = data::converter::AronEigenConverter::ConvertToVector3f(value);
 
             if (config_value != gui_value.get())
             {
                 if (proxy_->hasValueChanged(name))
                 {
                     auto variant =
-                        converter::AronEigenConverter::ConvertFromMatrix(gui_value.get());
+                        data::converter::AronEigenConverter::ConvertFromMatrix(gui_value.get());
                     value->setData(gui_value.get().size() * sizeof(float), variant->getData());
                 }
                 else
@@ -586,13 +586,13 @@ namespace armarx::aron::component_config
         const std::string name = pathToName(o);
         // TODO: does double work here?
         auto gui_value = proxy_->getValue<Eigen::Vector3f>(name);
-        const auto& quat =
-            simox::math::quat_to_rpy(converter::AronEigenConverter::ConvertToQuaternionf(value));
+        const auto& quat = simox::math::quat_to_rpy(
+            data::converter::AronEigenConverter::ConvertToQuaternionf(value));
         if (quat != gui_value.get())
         {
             if (proxy_->hasValueChanged(name))
             {
-                auto variant = converter::AronEigenConverter::ConvertFromQuaternion(
+                auto variant = data::converter::AronEigenConverter::ConvertFromQuaternion(
                     simox::math::rpy_to_quat(gui_value.get()));
                 value->setData(4 * sizeof(float), variant->getData());
             }
@@ -681,4 +681,4 @@ namespace armarx::aron::component_config
     }
 } // namespace armarx::aron::component_config
 
-#undef INPUT_GUARD
\ No newline at end of file
+#undef INPUT_GUARD
diff --git a/source/RobotAPI/libraries/skills/CMakeLists.txt b/source/RobotAPI/libraries/skills/CMakeLists.txt
index 30241deae7dc56e5ff773c473e895457cae38ba5..53f82b11a33901183e7eb321e7b3a18829f15527 100644
--- a/source/RobotAPI/libraries/skills/CMakeLists.txt
+++ b/source/RobotAPI/libraries/skills/CMakeLists.txt
@@ -11,6 +11,8 @@ armarx_add_library(
 
         RobotAPI::Core
         aronjsonconverter
+        arondatatypeconverter
+
     SOURCES  
         ./error/Exception.cpp
         ./manager/SkillManagerComponentPlugin.cpp