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/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/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/MemoryToIceAdapter.cpp b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
index 858f715c4ec5728edbf646e587cd4f02d5958798..d307d8e4e50bbde926147c5c68047533001005d2 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::disk::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->doLocked(
+                [&coreSegment, &input]()
                 {
-                    coreSegment->addProviderSegment(input.providerSegmentName);
-                }
-                catch (const armem::error::ContainerEntryAlreadyExists&)
-                {
-                    // 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);
+                    armem::wm::toMemory(m, updateResult.removedSnapshots);
 
-                        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);
-
-                        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,7 +243,8 @@ 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;
@@ -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/ltm/base/converter/image/exr/ExrConverter.cpp b/source/RobotAPI/libraries/armem/server/ltm/base/converter/image/exr/ExrConverter.cpp
index 6bf18cff45eea27f018c9dc7c371becbb5baf90a..4cc2c2868627ef8883ee5167e24d558d68a44e15 100644
--- 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
@@ -1,20 +1,20 @@
 #include "ExrConverter.h"
 
 // ArmarX
-#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
-
-#include <opencv2/opencv.hpp>
 #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::converter::image
 {
-    std::pair<std::vector<unsigned char>, std::string> ExrConverter::_convert(const aron::data::NDArrayPtr& data)
+    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);
+        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
@@ -25,9 +25,12 @@ namespace armarx::armem::server::ltm::converter::image
         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)
+    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);
+        return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
     }
-}
+} // namespace armarx::armem::server::ltm::converter::image
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
index 03453e6f6c4432e1efd0445ae393d1d14242a4bd..e9ba33ead6943777f2bac696421ad681590916e2 100644
--- 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
@@ -1,20 +1,20 @@
 #include "PngConverter.h"
 
 // ArmarX
-#include <RobotAPI/libraries/aron/converter/opencv/OpenCVConverter.h>
-
-#include <opencv2/opencv.hpp>
 #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::converter::image
 {
-    std::pair<std::vector<unsigned char>, std::string> PngConverter::_convert(const aron::data::NDArrayPtr& data)
+    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);
+        auto img = aron::data::converter::AronOpenCVConverter::ConvertToMat(data);
         std::vector<unsigned char> buffer;
 
 
@@ -39,23 +39,26 @@ namespace armarx::armem::server::ltm::converter::image
         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)
+    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);
+            return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
         }
 
         if (m == ".gs")
         {
             cv::Mat img = cv::imdecode(data, cv::IMREAD_GRAYSCALE);
-            return aron::converter::AronOpenCVConverter::ConvertFromMat(img, p);
+            return aron::data::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);
+        return aron::data::converter::AronOpenCVConverter::ConvertFromMat(img, p);
     }
-}
+} // namespace armarx::armem::server::ltm::converter::image
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
index c24125140309ee7c3c597fbd2a57eba5fff4caaa..468a6afb8aaa39b6a0476746b7676e61e04eacd2 100644
--- 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
@@ -1,21 +1,28 @@
 #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)
+    std::pair<std::vector<unsigned char>, std::string>
+    JsonConverter::_convert(const aron::data::DictPtr& data)
     {
-        nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
+        nlohmann::json j =
+            aron::data::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&)
+    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);
+        return aron::data::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(j,
+                                                                                               p);
     }
-}
+} // namespace armarx::armem::server::ltm::converter::object
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
index cc558297e32f82b6db21a2649f283292a0a11518..41180550733fc601a4b209d5f22237d954b9fe08 100644
--- a/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.cpp
+++ b/source/RobotAPI/libraries/armem/server/ltm/base/typeConverter/json/JsonConverter.cpp
@@ -4,17 +4,21 @@
 
 namespace armarx::armem::server::ltm::converter::type
 {
-    std::pair<std::vector<unsigned char>, std::string> JsonConverter::convert(const aron::type::ObjectPtr& data)
+    std::pair<std::vector<unsigned char>, std::string>
+    JsonConverter::convert(const aron::type::ObjectPtr& data)
     {
-        nlohmann::json j = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(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&)
+    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);
+        return aron::type::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONTypeObject(
+            j);
     }
-}
+} // namespace armarx::armem::server::ltm::converter::type
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/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/aron_conversions.h b/source/RobotAPI/libraries/armem_laser_scans/aron_conversions.h
index 80c15c08275b23509bb67f4a770a4c8e6c50e530..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/stl/StdVectorConverter.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_skills/server/segment/ExecutableSkillLibrarySegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/ExecutableSkillLibrarySegment.cpp
index db2a719d4842fcef88799211bb3eca0bc793024a..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/aron/DatatypeConverterVisitor.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::DatatypeConverterVisitor 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/aron_conversions.h b/source/RobotAPI/libraries/armem_vision/aron_conversions.h
index 7da8fe4e6546c5c46d05b0880cb14135029a144e..4d70758f166b66666b9feb22b2dd2a754082bb76 100644
--- a/source/RobotAPI/libraries/armem_vision/aron_conversions.h
+++ b/source/RobotAPI/libraries/armem_vision/aron_conversions.h
@@ -26,8 +26,8 @@
 #include <RobotAPI/libraries/armem_vision/aron/LaserScannerFeatures.aron.generated.h>
 #include <RobotAPI/libraries/armem_vision/aron/OccupancyGrid.aron.generated.h>
 #include <RobotAPI/libraries/armem_vision/types.h>
-#include <RobotAPI/libraries/aron/converter/stl/StdVectorConverter.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
@@ -51,7 +51,7 @@ namespace armarx::armem::vision
     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);
@@ -65,7 +65,7 @@ namespace armarx::armem::vision
     inline aron::data::NDArrayPtr
     toAron(const LaserScan& laserScan)
     {
-        using aron::converter::AronVectorConverter;
+        using aron::data::converter::AronVectorConverter;
         return AronVectorConverter::ConvertFromVector(laserScan);
     }
 
@@ -76,7 +76,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);
     }
 
     // LaserScannerFeatures
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 ebe331f668e2d09199a12d55f957142c3edb1ec4..692784791b779d28035abc83adb5354033a4b335 100644
--- a/source/RobotAPI/libraries/aron/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/CMakeLists.txt
@@ -3,5 +3,5 @@ add_subdirectory(common)
 add_subdirectory(converter)
 add_subdirectory(filter)
 add_subdirectory(codegeneration)
-add_subdirectory(similarity_measure)
+add_subdirectory(similarity)
 add_subdirectory(test)
diff --git a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
index 9f3a28977ac920638d9687e61b30f5a82b7bcce3..d1c054832bef05c9062baa5ee04f5eef9d1494f5 100644
--- a/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/CMakeLists.txt
@@ -3,8 +3,8 @@ add_subdirectory(pcl)
 add_subdirectory(eigen)
 add_subdirectory(opencv)
 add_subdirectory(json)
-add_subdirectory(stl)
-add_subdirectory(aron)
+add_subdirectory(stdstl)
+add_subdirectory(datatype)
 
 
 add_library(AronConverter INTERFACE)
@@ -17,7 +17,7 @@ target_link_libraries(AronConverter
         RobotAPI::aron::converter::opencv
         RobotAPI::aron::converter::json
         RobotAPI::aron::converter::stdstl
-        RobotAPI::aron::converter::aron
+        RobotAPI::aron::converter::datatype
 )
 
 add_library(aron::converter ALIAS AronConverter)
diff --git a/source/RobotAPI/libraries/aron/converter/aron/DatatypeConverterVisitor.cpp b/source/RobotAPI/libraries/aron/converter/aron/DatatypeConverterVisitor.cpp
deleted file mode 100644
index b20cc993b916c4dcab9ec21ccc876d8d917942f3..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/aron/DatatypeConverterVisitor.cpp
+++ /dev/null
@@ -1,151 +0,0 @@
-#include "DatatypeConverterVisitor.h"
-
-namespace armarx::aron::converter
-{
-    void DatatypeConverterVisitor::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())
-        {
-            DatatypeConverterVisitor converter;
-            aron::type::visit(converter, child);
-
-            dict->addElement(key, converter.latest);
-        }
-
-        latest = dict;
-    }
-
-    void DatatypeConverterVisitor::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();
-        DatatypeConverterVisitor converter;
-        aron::type::visit(converter, acceptedType);
-        dict->addElement(acceptedTypeMemberName, converter.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverterVisitor::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();
-        DatatypeConverterVisitor converter;
-        aron::type::visit(converter, acceptedType);
-        dict->addElement(acceptedTypeMemberName, converter.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverterVisitor::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();
-        DatatypeConverterVisitor converter1;
-        aron::type::visit(converter1, acceptedType1);
-        dict->addElement(firstAcceptedTypeMemberName, converter1.latest);
-
-        auto acceptedType2 = el->getSecondAcceptedType();
-        DatatypeConverterVisitor converter2;
-        aron::type::visit(converter2, acceptedType2);
-        dict->addElement(secondAcceptedTypeMemberName, converter2.latest);
-
-        latest = dict;
-    }
-
-    void DatatypeConverterVisitor::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())
-        {
-            DatatypeConverterVisitor converter;
-            aron::type::visit(converter, child);
-
-            dict->addElement(acceptedTypeMemberName + "_" + std::to_string(i++), converter.latest);
-        }
-
-        latest = dict;
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::MatrixPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::NDArrayPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::QuaternionPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::PointCloudPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::ImagePtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::IntEnumPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::IntPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::LongPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::FloatPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::DoublePtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::BoolPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::StringPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-
-    void DatatypeConverterVisitor::visitAronVariant(const type::AnyObjectPtr& el)
-    {
-        latest = aron::make_string(el->getFullName(), el->getPath());
-    }
-}
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/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/DatatypeConverter.h b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
deleted file mode 100644
index 34201b359d763ac81901135b475fd875714ab05c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
+++ /dev/null
@@ -1,62 +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 )
- * @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/visitor/variant/VariantVisitor.h>
-
-namespace armarx::aron::converter
-{
-    class DatatypeConverter :
-        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";
-
-        void visitAronVariant(const type::ObjectPtr&) override;
-        void visitAronVariant(const type::DictPtr&) override;
-        void visitAronVariant(const type::ListPtr&) override;
-        void visitAronVariant(const type::PairPtr&) override;
-        void visitAronVariant(const type::TuplePtr&) override;
-        void visitAronVariant(const type::MatrixPtr&) override;
-        void visitAronVariant(const type::NDArrayPtr&) override;
-        void visitAronVariant(const type::QuaternionPtr&) override;
-        void visitAronVariant(const type::PointCloudPtr&) override;
-        void visitAronVariant(const type::ImagePtr&) override;
-        void visitAronVariant(const type::IntEnumPtr&) override;
-        void visitAronVariant(const type::IntPtr&) override;
-        void visitAronVariant(const type::LongPtr&) override;
-        void visitAronVariant(const type::FloatPtr&) override;
-        void visitAronVariant(const type::DoublePtr&) override;
-        void visitAronVariant(const type::BoolPtr&) override;
-        void visitAronVariant(const type::StringPtr&) override;
-        void visitAronVariant(const type::AnyObjectPtr&) override;
-
-    public:
-        aron::data::VariantPtr latest;
-    };
-}
diff --git a/source/RobotAPI/libraries/aron/converter/aron/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
similarity index 80%
rename from source/RobotAPI/libraries/aron/converter/aron/CMakeLists.txt
rename to source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
index a29edce54dc9f9968bb17e7b5abcd3f2a2ea6508..6d176fdc275fef8c2aa5c1a188f9f98d6a3dd1f0 100644
--- a/source/RobotAPI/libraries/aron/converter/aron/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/datatype/CMakeLists.txt
@@ -9,11 +9,15 @@ set(LIBS
 )
 
 set(LIB_FILES
+    DatatypeConverter.cpp
     DatatypeConverterVisitor.cpp
+    aron_conversions.cpp
 )
 
 set(LIB_HEADERS
+    DatatypeConverter.h
     DatatypeConverterVisitor.h
+    aron_conversions.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
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/aron/DatatypeConverterVisitor.h b/source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h
similarity index 80%
rename from source/RobotAPI/libraries/aron/converter/aron/DatatypeConverterVisitor.h
rename to source/RobotAPI/libraries/aron/converter/datatype/DatatypeConverterVisitor.h
index 03573997a4ff721a4c41353522cfb1fad37b83d1..7b2601ad17de4477c1aea12e10cc11c8e4a93ba1 100644
--- a/source/RobotAPI/libraries/aron/converter/aron/DatatypeConverterVisitor.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 DatatypeConverterVisitor :
-        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..262c0b076f75fd2c88e90b2104cc0a277e902aaa 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,33 @@ 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
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..f2b7972b35515ef05e86568764ae60071d0616c5 100644
--- a/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/ivt/IVTConverter.h
@@ -29,17 +29,18 @@
 
 // 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
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..4b64a2f2485c1fbf9a1b5eac655171cabac33dcc 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,26 @@ 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
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..60efab3d54dfebd89fd778c7f0996ade24b35cf7 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,4 @@ namespace armarx::aron::converter
         static data::NDArrayPtr ConvertFromMat(const cv::Mat&, const armarx::aron::Path& = {});
     };
 
-}
+} // namespace armarx::aron::data::converter
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..21a922cfb303de6a2c03b49fc5f6e920004de4f1 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,38 @@
 
 // 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
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/stl/CMakeLists.txt b/source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt
similarity index 90%
rename from source/RobotAPI/libraries/aron/converter/stl/CMakeLists.txt
rename to source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt
index efbd807ac0bba2b7d7c7d187c9ac079db3ad60bb..f9b36927a0b03b4138a7b626d4a87e5b867730b4 100644
--- a/source/RobotAPI/libraries/aron/converter/stl/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/CMakeLists.txt
@@ -11,11 +11,13 @@ set(LIBS
 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}")
diff --git a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverter.cpp b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.cpp
similarity index 100%
rename from source/RobotAPI/libraries/aron/converter/stl/StdVectorConverter.cpp
rename to source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.cpp
diff --git a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverter.h b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h
similarity index 74%
rename from source/RobotAPI/libraries/aron/converter/stl/StdVectorConverter.h
rename to source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h
index 9d3f89acc69be65eb1ad3caca9314dcbc8b26fca..d330c99971b3b712cc1d4b67a3c2ab4ba0c8e615 100644
--- a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverter.h
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverter.h
@@ -23,8 +23,8 @@
 
 // STD/STL
 #include <memory>
-#include <string>
 #include <numeric>
+#include <string>
 
 // ArmarX
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
@@ -32,13 +32,14 @@
 #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 AronVectorConverter
     {
     private:
-        template<typename T>
-        static std::vector<T> convert_to_1d_vector(const unsigned char* data, const int offset, const int size)
+        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);
@@ -53,8 +54,9 @@ namespace armarx::aron::converter
     public:
         AronVectorConverter() = delete;
 
-        template<typename T>
-        static std::vector<std::vector<T>> ConvertTo2DVector(const data::NDArray& nav, int dim0size = -1)
+        template <typename T>
+        static std::vector<std::vector<T>>
+        ConvertTo2DVector(const data::NDArray& nav, int dim0size = -1)
         {
             const auto& dims = nav.getShape();
 
@@ -86,16 +88,18 @@ namespace armarx::aron::converter
             return v;
         }
 
-        template<typename T>
-        static std::vector<std::vector<T>> ConvertTo2DVector(const data::NDArrayPtr& nav)
+        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)
+        template <typename T>
+        static std::vector<T>
+        ConvertTo1DVector(const data::NDArray& nav)
         {
             const auto& dims = nav.getShape();
 
@@ -114,8 +118,9 @@ namespace armarx::aron::converter
             return v;
         }
 
-        template<typename T>
-        static std::vector<T> ConvertTo1DVector(const data::NDArrayPtr& nav)
+        template <typename T>
+        static std::vector<T>
+        ConvertTo1DVector(const data::NDArrayPtr& nav)
         {
             ARMARX_CHECK_NOT_NULL(nav);
 
@@ -123,31 +128,33 @@ namespace armarx::aron::converter
         }
 
         // alias
-        template<typename T>
-        static std::vector<T> ConvertToVector(const data::NDArrayPtr& nav)
+        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)
+        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()));
+            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)
+        template <typename T>
+        static data::NDArrayPtr
+        ConvertFromVector(const std::vector<T>& data)
         {
             return ConvertFrom1DVector<T>(data);
         }
-
     };
-}  // namespace armarx::aron::converter
+} // namespace armarx::aron::data::converter
diff --git a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.cpp b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp
similarity index 52%
rename from source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.cpp
rename to source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp
index 4eed9e5fa7194c07037b8dbcee0da3360eb8fbca..cfeb5a4f633320ed0ca98e7f43c91730eab206d2 100644
--- a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.cpp
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.cpp
@@ -1,6 +1,6 @@
 #include "StdVectorConverterVisitor.h"
 
-namespace armarx::aron::converter
+namespace armarx::aron::data::converter
 {
 
 }
diff --git a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.h b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h
similarity index 75%
rename from source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.h
rename to source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h
index 416087349e935209ccec94ed3a459229891c8d8e..317e11d1537598dd699dd52118e9cffcbf6ea23b 100644
--- a/source/RobotAPI/libraries/aron/converter/stl/StdVectorConverterVisitor.h
+++ b/source/RobotAPI/libraries/aron/converter/stdstl/StdVectorConverterVisitor.h
@@ -22,20 +22,20 @@
 #pragma once
 
 // ArmarX
-#include "StdVectorConverter.h"
-
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/data/visitor/variant/VariantVisitor.h>
 
-namespace armarx::aron::converter
+#include "StdVectorConverter.h"
+
+namespace armarx::aron::data::converter
 {
     namespace detail
     {
-        template<typename T, size_t D>
+        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;
+            typedef std::vector<typename multidimensional_vector<T, D - 1>::type> type;
         };
 
         template <typename T>
@@ -45,7 +45,8 @@ namespace armarx::aron::converter
         };
 
         template <typename T, size_t D>
-        class AronVectorConverterVisitorBase : public armarx::aron::data::RecursiveConstVariantVisitor
+        class AronVectorConverterVisitorBase :
+            public armarx::aron::data::RecursiveConstVariantVisitor
         {
         public:
             using VectorType = typename detail::multidimensional_vector<T, D>::type;
@@ -57,21 +58,22 @@ namespace armarx::aron::converter
         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>
+    class AronVectorConverterVisitor<float, 1> :
+        public detail::AronVectorConverterVisitorBase<float, 1>
     {
     public:
         using T = float;
 
-        void visitNDArray(Input &aron) override
+        void
+        visitNDArray(Input& aron) override
         {
             auto ndarray = armarx::aron::data::NDArray::DynamicCastAndCheck(aron);
 
@@ -80,14 +82,19 @@ namespace armarx::aron::converter
 
             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 = {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
+        void
+        visitInt(Input& aron) override
         {
             auto a = armarx::aron::data::Int::DynamicCastAndCheck(aron);
             memberInfo[a->getPath().toString()] = currentIndex;
@@ -95,7 +102,8 @@ namespace armarx::aron::converter
             data.push_back(T(a->getValue()));
         }
 
-        void visitLong(Input& aron) override
+        void
+        visitLong(Input& aron) override
         {
             auto a = armarx::aron::data::Long::DynamicCastAndCheck(aron);
             memberInfo[a->getPath().toString()] = currentIndex;
@@ -103,7 +111,8 @@ namespace armarx::aron::converter
             data.push_back(T(a->getValue()));
         }
 
-        void visitFloat(Input& aron) override
+        void
+        visitFloat(Input& aron) override
         {
             auto a = armarx::aron::data::Float::DynamicCastAndCheck(aron);
             memberInfo[a->getPath().toString()] = currentIndex;
@@ -111,7 +120,8 @@ namespace armarx::aron::converter
             data.push_back(T(a->getValue()));
         }
 
-        void visitDouble(Input& aron) override
+        void
+        visitDouble(Input& aron) override
         {
             auto a = armarx::aron::data::Double::DynamicCastAndCheck(aron);
             memberInfo[a->getPath().toString()] = currentIndex;
@@ -119,7 +129,8 @@ namespace armarx::aron::converter
             data.push_back(T(a->getValue()));
         }
 
-        void visitBool(Input& aron) override
+        void
+        visitBool(Input& aron) override
         {
             auto a = armarx::aron::data::Bool::DynamicCastAndCheck(aron);
             memberInfo[a->getPath().toString()] = currentIndex;
@@ -129,13 +140,15 @@ namespace armarx::aron::converter
     };
 
     template <>
-    class AronVectorConverterVisitor<char, 2> : public detail::AronVectorConverterVisitorBase<char, 2>
+    class AronVectorConverterVisitor<char, 2> :
+        public detail::AronVectorConverterVisitorBase<char, 2>
     {
     public:
         using T = char;
 
     public:
-        void visitNDArray(Input &aron) override
+        void
+        visitNDArray(Input& aron) override
         {
             auto ndarray = armarx::aron::data::NDArray::DynamicCastAndCheck(aron);
 
@@ -151,4 +164,4 @@ namespace armarx::aron::converter
         }
     };
 
-}  // namespace armarx::aron::converter
+} // 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/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
index 46ca5c4ae618984735c02ea64052a50705c97cb2..7111da3687d6f4b8640bedfce30190237fe8c502 100644
--- a/source/RobotAPI/libraries/aron/filter/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/filter/CMakeLists.txt
@@ -9,11 +9,13 @@ set(LIBS
 )
 
 set(LIB_FILES
-    DataFilter.cpp
+    data/WhitelistFilter.cpp
+    data/LambdaFilter.cpp
 )
 
 set(LIB_HEADERS
-    DataFilter.h
+    data/WhitelistFilter.h
+    data/LambdaFilter.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
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/DataFilter.cpp b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp
similarity index 64%
rename from source/RobotAPI/libraries/aron/filter/DataFilter.cpp
rename to source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp
index 51cb17110f7004c7a717981c897ed6dc8a1213b1..d3777a72b9615e066a110db208add1fa28738987 100644
--- a/source/RobotAPI/libraries/aron/filter/DataFilter.cpp
+++ b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.cpp
@@ -1,17 +1,17 @@
-#include "DataFilter.h"
+#include "WhitelistFilter.h"
 
 #include <SimoxUtility/algorithm/string.h>
 
-namespace armarx::aron::filter
+namespace armarx::aron::data::filter
 {
-    WhitelistDataFilterWithNormalization::WhitelistDataFilterWithNormalization(const std::vector<std::string>& whitelist, const std::map<std::string, Normalization>& normalization) :
-        whitelist(whitelist),
-        normalization(normalization)
+    WhitelistFilter::WhitelistFilter(const std::vector<std::string>& whitelist,
+                                     const std::map<std::string, Normalization>& normalization) :
+        whitelist(whitelist), normalization(normalization)
     {
-
     }
 
-    bool WhitelistDataFilterWithNormalization::pathInWhitelist(const aron::Path& p) const
+    bool
+    WhitelistFilter::pathInWhitelist(const aron::Path& p) const
     {
         for (const auto& w : whitelist)
         {
@@ -23,12 +23,13 @@ namespace armarx::aron::filter
         return false;
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::ListPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::ListPtr& aron)
     {
         auto l = aron::make_list(aron->getPath());
         for (const auto& el : aron->getElements())
         {
-            WhitelistDataFilterWithNormalization v(whitelist, normalization);
+            WhitelistFilter v(whitelist, normalization);
             aron::data::visit(v, el);
 
             if (v.data)
@@ -43,12 +44,13 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::DictPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::DictPtr& aron)
     {
         auto l = aron::make_dict(aron->getPath());
         for (const auto& [k, el] : aron->getElements())
         {
-            WhitelistDataFilterWithNormalization v(whitelist, normalization);
+            WhitelistFilter v(whitelist, normalization);
             aron::data::visit(v, el);
 
             if (v.data)
@@ -63,7 +65,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::NDArrayPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::NDArrayPtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -71,7 +74,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::IntPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::IntPtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -82,7 +86,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::LongPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::LongPtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -93,7 +98,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::FloatPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::FloatPtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -104,7 +110,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::DoublePtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::DoublePtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -115,7 +122,8 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::BoolPtr& aron)
+    void
+    WhitelistFilter::visitAronVariant(const data::BoolPtr& aron)
     {
         if (pathInWhitelist(aron->getPath()))
         {
@@ -126,11 +134,12 @@ namespace armarx::aron::filter
         }
     }
 
-    void WhitelistDataFilterWithNormalization::visitAronVariant(const data::StringPtr& aron)
+    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/DataFilter.h b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h
similarity index 87%
rename from source/RobotAPI/libraries/aron/filter/DataFilter.h
rename to source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h
index 8b00b3bcc21baca9b1045c44a8fafbf14deaf778..aa43790e00befde0a269c932e6ebebafc0387d00 100644
--- a/source/RobotAPI/libraries/aron/filter/DataFilter.h
+++ b/source/RobotAPI/libraries/aron/filter/data/WhitelistFilter.h
@@ -22,16 +22,15 @@
 #pragma once
 
 #include <algorithm>
-#include <vector>
 #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::filter
+namespace armarx::aron::data::filter
 {
-    class WhitelistDataFilterWithNormalization :
-            public aron::data::ConstVariantVisitor
+    class WhitelistFilter : public aron::data::ConstVariantVisitor
     {
     public:
         struct Normalization
@@ -40,7 +39,8 @@ namespace armarx::aron::filter
             float max;
         };
 
-        WhitelistDataFilterWithNormalization(const std::vector<std::string>& whitelist, const std::map<std::string, Normalization>& normalization = {});
+        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;
@@ -53,12 +53,12 @@ namespace armarx::aron::filter
         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)
+        T
+        checkForNormalization(const aron::Path& p, const T& t)
         {
             for (const auto& [n, v] : normalization)
             {
@@ -76,7 +76,6 @@ namespace armarx::aron::filter
         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_measure/CMakeLists.txt b/source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt
similarity index 59%
rename from source/RobotAPI/libraries/aron/similarity_measure/CMakeLists.txt
rename to source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt
index fdd23814311c41e0a3ba46379a0a2e6a40273ec7..9f1fdc1bc8a727847e9614e2a5f142807cd969e8 100644
--- a/source/RobotAPI/libraries/aron/similarity_measure/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/similarity/data/aron/CMakeLists.txt
@@ -1,4 +1,4 @@
-set(LIB_NAME aronsimilaritymeasure)
+set(LIB_NAME aronsimilarity)
 
 armarx_component_set_name("${LIB_NAME}")
 armarx_set_target("Library: ${LIB_NAME}")
@@ -9,14 +9,14 @@ set(LIBS
 )
 
 set(LIB_FILES
-    ndarray/image/MSE.cpp
+    data/image/mse.cpp
 )
 
 set(LIB_HEADERS
-    ndarray/image/MSE.h
+    data/image/mse.h
 )
 
 armarx_add_library("${LIB_NAME}" "${LIB_FILES}" "${LIB_HEADERS}" "${LIBS}")
 
 
-add_library(RobotAPI::aron::similarity_measure ALIAS aronsimilaritymeasure)
+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_measure/ndarray/image/MSE.h b/source/RobotAPI/libraries/aron/similarity/data/image/mse.h
similarity index 74%
rename from source/RobotAPI/libraries/aron/similarity_measure/ndarray/image/MSE.h
rename to source/RobotAPI/libraries/aron/similarity/data/image/mse.h
index c8f9bf5d817263ccf975d9224e5095ca6192ac43..461768d99d4624a5a5d92d82ed749845ceef94f1 100644
--- a/source/RobotAPI/libraries/aron/similarity_measure/ndarray/image/MSE.h
+++ b/source/RobotAPI/libraries/aron/similarity/data/image/mse.h
@@ -22,18 +22,12 @@
 #pragma once
 
 #include <algorithm>
-#include <vector>
 #include <map>
+#include <vector>
 
-#include <RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
 
-namespace armarx::aron::similarity_measure::ndarray::image
+namespace armarx::aron::similarity::mse
 {
-    class MSE
-    {
-    public:
-        MSE() = delete;
-
-        static size_t similarity(const aron::data::NDArrayPtr& p1, const aron::data::NDArrayPtr& p2);
-    };
+    double compute_similarity(const aron::data::NDArrayPtr& p1, const aron::data::NDArrayPtr& p2);
 }
diff --git a/source/RobotAPI/libraries/aron/similarity_measure/ndarray/image/MSE.cpp b/source/RobotAPI/libraries/aron/similarity_measure/ndarray/image/MSE.cpp
deleted file mode 100644
index e3e37f6dca14834d9347e074ba341d0917bc2bf6..0000000000000000000000000000000000000000
--- a/source/RobotAPI/libraries/aron/similarity_measure/ndarray/image/MSE.cpp
+++ /dev/null
@@ -1,11 +0,0 @@
-#include "MSE.h"
-
-#include <SimoxUtility/algorithm/string.h>
-
-namespace armarx::aron::similarity_measure::ndarray::image
-{
-    size_t MSE::similarity(const aron::data::NDArrayPtr& p1, const aron::data::NDArrayPtr& p2)
-    {
-        return 0;
-    }
-}
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