diff --git a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
index b63913fdc88671f583339c7850134e23d8c5fbef..cdc049a27ad64057d179096185a2a5968f34d0d0 100644
--- a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
+++ b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
@@ -26,6 +26,7 @@
 // ArmarX
 #include <RobotAPI/libraries/armem_robot_state/aron/Proprioception.aron.generated.h>
 #include <RobotAPI/libraries/armem_robot_state/aron/Transform.aron.generated.h>
+#include <RobotAPI/libraries/armem_robot/aron/RobotDescription.aron.generated.h>
 
 namespace armarx::armem
 {
@@ -86,7 +87,7 @@ namespace armarx::armem
 
         // is this corect??
         prop.platform.acceleration = Eigen::Vector3f();
-        prop.platform.relativePosition = Eigen::Vector3f(update.platformPose.x,
+        prop.platform.relativePosition = Eigen::Vector3f(update.platformPose.x, // this should be globasl AFAIK
                                                          update.platformPose.y,
                                                          update.platformPose.rotationAroundZ);
         prop.platform.velocity = Eigen::Vector3f(std::get<0>(update.platformVelocity),
@@ -104,7 +105,7 @@ namespace armarx::armem
 
         ARMARX_DEBUG << "Committing " << entityUpdate;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(entityUpdate);
-        ARMARX_INFO << updateResult;
+        ARMARX_DEBUG << updateResult;
         if (!updateResult.success)
         {
             ARMARX_ERROR << updateResult.errorMessage;
@@ -119,9 +120,9 @@ namespace armarx::armem
             transform.header.timestamp = IceUtil::Time::microSeconds(_timestampUpdateFirstModifiedInUs);
 
             Eigen::Isometry3f tf = Eigen::Isometry3f::Identity();
-            tf.translation().x() = std::get<0>(update.platformOdometryPose);
-            tf.translation().y() = std::get<1>(update.platformOdometryPose);
-            tf.linear() = Eigen::AngleAxisf(std::get<2>(update.platformOdometryPose), Eigen::Vector3f::UnitZ()).toRotationMatrix();
+            tf.translation().x() = (update.platformPose.x);
+            tf.translation().y() = (update.platformPose.y);
+            tf.linear() = Eigen::AngleAxisf((update.platformPose.rotationAroundZ), Eigen::Vector3f::UnitZ()).toRotationMatrix();
 
             transform.transform = tf.matrix();
 
@@ -135,7 +136,7 @@ namespace armarx::armem
 
             ARMARX_DEBUG << "Committing " << entityUpdate;
             armem::EntityUpdateResult updateResult = memoryWriter.commit(locUpdate);
-            ARMARX_INFO << updateResult;
+            ARMARX_DEBUG << updateResult;
             if (!updateResult.success)
             {
                 ARMARX_ERROR << updateResult.errorMessage;
@@ -173,7 +174,7 @@ namespace armarx::armem
     {
         ARMARX_DEBUG << "Got an update for joint vels";
         std::lock_guard l(updateMutex);
-        update.jointAngles = m;
+        update.jointVelocities = m;
         updateTimestamps(ts);
     }
 
@@ -181,7 +182,7 @@ namespace armarx::armem
     {
         ARMARX_DEBUG << "Got an update for joint torques";
         std::lock_guard l(updateMutex);
-        update.jointAngles = m;
+        update.jointTorques = m;
         updateTimestamps(ts);
     }
 
@@ -189,7 +190,7 @@ namespace armarx::armem
     {
         ARMARX_DEBUG << "Got an update for joint accels";
         std::lock_guard l(updateMutex);
-        update.jointAngles = m;
+        update.jointAccelerations = m;
         updateTimestamps(ts);
     }
 
@@ -197,7 +198,7 @@ namespace armarx::armem
     {
         ARMARX_DEBUG << "Got an update for joint currents";
         std::lock_guard l(updateMutex);
-        update.jointAngles = m;
+        update.jointCurrents = m;
         updateTimestamps(ts);
     }
 
@@ -241,6 +242,33 @@ namespace armarx::armem
         updateTimestamps(now);
     }
 
+    void LegacyRobotStateMemoryAdapter::commitArmar3RobotDescription()
+    {
+        ARMARX_IMPORTANT << "Commiting Armar3 to descriptions";
+        armem::arondto::RobotDescription desc;
+        desc.name = "Armar3";
+        desc.timestamp = armem::Time::now();
+        desc.xml.package = "RobotAPI";
+        desc.xml.path = "RobotAPI/robots/Armar3/ArmarIII.xml";
+
+        armem::Commit c;
+        auto& entityUpdate = c.add();
+
+        entityUpdate.confidence = 1.0;
+        entityUpdate.entityID.memoryName = "RobotState";
+        entityUpdate.entityID.coreSegmentName = "Description";
+        entityUpdate.entityID.providerSegmentName = "Armar3";
+        entityUpdate.entityID.entityName = "Armar3";
+
+        entityUpdate.instancesData = { desc.toAron() };
+        entityUpdate.timeCreated = armem::Time::now();
+        auto res = memoryWriter.commit(c);
+        if (!res.allSuccess())
+        {
+            ARMARX_WARNING << "Could not send data to memory." << res.allErrorMessages();
+        }
+    }
+
 
     void LegacyRobotStateMemoryAdapter::onInitComponent()
     {
@@ -273,6 +301,9 @@ namespace armarx::armem
             return;
         }
 
+        // update RobotDescription (since there will be no robot unit, we have to submit the description by ourselves)
+        commitArmar3RobotDescription();
+
         runningTask->start();
     }
 
diff --git a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.h b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.h
index 10f6c20ee094a657806ab21217b0bcba79758ad9..50f2c1973ada697cf5747253ca298348e77f2e19 100644
--- a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.h
+++ b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.h
@@ -80,6 +80,8 @@ namespace armarx::armem
         void onExitComponent() override;
 
     private:
+        void commitArmar3RobotDescription();
+
         void updateTimestamps(long dataGeneratedUs);
         void checkUpdateAndSendToMemory();
 
diff --git a/source/RobotAPI/components/armem/server/GraspMemory/CMakeLists.txt b/source/RobotAPI/components/armem/server/GraspMemory/CMakeLists.txt
index 6f09f46f79512819800b879bbd7701677fde1118..711482a70e3caff55f4b0ab3689d86dc40a84e9e 100644
--- a/source/RobotAPI/components/armem/server/GraspMemory/CMakeLists.txt
+++ b/source/RobotAPI/components/armem/server/GraspMemory/CMakeLists.txt
@@ -6,7 +6,7 @@ set(COMPONENT_LIBS
     ArmarXGuiComponentPlugins
     RobotAPICore RobotAPIInterfaces armem_server
     RobotAPIComponentPlugins  # for ArViz and other plugins
-
+    armem_grasping
     ${IVT_LIBRARIES}
 )
 
diff --git a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.cpp b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.cpp
index b50b214509fb791a4b9f0394bd2c82867ee192ff..2c6d48126cf3dc968b305c3f04e78d92eef23d0a 100644
--- a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.cpp
+++ b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.cpp
@@ -1,4 +1,3 @@
-
 #include "GraspMemory.h"
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
@@ -9,6 +8,7 @@
 #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h>
 
 #include <RobotAPI/libraries/GraspingUtility/aron/GraspCandidate.aron.generated.h>
+#include <RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.aron.generated.h>
 
 namespace armarx::armem::server::grasp
 {
@@ -29,22 +29,28 @@ namespace armarx::armem::server::grasp
         return "GraspMemory";
     }
 
+    GraspMemory::GraspMemory() :
+        knownGraspProviderSegment(iceAdapter())
+    {
+    }
+
     void GraspMemory::onInitComponent()
     {
         workingMemory().name() = memoryName;
-
         workingMemory().addCoreSegment("GraspCandidate",
                                      armarx::grasping::arondto::GraspCandidate::toAronType());
         workingMemory().addCoreSegment("BimanualGraspCandidate",
                                      armarx::grasping::arondto::BimanualGraspCandidate::toAronType());
+        workingMemory().addCoreSegment("KnownGraspCandidate",
+                                     armarx::armem::grasping::arondto::KnownGraspInfo::toAronType());
+
+        knownGraspProviderSegment.init();
     }
 
     void GraspMemory::onConnectComponent()
     {
-
         createRemoteGuiTab();
         RemoteGui_startRunningTask();
-
     }
 
     void GraspMemory::onDisconnectComponent()
@@ -75,13 +81,10 @@ namespace armarx::armem::server::grasp
 
 
     // REMOTE GUI
-
     void GraspMemory::createRemoteGuiTab()
     {
         using namespace armarx::RemoteGui::Client;
-
         {
-
             tab.memoryGroup = armem::server::MemoryRemoteGui().makeGroupBox(workingMemory());
         }
 
diff --git a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
index 7e83132236f7478cf9570747a6c0e83add0e1fab..ea7dceaddd3af6671ac35b151e3bc803222d65ca 100644
--- a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
+++ b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
@@ -9,6 +9,8 @@
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 #include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h>
 
+#include <RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.h>
+
 namespace armarx::armem::server::grasp
 {
     /**
@@ -30,6 +32,8 @@ namespace armarx::armem::server::grasp
     {
     public:
 
+        GraspMemory();
+
         /// @see armarx::ManagedIceObject::getDefaultName()
         std::string getDefaultName() const override;
 
@@ -57,10 +61,10 @@ namespace armarx::armem::server::grasp
 
         DebugObserverInterfacePrx debugObserver;
 
-
         std::string memoryName = "Grasp";
 
-
+        // segments
+        armem::grasping::segment::KnownGraspProviderSegment knownGraspProviderSegment;
 
         struct RemoteGuiTab : RemoteGui::Client::Tab
         {
diff --git a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
index 6cc5b6a88cc2e6540aa11067ef6addd3b2d6d4ef..0aef2635f6cec7714f654a3437fc95268e0f6963 100644
--- a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
+++ b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp
@@ -119,10 +119,10 @@ namespace armarx::armem::server::robot_state
             includePaths.insert(includePaths.end(), projectIncludePaths.begin(), projectIncludePaths.end());
         }
 
-	if (robotUnit.waitForRobotUnit)
-	{
-		usingProxy(robotUnit.plugin->getRobotUnitName());
-	}
+        if (robotUnit.waitForRobotUnit)
+        {
+            usingProxy(robotUnit.plugin->getRobotUnitName());
+        }
     }
 
 
diff --git a/source/RobotAPI/components/skills/SkillProviderExample/CMakeLists.txt b/source/RobotAPI/components/skills/SkillProviderExample/CMakeLists.txt
index f3215ba1d02972ba2ce76353b681017601f71881..ee1ea4e51bb0156822513f8481cc13338cc79b62 100644
--- a/source/RobotAPI/components/skills/SkillProviderExample/CMakeLists.txt
+++ b/source/RobotAPI/components/skills/SkillProviderExample/CMakeLists.txt
@@ -21,5 +21,12 @@ set(HEADERS
 
 armarx_add_component("${SOURCES}" "${HEADERS}")
 
+armarx_enable_aron_file_generation_for_target(
+    TARGET_NAME
+        ${ARMARX_COMPONENT_NAME}
+    ARON_FILES
+        aron/HelloWorldAcceptedType.xml
+)
+
 #generate the application
 armarx_generate_and_add_component_executable(COMPONENT_NAMESPACE "armarx::skills::provider")
diff --git a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
index 804b8d68002b2c43b8423015f466900e5ccb29eb..485a5e07d83fd42776d0f959186b4b4c764b1bf5 100644
--- a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
+++ b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.cpp
@@ -6,9 +6,20 @@
 #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
 {
-    Skill::Status HelloWorldSkill::execute(const aron::data::DictPtr& d, const CallbackT&)
+    HelloWorldSkill::HelloWorldSkill() :
+        Skill(SkillDescription{
+            "HelloWorld",
+            "This skill logs a message on ARMARX_IMPORTANT",
+            {},
+            1000,
+            armarx::skills::Example::HelloWorldAcceptedType::toAronType()
+        })
+    {}
+    Skill::Status HelloWorldSkill::_execute(const aron::data::DictPtr& d, const CallbackT&)
     {
         ARMARX_IMPORTANT << "Hi, from the Hello World Skill.\n" <<
                             "I received the following data: \n" <<
@@ -17,7 +28,16 @@ namespace armarx::skills::provider
         return Skill::Status::Succeeded;
     }
 
-    Skill::Status TimeoutSkill::execute(const aron::data::DictPtr& d, const CallbackT&)
+    TimeoutSkill::TimeoutSkill() :
+        Skill(SkillDescription{
+            "Timeout",
+            "This fails with timeout reached",
+            {},
+            1000,
+            nullptr
+        })
+    {}
+    Skill::Status TimeoutSkill::_execute(const aron::data::DictPtr& d, const CallbackT&)
     {
         int i = 0;
         while (!timeoutReached)
@@ -26,12 +46,25 @@ namespace armarx::skills::provider
             std::this_thread::sleep_for(std::chrono::milliseconds(200));
 
             // check if work is done
-            if(i++ > 15) return Skill::Status::Succeeded;
+            if(i++ > 15)
+            {
+                ARMARX_IMPORTANT << "Somehow the timeout check succeceded....";
+                return Skill::Status::Succeeded;
+            }
         }
         return Skill::Status::TimeoutReached;
     }
 
-    Skill::Status CallbackSkill::execute(const aron::data::DictPtr& d, const CallbackT& callback)
+    CallbackSkill::CallbackSkill() :
+        Skill(SkillDescription{
+            "ShowMeCallbacks",
+            "This skill does shows callbacks",
+            {},
+            1000,
+            nullptr
+        })
+    {}
+    Skill::Status CallbackSkill::_execute(const aron::data::DictPtr& d, const CallbackT& callback)
     {
         ARMARX_IMPORTANT << "Logging three updates via the callback";
         auto up1 = std::make_shared<aron::data::Dict>();
@@ -68,21 +101,7 @@ namespace armarx::skills::provider
     void SkillProviderExample::onInitComponent()
     {
         // Add example skill
-        {
-            auto helloWorldAcceptedType = std::make_shared<aron::type::Object>("helloWorldAcceptedType");
-            auto helloWorldAcceptedTypeText = std::make_shared<aron::type::String>(aron::Path({"text"}));
-            helloWorldAcceptedType->addMemberType("text", helloWorldAcceptedTypeText);
-
-            auto helloWorldAcceptedTypeInt = std::make_shared<aron::type::Int>(aron::Path({"int"}));
-            helloWorldAcceptedType->addMemberType("int", helloWorldAcceptedTypeInt);
-
-            skills::SkillDescription helloWorldDesc;
-            helloWorldDesc.description = "This skill logs a message on ARMARX_IMPORTANT";
-            helloWorldDesc.skillName = "HelloWorld";
-            helloWorldDesc.acceptedType = helloWorldAcceptedType;
-            helloWorldDesc.timeoutMs = 1000;
-            addSkill(std::make_shared<HelloWorldSkill>(), helloWorldDesc);
-        }
+        addSkill(std::make_shared<HelloWorldSkill>());
 
         // Add another lambda example skill
         {
@@ -95,24 +114,10 @@ namespace armarx::skills::provider
         }
 
         // Add another example skill
-        {
-            skills::SkillDescription cbDesc;
-            cbDesc.acceptedType = nullptr; // accept everything
-            cbDesc.description = "This skill does shows callbacks.";
-            cbDesc.skillName = "ShowMeCallbacks";
-            cbDesc.timeoutMs = 1000;
-            addSkill(std::make_shared<CallbackSkill>(), cbDesc);
-        }
+        addSkill(std::make_shared<CallbackSkill>());
 
         // Add timeout skill
-        {
-            skills::SkillDescription tDesc;
-            tDesc.acceptedType = nullptr; // accept everything
-            tDesc.description = "This fails with timeout reached.";
-            tDesc.skillName = "Timeout";
-            tDesc.timeoutMs = 1000;
-            addSkill(std::make_shared<TimeoutSkill>(), tDesc);
-        }
+        addSkill(std::make_shared<TimeoutSkill>());
     }
 
     void SkillProviderExample::onConnectComponent()
@@ -126,5 +131,7 @@ namespace armarx::skills::provider
     }
 
     void SkillProviderExample::onExitComponent()
-    {}
+    {
+
+    }
 }
diff --git a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.h b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.h
index 42ad812f103cd230e0d6bd73c4a1c65a1dded774..2cd96b5ebea1cd9ab860521f1cc48b103ee21fec 100644
--- a/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.h
+++ b/source/RobotAPI/components/skills/SkillProviderExample/SkillProviderExample.h
@@ -35,21 +35,24 @@ namespace armarx::skills::provider
     class HelloWorldSkill : public Skill
     {
     public:
-        Status execute(const aron::data::DictPtr&, const CallbackT&) final;
+        HelloWorldSkill();
+        Status _execute(const aron::data::DictPtr&, const CallbackT&) final;
     };
 
 
     class TimeoutSkill : public Skill
     {
     public:
-        Status execute(const aron::data::DictPtr&, const CallbackT&) final;
+        TimeoutSkill();
+        Status _execute(const aron::data::DictPtr&, const CallbackT&) final;
     };
 
 
     class CallbackSkill : public Skill
     {
     public:
-        Status execute(const aron::data::DictPtr&, const CallbackT&) final;
+        CallbackSkill();
+        Status _execute(const aron::data::DictPtr&, const CallbackT&) final;
     };
 
     /**
diff --git a/source/RobotAPI/components/skills/SkillProviderExample/aron/HelloWorldAcceptedType.xml b/source/RobotAPI/components/skills/SkillProviderExample/aron/HelloWorldAcceptedType.xml
new file mode 100644
index 0000000000000000000000000000000000000000..553a93ad0898ddc40d112e097af9c95ca801da55
--- /dev/null
+++ b/source/RobotAPI/components/skills/SkillProviderExample/aron/HelloWorldAcceptedType.xml
@@ -0,0 +1,17 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <GenerateTypes>
+        <Object name='armarx::skills::Example::HelloWorldAcceptedType'>
+            <ObjectChild key='some_int'>
+                <Int />
+            </ObjectChild>
+            <ObjectChild key='some_float'>
+                <Float />
+            </ObjectChild>
+            <ObjectChild key='some_text'>
+                <String />
+            </ObjectChild>
+        </Object>
+    </GenerateTypes>
+
+</AronTypeDefinition>
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.cpp
deleted file mode 100644
index 0df59db31a93124f7ec5b776fe7e876afe2fb414..0000000000000000000000000000000000000000
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.cpp
+++ /dev/null
@@ -1,349 +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/>.
- *
- * \package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
- * \author     Raphael Grimm ( raphael dot grimm at kit dot edu )
- * \date       2020
- * \copyright  http://www.gnu.org/licenses/gpl-2.0.txt
- *             GNU General Public License
- */
-
-#include <string>
-
-#include <ArmarXCore/util/CPPUtility/Iterator.h>
-
-#include "AronTreeWidgetEditor.h"
-
-// debug
-#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
-
-//visitors
-namespace armarx
-{
-
-    void
-    AronTreeViewWidgetCreatorVisitor::createSimpleTreeViewWidget(Input& i)
-    {
-        ARMARX_CHECK_NOT_NULL(i);
-        ARMARX_CHECK_NOT_NULL(parentItem);
-
-        auto key = i->getPath().getLastElement();
-        createdQWidgetItem = new QTreeWidgetItem(parentItem);
-        createdQWidgetItem->setText(0, QString::fromStdString(key));
-        createdQWidgetItem->setText(2, QString::fromStdString(i->getShortName()));
-        createdQWidgetItem->setText(3, QString::fromStdString(i->getDefaultFromString()));
-        createdQWidgetItem->setFlags(createdQWidgetItem->flags() | Qt::ItemIsEditable);
-    }
-
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
-    {
-        ARMARX_CHECK_NOT_NULL(i);
-        ARMARX_CHECK_NOT_NULL(parentItem);
-
-        auto key = i->getObjectName();
-        if (i->getPath().hasElement())
-        {
-            key = i->getPath().getLastElement();
-        }
-
-        createdQWidgetItem = new QTreeWidgetItem(parentItem);
-        createdQWidgetItem->setText(0, QString::fromStdString(key));
-
-        for (const auto& [key, value] : i->getMemberTypes())
-        {
-            AronTreeViewWidgetCreatorVisitor v(createdQWidgetItem);
-            aron::type::visit(v, value);
-
-            if (v.createdQWidgetItem)
-            {
-                createdQWidgetItem->addChild(v.createdQWidgetItem);
-            }
-        }
-    }
-
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::DictPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::PairPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::TuplePtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::ListPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::NDArrayPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::MatrixPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::QuaternionPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::PositionPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::OrientationPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::PosePtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::ImagePtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::PointCloudPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::IntEnumPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::IntPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::LongPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::FloatPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::DoublePtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::BoolPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::StringPtr& i)
-    { createSimpleTreeViewWidget(i); }
-    void
-    AronTreeViewWidgetCreatorVisitor::visitAronVariant(const aron::type::TimePtr& i)
-    { createSimpleTreeViewWidget(i); }
-
-    void AronTreeViewWidgetCreatorVisitor::visitUnknown(Input&)
-    {
-        ARMARX_WARNING_S << "Received an unknown type when trying to create a tree view widget for a skill argument type.";
-    }
-
-
-
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
-    {
-        auto createdAronDict = std::make_shared<aron::data::Dict>();
-        createdAron = createdAronDict;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        unsigned int x = 0;
-        for (const auto& [key, value] : i->getMemberTypes())
-        {
-            AronTreeViewWidgetConverterVisitor v(el, x++);
-            aron::type::visit(v, value);
-
-            if (v.createdAron)
-            {
-                createdAronDict->addElement(key, v.createdAron);
-            }
-        }
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::DictPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::PairPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::TuplePtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::ListPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::NDArrayPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::MatrixPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::QuaternionPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::PositionPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::OrientationPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::PosePtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::ImagePtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::PointCloudPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::IntEnumPtr& i)
-    {
-        // TODO
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::IntPtr& i)
-    {
-        auto createdAronInt = std::make_shared<aron::data::Int>();
-        createdAron = createdAronInt;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        if (str.empty())
-        {
-            createdAronInt->setValue(0);
-            return;
-        }
-
-        int val = std::stoi(str);
-        createdAronInt->setValue(val);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::LongPtr& i)
-    {
-        auto createdAronLong = std::make_shared<aron::data::Long>();
-        createdAron = createdAronLong;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        if (str.empty())
-        {
-            str = el->text(3).toStdString();
-        }
-
-        createdAronLong->fromString(str);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::FloatPtr& i)
-    {
-        auto createdAronFloat = std::make_shared<aron::data::Float>();
-        createdAron = createdAronFloat;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        if (str.empty())
-        {
-            str = el->text(3).toStdString();
-        }
-
-        createdAronFloat->fromString(str);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::DoublePtr& i)
-    {
-        auto createdAronDouble = std::make_shared<aron::data::Double>();
-        createdAron = createdAronDouble;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        if (str.empty())
-        {
-            str = el->text(3).toStdString();
-        }
-
-        createdAronDouble->fromString(str);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::BoolPtr& i)
-    {
-        auto createdAronBool = std::make_shared<aron::data::Bool>();
-        createdAron = createdAronBool;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        if (str.empty())
-        {
-            str = el->text(3).toStdString();
-        }
-
-        createdAronBool->fromString(str);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::StringPtr& i)
-    {
-        auto createdAronString = std::make_shared<aron::data::String>();
-        createdAron = createdAronString;
-        QTreeWidgetItem* el = parentItem->child(index);
-
-        std::string str = el->text(1).toStdString();
-        createdAronString->fromString(str);
-    }
-
-    void
-    AronTreeViewWidgetConverterVisitor::visitAronVariant(const aron::type::TimePtr& i)
-    {
-        auto l = std::make_shared<aron::type::Long>();
-        visitLong(l);
-    }
-
-    void AronTreeViewWidgetConverterVisitor::visitUnknown(Input&)
-    {
-        ARMARX_WARNING_S << "Received an unknown type when trying to convert a skill argument type to an aron data object.";
-    }
-}
-
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.cpp
deleted file mode 100644
index 25ec39a7056226f53ae8882e60877f1c512d551c..0000000000000000000000000000000000000000
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.cpp
+++ /dev/null
@@ -1,38 +0,0 @@
-#include "AronTreeWidgetInputModalController.h"
-
-namespace armarx
-{
-    AronTreeWidgetInputModalController::AronTreeWidgetInputModalController(const std::string& name, const std::string& placeholder, QWidget * parent) :
-        QDialog(parent),
-        placeholder(placeholder)
-    {
-        widget.setupUi(this);
-
-        // set header
-        widget.groupBoxInput->setTitle(QString::fromStdString(name));
-        widget.textEditInput->setPlainText(QString::fromStdString(placeholder));
-
-        // connect signals
-        connect(widget.pushButtonReset, &QPushButton::clicked,
-                  this, &AronTreeWidgetInputModalController::reset);
-        connect(widget.pushButtonSubmit, &QPushButton::clicked,
-                  this, &AronTreeWidgetInputModalController::submit);
-    }
-
-    QString AronTreeWidgetInputModalController::getInput() const
-    {
-        return widget.textEditInput->toPlainText();
-    }
-
-
-    void AronTreeWidgetInputModalController::reset()
-    {
-        // reset to initial value
-        widget.textEditInput->setPlainText(QString::fromStdString(placeholder));
-    }
-
-    void AronTreeWidgetInputModalController::submit()
-    {
-        accept();
-    }
-}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.h
deleted file mode 100644
index 1f4a0d0f93f4cc1cece3468070dd1e3721633473..0000000000000000000000000000000000000000
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModalController.h
+++ /dev/null
@@ -1,34 +0,0 @@
-#pragma once
-
-#include <stack>
-#include <ArmarXCore/core/system/ImportExportComponent.h>
-
-#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
-#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
-#include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
-
-#include <RobotAPI/gui-plugins/SkillManagerPlugin/ui_AronTreeWidgetInputModal.h>
-
-#include <QDialog>
-
-namespace armarx
-{
-    class ARMARXCOMPONENT_IMPORT_EXPORT
-        AronTreeWidgetInputModalController :
-        public QDialog
-    {
-        Q_OBJECT
-    public:
-        AronTreeWidgetInputModalController(const std::string& label, const std::string& placeholder = "", QWidget * parent = 0);
-
-        QString getInput() const;
-
-    private slots:
-        void reset();
-        void submit();
-
-    private:
-        std::string placeholder;
-        Ui::AronTreeWidgetInputModalWidget widget;
-    };
-}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/CMakeLists.txt b/source/RobotAPI/gui-plugins/SkillManagerPlugin/CMakeLists.txt
index b23252198252a9799bc69de20581a675057cf26e..749a9e26330f60a2ffaee4ae251a65495887f771 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/CMakeLists.txt
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/CMakeLists.txt
@@ -5,18 +5,36 @@ armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
 
 # do not rename this variable, it is used in armarx_gui_library()...
 set(SOURCES
-    AronTreeWidgetEditor.cpp
-    AronTreeWidgetInputModalController.cpp
+    aronTreeWidget/visitors/AronTreeWidgetCreator.cpp
+    aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
+    aronTreeWidget/visitors/AronTreeWidgetModalCreator.cpp
+    aronTreeWidget/Data.cpp
+    aronTreeWidget/AronTreeWidgetItem.cpp
+    aronTreeWidget/AronTreeWidgetController.cpp
+    aronTreeWidget/modal/AronTreeWidgetModal.cpp
+    aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.cpp
+    aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.cpp
     SkillManagerMonitorWidgetController.cpp
 )
 
 set(HEADERS
-    AronTreeWidgetEditor.h
-    AronTreeWidgetInputModalController.h
+    aronTreeWidget/visitors/AronTreeWidgetCreator.h
+    aronTreeWidget/visitors/AronTreeWidgetConverter.h
+    aronTreeWidget/visitors/AronTreeWidgetModalCreator.h
+    aronTreeWidget/Data.h
+    aronTreeWidget/AronTreeWidgetItem.h
+    aronTreeWidget/AronTreeWidgetController.h
+    aronTreeWidget/modal/AronTreeWidgetModal.h
+    aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.h
+    aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.h
     SkillManagerMonitorWidgetController.h
 )
 
-set(GUI_UIS SkillManagerMonitorWidget.ui AronTreeWidgetInputModal.ui)
+set(GUI_UIS
+    SkillManagerMonitorWidget.ui
+    aronTreeWidget/modal/text/AronTreeWidgetTextInputModal.ui
+    aronTreeWidget/modal/dict/AronTreeWidgetDictInputModal.ui
+)
 
 # Add more libraries you depend on here, e.g. ${QT_LIBRARIES}.
 set(COMPONENT_LIBS RobotAPIInterfaces aron skills aronjsonconverter SimpleConfigDialog)
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidget.ui b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidget.ui
index 927d6daf0431c4988ab05bb62171910aac25dbe8..15678facbdf134eb61542300528e6aa3290a0dc9 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidget.ui
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidget.ui
@@ -24,14 +24,14 @@
        <string>Manager</string>
       </property>
       <layout class="QGridLayout" name="gridLayout">
-       <item row="0" column="0">
-        <widget class="QPushButton" name="pushButtonRefreshProvidedSkills">
+       <item row="2" column="0">
+        <widget class="QLabel" name="label">
          <property name="text">
-          <string>Refresh</string>
+          <string>Update Frequency:</string>
          </property>
         </widget>
        </item>
-       <item row="1" column="0">
+       <item row="3" column="0" colspan="3">
         <widget class="QTreeWidget" name="treeWidgetSkills">
          <column>
           <property name="text">
@@ -50,6 +50,9 @@
          </column>
         </widget>
        </item>
+       <item row="2" column="1">
+        <widget class="QDoubleSpinBox" name="doubleSpinBoxUpdateFreq"/>
+       </item>
       </layout>
      </widget>
      <widget class="QGroupBox" name="groupBoxSkillDetails">
@@ -57,21 +60,28 @@
        <string>Skill Details</string>
       </property>
       <layout class="QGridLayout" name="gridLayout_2">
-       <item row="5" column="0">
+       <item row="0" column="0">
+        <widget class="QPushButton" name="pushButtonPaste">
+         <property name="text">
+          <string>Set from clipboard</string>
+         </property>
+        </widget>
+       </item>
+       <item row="6" column="0">
         <widget class="QPushButton" name="pushButtonStopSkill">
          <property name="text">
           <string>Stop</string>
          </property>
         </widget>
        </item>
-       <item row="1" column="0">
-        <widget class="QPushButton" name="pushButtonExecuteSkill">
+       <item row="0" column="1">
+        <widget class="QPushButton" name="pushButtonCopy">
          <property name="text">
-          <string>Execute</string>
+          <string>Copy args to clipboard</string>
          </property>
         </widget>
        </item>
-       <item row="0" column="0">
+       <item row="1" column="0" colspan="2">
         <widget class="QTreeWidget" name="treeWidgetSkillDetails">
          <column>
           <property name="text">
@@ -95,6 +105,13 @@
          </column>
         </widget>
        </item>
+       <item row="6" column="1">
+        <widget class="QPushButton" name="pushButtonExecuteSkill">
+         <property name="text">
+          <string>Execute</string>
+         </property>
+        </widget>
+       </item>
       </layout>
      </widget>
     </widget>
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
index 720304e622303a74a0390c17297b0ec4a17dd91c..4a458d690633e611e64a4402238ec6793ae388d6 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.cpp
@@ -26,12 +26,21 @@
 
 #include "SkillManagerMonitorWidgetController.h"
 
-#include "AronTreeWidgetEditor.h"
-#include "AronTreeWidgetInputModalController.h"
+#include "aronTreeWidget/visitors/AronTreeWidgetCreator.h"
+#include "aronTreeWidget/visitors/AronTreeWidgetConverter.h"
+#include "aronTreeWidget/visitors/AronTreeWidgetModalCreator.h"
+
+// modals
+#include "aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.h"
 
 // debug
 #include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
 
+#include <QDoubleSpinBox>
+#include <QClipboard>
+
+#include "aronTreeWidget/Data.h"
+
 //config
 namespace armarx
 {
@@ -64,9 +73,27 @@ namespace armarx
     SkillManagerMonitorWidgetController::SkillManagerMonitorWidgetController()
     {
         widget.setupUi(getWidget());
-        connect(widget.pushButtonRefreshProvidedSkills, &QPushButton::clicked,
+
+        widget.doubleSpinBoxUpdateFreq->setValue(5.0);
+        widget.doubleSpinBoxUpdateFreq->setMinimum(0);
+        widget.doubleSpinBoxUpdateFreq->setMaximum(100);
+        widget.doubleSpinBoxUpdateFreq->setSingleStep(0.5);
+        widget.doubleSpinBoxUpdateFreq->setSuffix(" Hz");
+
+        refreshSkillsResultTimer = new QTimer(this);
+        refreshSkillsResultTimer->setInterval(1000 / 5);  // Keep this stable.
+        refreshSkillsResultTimer->start();
+
+        connect(widget.doubleSpinBoxUpdateFreq, &QDoubleSpinBox::editingFinished,
+                this, &SkillManagerMonitorWidgetController::updateTimerFrequency);
+        connect(refreshSkillsResultTimer, &QTimer::timeout,
                 this, &SkillManagerMonitorWidgetController::refreshSkills);
 
+        connect(widget.pushButtonCopy, &QPushButton::clicked,
+                this, &SkillManagerMonitorWidgetController::copyCurrentConfig);
+        connect(widget.pushButtonPaste, &QPushButton::clicked,
+                this, &SkillManagerMonitorWidgetController::pasteCurrentConfig);
+
         connect(widget.pushButtonExecuteSkill, &QPushButton::clicked,
                 this, &SkillManagerMonitorWidgetController::executeSkill);
         connect(widget.pushButtonStopSkill, &QPushButton::clicked,
@@ -91,14 +118,19 @@ namespace armarx
 
 
     void SkillManagerMonitorWidgetController::onConnectComponent()
-    { getProxy(manager, observerName);
+    {
+        getProxy(manager, observerName);
         widget.groupBoxSkills->setTitle(QString::fromStdString(observerName));
         widget.treeWidgetSkillDetails->setEditTriggers(QAbstractItemView::EditTrigger::NoEditTriggers);
         widget.treeWidgetSkillDetails->setColumnHidden(3, true);
+
+        connected = true;
     }
 
     void SkillManagerMonitorWidgetController::onDisconnectComponent()
     {
+        connected = false;
+
         // reset all
         skills.clear();
         widget.treeWidgetSkills->clear();
@@ -108,29 +140,73 @@ namespace armarx
         selectedSkill.skillName = "";
     }
 
+    void SkillManagerMonitorWidgetController::updateTimerFrequency()
+    {
+        int f = static_cast<int>(std::round(1000 / widget.doubleSpinBoxUpdateFreq->value()));
+        refreshSkillsResultTimer->setInterval(f);
+    }
+
     void SkillManagerMonitorWidgetController::refreshSkills()
     {
-        // get all skills
-        skills.clear();
-        for (const auto& [providerName, provider] : manager->getSkillProviders())
+        if (!connected)
+            return;
+
+        // remove non-existing ones
+        auto managerSkills = manager->getSkillProviders();
+        std::vector<std::string> removedProviders;
+        for (auto it = skills.begin(); it != skills.end();)
         {
-            SkillProviderData providerData;
-            providerData.providerName = providerName;
-            providerData.skillDescriptions = provider->getSkills();
-            skills.insert(std::make_pair(providerName, providerData));
+            // TODO: iterate over skills, not just over providers!
+            std::string providerName = it->first;
+            if (managerSkills.find(providerName) == managerSkills.end())
+            {
+                removedProviders.push_back(providerName);
+                it = skills.erase(it);
+            }
+            else
+            {
+                it++;
+            }
         }
 
-        // put skills into tree view
-        widget.treeWidgetSkills->clear();
+        // add new ones
+        std::vector<std::string> newProviders;
+        for (const auto& [providerName, provider] : managerSkills)
+        {
+            if (skills.find(providerName) == skills.end())
+            {
+                SkillProviderData providerData;
+                providerData.providerName = providerName;
+                providerData.skillDescriptions = provider->getSkills();
+                skills.insert(std::make_pair(providerName, providerData));
+
+                newProviders.push_back(providerName);
+            }
+        }
+
+        // remove providers from tree
+        for (int i = 0; i < widget.treeWidgetSkills->topLevelItemCount(); ++i)
+        {
+            QTreeWidgetItem* item = widget.treeWidgetSkills->topLevelItem(i);
+            if (std::find(removedProviders.begin(), removedProviders.end(), item->text(0).toStdString()) != removedProviders.end())
+            {
+                delete widget.treeWidgetSkills->takeTopLevelItem(i);
+            }
+        }
+
+        // add new providers
         for (const auto& [providerName, provider] : skills)
         {
-            auto it = new QTreeWidgetItem(widget.treeWidgetSkills);
-            it->setText(0, QString::fromStdString(providerName));
-            for (const auto& [name, sk] : provider.skillDescriptions)
+            if (std::find(newProviders.begin(), newProviders.end(), providerName) != newProviders.end())
             {
-                auto itsk = new QTreeWidgetItem(it);
-                it->addChild(itsk);
-                itsk->setText(0, QString::fromStdString(name));
+                auto it = new QTreeWidgetItem(widget.treeWidgetSkills);
+                it->setText(0, QString::fromStdString(providerName));
+                for (const auto& [name, sk] : provider.skillDescriptions)
+                {
+                    auto itsk = new QTreeWidgetItem(it);
+                    it->addChild(itsk);
+                    itsk->setText(0, QString::fromStdString(name));
+                }
             }
         }
     }
@@ -148,22 +224,12 @@ namespace armarx
             return;
         }
 
-        const auto& skillDescription = prv.skillDescriptions.at(selectedSkill.skillName);
+        auto data = getConfigAsAron();
+
         skills::manager::dto::SkillExecutionInfo exInfo;
         exInfo.providerName = selectedSkill.providerName;
         exInfo.skillName = selectedSkill.skillName;
-
-        // create argument aron (if there is an accepted type set)
-        if (skillsArgumentsTreeWidgetItem)
-        {
-            auto aron_accepted_type = std::make_shared<aron::type::Object>(*skillDescription.acceptedType);
-
-            AronTreeViewWidgetConverterVisitor v(skillsArgumentsTreeWidgetItem, 0);
-            aron::type::visit(v, aron_accepted_type);
-
-            auto aron_args = aron::data::Dict::DynamicCastAndCheck(v.createdAron);
-            exInfo.params = aron_args->toAronDictPtr();
-        }
+        exInfo.params = aron::data::Dict::ToAronDictDTO(data);
 
         ARMARX_INFO << "Executing skill from GUI: " << selectedSkill.providerName << "/" << selectedSkill.skillName;
         manager->executeSkill(exInfo);
@@ -221,6 +287,7 @@ namespace armarx
 
         // setup table view
         widget.treeWidgetSkillDetails->clear();
+        aronTreeWidgetController = nullptr;
         skillsArgumentsTreeWidgetItem = nullptr;
 
         auto skillDesc = skills.at(selectedSkill.providerName).skillDescriptions.at(selectedSkill.skillName);
@@ -256,13 +323,7 @@ namespace armarx
             skillsArgumentsTreeWidgetItem = new QTreeWidgetItem(widget.treeWidgetSkillDetails,
                                           {QString::fromStdString("Arguments")});
 
-            AronTreeViewWidgetCreatorVisitor v(skillsArgumentsTreeWidgetItem);
-            aron::type::visit(v, aron_args);
-
-            if (v.createdQWidgetItem)
-            {
-                skillsArgumentsTreeWidgetItem->addChild(v.createdQWidgetItem);
-            }
+            aronTreeWidgetController = std::make_shared<AronTreeWidgetController>(widget.treeWidgetSkillDetails, skillsArgumentsTreeWidgetItem, aron_args);
         }
         else
         {
@@ -271,24 +332,64 @@ namespace armarx
         }
     }
 
-    void SkillManagerMonitorWidgetController::onTreeWidgetItemDoubleClicked(QTreeWidgetItem * item, int column)
+    aron::data::DictPtr SkillManagerMonitorWidgetController::getConfigAsAron() const
+    {
+        // create argument aron (if there is an accepted type set)
+        if (aronTreeWidgetController)
+        {
+            return aronTreeWidgetController->convertToAron();
+        }
+        return nullptr;
+    }
+
+    void SkillManagerMonitorWidgetController::copyCurrentConfig()
+    {
+        auto data = getConfigAsAron();
+        if (!data)
+        {
+            return;
+        }
+
+        auto json = aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(data);
+        QClipboard* clipboard = QApplication::clipboard();
+        clipboard->setText(QString::fromStdString(json.dump(2)));
+    }
+
+    void SkillManagerMonitorWidgetController::pasteCurrentConfig()
+    {
+        QClipboard* clipboard = QApplication::clipboard();
+        std::string s = clipboard->text().toStdString();
+        nlohmann::json json = nlohmann::json::parse(s);
+        auto data = aron::converter::AronNlohmannJSONConverter::ConvertFromNlohmannJSONObject(json);
+
+        if (!aronTreeWidgetController)
+        {
+            return;
+        }
+
+        aronTreeWidgetController->setFromAron(data);
+    }
+
+    void SkillManagerMonitorWidgetController::onTreeWidgetItemDoubleClicked(QTreeWidgetItem* item, int column)
     {
+        if (!item)
+        {
+            return;
+        }
+
         if (column == 1)
         {
             if (item->flags() & Qt::ItemIsEditable) // we use the flag to indicate whether the item is editable or not
             {
-                std::string name = item->text(0).toStdString();
-                std::string placeholder = item->text(1).toStdString();
-                if (placeholder.empty())
-                {
-                    placeholder = item->text(3).toStdString();
-                    ARMARX_IMPORTANT << "Setting placeholder to " << placeholder;
-                }
-
-                auto modal = AronTreeWidgetInputModalController(name, placeholder, getWidget());
-                modal.exec();
-
-                item->setText(1, modal.getInput());
+                // we assume its aron item
+                AronTreeWidgetItem* aItem = AronTreeWidgetItem::DynamicCastAndCheck(item);
+                std::string name = aItem->text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME).toStdString();
+                std::string type = aItem->text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_TYPE).toStdString();
+
+                AronTreeWidgetModalCreatorVisitor v(name, aItem, widget.treeWidgetSkillDetails);
+                aron::type::visit(v, aItem->aronType);
+                auto modal = v.createdModal;
+                modal->exec();
             }
         }
     }
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.h
index ae65fcbcbfac3b839163244015174d3bfdbb2e59..9ba0d8a378411a688f650012ec96d55525a164c2 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.h
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/SkillManagerMonitorWidgetController.h
@@ -32,11 +32,14 @@
 
 #include <RobotAPI/gui-plugins/SkillManagerPlugin/ui_SkillManagerMonitorWidget.h>
 
+#include "aronTreeWidget/AronTreeWidgetController.h"
 
 #include <RobotAPI/libraries/aron/core/type/variant/All.h>
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 #include <RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h>
 
+#include <QTimer>
+
 namespace armarx
 {
     class ARMARXCOMPONENT_IMPORT_EXPORT
@@ -76,10 +79,17 @@ namespace armarx
         void stopSkill();
         void executeSkill();
 
+        void updateTimerFrequency();
         void refreshSkills();
 
+        void copyCurrentConfig();
+        void pasteCurrentConfig();
+
         void onTreeWidgetItemDoubleClicked(QTreeWidgetItem * item, int column);
 
+    private:
+        aron::data::DictPtr getConfigAsAron() const;
+
     private:
         /**
          * Widget Form
@@ -110,6 +120,11 @@ namespace armarx
 
         // Helper to get the treeWidgetItem easily
         QTreeWidgetItem* skillsArgumentsTreeWidgetItem = nullptr;
+        AronTreeWidgetControllerPtr aronTreeWidgetController = nullptr;
+
+        // others
+        std::atomic_bool connected = false;
+        QTimer* refreshSkillsResultTimer;
     };
 }
 
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..1eeaf00ff53e332fb43999311fdf8e4b11ea7d5e
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.cpp
@@ -0,0 +1,38 @@
+#include "AronTreeWidgetController.h"
+
+#include "visitors/AronTreeWidgetConverter.h"
+
+namespace armarx
+{
+    AronTreeWidgetController::AronTreeWidgetController(QTreeWidget* tree, QTreeWidgetItem* parent, const aron::type::ObjectPtr& type):
+        parent(parent),
+        tree(tree),
+        type(type)
+    {
+        AronTreeWidgetCreatorVisitor v;
+        aron::type::visit(v, type);
+
+        if (v.createdQWidgetItem)
+        {
+            parent->addChild(v.createdQWidgetItem);
+        }
+    }
+
+    aron::data::DictPtr AronTreeWidgetController::convertToAron() const
+    {
+        if (parent)
+        {
+            AronTreeWidgetConverterVisitor v(parent, 0);
+            aron::type::visit(v, type);
+
+            auto aron_args = aron::data::Dict::DynamicCastAndCheck(v.createdAron);
+            return aron_args;
+        }
+        return nullptr;
+    }
+
+    void AronTreeWidgetController::setFromAron(const aron::data::DictPtr&)
+    {
+
+    }
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.h
new file mode 100644
index 0000000000000000000000000000000000000000..4e73deb0592b30548bd72011ace95d29db070edf
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetController.h
@@ -0,0 +1,34 @@
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include "Data.h"
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+
+#include <QTreeWidget>
+#include "visitors/AronTreeWidgetCreator.h"
+#include "AronTreeWidgetItem.h"
+
+namespace armarx
+{
+    class AronTreeWidgetController
+    {
+
+    public:
+        AronTreeWidgetController(QTreeWidget* tree, QTreeWidgetItem* parent, const aron::type::ObjectPtr& type);
+
+        aron::data::DictPtr convertToAron() const;
+        void setFromAron(const aron::data::DictPtr&);
+
+    private:
+        QTreeWidgetItem* parent;
+        QTreeWidget* tree;
+
+        aron::type::ObjectPtr type;
+    };
+
+    using AronTreeWidgetControllerPtr = std::shared_ptr<AronTreeWidgetController>;
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e53161bb8b2ee4aee0c34ac2fc82c3214894f0cd
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.cpp
@@ -0,0 +1,28 @@
+#include "AronTreeWidgetItem.h"
+
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+
+namespace armarx
+{
+    AronTreeWidgetItem* AronTreeWidgetItem::DynamicCast(QTreeWidgetItem* i)
+    {
+        return dynamic_cast<AronTreeWidgetItem*>(i);
+    }
+
+    AronTreeWidgetItem* AronTreeWidgetItem::copy()
+    {
+        AronTreeWidgetItem* ret = new AronTreeWidgetItem(*this);
+        return ret;
+    }
+
+    AronTreeWidgetItem* AronTreeWidgetItem::DynamicCastAndCheck(QTreeWidgetItem* i)
+    {
+        if (!i)
+        {
+            return nullptr;
+        }
+        auto c = DynamicCast(i);
+        ARMARX_CHECK_NOT_NULL(c);
+        return c;
+    }
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..3d6d0c2a329c5a4376fb24a406dadf706d6b898b
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/AronTreeWidgetItem.h
@@ -0,0 +1,39 @@
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include "Data.h"
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+
+#include <RobotAPI/libraries/aron/core/type/variant/Variant.h>
+
+#include <QTreeWidget>
+
+namespace armarx
+{
+    class AronTreeWidgetItem : public QObject, public QTreeWidgetItem
+    {
+        Q_OBJECT
+    public:
+        AronTreeWidgetItem(const AronTreeWidgetItem& other) :
+            QObject(),
+            QTreeWidgetItem(other)
+        {
+            aronType = other.aronType;
+        }
+
+        using QTreeWidgetItem::QTreeWidgetItem;
+
+        AronTreeWidgetItem* copy(); // differs from clone!!!!
+
+        static AronTreeWidgetItem* DynamicCast(QTreeWidgetItem*);
+
+        static AronTreeWidgetItem* DynamicCastAndCheck(QTreeWidgetItem*);
+
+        aron::type::VariantPtr aronType;
+
+    };
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..48b5816e7be127db579245f1044e4dd35aef4d77
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.cpp
@@ -0,0 +1,6 @@
+#include "Data.h"
+
+namespace armarx
+{
+
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.h
new file mode 100644
index 0000000000000000000000000000000000000000..3fea187d34f34cfcffa79a12ead1af3e5d97a55d
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/Data.h
@@ -0,0 +1,13 @@
+#pragma once
+
+#include <string>
+
+namespace armarx::aron_tree_widget::constantes
+{
+    const int TREE_WIDGET_ITEM_NAME = 0;
+    const int TREE_WIDGET_ITEM_VALUE = 1;
+    const int TREE_WIDGET_ITEM_TYPE = 2;
+
+    const std::string ITEM_EMPTY_MESSAGE = "(double click to edit)";
+    const std::string NEW_ITEM_DEFAULT_MESSAGE = "(Please set via main GUI (not in modal))";
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8fbd9c5ba1abdb5e2d2175b1ff545579034c7376
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.cpp
@@ -0,0 +1,20 @@
+#include "AronTreeWidgetModal.h"
+
+namespace armarx
+{
+    AronTreeWidgetModal::AronTreeWidgetModal(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent) :
+        QDialog(parent),
+        item(item),
+        label(label),
+        parent(parent)
+    {
+        init.aronType = item->aronType;
+        init.setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME, item->text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME));
+        init.setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE, item->text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE));
+        init.setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_TYPE, item->text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_TYPE));
+        for (int i = 0; i < item->childCount(); ++i)
+        {
+            init.addChild(item->child(i)->clone());
+        }
+    }
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.h
new file mode 100644
index 0000000000000000000000000000000000000000..cda9f7e728df6da713fb1e09001bc37e8502b9e6
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/AronTreeWidgetModal.h
@@ -0,0 +1,57 @@
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include "../AronTreeWidgetItem.h"
+#include "../Data.h"
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+
+#include <QDialog>
+#include <QTreeWidget>
+
+namespace armarx
+{
+    class AronTreeWidgetModal  :
+            public QDialog
+    {
+        Q_OBJECT
+
+    public:
+        AronTreeWidgetModal(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent);
+
+    protected slots:
+        virtual void reset()
+        {
+            item->aronType = init.aronType;
+            item->setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME, init.text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME));
+            item->setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE, init.text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE));
+            item->setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_TYPE, init.text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_TYPE));
+            for (int i = 0; i < item->childCount(); ++i)
+            {
+                item->removeChild(item->child(i));
+            }
+            for (int i = 0; i < init.childCount(); ++i)
+            {
+                item->addChild(init.child(i)->clone());
+            }
+        }
+        virtual void submit()
+        {
+            accept();
+        }
+
+    protected:
+
+        AronTreeWidgetItem init;
+        AronTreeWidgetItem* item;
+
+    private:
+        std::string label;
+        QTreeWidget* parent;
+    };
+
+    using AronTreeWidgetModalControllerPtr = std::shared_ptr<AronTreeWidgetModal>;
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModal.ui b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModal.ui
new file mode 100644
index 0000000000000000000000000000000000000000..b9b800ed26a2b2170b8ab06633e8e795b1957be4
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModal.ui
@@ -0,0 +1,88 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>AronTreeWidgetDictInputModalWidget</class>
+ <widget class="QWidget" name="AronTreeWidgetDictInputModalWidget">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1015</width>
+    <height>498</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>SkillManagerMonitorWidget</string>
+  </property>
+  <layout class="QVBoxLayout" name="verticalLayout">
+   <item>
+    <widget class="QSplitter" name="splitter">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <widget class="QGroupBox" name="groupBoxInput">
+      <property name="title">
+       <string>InputField</string>
+      </property>
+      <layout class="QGridLayout" name="gridLayout">
+       <item row="0" column="0" colspan="5">
+        <widget class="QTreeWidget" name="treeWidgetDict">
+         <column>
+          <property name="text">
+           <string>Key</string>
+          </property>
+         </column>
+         <column>
+          <property name="text">
+           <string>Value</string>
+          </property>
+         </column>
+         <column>
+          <property name="text">
+           <string>Type</string>
+          </property>
+         </column>
+        </widget>
+       </item>
+       <item row="1" column="3" colspan="2">
+        <widget class="QPushButton" name="pushButtonAddElement">
+         <property name="text">
+          <string>+ Add element</string>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="0" colspan="3">
+        <widget class="QLineEdit" name="lineEditKey">
+         <property name="maximumSize">
+          <size>
+           <width>880</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>Enter Key</string>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="0">
+        <widget class="QPushButton" name="pushButtonReset">
+         <property name="text">
+          <string>Reset</string>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="1" colspan="4">
+        <widget class="QPushButton" name="pushButtonSubmit">
+         <property name="text">
+          <string>Submit</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </widget>
+    </widget>
+   </item>
+  </layout>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..f7d83d98b6cde491cad878822b69b50adb34d355
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.cpp
@@ -0,0 +1,73 @@
+#include "AronTreeWidgetDictInputModalController.h"
+
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+#include "../../visitors/AronTreeWidgetCreator.h"
+
+namespace armarx
+{
+    AronTreeWidgetDictInputModalController::AronTreeWidgetDictInputModalController(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent) :
+        AronTreeWidgetModal(label, item, parent)
+    {
+        widget.setupUi(this);
+
+        // set header
+        widget.groupBoxInput->setTitle(QString::fromStdString(label));
+        reset();
+
+        // connect signals
+        connect(widget.pushButtonAddElement, &QPushButton::clicked,
+                this, &AronTreeWidgetDictInputModalController::addEmptyElement);
+
+        connect(widget.pushButtonReset, &QPushButton::clicked,
+                  this, &AronTreeWidgetDictInputModalController::reset);
+        connect(widget.pushButtonSubmit, &QPushButton::clicked,
+                  this, &AronTreeWidgetDictInputModalController::submit);
+
+    }
+
+    void AronTreeWidgetDictInputModalController::submit()
+    {
+        for (const auto& added : addedItems)
+        {
+            item->addChild(added->copy());
+        }
+
+        AronTreeWidgetModal::submit();
+    }
+
+    void AronTreeWidgetDictInputModalController::reset()
+    {
+        AronTreeWidgetModal::reset();
+
+        // reset to initial value
+        widget.treeWidgetDict->clear();
+        for (int i = 0; i < init.childCount(); ++i)
+        {
+            auto el = init.child(i);
+            widget.treeWidgetDict->addTopLevelItem(el->clone());
+        }
+    }
+
+    void AronTreeWidgetDictInputModalController::addEmptyElement()
+    {
+        QString s = widget.lineEditKey->text();
+        widget.lineEditKey->setText("Enter Key");
+
+        if (widget.treeWidgetDict->findItems(s, Qt::MatchFlag::MatchExactly, 0).empty())
+        {
+            auto t = item->aronType;
+            auto d = aron::type::Dict::DynamicCastAndCheck(t);
+            auto ac = d->getAcceptedType();
+
+            AronTreeWidgetCreatorVisitor v;
+            aron::type::visit(v, ac);
+
+            if (v.createdQWidgetItem)
+            {
+                v.createdQWidgetItem->setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_NAME, s);
+                addedItems.push_back(v.createdQWidgetItem);
+                widget.treeWidgetDict->addTopLevelItem(v.createdQWidgetItem);
+            }
+        }
+    }
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.h
new file mode 100644
index 0000000000000000000000000000000000000000..f5d94a04b46994220fb0ff9c81e1fff50a9c3091
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/AronTreeWidgetDictInputModalController.h
@@ -0,0 +1,36 @@
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
+
+#include "../AronTreeWidgetModal.h"
+
+#include <RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/dict/ui_AronTreeWidgetDictInputModal.h>
+
+#include <QDialog>
+
+namespace armarx
+{
+    class AronTreeWidgetDictInputModalController :
+        public AronTreeWidgetModal
+    {
+    public:
+
+        AronTreeWidgetDictInputModalController(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent);
+
+    private slots:
+
+        void submit() final;
+        void reset() final;
+
+        void addEmptyElement();
+
+    private:
+        std::vector<AronTreeWidgetItem*> addedItems;
+        Ui::AronTreeWidgetDictInputModalWidget widget;
+    };
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/others_are_TODO b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/others_are_TODO
new file mode 100644
index 0000000000000000000000000000000000000000..e69de29bb2d1d6434b8b29ae775ad8c2e48c5391
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModal.ui b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModal.ui
similarity index 91%
rename from source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModal.ui
rename to source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModal.ui
index baec62815f1b8b7f2c6b46b7e2f3847130a9509e..ed40962f96639ff34eed30b85331d7774b2eef9d 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetInputModal.ui
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModal.ui
@@ -1,7 +1,7 @@
 <?xml version="1.0" encoding="UTF-8"?>
 <ui version="4.0">
- <class>AronTreeWidgetInputModalWidget</class>
- <widget class="QWidget" name="AronTreeWidgetInputModalWidget">
+ <class>AronTreeWidgetTextInputModalWidget</class>
+ <widget class="QWidget" name="AronTreeWidgetTextInputModalWidget">
   <property name="geometry">
    <rect>
     <x>0</x>
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..972fe6ff98b20e2bfe0970455df1ed760a4c4203
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.cpp
@@ -0,0 +1,35 @@
+#include "AronTreeWidgetTextInputModalController.h"
+
+namespace armarx
+{
+    AronTreeWidgetTextInputModalController::AronTreeWidgetTextInputModalController(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent) :
+        AronTreeWidgetModal(label, item, parent)
+    {
+        widget.setupUi(this);
+
+        // set header
+        widget.groupBoxInput->setTitle(QString::fromStdString(label));
+        reset();
+
+        // connect signals
+        connect(widget.pushButtonReset, &QPushButton::clicked,
+                  this, &AronTreeWidgetTextInputModalController::reset);
+        connect(widget.pushButtonSubmit, &QPushButton::clicked,
+                  this, &AronTreeWidgetTextInputModalController::submit);
+    }
+
+    void AronTreeWidgetTextInputModalController::submit()
+    {
+        item->setText(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE, widget.textEditInput->toPlainText());
+
+        AronTreeWidgetModal::submit();
+    }
+
+    void AronTreeWidgetTextInputModalController::reset()
+    {
+        AronTreeWidgetModal::reset();
+
+        // reset to initial value
+        widget.textEditInput->setPlainText(init.text(aron_tree_widget::constantes::TREE_WIDGET_ITEM_VALUE));
+    }
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.h
new file mode 100644
index 0000000000000000000000000000000000000000..216451f4ad761080357b368744b3c7c1a65e77dc
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/AronTreeWidgetTextInputModalController.h
@@ -0,0 +1,34 @@
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
+
+#include "../AronTreeWidgetModal.h"
+
+#include <RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/modal/text/ui_AronTreeWidgetTextInputModal.h>
+
+#include <QDialog>
+
+namespace armarx
+{
+    class AronTreeWidgetTextInputModalController :
+        public AronTreeWidgetModal
+    {
+
+    public:
+
+        AronTreeWidgetTextInputModalController(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent);
+
+    private slots:
+
+        void submit() final;
+        void reset() final;
+
+    private:
+        Ui::AronTreeWidgetTextInputModalWidget widget;
+    };
+}
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..e9effb321210d3c3201adaa40368a359785a1524
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.cpp
@@ -0,0 +1,252 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * \package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
+ * \author     Raphael Grimm ( raphael dot grimm at kit dot edu )
+ * \date       2020
+ * \copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include <string>
+
+#include <ArmarXCore/util/CPPUtility/Iterator.h>
+
+#include "AronTreeWidgetConverter.h"
+
+// debug
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+//visitors
+namespace armarx
+{
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
+    {
+        auto createdAronDict = std::make_shared<aron::data::Dict>();
+        createdAron = createdAronDict;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        unsigned int x = 0;
+        for (const auto& [key, value] : i->getMemberTypes())
+        {
+            AronTreeWidgetConverterVisitor v(el, x++);
+            aron::type::visit(v, value);
+
+            if (v.createdAron)
+            {
+                createdAronDict->addElement(key, v.createdAron);
+            }
+        }
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::DictPtr& i)
+    {
+        auto createdAronDict = std::make_shared<aron::data::Dict>();
+        createdAron = createdAronDict;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        for (int x = 0; x < el->childCount(); ++x)
+        {
+            auto it = el->child(x);
+            AronTreeWidgetConverterVisitor v(el, x);
+            aron::type::visit(v, i->getAcceptedType());
+
+            if (v.createdAron)
+            {
+                createdAronDict->addElement(it->text(0).toStdString(), v.createdAron);
+            }
+        }
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::PairPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::TuplePtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::ListPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::NDArrayPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::MatrixPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::QuaternionPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::PositionPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::OrientationPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::PosePtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::ImagePtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::PointCloudPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::IntEnumPtr& i)
+    {
+        // TODO
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::IntPtr& i)
+    {
+        auto createdAronInt = std::make_shared<aron::data::Int>();
+        createdAron = createdAronInt;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        if (str.empty())
+        {
+            createdAronInt->setValue(0);
+            return;
+        }
+
+        int val = std::stoi(str);
+        createdAronInt->setValue(val);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::LongPtr& i)
+    {
+        auto createdAronLong = std::make_shared<aron::data::Long>();
+        createdAron = createdAronLong;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        if (str.empty())
+        {
+            str = el->text(3).toStdString();
+        }
+
+        createdAronLong->fromString(str);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::FloatPtr& i)
+    {
+        auto createdAronFloat = std::make_shared<aron::data::Float>();
+        createdAron = createdAronFloat;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        if (str.empty())
+        {
+            str = el->text(3).toStdString();
+        }
+
+        createdAronFloat->fromString(str);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::DoublePtr& i)
+    {
+        auto createdAronDouble = std::make_shared<aron::data::Double>();
+        createdAron = createdAronDouble;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        if (str.empty())
+        {
+            str = el->text(3).toStdString();
+        }
+
+        createdAronDouble->fromString(str);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::BoolPtr& i)
+    {
+        auto createdAronBool = std::make_shared<aron::data::Bool>();
+        createdAron = createdAronBool;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        if (str.empty())
+        {
+            str = el->text(3).toStdString();
+        }
+
+        createdAronBool->fromString(str);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::StringPtr& i)
+    {
+        auto createdAronString = std::make_shared<aron::data::String>();
+        createdAron = createdAronString;
+        QTreeWidgetItem* el = parentItem->child(index);
+
+        std::string str = el->text(1).toStdString();
+        createdAronString->fromString(str);
+    }
+
+    void
+    AronTreeWidgetConverterVisitor::visitAronVariant(const aron::type::TimePtr& i)
+    {
+        auto l = std::make_shared<aron::type::Long>();
+        visitLong(l);
+    }
+
+    void AronTreeWidgetConverterVisitor::visitUnknown(Input&)
+    {
+        ARMARX_WARNING_S << "Received an unknown type when trying to convert a skill argument type to an aron data object.";
+    }
+}
+
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.h
similarity index 60%
rename from source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.h
rename to source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.h
index 3d391783077458df2e9257d40e188cd81bf36188..5021cb5ae473c3212ec3bcde32708940fcb23f9d 100644
--- a/source/RobotAPI/gui-plugins/SkillManagerPlugin/AronTreeWidgetEditor.h
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetConverter.h
@@ -39,48 +39,8 @@
 
 namespace armarx
 {
-    // Convert aron type to tree widget
-    class AronTreeViewWidgetCreatorVisitor :
-            public armarx::aron::type::ConstVariantVisitor
-    {
-    public:
-        QTreeWidgetItem* parentItem;
-        QTreeWidgetItem* createdQWidgetItem;
-
-        AronTreeViewWidgetCreatorVisitor() = delete;
-        AronTreeViewWidgetCreatorVisitor(QTreeWidgetItem* i) :
-            parentItem(i)
-        {}
-
-        void createSimpleTreeViewWidget(Input& i);
-
-        void visitAronVariant(const aron::type::ObjectPtr&) override;
-        void visitAronVariant(const aron::type::DictPtr& i) override;
-        void visitAronVariant(const aron::type::PairPtr& i) override;
-        void visitAronVariant(const aron::type::TuplePtr& i) override;
-        void visitAronVariant(const aron::type::ListPtr& i) override;
-        void visitAronVariant(const aron::type::NDArrayPtr& i) override;
-        void visitAronVariant(const aron::type::MatrixPtr& i) override;
-        void visitAronVariant(const aron::type::QuaternionPtr& i) override;
-        void visitAronVariant(const aron::type::PositionPtr& i) override;
-        void visitAronVariant(const aron::type::OrientationPtr& i) override;
-        void visitAronVariant(const aron::type::PosePtr& i) override;
-        void visitAronVariant(const aron::type::ImagePtr& i) override;
-        void visitAronVariant(const aron::type::PointCloudPtr& i) override;
-        void visitAronVariant(const aron::type::IntEnumPtr& i) override;
-        void visitAronVariant(const aron::type::IntPtr& i) override;
-        void visitAronVariant(const aron::type::LongPtr& i) override;
-        void visitAronVariant(const aron::type::FloatPtr& i) override;
-        void visitAronVariant(const aron::type::DoublePtr& i) override;
-        void visitAronVariant(const aron::type::BoolPtr& i) override;
-        void visitAronVariant(const aron::type::StringPtr& i) override;
-        void visitAronVariant(const aron::type::TimePtr& i) override;
-        void visitUnknown(Input&) override;
-    };
-
-
     // Conversion from TreeView to aron data
-    class AronTreeViewWidgetConverterVisitor :
+    class AronTreeWidgetConverterVisitor :
             public armarx::aron::type::ConstVariantVisitor
     {
     public:
@@ -88,8 +48,8 @@ namespace armarx
         int index;
         aron::data::VariantPtr createdAron;
 
-        AronTreeViewWidgetConverterVisitor() = delete;
-        AronTreeViewWidgetConverterVisitor(QTreeWidgetItem* i, int x) :
+        AronTreeWidgetConverterVisitor() = delete;
+        AronTreeWidgetConverterVisitor(QTreeWidgetItem* i, int x) :
             parentItem(i), index(x)
         {}
 
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..b3a8682081312bc1f3dbc7f036db10dbe40fb5f9
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.cpp
@@ -0,0 +1,144 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * \package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
+ * \author     Raphael Grimm ( raphael dot grimm at kit dot edu )
+ * \date       2020
+ * \copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include <string>
+
+#include <ArmarXCore/util/CPPUtility/Iterator.h>
+
+#include "AronTreeWidgetCreator.h"
+
+// debug
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
+#include "../Data.h"
+
+//visitors
+namespace armarx
+{
+    void
+    AronTreeWidgetCreatorVisitor::createSimpleTreeViewWidget(Input& i, const std::string& defaul)
+    {
+        ARMARX_CHECK_NOT_NULL(i);
+
+        auto key = i->getPath().getLastElement();
+        createdQWidgetItem = new AronTreeWidgetItem();
+        createdQWidgetItem->aronType = i;
+        createdQWidgetItem->setText(0, QString::fromStdString(key));
+        createdQWidgetItem->setText(1, QString::fromStdString(defaul));
+        createdQWidgetItem->setText(2, QString::fromStdString(i->getShortName()));
+        createdQWidgetItem->setText(3, QString::fromStdString(aron_tree_widget::constantes::ITEM_EMPTY_MESSAGE) /*QString::fromStdString(i->getDefaultFromString())*/);
+        createdQWidgetItem->setFlags(createdQWidgetItem->flags() | Qt::ItemIsEditable);
+    }
+
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
+    {
+        ARMARX_CHECK_NOT_NULL(i);
+
+        auto key = i->getObjectName();
+        if (i->getPath().hasElement())
+        {
+            key = i->getPath().getLastElement();
+        }
+
+        createdQWidgetItem = new AronTreeWidgetItem();
+        createdQWidgetItem->setText(0, QString::fromStdString(key));
+
+        for (const auto& [key, value] : i->getMemberTypes())
+        {
+            AronTreeWidgetCreatorVisitor v;
+            aron::type::visit(v, value);
+
+            if (v.createdQWidgetItem)
+            {
+                createdQWidgetItem->addChild(v.createdQWidgetItem);
+            }
+        }
+    }
+
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::DictPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::PairPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::TuplePtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::ListPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::NDArrayPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::MatrixPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::QuaternionPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::PositionPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::OrientationPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::PosePtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::ImagePtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::PointCloudPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::IntEnumPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::IntPtr& i)
+    { createSimpleTreeViewWidget(i, "0"); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::LongPtr& i)
+    { createSimpleTreeViewWidget(i, "0"); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::FloatPtr& i)
+    { createSimpleTreeViewWidget(i, "0.0"); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::DoublePtr& i)
+    { createSimpleTreeViewWidget(i, "0.0"); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::BoolPtr& i)
+    { createSimpleTreeViewWidget(i, "false"); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::StringPtr& i)
+    { createSimpleTreeViewWidget(i, ""); }
+    void
+    AronTreeWidgetCreatorVisitor::visitAronVariant(const aron::type::TimePtr& i)
+    { createSimpleTreeViewWidget(i, "0"); }
+
+    void AronTreeWidgetCreatorVisitor::visitUnknown(Input&)
+    {
+        ARMARX_WARNING_S << "Received an unknown type when trying to create a tree view widget for a skill argument type.";
+    }
+}
+
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.h
new file mode 100644
index 0000000000000000000000000000000000000000..a81d1137df6f29636f790cc5083f744c7b13f1b0
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetCreator.h
@@ -0,0 +1,79 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
+ * @author     Raphael Grimm ( raphael dot grimm at kit dot edu )
+ * @date       2020
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
+
+#include <RobotAPI/interface/skills/SkillMemoryInterface.h>
+
+#include <RobotAPI/gui-plugins/SkillManagerPlugin/ui_SkillManagerMonitorWidget.h>
+
+#include "../AronTreeWidgetItem.h"
+
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h>
+
+namespace armarx
+{
+    // Convert aron type to tree widget
+    class AronTreeWidgetCreatorVisitor :
+            public armarx::aron::type::ConstVariantVisitor
+    {
+    public:
+        AronTreeWidgetItem* createdQWidgetItem;
+
+        AronTreeWidgetCreatorVisitor() = default;
+
+        void createSimpleTreeViewWidget(Input& i, const std::string&);
+
+        void visitAronVariant(const aron::type::ObjectPtr&) override;
+        void visitAronVariant(const aron::type::DictPtr& i) override;
+        void visitAronVariant(const aron::type::PairPtr& i) override;
+        void visitAronVariant(const aron::type::TuplePtr& i) override;
+        void visitAronVariant(const aron::type::ListPtr& i) override;
+        void visitAronVariant(const aron::type::NDArrayPtr& i) override;
+        void visitAronVariant(const aron::type::MatrixPtr& i) override;
+        void visitAronVariant(const aron::type::QuaternionPtr& i) override;
+        void visitAronVariant(const aron::type::PositionPtr& i) override;
+        void visitAronVariant(const aron::type::OrientationPtr& i) override;
+        void visitAronVariant(const aron::type::PosePtr& i) override;
+        void visitAronVariant(const aron::type::ImagePtr& i) override;
+        void visitAronVariant(const aron::type::PointCloudPtr& i) override;
+        void visitAronVariant(const aron::type::IntEnumPtr& i) override;
+        void visitAronVariant(const aron::type::IntPtr& i) override;
+        void visitAronVariant(const aron::type::LongPtr& i) override;
+        void visitAronVariant(const aron::type::FloatPtr& i) override;
+        void visitAronVariant(const aron::type::DoublePtr& i) override;
+        void visitAronVariant(const aron::type::BoolPtr& i) override;
+        void visitAronVariant(const aron::type::StringPtr& i) override;
+        void visitAronVariant(const aron::type::TimePtr& i) override;
+        void visitUnknown(Input&) override;
+    };
+}
+
+
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.cpp b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a2a2240d354758a257a022fa07e211b1d993495b
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.cpp
@@ -0,0 +1,146 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * \package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
+ * \author     Raphael Grimm ( raphael dot grimm at kit dot edu )
+ * \date       2020
+ * \copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#include <string>
+
+#include <ArmarXCore/util/CPPUtility/Iterator.h>
+
+#include "AronTreeWidgetModalCreator.h"
+
+#include <SimoxUtility/algorithm/string.h>
+
+// debug
+#include "../modal/text/AronTreeWidgetTextInputModalController.h"
+#include "../modal/dict/AronTreeWidgetDictInputModalController.h"
+
+//visitors
+namespace armarx
+{
+
+    void AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::ObjectPtr& i)
+    {
+        // should not happen, right?
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::DictPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetDictInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::PairPtr& i)
+    {
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::TuplePtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::ListPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::NDArrayPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::MatrixPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::QuaternionPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::PositionPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::OrientationPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::PosePtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::ImagePtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::PointCloudPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::IntEnumPtr& i)
+    { }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::IntPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::LongPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::FloatPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::DoublePtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::BoolPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::StringPtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void
+    AronTreeWidgetModalCreatorVisitor::visitAronVariant(const aron::type::TimePtr& i)
+    {
+        createdModal = std::make_shared<AronTreeWidgetTextInputModalController>(label, item, parent);
+    }
+
+    void AronTreeWidgetModalCreatorVisitor::visitUnknown(Input&)
+    {
+        ARMARX_WARNING_S << "Received an unknown type when trying to create a tree view widget modal for a skill argument type.";
+    }
+}
+
diff --git a/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.h b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.h
new file mode 100644
index 0000000000000000000000000000000000000000..c1bba0790bb2ddeb00c3d6c166242f324bf74922
--- /dev/null
+++ b/source/RobotAPI/gui-plugins/SkillManagerPlugin/aronTreeWidget/visitors/AronTreeWidgetModalCreator.h
@@ -0,0 +1,87 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI::gui-plugins::SkillManagerMonitorWidgetController
+ * @author     Raphael Grimm ( raphael dot grimm at kit dot edu )
+ * @date       2020
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+#pragma once
+
+#include <stack>
+#include <ArmarXCore/core/system/ImportExportComponent.h>
+
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXGuiPlugin.h>
+#include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
+#include <ArmarXGui/libraries/SimpleConfigDialog/SimpleConfigDialog.h>
+
+#include <RobotAPI/interface/skills/SkillMemoryInterface.h>
+
+#include <RobotAPI/gui-plugins/SkillManagerPlugin/ui_SkillManagerMonitorWidget.h>
+
+#include "../modal/AronTreeWidgetModal.h"
+
+#include <RobotAPI/libraries/aron/core/type/variant/All.h>
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h>
+
+#include <QTreeWidget>
+
+namespace armarx
+{
+    // Convert aron type to tree widget
+    class AronTreeWidgetModalCreatorVisitor :
+            public armarx::aron::type::ConstVariantVisitor
+    {
+    public:
+        std::string label;
+        AronTreeWidgetItem* item;
+        QTreeWidget* parent;
+        AronTreeWidgetModalControllerPtr createdModal;
+
+        AronTreeWidgetModalCreatorVisitor() = delete;
+        AronTreeWidgetModalCreatorVisitor(const std::string& label, AronTreeWidgetItem* item, QTreeWidget* parent) :
+            label(label),
+            item(item),
+            parent(parent)
+        {}
+
+        void visitAronVariant(const aron::type::ObjectPtr&) override;
+        void visitAronVariant(const aron::type::DictPtr& i) override;
+        void visitAronVariant(const aron::type::PairPtr& i) override;
+        void visitAronVariant(const aron::type::TuplePtr& i) override;
+        void visitAronVariant(const aron::type::ListPtr& i) override;
+        void visitAronVariant(const aron::type::NDArrayPtr& i) override;
+        void visitAronVariant(const aron::type::MatrixPtr& i) override;
+        void visitAronVariant(const aron::type::QuaternionPtr& i) override;
+        void visitAronVariant(const aron::type::PositionPtr& i) override;
+        void visitAronVariant(const aron::type::OrientationPtr& i) override;
+        void visitAronVariant(const aron::type::PosePtr& i) override;
+        void visitAronVariant(const aron::type::ImagePtr& i) override;
+        void visitAronVariant(const aron::type::PointCloudPtr& i) override;
+        void visitAronVariant(const aron::type::IntEnumPtr& i) override;
+        void visitAronVariant(const aron::type::IntPtr& i) override;
+        void visitAronVariant(const aron::type::LongPtr& i) override;
+        void visitAronVariant(const aron::type::FloatPtr& i) override;
+        void visitAronVariant(const aron::type::DoublePtr& i) override;
+        void visitAronVariant(const aron::type::BoolPtr& i) override;
+        void visitAronVariant(const aron::type::StringPtr& i) override;
+        void visitAronVariant(const aron::type::TimePtr& i) override;
+        void visitUnknown(Input&) override;
+    };
+}
+
+
diff --git a/source/RobotAPI/libraries/ArmarXObjects/ObjectInfo.h b/source/RobotAPI/libraries/ArmarXObjects/ObjectInfo.h
index ebd0fc51b4ddb660613dd0c5f18aa322c2942795..70fd46b47fb7a8a3c992dfe5d6c3d4676915aed7 100644
--- a/source/RobotAPI/libraries/ArmarXObjects/ObjectInfo.h
+++ b/source/RobotAPI/libraries/ArmarXObjects/ObjectInfo.h
@@ -61,7 +61,6 @@ namespace armarx
 
         void setLogError(bool enabled);
 
-
         std::string package() const;
 
         std::string dataset() const;
@@ -129,9 +128,11 @@ namespace armarx
         virtual bool checkPaths() const;
 
 
+
     private:
 
         path objectDirectory() const;
+
         std::optional<std::vector<std::string>> loadNames(const std::string& jsonKey) const;
 
 
diff --git a/source/RobotAPI/libraries/PriorKnowledge/CMakeLists.txt b/source/RobotAPI/libraries/PriorKnowledge/CMakeLists.txt
index 596f554c1f0ec2689d12cc9776539b0d4fd7377f..7c22f824a7161e844590073789f55b4a3e7f5ef9 100644
--- a/source/RobotAPI/libraries/PriorKnowledge/CMakeLists.txt
+++ b/source/RobotAPI/libraries/PriorKnowledge/CMakeLists.txt
@@ -1,4 +1,5 @@
 add_subdirectory(core)
 add_subdirectory(motions)
+add_subdirectory(objects)
 #add_subdirectory(subjects)
 
diff --git a/source/RobotAPI/libraries/PriorKnowledge/objects/CMakeLists.txt b/source/RobotAPI/libraries/PriorKnowledge/objects/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..cdf52fa7d1aa8dff4eda392dcb0cebdd77ec8f00
--- /dev/null
+++ b/source/RobotAPI/libraries/PriorKnowledge/objects/CMakeLists.txt
@@ -0,0 +1,19 @@
+set(LIB_NAME       ${PROJECT_NAME}PriorKnowledgeObjects)
+
+armarx_component_set_name("${LIB_NAME}")
+armarx_set_target("Library: ${LIB_NAME}")
+
+armarx_add_library(
+    LIBS
+        RobotAPI::Core
+        RobotAPI::Aron::Common
+    SOURCES
+        ObjectFinder.cpp
+    HEADERS
+        ObjectFinder.h
+)
+
+add_library(${PROJECT_NAME}::PriorKnowledge::Objects ALIAS ${PROJECT_NAME}PriorKnowledgeObjects)
+
+# add unit tests
+#add_subdirectory(test)
diff --git a/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.cpp b/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..ed1b6768e170f9416db52ba6f27fe44ac18b8adc
--- /dev/null
+++ b/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.cpp
@@ -0,0 +1,71 @@
+// Simox
+#include <SimoxUtility/algorithm/vector.hpp>
+
+// BaseClass
+#include "ObjectFinder.h"
+
+// ArmarX
+
+namespace armarx::priorknowledge::objects
+{
+    std::vector<ObjectFinderInfo> ObjectFinder::findAll() const
+    {
+        const std::filesystem::path absPath = Base::Base::getFullPath();
+        if (std::filesystem::is_regular_file(absPath))
+        {
+            ARMARX_WARNING << "The entered path is leading to a file!";
+            return {};
+        }
+
+        std::vector<ObjectFinderInfo> ret;
+        for (const auto& d : std::filesystem::directory_iterator(absPath))
+        {
+            if (!d.is_directory())
+            {
+                ARMARX_WARNING << "Found invalid path: " << d.path();
+                continue;
+            }
+            std::string k = d.path().filename();
+            if (simox::alg::contains(DATASET_FOLDERS_BLACKLIST, k))
+            {
+                continue;
+            }
+
+            auto motionsForDataset = this->findAll(k);
+            simox::alg::append(ret, motionsForDataset);
+        }
+        return ret;
+    }
+
+    std::vector<ObjectFinderInfo> ObjectFinder::findAll(const std::string &dataset) const
+    {
+        const std::filesystem::path absPathToDataset = this->getFullPath(dataset);
+        if (std::filesystem::is_regular_file(absPathToDataset))
+        {
+            ARMARX_WARNING << "The entered path is leading to a file!";
+            return {};
+        }
+
+        std::vector<ObjectFinderInfo> ret;
+        for (const auto& d : std::filesystem::directory_iterator(absPathToDataset))
+        {
+            if (!d.is_directory())
+            {
+                ARMARX_WARNING << "Found invalid path: " << d.path();
+                continue;
+            }
+            std::string k = d.path().filename();
+            if (simox::alg::contains(ID_FOLDERS_BLACKLIST, k))
+            {
+                continue;
+            }
+
+            if(auto op = this->find(dataset, k); op.has_value())
+            {
+                ret.emplace_back(op.value());
+            }
+        }
+        return ret;
+    }
+
+}
diff --git a/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.h b/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.h
new file mode 100644
index 0000000000000000000000000000000000000000..a0e5b1820af5a9cafa561273aafabcad099820b3
--- /dev/null
+++ b/source/RobotAPI/libraries/PriorKnowledge/objects/ObjectFinder.h
@@ -0,0 +1,41 @@
+#include <RobotAPI/libraries/PriorKnowledge/core/FinderBase.h>
+#include <RobotAPI/libraries/PriorKnowledge/core/FinderInfoBase.h>
+
+// TODO!!!
+namespace armarx::priorknowledge::objects
+{
+    class ObjectFinderInfo : public core::DatasetFinderInfoBase<std::string, std::string>
+    {
+        using Base = core::DatasetFinderInfoBase<std::string, std::string>;
+
+    public:
+        ObjectFinderInfo(const std::string& packageName,
+                         const std::filesystem::path& absPackageDataDir,
+                         const std::filesystem::path& relPackageDataPath,
+                         const std::filesystem::path& relDatasetPath,
+                         const std::string& dataset,
+                         const std::string& id) :
+            Base(packageName, absPackageDataDir, relPackageDataPath, relDatasetPath, dataset, id)
+        {
+        }
+    };
+
+    class ObjectFinder : public core::DatasetFinderBase<std::string, std::string, ObjectFinderInfo>
+    {
+        using Base = core::DatasetFinderBase<std::string, std::string, ObjectFinderInfo>;
+
+    public:
+        ObjectFinder(const std::string& packageName, const std::filesystem::path& relDir) :
+            Base(packageName, relDir)
+        {}
+
+        std::vector<ObjectFinderInfo> findAll() const;
+
+        std::vector<ObjectFinderInfo> findAll(const std::string& dataset) const;
+
+    private:
+        std::vector<std::string> DATASET_FOLDERS_BLACKLIST = {};
+        std::vector<std::string> ID_FOLDERS_BLACKLIST = {"script"};
+    };
+
+}
diff --git a/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
index d2339f87f009bd35a3b78812555e652884719238..1e19f25a7b08671b1e3f65ea2649f056a107361a 100644
--- a/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
@@ -22,13 +22,13 @@ namespace armarx::armem::base
 
     void detail::toIce(aron::data::dto::DictPtr& ice, const aron::data::DictPtr& data)
     {
-        ice = data ? data->toAronDictPtr() : nullptr;
+        ice = data ? data->toAronDictDTO() : nullptr;
     }
     void detail::fromIce(const aron::data::dto::DictPtr& ice, aron::data::DictPtr& data)
     {
         if (ice)
         {
-            data = aron::data::Dict::FromAronDictPtr(ice);
+            data = aron::data::Dict::FromAronDictDTO(ice);
         }
         else
         {
diff --git a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
index f019f3d78a9ed3a38116ee86a11ef42ef942e9d4..29f57ca33e82e865e52c49f08241581a632e0fca 100644
--- a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
@@ -83,7 +83,7 @@ namespace armarx
         update.instancesData.clear();
         update.instancesData.reserve(ice.instancesData.size());
         std::transform(ice.instancesData.begin(), ice.instancesData.end(), std::back_inserter(update.instancesData),
-                       aron::data::Dict::FromAronDictPtr);
+                       aron::data::Dict::FromAronDictDTO);
 
         update.timeCreated = Time::microSeconds(ice.timeCreatedMicroSeconds);
 
@@ -98,7 +98,7 @@ namespace armarx
         ice.instancesData.clear();
         ice.instancesData.reserve(update.instancesData.size());
         std::transform(update.instancesData.begin(), update.instancesData.end(), std::back_inserter(ice.instancesData),
-                       aron::data::Dict::ToAronDictPtr);
+                       aron::data::Dict::ToAronDictDTO);
 
         ice.timeCreatedMicroSeconds = update.timeCreated.toMicroSeconds();
 
diff --git a/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
index 91b1a6584269820bfc020b36145cd656feec76d4..dacedd5e05177028fea42114a3dd02d4b609ad9a 100644
--- a/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
@@ -23,16 +23,16 @@ void armarx::armem::from_aron(const aron::data::DictPtr& metadata, const aron::d
     e.data() = data;
 
     auto timeCreated = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_CREATED_FIELD));
-    m.timeCreated = Time::microSeconds(timeCreated->toAronLongPtr()->value);
+    m.timeCreated = Time::microSeconds(timeCreated->toAronLongDTO()->value);
 
     auto timeSent = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_SENT_FIELD));
-    m.timeSent = Time::microSeconds(timeSent->toAronLongPtr()->value);
+    m.timeSent = Time::microSeconds(timeSent->toAronLongDTO()->value);
 
     auto timeArrived = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_ARRIVED_FIELD));
-    m.timeArrived = Time::microSeconds(timeArrived->toAronLongPtr()->value);
+    m.timeArrived = Time::microSeconds(timeArrived->toAronLongDTO()->value);
 
     auto confidence = aron::data::Double::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_CONFIDENCE_FIELD));
-    m.confidence = static_cast<float>(confidence->toAronDoublePtr()->value);
+    m.confidence = static_cast<float>(confidence->toAronDoubleDTO()->value);
 }
 
 
diff --git a/source/RobotAPI/libraries/armem_grasping/CMakeLists.txt b/source/RobotAPI/libraries/armem_grasping/CMakeLists.txt
index f79f688800f1129a2c63a8da65d3c560b043bad2..c555283cc5506ae12391f4acacf94cf40acd4488 100644
--- a/source/RobotAPI/libraries/armem_grasping/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_grasping/CMakeLists.txt
@@ -6,37 +6,36 @@ armarx_set_target("Library: ${LIB_NAME}")
 
 armarx_add_library(
     LIBS
+        armem
+        armem_server
+        aron
+        RobotAPI::ArmarXObjects
         GraspingUtility
 
     HEADERS
         armem_grasping.h
 
-        aron_conversions.h
-        GraspCandidateWriter.h
-        GraspCandidateReader.h
-        aron/GraspCandidate.aron.generated.h
+        server/KnownGraspProviderSegment.h
+
+        client/KnownGraspCandidateReader.h
+
+        # TODO: move client code in client folder
+        aron_conversions.h # TODO: Please also provide cpp files (they can be empty except of include<header>)
+        GraspCandidateWriter.h # dito
+        GraspCandidateReader.h # dito
+        aron/GraspCandidate.aron.generated.h # Please only use the xml and let the aron converter generate the header file.
 
     SOURCES
         armem_grasping.cpp
+
+        server/KnownGraspProviderSegment.cpp
+
+        client/KnownGraspCandidateReader.cpp
+
+    ARON_FILES
+        aron/KnownGraspCandidate.xml
 )
 
 add_library(${PROJECT_NAME}::armem_grasping ALIAS armem_grasping)
 
 
-#armarx_add_library(armem_grasping
-#    SOURCES
-#        ./armem_grasping.cpp
-#    HEADERS
-#        ./armem_grasping.h
-#    DEPENDENCIES
-#        ArmarXCoreInterfaces
-#        ArmarXCore
-#)
-
- 
-#armarx_add_test(armem_graspingTest
-#    TEST_FILES
-#        test/armem_graspingTest.cpp
-#    DEPENDENCIES
-#        RobotAPI::armem_grasping
-#)
diff --git a/source/RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.xml b/source/RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.xml
new file mode 100644
index 0000000000000000000000000000000000000000..8397a5d2c65f9d1145b69ab45f0b8e21bba33c20
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.xml
@@ -0,0 +1,62 @@
+<?xml version="1.0" encoding="UTF-8" ?>
+<AronTypeDefinition>
+    <AronIncludes>
+        <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" autoinclude="true" />
+        <Include include="<RobotAPI/libraries/aron/common/aron/PackagePath.xml>" autoinclude="true" />
+    </AronIncludes>
+    <GenerateTypes>
+        <Object name='armarx::armem::grasping::arondto::KnownGrasp'>
+
+            <ObjectChild key='name'>
+                <string />
+            </ObjectChild>
+
+            <ObjectChild key='creator'>
+                <string />
+            </ObjectChild>
+
+            <ObjectChild key='quality'>
+                <float />
+            </ObjectChild>
+
+            <ObjectChild key='pose'>
+                <Pose />
+            </ObjectChild>
+
+        </Object>
+
+        <Object name='armarx::armem::grasping::arondto::KnownGraspSet'>
+
+            <ObjectChild key='name'>
+                <string />
+            </ObjectChild>
+
+            <ObjectChild key='grasps'>
+                <Dict>
+                    <armarx::armem::grasping::arondto::KnownGrasp />
+                </Dict>
+            </ObjectChild>
+
+        </Object>
+
+        <Object name='armarx::armem::grasping::arondto::KnownGraspInfo'>
+
+            <ObjectChild key='correspondingObject'>
+                <armarx::armem::arondto::MemoryID />
+            </ObjectChild>
+
+            <ObjectChild key='graspSets'>
+                <Dict>
+                    <armarx::armem::grasping::arondto::KnownGraspSet />
+                </Dict>
+            </ObjectChild>
+
+            <ObjectChild key='xml'>
+                <armarx::arondto::PackagePath />
+            </ObjectChild>
+
+        </Object>
+
+    </GenerateTypes>
+</AronTypeDefinition>
+
diff --git a/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.cpp b/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..17dfd176e77f561e744be85802df356edbf4d804
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.cpp
@@ -0,0 +1,101 @@
+#include "KnownGraspCandidateReader.h"
+
+#include <mutex>
+#include <optional>
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/PackagePath.h>
+
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/util/util.h>
+#include <RobotAPI/libraries/armem_robot/robot_conversions.h>
+#include <RobotAPI/libraries/armem_robot/aron_conversions.h>
+#include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
+#include <RobotAPI/libraries/armem_objects/aron/Attachment.aron.generated.h>
+#include <RobotAPI/libraries/armem_objects/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
+
+
+namespace armarx::armem::grasping::known_grasps
+{
+    Reader::Reader(armem::client::MemoryNameSystem& memoryNameSystem) :
+        memoryNameSystem(memoryNameSystem)
+    {}
+
+    void Reader::registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def)
+    {
+        ARMARX_DEBUG << "Reader: registerPropertyDefinitions";
+
+        const std::string prefix = propertyPrefix;
+
+        def->optional(properties.memoryName, prefix + "MemoryName");
+
+        def->optional(properties.coreSegmentName,
+                      prefix + "CoreSegment",
+                      "Name of the memory core segment to use for object instances.");
+    }
+
+
+    void Reader::connect()
+    {
+        // Wait for the memory to become available and add it as dependency.
+        ARMARX_IMPORTANT << "Reader: Waiting for memory '" << properties.memoryName << "' ...";
+        try
+        {
+            memoryReader = memoryNameSystem.useReader(properties.memoryName);
+            ARMARX_IMPORTANT << "Reader: Connected to memory '" << properties.memoryName << "'";
+        }
+        catch (const armem::error::CouldNotResolveMemoryServer& e)
+        {
+            ARMARX_ERROR << e.what();
+            return;
+        }
+    }
+
+    std::optional<armem::grasping::arondto::KnownGraspInfo> Reader::queryKnownGraspInfo(const armem::wm::Memory& memory, const armem::Time&)
+    {
+        // clang-format off
+        const armem::wm::CoreSegment& s = memory
+                .getCoreSegment(properties.coreSegmentName);
+        // clang-format on
+
+        const armem::wm::EntityInstance* instance = nullptr;
+        s.forEachInstance([&instance](const wm::EntityInstance& i)
+                                        { instance = &i; });
+        if (instance == nullptr)
+        {
+            ARMARX_WARNING << "No entity snapshots found";
+            return std::nullopt;
+        }
+        return armem::grasping::arondto::KnownGraspInfo::FromAron(instance->data());
+    }
+
+    std::optional<armarx::armem::grasping::arondto::KnownGraspInfo> Reader::queryKnownGraspInfoByEntityName(const std::string& entityName, const armem::Time& timestamp)
+    {
+        // Query all entities from all provider.
+        armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties.coreSegmentName)
+        .providerSegments().all()
+        .entities().withName(entityName)
+        .snapshots().beforeOrAtTime(timestamp);
+        // clang-format on
+
+        const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
+
+        ARMARX_DEBUG << "Lookup result in reader: " << qResult;
+
+        if (not qResult.success) /* c++20 [[unlikely]] */
+        {
+            return std::nullopt;
+        }
+
+        return queryKnownGraspInfo(qResult.memory, timestamp);
+    }
+
+}  // namespace armarx::armem::attachment
diff --git a/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.h b/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.h
new file mode 100644
index 0000000000000000000000000000000000000000..945670d82d8b2b130da2e04b3aad0ace5977efee
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_grasping/client/KnownGraspCandidateReader.h
@@ -0,0 +1,65 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <mutex>
+#include <optional>
+
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+
+#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
+#include <RobotAPI/libraries/armem/client/Reader.h>
+
+#include <RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.aron.generated.h>
+
+
+namespace armarx::armem::grasping::known_grasps
+{
+    class Reader
+    {
+    public:
+        Reader(armem::client::MemoryNameSystem& memoryNameSystem);
+        virtual ~Reader() = default;
+
+        void registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def);
+        void connect();
+
+        std::optional<armem::grasping::arondto::KnownGraspInfo> queryKnownGraspInfoByEntityName(const std::string&, const armem::Time&);
+        std::optional<armem::grasping::arondto::KnownGraspInfo> queryKnownGraspInfo(const armem::wm::Memory& memory, const armem::Time&);
+
+    private:
+
+        struct Properties
+        {
+            std::string memoryName                  = "Grasp";
+            std::string coreSegmentName             = "KnownGraspCandidate";
+        } properties;
+
+        const std::string propertyPrefix = "mem.grasping.knowngrasps.";
+
+        armem::client::MemoryNameSystem& memoryNameSystem;
+        armem::client::Reader memoryReader;
+        std::mutex memoryWriterMutex;
+    };
+
+
+}  // namespace armarx::armem::attachment
diff --git a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..5b8aaafea2d04db384f510d23788b16d94fe34db
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
@@ -0,0 +1,144 @@
+#include "KnownGraspProviderSegment.h"
+
+#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h>
+#include <ArmarXCore/core/rapidxml/wrapper/RapidXmlReader.h>
+
+namespace armarx::armem::grasping::segment
+{
+    KnownGraspProviderSegment::KnownGraspProviderSegment(armem::server::MemoryToIceAdapter& iceMemory) :
+        Base(iceMemory, PROVIDER_SEGMENT_NAME, CORE_SEGMENT_NAME)
+    {
+
+    }
+
+    void KnownGraspProviderSegment::init()
+    {
+        Base::init();
+
+        loadMemory();
+    }
+
+    std::optional<arondto::KnownGraspInfo> KnownGraspProviderSegment::knownGraspInfoFromObjectInfo(const ObjectInfo& info)
+    {
+        std::string objectClassName = info.className();
+        auto fileLocInfo = info.file(".xml", "_Grasps");
+        std::filesystem::path graspFilePath = fileLocInfo.absolutePath;
+
+        if (std::filesystem::is_regular_file(graspFilePath))
+        {
+            auto reader = RapidXmlReader::FromFile(graspFilePath);
+            RapidXmlReaderNode root = reader->getRoot();
+
+            std::string objectClassNameXML = root.attribute_value("name");
+            ARMARX_CHECK_EQUAL(objectClassName, objectClassNameXML);
+
+            arondto::KnownGraspInfo ret;
+            ret.correspondingObject.memoryName = "Object";
+            ret.correspondingObject.coreSegmentName = "Class";
+            ret.correspondingObject.providerSegmentName = "PriorKnowledgeData";
+            ret.correspondingObject.entityName = info.idStr();
+            ret.xml.package = fileLocInfo.package;
+            ret.xml.path = fileLocInfo.relativePath;
+
+            for (const auto& graspSetNode : root.nodes())
+            {
+                if (graspSetNode.name() != "GraspSet")
+                {
+                    continue;
+                }
+
+                arondto::KnownGraspSet retGraspSet;
+
+                retGraspSet.name = graspSetNode.attribute_value("name");
+                //std::string robotType = graspSetNode.attribute_value("RobotType");
+                //std::string endEffector = graspSetNode.attribute_value("EndEffector");
+
+                for (const auto& graspNode : graspSetNode.nodes())
+                {
+                    if (graspNode.name() != "Grasp")
+                    {
+                        continue;
+                    }
+
+                    arondto::KnownGrasp retGrasp;
+
+                    retGrasp.name = graspNode.attribute_value("name");
+                    retGrasp.quality = std::stof(graspNode.attribute_value("quality"));
+                    retGrasp.creator = graspNode.attribute_value("Creation");
+
+                    ARMARX_CHECK_EQUAL(graspNode.nodes().size(), 1);
+                    RapidXmlReaderNode transformNode = graspNode.nodes()[0];
+
+                    ARMARX_CHECK_EQUAL(transformNode.nodes().size(), 1);
+                    RapidXmlReaderNode matrixNode = transformNode.nodes()[0];
+
+                    ARMARX_CHECK_EQUAL(matrixNode.nodes().size(), 4);
+                    RapidXmlReaderNode row0 = matrixNode.nodes()[0];
+                    RapidXmlReaderNode row1 = matrixNode.nodes()[1];
+                    RapidXmlReaderNode row2 = matrixNode.nodes()[2];
+                    RapidXmlReaderNode row3 = matrixNode.nodes()[3];
+
+                    retGrasp.pose(0, 0) = std::stof(row0.attribute_value("c1"));
+                    retGrasp.pose(0, 1) = std::stof(row0.attribute_value("c2"));
+                    retGrasp.pose(0, 2) = std::stof(row0.attribute_value("c3"));
+                    retGrasp.pose(0, 3) = std::stof(row0.attribute_value("c4"));
+                    retGrasp.pose(1, 0) = std::stof(row1.attribute_value("c1"));
+                    retGrasp.pose(1, 1) = std::stof(row1.attribute_value("c2"));
+                    retGrasp.pose(1, 2) = std::stof(row1.attribute_value("c3"));
+                    retGrasp.pose(1, 3) = std::stof(row1.attribute_value("c4"));
+                    retGrasp.pose(2, 0) = std::stof(row2.attribute_value("c1"));
+                    retGrasp.pose(2, 1) = std::stof(row2.attribute_value("c2"));
+                    retGrasp.pose(2, 2) = std::stof(row2.attribute_value("c3"));
+                    retGrasp.pose(2, 3) = std::stof(row2.attribute_value("c4"));
+                    retGrasp.pose(3, 0) = std::stof(row3.attribute_value("c1"));
+                    retGrasp.pose(3, 1) = std::stof(row3.attribute_value("c2"));
+                    retGrasp.pose(3, 2) = std::stof(row3.attribute_value("c3"));
+                    retGrasp.pose(3, 3) = std::stof(row3.attribute_value("c4"));
+
+                    ARMARX_INFO << "Found grasp '" << retGrasp.name << "' in set '" << retGraspSet.name << "' for obj '" << objectClassName << "' with pose \n" << retGrasp.pose;
+
+                    retGraspSet.grasps[retGrasp.name] = retGrasp;
+                }
+                ret.graspSets[retGraspSet.name] = retGraspSet;
+            }
+            return ret;
+        }
+        return std::nullopt;
+    }
+
+    void KnownGraspProviderSegment::loadMemory()
+    {
+        // load data from prior knowledge
+        ObjectFinder objectFinder;
+        const auto now = armem::Time::now();
+
+        const bool checkPaths = false;
+        std::vector<ObjectInfo> infos = objectFinder.findAllObjects(checkPaths);
+
+        const MemoryID providerID = segmentPtr->id().withProviderSegmentName(objectFinder.getPackageName());
+        ARMARX_INFO << "Checking up to " << infos.size() << " object classes from '" << objectFinder.getPackageName() << "' ...";
+
+        Commit commit;
+        for (ObjectInfo& info : infos)
+        {
+            info.setLogError(false);
+            if (auto knownGraspCandidate = knownGraspInfoFromObjectInfo(info); knownGraspCandidate)
+            {
+                EntityUpdate& update = commit.add();
+                update.entityID = providerID.withEntityName(info.id().str());
+                update.entityID.timestamp = update.timeArrived = update.timeCreated = update.timeSent = now;
+
+                update.instancesData =
+                {
+                    knownGraspCandidate->toAron()
+                };
+            }
+        }
+        ARMARX_INFO << "Loaded " << commit.updates.size() << " grasp candidates from object classes from '" << objectFinder.getPackageName() << "'.";
+        auto result = iceMemory.commit(commit);
+        if (!result.allSuccess())
+        {
+            ARMARX_WARNING << "Got errors for commit: " << result.allErrorMessages();
+        }
+    }
+}
diff --git a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.h b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.h
new file mode 100644
index 0000000000000000000000000000000000000000..de92372581076450341fb53e4628c4dd7ae4ba7c
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.h
@@ -0,0 +1,27 @@
+# pragma once
+
+#include <RobotAPI/libraries/armem/server/segment/SpecializedSegment.h>
+
+#include <RobotAPI/libraries/ArmarXObjects/ObjectFinder.h>
+#include <RobotAPI/libraries/armem_grasping/aron/KnownGraspCandidate.aron.generated.h>
+
+namespace armarx::armem::grasping::segment
+{
+    class KnownGraspProviderSegment : public armem::server::segment::SpecializedProviderSegment
+    {
+        using Base = armem::server::segment::SpecializedProviderSegment;
+
+    public:
+        KnownGraspProviderSegment(armem::server::MemoryToIceAdapter& iceMemory);
+
+        void init() override;
+
+    private:
+        void loadMemory();
+        std::optional<arondto::KnownGraspInfo> knownGraspInfoFromObjectInfo(const ObjectInfo&);
+
+    public:
+        static const constexpr char* CORE_SEGMENT_NAME = "KnownGraspCandidate";
+        static const constexpr char* PROVIDER_SEGMENT_NAME = "PriorKnowledgeData";
+    };
+}
diff --git a/source/RobotAPI/libraries/armem_objects/CMakeLists.txt b/source/RobotAPI/libraries/armem_objects/CMakeLists.txt
index 88fd8cf80f190ee13489c8180e4c4a53f652caff..74928ae14dc40cc72b49c6a81570525336c48bfa 100644
--- a/source/RobotAPI/libraries/armem_objects/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_objects/CMakeLists.txt
@@ -44,6 +44,8 @@ armarx_add_library(
 
         client/attachment/Reader.h
         client/attachment/Writer.h
+        
+        client/instance/ObjectReader.h
 
     SOURCES
         aron_conversions.cpp
@@ -58,6 +60,8 @@ armarx_add_library(
 
         client/attachment/Reader.cpp
         client/attachment/Writer.cpp
+        
+        client/instance/ObjectReader.cpp
 
     ARON_FILES
         aron/ObjectClass.xml
diff --git a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.cpp b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..49dbdcf6140717e63ceec39e8cbf7d0f9b91dd77
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.cpp
@@ -0,0 +1,138 @@
+#include "ObjectReader.h"
+
+#include <mutex>
+#include <optional>
+
+#include <ArmarXCore/core/logging/Logging.h>
+#include <ArmarXCore/core/PackagePath.h>
+
+#include <RobotAPI/libraries/armem/core/Time.h>
+#include <RobotAPI/libraries/armem/core/error.h>
+#include <RobotAPI/libraries/armem/client/query/Builder.h>
+#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h>
+#include <RobotAPI/libraries/armem/util/util.h>
+#include <RobotAPI/libraries/armem_robot/robot_conversions.h>
+#include <RobotAPI/libraries/armem_robot/aron_conversions.h>
+#include <RobotAPI/libraries/armem_robot/aron/Robot.aron.generated.h>
+#include <RobotAPI/libraries/armem_objects/aron/Attachment.aron.generated.h>
+#include <RobotAPI/libraries/armem_objects/aron_conversions.h>
+#include <RobotAPI/libraries/aron/common/aron_conversions.h>
+
+
+namespace armarx::armem::obj::instance
+{
+    Reader::Reader(armem::client::MemoryNameSystem& memoryNameSystem) :
+        memoryNameSystem(memoryNameSystem)
+    {}
+
+    void Reader::registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def)
+    {
+        ARMARX_DEBUG << "Reader: registerPropertyDefinitions";
+
+        const std::string prefix = propertyPrefix;
+
+        def->optional(properties.memoryName, prefix + "MemoryName");
+
+        def->optional(properties.coreSegmentName,
+                      prefix + "CoreSegment",
+                      "Name of the memory core segment to use for object instances.");
+    }
+
+
+    void Reader::connect()
+    {
+        // Wait for the memory to become available and add it as dependency.
+        ARMARX_IMPORTANT << "Reader: Waiting for memory '" << properties.memoryName << "' ...";
+        try
+        {
+            memoryReader = memoryNameSystem.useReader(properties.memoryName);
+            ARMARX_IMPORTANT << "Reader: Connected to memory '" << properties.memoryName << "'";
+        }
+        catch (const armem::error::CouldNotResolveMemoryServer& e)
+        {
+            ARMARX_ERROR << e.what();
+            return;
+        }
+    }
+
+    std::optional<armarx::armem::arondto::ObjectInstance> Reader::queryObject(const armem::wm::Memory& memory, const armem::Time& timestamp)
+    {
+        // clang-format off
+        const armem::wm::CoreSegment& s = memory
+                .getCoreSegment(properties.coreSegmentName);
+        // clang-format on
+
+        // What to do with timestamp?
+        const armem::wm::EntityInstance* instance = nullptr;
+        s.forEachInstance([&instance](const wm::EntityInstance& i)
+                                        { instance = &i; });
+        if (instance == nullptr)
+        {
+            return std::nullopt;
+        }
+        return armem::arondto::ObjectInstance::FromAron(instance->data());
+    }
+
+    std::optional<armarx::armem::arondto::ObjectInstance> Reader::queryObjectByEntityID(const std::string& entityName, const armem::Time& timestamp)
+    {
+        // Query all entities from all provider.
+        armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties.coreSegmentName)
+        .providerSegments().all()
+        .entities().withName(entityName)
+        .snapshots().beforeOrAtTime(timestamp);
+        // clang-format on
+
+        const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
+
+        ARMARX_DEBUG << "Lookup result in reader: " << qResult;
+
+        if (not qResult.success) /* c++20 [[unlikely]] */
+        {
+            return std::nullopt;
+        }
+
+        return queryObject(qResult.memory, timestamp);
+    }
+
+    std::optional<armarx::armem::arondto::ObjectInstance> Reader::queryObjectByObjectID(const std::string& objectId, const armem::Time& timestamp)
+    {
+        // Query all entities from all provider.
+        armem::client::query::Builder qb;
+
+        // clang-format off
+        qb
+        .coreSegments().withName(properties.coreSegmentName)
+        .providerSegments().all()
+        .entities().all()
+        .snapshots().beforeOrAtTime(timestamp);
+        // clang-format on
+
+        const armem::client::QueryResult qResult = memoryReader.query(qb.buildQueryInput());
+
+        ARMARX_DEBUG << "Lookup result in reader: " << qResult;
+
+        if (not qResult.success) /* c++20 [[unlikely]] */
+        {
+            return std::nullopt;
+        }
+
+        // clang-format off
+        const armem::wm::CoreSegment& s = qResult.memory
+                .getCoreSegment(properties.coreSegmentName);
+        // clang-format on
+
+        const armem::wm::EntityInstance* instance = nullptr;
+        s.forEachInstance([&instance, &objectId](const wm::EntityInstance& i)
+                                        { if (simox::alg::starts_with(i.id().entityName, objectId)) instance = &i; });
+        if (instance == nullptr)
+        {
+            return std::nullopt;
+        }
+        return armem::arondto::ObjectInstance::FromAron(instance->data());
+    }
+
+}  // namespace armarx::armem::attachment
diff --git a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h
new file mode 100644
index 0000000000000000000000000000000000000000..8db6a1cab642e103dd6c25105b607c47651ccb15
--- /dev/null
+++ b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectReader.h
@@ -0,0 +1,70 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Reister ( fabian dot reister at kit dot edu )
+ * @date       2021
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <mutex>
+#include <optional>
+
+#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h>
+
+#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h>
+#include <RobotAPI/libraries/armem/client/Reader.h>
+#include <RobotAPI/libraries/armem_objects/types.h>
+
+#include <RobotAPI/libraries/armem_objects/aron/ObjectInstance.aron.generated.h>
+
+
+namespace armarx::armem::obj::instance
+{
+    class Reader
+    {
+    public:
+        Reader(armem::client::MemoryNameSystem& memoryNameSystem);
+        virtual ~Reader() = default;
+
+        void registerPropertyDefinitions(armarx::PropertyDefinitionsPtr& def);
+        void connect();
+
+
+        std::optional<armem::arondto::ObjectInstance> queryObject(const armem::wm::Memory& memory, const armem::Time&);
+        std::optional<armem::arondto::ObjectInstance> queryObjectByEntityID(const std::string& entityName, const armem::Time&);
+        std::optional<armem::arondto::ObjectInstance> queryObjectByObjectID(const std::string& objectId, const armem::Time&);
+
+
+    private:
+
+
+        struct Properties
+        {
+            std::string memoryName                  = "Object";
+            std::string coreSegmentName             = "Instance";
+        } properties;
+
+        const std::string propertyPrefix = "mem.obj.instance.";
+
+        armem::client::MemoryNameSystem& memoryNameSystem;
+        armem::client::Reader memoryReader;
+        std::mutex memoryWriterMutex;
+    };
+
+
+}  // namespace armarx::armem::attachment
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
index 4428f3d967085e9d1f1a8e1951c5524d1097b2e7..bdeeb0bd659f42333abe3450ac319d17e91847b0 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotReader.cpp
@@ -174,7 +174,7 @@ namespace armarx::armem::robot_state
 
     std::optional<robot::RobotState::JointMap>
     RobotReader::queryJointState(const robot::RobotDescription& description,
-                                 const armem::Time& timestamp) const
+                                 const armem::Time& timestamp) const // Why timestamp?!?!
     {
         // TODO(fabian.reister): how to deal with multiple providers?
 
diff --git a/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
index dce0a7f051c96ead6968faef643ed261735abb9d..57151c646f1206a45e689714c37dfac3508aeb88 100644
--- a/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
+++ b/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
@@ -40,7 +40,7 @@ namespace armarx::skills::segment
         skills::manager::dto::SkillExecutionInfo info;
         info.providerName = request.providerName;
         info.skillName = request.skillName;
-        info.params = params->toAronDictPtr();
+        info.params = aron::data::Dict::ToAronDictDTO(params);
         return info;
     }
 
@@ -58,9 +58,7 @@ namespace armarx::skills::segment
 
         auto aron = request.toAron();
 
-        aron::data::DictPtr aron_params = nullptr;
-        if (info.params) aron_params = std::make_shared<aron::data::Dict>(info.params);
-
+        aron::data::DictPtr aron_params = aron::data::Dict::FromAronDictDTO(info.params);
         aron->addElement("params", aron_params); // todo add as any type
 
         armem::MemoryID skillExecutionMemID = id();
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/Variant.h b/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
index 04c39ea84332665c56269b7e8d16c17aacd83aa4..aee8c55fc02d07395e67ff7fd907a8fb5b207999 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/Variant.h
@@ -144,9 +144,6 @@ namespace armarx::aron::data
         /// convert the variant to the ice representation
         virtual data::dto::GenericDataPtr toAronDTO() const = 0;
 
-        /// set a variant from a std string
-        virtual void fromString(const std::string& setter) = 0;
-
     protected:
         const data::Descriptor descriptor;
         const Path path;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.cpp b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.cpp
index c5a8b08ab2b68ded38ca90859c77a0168fb3887d..7de89a06a92c1da3e84046c3af98c2d10d602515 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.cpp
@@ -87,6 +87,10 @@ namespace armarx::aron::data
     // static methods
     NDArrayPtr NDArray::FromNDArrayDTO(const data::dto::NDArrayPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<NDArray>(aron);
     }
 
@@ -156,11 +160,6 @@ namespace armarx::aron::data
     }
 
     // virtual implementations
-    void NDArray::fromString(const std::string& setter)
-    {
-        // TODO!
-    }
-
     std::string NDArray::getShortName() const
     {
         return "NDArray";
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
index 92dbed05e7433e90fd9725690413687bda908c31..31677060acad93fe7fbbbe949b4439d434392931 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/complex/NDArray.h
@@ -90,8 +90,6 @@ namespace armarx::aron::data
             return ret;
         }
 
-        void fromString(const std::string& setter) override;
-
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.cpp b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.cpp
index ef895067b7b299f89be4e031b5d86d69cc8d3182..0e7de7dae17c7aaa92d956a8dd56a27a7f9bbba3 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.cpp
@@ -90,17 +90,21 @@ namespace armarx::aron::data
     }
 
     // static methods
-    DictPtr Dict::FromAronDictPtr(const data::dto::DictPtr& aron)
+    DictPtr Dict::FromAronDictDTO(const data::dto::DictPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Dict>(aron);
     }
 
-    data::dto::DictPtr Dict::ToAronDictPtr(const DictPtr& navigator)
+    data::dto::DictPtr Dict::ToAronDictDTO(const DictPtr& navigator)
     {
-        return navigator ? navigator->toAronDictPtr() : nullptr;
+        return navigator ? navigator->toAronDictDTO() : nullptr;
     }
 
-    data::dto::DictPtr Dict::toAronDictPtr() const
+    data::dto::DictPtr Dict::toAronDictDTO() const
     {
         return aron;
     }
@@ -186,11 +190,6 @@ namespace armarx::aron::data
     }
 
     // virtual implementations
-    void Dict::fromString(const std::string& setter)
-    {
-        // TODO!
-    }
-
     std::string Dict::getShortName() const
     {
         return "Dict";
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
index 99d7a368293c3d3613937a0316c208261bfa3caf..3c8f5a74d3e87cb7ae90bab620c58435817e39c7 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/Dict.h
@@ -53,11 +53,11 @@ namespace armarx::aron::data
         bool operator==(const DictPtr&) const override;
         VariantPtr operator[](const std::string&) const;
 
-        static PointerType FromAronDictPtr(const data::dto::DictPtr& aron);
-        static data::dto::DictPtr ToAronDictPtr(const PointerType& navigator);
+        static PointerType FromAronDictDTO(const data::dto::DictPtr& aron);
+        static data::dto::DictPtr ToAronDictDTO(const PointerType& navigator);
 
         // public member functions
-        data::dto::DictPtr toAronDictPtr() const;
+        data::dto::DictPtr toAronDictDTO() const;
         std::vector<std::string> getAllKeys() const;
         std::string getAllKeysAsString() const;
 
@@ -82,8 +82,6 @@ namespace armarx::aron::data
             return ret;
         }
 
-        void fromString(const std::string& setter) override;
-
         std::string getShortName() const override;
         std::string getFullName() const override;
         std::vector<VariantPtr> getChildren() const override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/List.cpp b/source/RobotAPI/libraries/aron/core/data/variant/container/List.cpp
index 0d4dffe9bc20479e12c03797964dc4ccba4a42f0..bb86d4f1baff4013c62c788a7f6ddf0f99f80a1c 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/List.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/List.cpp
@@ -93,14 +93,18 @@ namespace armarx::aron::data
     }
 
     // static methods
-    ListPtr List::FromAronListPtr(const data::dto::ListPtr& aron)
+    ListPtr List::FromAronListDTO(const data::dto::ListPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<List>(aron);
     }
 
-    data::dto::ListPtr List::ToAronListPtr(const ListPtr& navigator)
+    data::dto::ListPtr List::ToAronListDTO(const ListPtr& navigator)
     {
-        return navigator ? navigator->toAronListPtr() : nullptr;
+        return navigator ? navigator->toAronListDTO() : nullptr;
     }
 
     // public member functions
@@ -183,17 +187,12 @@ namespace armarx::aron::data
         aron->elements.clear();
     }
 
-    data::dto::ListPtr List::toAronListPtr() const
+    data::dto::ListPtr List::toAronListDTO() const
     {
         return aron;
     }
 
     // virtual implementations
-    void List::fromString(const std::string& setter)
-    {
-        // TODO!
-    }
-
     std::string List::getShortName() const
     {
         return "List";
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/container/List.h b/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
index cab6a38e5fd1ff8bd85a996fe3336a7ddff16504..b766ce5aae83416ae632b7e0ff27c30ade72c0e0 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/container/List.h
@@ -54,13 +54,13 @@ namespace armarx::aron::data
         bool operator==(const ListPtr&) const override;
 
         // static methods
-        static PointerType FromAronListPtr(const data::dto::ListPtr& aron);
-        static data::dto::ListPtr ToAronListPtr(const PointerType& navigator);
+        static PointerType FromAronListDTO(const data::dto::ListPtr& aron);
+        static data::dto::ListPtr ToAronListDTO(const PointerType& navigator);
 
         // public member functions
         DictPtr getAsDict() const;
 
-        data::dto::ListPtr toAronListPtr() const;
+        data::dto::ListPtr toAronListDTO() const;
 
         void addElement(const VariantPtr&);
         void setElement(unsigned int, const VariantPtr&);
@@ -83,8 +83,6 @@ namespace armarx::aron::data
             return ret;
         }
 
-        void fromString(const std::string& setter) override;
-
         std::string getShortName() const override;
         std::string getFullName() const override;
         std::vector<VariantPtr> getChildren() const override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h b/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
index b7356be2074a27ba2ac4285ffafd2a400fcf1864..849d146d5c398966f4328f03ffd1f0d286488877 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/detail/PrimitiveVariant.h
@@ -71,6 +71,9 @@ namespace armarx::aron::data::detail
             return this->aron->value == x;
         }*/
 
+        /// set a primitive from a std string
+        virtual void fromString(const std::string& setter) = 0;
+
         // virtual implementations
         VariantPtr navigateAbsolute(const Path &path) const override
         {
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.cpp
index 59f8ffa1602955de4f00c60346b3c0b480d24683..7c5e526822769e56b61e3b0099509274f6ae9224 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.cpp
@@ -44,7 +44,7 @@ namespace armarx::aron::data
     /* operators */
     bool Bool::operator==(const Bool& other) const
     {
-        const auto& otherAron = other.toAronBoolPtr();
+        const auto& otherAron = other.toAronBoolDTO();
         if (aron->value != otherAron->value)
         {
             return false;
@@ -62,18 +62,22 @@ namespace armarx::aron::data
 
 
     /* static methods */
-    BoolPtr Bool::FromAronBoolPtr(const data::dto::AronBoolPtr& aron)
+    BoolPtr Bool::FromAronBoolDTO(const data::dto::AronBoolPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Bool>(aron);
     }
 
-    data::dto::AronBoolPtr Bool::ToAronBoolPtr(const BoolPtr& navigator)
+    data::dto::AronBoolPtr Bool::ToAronBoolDTO(const BoolPtr& navigator)
     {
-        return navigator ? navigator->toAronBoolPtr() : nullptr;
+        return navigator ? navigator->toAronBoolDTO() : nullptr;
     }
 
     /* public member functions */
-    data::dto::AronBoolPtr Bool::toAronBoolPtr() const
+    data::dto::AronBoolPtr Bool::toAronBoolDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.h
index f76f9396ce4a640e18b9c16d46b9d6383cbee8ba..65cfc31a7bec67f63e8f9bf5101f697c7d61e2c7 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Bool.h
@@ -52,11 +52,11 @@ namespace armarx::aron::data
         bool operator==(const BoolPtr&) const override;
 
         // static methods
-        static BoolPtr FromAronBoolPtr(const data::dto::AronBoolPtr& aron);
-        static data::dto::AronBoolPtr ToAronBoolPtr(const BoolPtr& navigator);
+        static BoolPtr FromAronBoolDTO(const data::dto::AronBoolPtr& aron);
+        static data::dto::AronBoolPtr ToAronBoolDTO(const BoolPtr& navigator);
 
         // class methods
-        data::dto::AronBoolPtr toAronBoolPtr() const;
+        data::dto::AronBoolPtr toAronBoolDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.cpp
index e96cd84855419855414946958162f3370a7adba8..729e5bda480e8a21d14e16be1f454a02d1f7cf9b 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.cpp
@@ -48,7 +48,7 @@ namespace armarx::aron::data
     /* operators */
     bool Double::operator==(const Double& other) const
     {
-        const auto& otherAron = other.toAronDoublePtr();
+        const auto& otherAron = other.toAronDoubleDTO();
         if (this->aron->value != otherAron->value)
         {
             return false;
@@ -65,19 +65,23 @@ namespace armarx::aron::data
     }
 
     /* static methods */
-    DoublePtr Double::FromAronDoublePtr(const data::dto::AronDoublePtr& aron)
+    DoublePtr Double::FromAronDoubleDTO(const data::dto::AronDoublePtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Double>(aron);
     }
 
-    data::dto::AronDoublePtr Double::ToAronDoublePtr(const DoublePtr& navigator)
+    data::dto::AronDoublePtr Double::ToAronDoubleDTO(const DoublePtr& navigator)
     {
-        return navigator ? navigator->toAronDoublePtr() : nullptr;
+        return navigator ? navigator->toAronDoubleDTO() : nullptr;
     }
 
 
     /* public member functions */
-    data::dto::AronDoublePtr Double::toAronDoublePtr() const
+    data::dto::AronDoublePtr Double::toAronDoubleDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.h
index fdaba984aa6583523062995451ce062db3a56123..b02571f1dd7cef61635849b21edddf943469c7cd 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Double.h
@@ -52,11 +52,11 @@ namespace armarx::aron::data
         bool operator==(const DoublePtr&) const override;
 
         /* static methods */
-        static DoublePtr FromAronDoublePtr(const data::dto::AronDoublePtr& aron);
-        static data::dto::AronDoublePtr ToAronDoublePtr(const DoublePtr& navigator);
+        static DoublePtr FromAronDoubleDTO(const data::dto::AronDoublePtr& aron);
+        static data::dto::AronDoublePtr ToAronDoubleDTO(const DoublePtr& navigator);
 
         /* public member functions */
-        data::dto::AronDoublePtr toAronDoublePtr() const;
+        data::dto::AronDoublePtr toAronDoubleDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.cpp
index 35fd408454f77d91c3e45a260ead10d2a23ae037..f638882eaf80af2a6a4cba0f9d1fffe43cd6e304 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.cpp
@@ -44,7 +44,7 @@ namespace armarx::aron::data
     /* operators */
     bool Float::operator==(const Float& other) const
     {
-        const auto& otherAron = other.toAronFloatPtr();
+        const auto& otherAron = other.toAronFloatDTO();
         if (this->aron->value != otherAron->value)
         {
             return false;
@@ -62,18 +62,22 @@ namespace armarx::aron::data
 
 
     /* static methods */
-    FloatPtr Float::FromAronFloatPtr(const data::dto::AronFloatPtr& aron)
+    FloatPtr Float::FromAronFloatDTO(const data::dto::AronFloatPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Float>(aron);
     }
 
-    data::dto::AronFloatPtr Float::ToAronFloatPtr(const FloatPtr& navigator)
+    data::dto::AronFloatPtr Float::ToAronFloatDTO(const FloatPtr& navigator)
     {
-        return navigator ? navigator->toAronFloatPtr() : nullptr;
+        return navigator ? navigator->toAronFloatDTO() : nullptr;
     }
 
     /* public member functions */
-    data::dto::AronFloatPtr Float::toAronFloatPtr() const
+    data::dto::AronFloatPtr Float::toAronFloatDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.h
index 52f3f41cfc0ef98bc13fa47a17c5a160d95ae992..d7b44e56784ef2a6a1c8b35ebb3b7b3841448426 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Float.h
@@ -52,11 +52,11 @@ namespace armarx::aron::data
         bool operator==(const FloatPtr&) const override;
 
         /* static methods */
-        static FloatPtr FromAronFloatPtr(const data::dto::AronFloatPtr& aron);
-        static data::dto::AronFloatPtr ToAronFloatPtr(const FloatPtr& navigator);
+        static FloatPtr FromAronFloatDTO(const data::dto::AronFloatPtr& aron);
+        static data::dto::AronFloatPtr ToAronFloatDTO(const FloatPtr& navigator);
 
         /* public member functions */
-        data::dto::AronFloatPtr toAronFloatPtr() const;
+        data::dto::AronFloatPtr toAronFloatDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.cpp
index ba774f9e5b498f2546b231f795e644a79d39ec35..b5f0d39196b750084876ad85a49f9f77cdf23112 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.cpp
@@ -47,7 +47,7 @@ namespace armarx::aron::data
     /* operators */
     bool Int::operator==(const Int& other) const
     {
-        const auto& otherAron = other.toAronIntPtr();
+        const auto& otherAron = other.toAronIntDTO();
         if (this->aron->value != otherAron->value)
         {
             return false;
@@ -65,18 +65,22 @@ namespace armarx::aron::data
 
 
     /* static methods */
-    IntPtr Int::FromAronIntPtr(const data::dto::AronIntPtr& aron)
+    IntPtr Int::FromAronIntDTO(const data::dto::AronIntPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Int>(aron);
     }
 
-    data::dto::AronIntPtr Int::ToAronIntPtr(const IntPtr& navigator)
+    data::dto::AronIntPtr Int::ToAronIntDTO(const IntPtr& navigator)
     {
-        return navigator ? navigator->toAronIntPtr() : nullptr;
+        return navigator ? navigator->toAronIntDTO() : nullptr;
     }
 
     /* public member functions */
-    data::dto::AronIntPtr Int::toAronIntPtr() const
+    data::dto::AronIntPtr Int::toAronIntDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.h
index 7cf20562d95eeadd431eb27c35b19de39d57e02f..9a803a035d0be45cd7f38241a937f67179c2bfa2 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Int.h
@@ -53,11 +53,11 @@ namespace armarx::aron::data
         bool operator==(const IntPtr&) const override;
 
         /* static methods */
-        static IntPtr FromAronIntPtr(const data::dto::AronIntPtr& aron);
-        static data::dto::AronIntPtr ToAronIntPtr(const IntPtr& navigator);
+        static IntPtr FromAronIntDTO(const data::dto::AronIntPtr& aron);
+        static data::dto::AronIntPtr ToAronIntDTO(const IntPtr& navigator);
 
         /* public member functions */
-        data::dto::AronIntPtr toAronIntPtr() const;
+        data::dto::AronIntPtr toAronIntDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.cpp
index 4a65a39333df0f16e02e5db7eb9b5d6cbb036bb8..1885fc750b5cee8a7b477627167972c37e514db9 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.cpp
@@ -48,7 +48,7 @@ namespace armarx::aron::data
     /* operators */
     bool Long::operator==(const Long& other) const
     {
-        const auto& otherAron = other.toAronLongPtr();
+        const auto& otherAron = other.toAronLongDTO();
         if (this->aron->value != otherAron->value)
         {
             return false;
@@ -66,18 +66,22 @@ namespace armarx::aron::data
 
 
     /* static methods */
-    LongPtr Long::FromAronLongPtr(const data::dto::AronLongPtr& aron)
+    LongPtr Long::FromAronLongDTO(const data::dto::AronLongPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<Long>(aron);
     }
 
-    data::dto::AronLongPtr Long::ToAronLongPtr(const LongPtr& navigator)
+    data::dto::AronLongPtr Long::ToAronLongDTO(const LongPtr& navigator)
     {
-        return navigator ? navigator->toAronLongPtr() : nullptr;
+        return navigator ? navigator->toAronLongDTO() : nullptr;
     }
 
     /* public member functions */
-    data::dto::AronLongPtr Long::toAronLongPtr() const
+    data::dto::AronLongPtr Long::toAronLongDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.h
index e8136ed7b3e08a1015c3cc8013105ef1ebb39f2c..82b9481be9f957271735d55686659767b60c53ec 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/Long.h
@@ -53,11 +53,11 @@ namespace armarx::aron::data
         bool operator==(const LongPtr&) const override;
 
         /* static methods */
-        static LongPtr FromAronLongPtr(const data::dto::AronLongPtr& aron);
-        static data::dto::AronLongPtr ToAronLongPtr(const LongPtr& navigator);
+        static LongPtr FromAronLongDTO(const data::dto::AronLongPtr& aron);
+        static data::dto::AronLongPtr ToAronLongDTO(const LongPtr& navigator);
 
         /* public member functions */
-        data::dto::AronLongPtr toAronLongPtr() const;
+        data::dto::AronLongPtr toAronLongDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.cpp b/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.cpp
index 4ca2ff4d854a4ac028792aa166be41172640f992..b896221b06d79f3e9cee12b2d84ec9156216dc7f 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.cpp
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.cpp
@@ -44,7 +44,7 @@ namespace armarx::aron::data
     /* operators */
     bool String::operator==(const String& other) const
     {
-        const auto& otherAron = other.toAronStringPtr();
+        const auto& otherAron = other.toAronStringDTO();
         if (this->aron->value != otherAron->value)
         {
             return false;
@@ -62,18 +62,22 @@ namespace armarx::aron::data
 
 
     /* static methods */
-    StringPtr String::FromAronStringPtr(const data::dto::AronStringPtr& aron)
+    StringPtr String::FromAronStringDTO(const data::dto::AronStringPtr& aron)
     {
+        if (!aron)
+        {
+            return nullptr;
+        }
         return std::make_shared<String>(aron);
     }
 
-    data::dto::AronStringPtr String::ToAronStringPtr(const StringPtr& navigator)
+    data::dto::AronStringPtr String::ToAronStringDTO(const StringPtr& navigator)
     {
-        return navigator ? navigator->toAronStringPtr() : nullptr;
+        return navigator ? navigator->toAronStringDTO() : nullptr;
     }
 
     /* public member functions */
-    data::dto::AronStringPtr String::toAronStringPtr() const
+    data::dto::AronStringPtr String::toAronStringDTO() const
     {
         return aron;
     }
diff --git a/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.h b/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.h
index b8ec3ec038c459f37a907e3526ba7cdd034a9f1f..33e9ef6ea7d160bc5dab7e64cc043cc7948c1e34 100644
--- a/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.h
+++ b/source/RobotAPI/libraries/aron/core/data/variant/primitive/String.h
@@ -52,11 +52,11 @@ namespace armarx::aron::data
         bool operator==(const StringPtr&) const override;
 
         /* static methods */
-        static StringPtr FromAronStringPtr(const data::dto::AronStringPtr& aron);
-        static data::dto::AronStringPtr ToAronStringPtr(const StringPtr& navigator);
+        static StringPtr FromAronStringDTO(const data::dto::AronStringPtr& aron);
+        static data::dto::AronStringPtr ToAronStringDTO(const StringPtr& navigator);
 
         /* public member functions */
-        data::dto::AronStringPtr toAronStringPtr() const;
+        data::dto::AronStringPtr toAronStringDTO() const;
 
         /* virtual implementations */
         void fromString(const std::string& setter) override;
diff --git a/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp b/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp
index 77a9ad525476d265e7919cf112abf761552670dd..33bb9c3208e99bf053c881556ff3a576e1b2948a 100644
--- a/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp
+++ b/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp
@@ -107,7 +107,7 @@ void test_toAronType(T& in, T& out)
     {
         type::ObjectPtr in_type_nav = in.toAronType();
 
-        type::dto::AronObjectPtr in_type = in_type_nav->toObjectDTO();
+        type::dto::AronObjectPtr in_type = in_type_nav->toAronObjectDTO();
         BOOST_CHECK(in_type);
 
         armarx::aron::type::writer::NlohmannJSONWriter json_writer_in;
@@ -120,7 +120,7 @@ void test_toAronType(T& in, T& out)
     {
         type::ObjectPtr out_type_nav = out.toAronType();
 
-        type::dto::AronObjectPtr out_type = out_type_nav->toObjectDTO();
+        type::dto::AronObjectPtr out_type = out_type_nav->toAronObjectDTO();
         BOOST_CHECK(out_type);
 
         armarx::aron::type::writer::NlohmannJSONWriter json_writer_out;
@@ -147,7 +147,7 @@ void test_toAron(T& in, T& out)
     }
 
     BOOST_TEST_INFO("getting in aron");
-    data::dto::DictPtr in_aron = in_aron_nav->toAronDictPtr();
+    data::dto::DictPtr in_aron = in_aron_nav->toAronDictDTO();
     BOOST_CHECK(in_aron);
 
     //BOOST_TEST_MESSAGE("in_aron_nav: \n" << converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(in_aron_nav).dump(2));
@@ -162,7 +162,7 @@ void test_toAron(T& in, T& out)
         out_aron_nav = out.toAron();
         BOOST_CHECK(*in_aron_nav == *out_aron_nav);
 
-        data::dto::DictPtr out_aron = out_aron_nav->toAronDictPtr();
+        data::dto::DictPtr out_aron = out_aron_nav->toAronDictDTO();
         BOOST_CHECK(out_aron);
     }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/Variant.h b/source/RobotAPI/libraries/aron/core/type/variant/Variant.h
index aba2fdd514cc43a18281e349de0a63e378ad8264..ab996582c630a9083bafb45bc7ec19755e59bb67 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/Variant.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/Variant.h
@@ -115,9 +115,6 @@ namespace armarx::aron::type
         /// get the full name of this specific type
         virtual std::string getFullName() const = 0;
 
-        /// the default string to set the corresponding data object from string
-        virtual std::string getDefaultFromString() const = 0;
-
         /// get all child elements
         virtual std::vector<VariantPtr> getChildren() const = 0;
         virtual size_t childrenSize() const = 0;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp
index c58669203698b39693ce57fd7e1b8efb4bfc03f8..3919bf8447c76e594ca0873277b24626ae4d4ffb 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp
@@ -80,15 +80,6 @@ namespace armarx::aron::type
         return "armarx::aron::type::Dict<" + acceptedType->getFullName() + ">";
     }
 
-    std::string Dict::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "{" << "\n";
-        ss << "\t" << "\"key\": " << acceptedType->getDefaultFromString() << "\n";
-        ss << "}";
-        return ss.str();
-    }
-
     VariantPtr Dict::navigateAbsolute(const Path& path) const
     {
         if (!path.hasElement())
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h
index 0c2e11ee5c58391e0ba2d0a349d5fe1d27071a71..4dfdd35e238b39b729d67c583ec9378fc19f5c0e 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h
@@ -56,7 +56,6 @@ namespace armarx::aron::type
 
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp b/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp
index d019192030891998cbb89c5de371357e6c0f6344..807d64fedf211b1d14949ece0409ab2baea952bb 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp
@@ -80,15 +80,6 @@ namespace armarx::aron::type
         return "armarx::aron::type::List<" + acceptedType->getFullName() + ">";
     }
 
-    std::string List::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "[" << "\n";
-        ss << "\t" << acceptedType->getDefaultFromString() << "\n";
-        ss << "]";
-        return ss.str();
-    }
-
     VariantPtr List::navigateAbsolute(const Path& path) const
     {
         if (!path.hasElement())
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/List.h b/source/RobotAPI/libraries/aron/core/type/variant/container/List.h
index c739d069449fcbdcc599c0862f44148d806293d0..532146e010bf8217c4669649ee2da9771c0623ec 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/List.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/List.h
@@ -55,7 +55,6 @@ namespace armarx::aron::type
 
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp
index ee9ab1195b302832d096e64e970f6811a840091a..b3bf456051a2bc19095c6b050f88347c72cfbcbf 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp
@@ -54,6 +54,24 @@ namespace armarx::aron::type
         }
     }
 
+    ObjectPtr Object::FromAronObjectDTO(const type::dto::AronObjectPtr& aron)
+    {
+        if (!aron)
+        {
+            return nullptr;
+        }
+        return std::make_shared<Object>(*aron);
+    }
+
+    type::dto::AronObjectPtr Object::ToAronObjectDTO(const ObjectPtr& aron)
+    {
+        if (!aron)
+        {
+            return nullptr;
+        }
+        return aron->toAronObjectDTO();
+    }
+
     bool Object::checkObjectName(const std::string& s) const
     {
         if (s.empty())
@@ -117,7 +135,7 @@ namespace armarx::aron::type
     void Object::setExtends(const std::shared_ptr<Object>& p)
     {
         ARMARX_CHECK_NOT_NULL(p);
-        type::dto::AronObjectPtr ex = p->toObjectDTO();
+        type::dto::AronObjectPtr ex = p->toAronObjectDTO();
         ARMARX_CHECK_NOT_NULL(ex);
         extends = p;
     }
@@ -154,7 +172,7 @@ namespace armarx::aron::type
         return ret;
     }
 
-    type::dto::AronObjectPtr Object::toObjectDTO() const
+    type::dto::AronObjectPtr Object::toAronObjectDTO() const
     {
         // TODO: Shall we allow empty objects? For now yes!
         //if(acceptedTypeNavigators.empty())
@@ -197,13 +215,6 @@ namespace armarx::aron::type
         return "armarx::aron::type::Object<" + this->aron->objectName + (extends ? (" : " + extends->getFullName()) : "") + ">";
     }
 
-    std::string Object::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "TODO!";
-        return ss.str();
-    }
-
     VariantPtr Object::navigateAbsolute(const Path& path) const
     {
         if (!path.hasElement())
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h
index 15a3273a0d7077af1d2ab313e45e13598b598229..094d1f532a357128d329fe52d673c9f7ec248960 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h
@@ -48,6 +48,9 @@ namespace armarx::aron::type
         Object(const std::string&, const std::map<std::string, VariantPtr>& = {}, const Path& = Path());
         Object(const type::dto::AronObject&, const Path& = Path());
 
+        static ObjectPtr FromAronObjectDTO(const type::dto::AronObjectPtr&);
+        static type::dto::AronObjectPtr ToAronObjectDTO(const ObjectPtr&);
+
         // public member functions
         bool checkObjectName(const std::string&) const;
 
@@ -65,14 +68,13 @@ namespace armarx::aron::type
 
         std::vector<std::string> getAllKeys() const;
 
-        type::dto::AronObjectPtr toObjectDTO() const;
+        type::dto::AronObjectPtr toAronObjectDTO() const;
 
         // virtual implementations
         VariantPtr navigateAbsolute(const Path& path) const override;
 
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp
index fb938e302a9fba89bd3be70c1643645db7b7e987..48e0c6f4dea325fc7e58ecc0cede68cbb8138854 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp
@@ -115,13 +115,6 @@ namespace armarx::aron::type
         return "armarx::aron::type::Pair<" + acceptedType1->getFullName() + ", " + acceptedType2->getFullName() + ">";
     }
 
-    std::string Pair::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "TODO!";
-        return ss.str();
-    }
-
     VariantPtr Pair::navigateAbsolute(const Path& path) const
     {
         if (!path.hasElement())
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h
index 9798548d0c95fea7a9568563d4191077cbaec90c..a63f6819406ce2b328e97a4026aeae21127d7b09 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h
@@ -59,7 +59,6 @@ namespace armarx::aron::type
 
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp
index c06d9d1c8ad61053240658f1786ddd8faf75e46a..9fdca45e77972d2e58066e4fe47b0d9b492f9f44 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp
@@ -107,13 +107,6 @@ namespace armarx::aron::type
         return "armarx::aron::type::Tuple<" + simox::alg::to_string(names, ", ") + ">";
     }
 
-    std::string Tuple::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "TODO!";
-        return ss.str();
-    }
-
     VariantPtr Tuple::navigateAbsolute(const Path& path) const
     {
         if (!path.hasElement())
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h
index d17df06b74a59b83176424cbbdf6e23a4692d956..d464f83269d5074e1ec6e759119b433c76de0f7d 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h
@@ -56,7 +56,6 @@ namespace armarx::aron::type
 
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.cpp b/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.cpp
index d425e0af8bf802dc1aebc6f0ae4563bf626eb329..734509d9e3272271c0ca3baece597c6e5b1b8d7a 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.cpp
@@ -111,10 +111,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::IntEnum";
     }
-
-    std::string IntEnum::getDefaultFromString() const
-    {
-        return "0";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.h b/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.h
index 1fd5661e3fde44db8d94d71db13383308e90aeab..cf652d23cfb225d1ba4efde9c7d48af7c0e34966 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/enum/IntEnum.h
@@ -64,6 +64,5 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.cpp
index 4ea9d7c9333cc8bc646cc12a52bc713bf5a6bf68..987a85ce26779811ecba5296eb4743c1022b49f4 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.cpp
@@ -77,10 +77,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Image<" + Pixeltype2String.at(this->aron->pixelType) + ">";
     }
-
-    std::string Image::getDefaultFromString() const
-    {
-        return "TODO!";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.h
index e6bdee312e17b0800827301b26b983d1481b5f84..0b9f9dd0992c79187368a7136b7fa957a42cacae 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Image.h
@@ -53,7 +53,6 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
 
         static const std::map<image::PixelType, std::string> Pixeltype2String;
         static const std::map<std::string, image::PixelType> String2Pixeltype;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.cpp
index f471b23989280e2d479efbcc0910a69dec2dca8b..62eabd986890eb92cd5bf9b050c887ff985da6d6 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.cpp
@@ -104,10 +104,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Matrix<" + std::to_string(this->aron->rows) + ", " + std::to_string(this->aron->cols) + ", " + Elementtype2String.at(this->aron->elementType) + ">";
     }
-
-    std::string Matrix::getDefaultFromString() const
-    {
-        return "TODO!";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.h
index fa2a7cabe82c931d7b87ce377dd589edee132cc1..da9fd537dbcf62f9e17e54b9c42815009d408e8a 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Matrix.h
@@ -57,7 +57,6 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
 
         static const std::map<matrix::ElementType, std::string> Elementtype2String;
         static const std::map<std::string, matrix::ElementType> String2Elementtype;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.cpp
index e30a71b2cdf544bf368918554a105b0c9cc14c71..cbbf517ba53d9e3d50342298b1c34b2652662216 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.cpp
@@ -77,10 +77,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::NDArray";
     }
-
-    std::string NDArray::getDefaultFromString() const
-    {
-        return "TODO!";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.h
index b17f6f7ea68db4182db6ac83eddb96956e639dff..d04d218eb5ce19a1d53b8d1851b00d3a9ba7925a 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/NDArray.h
@@ -56,6 +56,5 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.cpp
index 58b7f948c6b43465cd05671f0d1393d92ad1702c..031fd6f73e7d2f924d8723107325cb16c3b57d46 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.cpp
@@ -52,10 +52,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Orientation";
     }
-
-    std::string Orientation::getDefaultFromString() const
-    {
-        return "TODO!";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.h
index 3a8107a261f2f6804e1e8f0a80de13acbef03a89..b4bebb8ca5e40d782681e88bed6f9bad30afd128 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Orientation.h
@@ -50,6 +50,5 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.cpp
index 8278b017d810244005e21b3c537d965e22136046..10a3473021b616c78cc7e88b2e45dc94226663bb 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.cpp
@@ -75,10 +75,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::PointCloud<" + Voxeltype2String.at(this->aron->voxelType) + ">";
     }
-
-    std::string PointCloud::getDefaultFromString() const
-    {
-        return "TODO!";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.h
index bec4627de7ecf9fa2b2fa707243773b4bf04f281..37d3aacdbed11c396cdc7351f8e7077705f2e2a6 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/PointCloud.h
@@ -54,7 +54,6 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
 
         static const std::map<pointcloud::VoxelType, std::string> Voxeltype2String;
         static const std::map<std::string, pointcloud::VoxelType> String2Voxeltype;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.cpp
index 8ac9dc88699886788a58125198028d1abb81d363..c6965c12ba714ef01242c4e1420a9579ec11aa4e 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.cpp
@@ -52,15 +52,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Pose";
     }
-
-    std::string Pose::getDefaultFromString() const
-    {
-        std::stringstream ss;
-        ss << "0, 0, 0, 0" << "\n";
-        ss << "0, 0, 0, 0" << "\n";
-        ss << "0, 0, 0, 0" << "\n";
-        ss << "0, 0, 0, 0";
-        return ss.str();
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.h
index 20037341ddb6b7928f907efbe5b48a4100c11df7..fa2c1f184799004ab64f875cfe3cb749d743b6c9 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Pose.h
@@ -50,6 +50,5 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.cpp
index 8a169dbf223c7431bf08860e982d85200ee23b0f..68effb684d71d5745e02df03e4a396ac00cc2551 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.cpp
@@ -52,10 +52,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Position";
     }
-
-    std::string Position::getDefaultFromString() const
-    {
-        return "[0, 0, 0]";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.h
index 1ed5a040c521c942e56d412e6e5504d686b5120e..427f0f43a6f5c32dd7b7d16950cbc301de3f309a 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Position.h
@@ -50,6 +50,5 @@ namespace armarx::aron::type
         // virtual implementations
         std::string getShortName() const override;
         std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.cpp b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.cpp
index 4d439844fbefcdfda9567efc91eb5fdd651b85b8..5457ee84421cc570dda07881070f6f9249359b73 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.cpp
@@ -71,10 +71,5 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Quaternion<" + Elementtype2String.at(this->aron->elementType) + ">";
     }
-
-    std::string Quaternion::getDefaultFromString() const
-    {
-        return "[0, 0, 0]";
-    }
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.h b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.h
index 77f181907a092db2959738608da2aae133a2f932..f660702be8c84613877d164763914bcf4cd57bc9 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/ndarray/Quaternion.h
@@ -53,7 +53,6 @@ namespace armarx::aron::type
         // virtual implementations
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
 
         static const std::map<quaternion::ElementType, std::string> Elementtype2String;
         static const std::map<std::string, quaternion::ElementType> String2Elementtype;
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.cpp
index 4ab368a3472a5cadf07319d89ad23f55864dce0e..9eca559042cb6d38e575399b604e51f194f8aec7 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.cpp
@@ -57,9 +57,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Bool";
     }
-
-    std::string Bool::getDefaultFromString() const
-    {
-        return "true|false";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.h
index 104849a7146979ec9c54cadd98aafc8de7e3488f..eac4aeaea068387ba065a98376a64212a2fc2307 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Bool.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.cpp
index 9e2f558b3cb913b0bc71e3b78d2f3c2bae074a97..256e0a61fa70bb46f1580553de206f16ef2fbddd 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.cpp
@@ -57,9 +57,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Double";
     }
-
-    std::string Double::getDefaultFromString() const
-    {
-        return "0.0";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.h
index 998a2cdf7a2063b94067416d002583a0f2937557..17aa98ad764ac8081cfcd2e23aad38f388749d18 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Double.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.cpp
index f98587a18166c76f70d70d081b0de7d2ce1db2d1..3d08b5bdaae4aa689761bb181aee1d688e0dd8a2 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.cpp
@@ -57,9 +57,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Float";
     }
-
-    std::string Float::getDefaultFromString() const
-    {
-        return "0.0";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.h
index 77ff6e4a39f234a369646463fa19f3c8d5324efa..2dedfb1739b6f000baddc8bb13306781a3d34a99 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Float.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.cpp
index 511512cfda190fa912898990e1d8849a25f025ef..b371f53ddf1f82275d334e0752367e01fec57c93 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.cpp
@@ -57,9 +57,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Int";
     }
-
-    std::string Int::getDefaultFromString() const
-    {
-        return "0";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.h
index 6a20a43a458c99649a6974aa4952ded887c27ebd..240cd4a50df8687f8cdba2ff15c040d21ec27fbe 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Int.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.cpp
index 9d945e717e5cc5bb155415694b370dafbab40273..2654a773d6f00f2552e7246007294baa161de1bf 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.cpp
@@ -57,9 +57,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Long";
     }
-
-    std::string Long::getDefaultFromString() const
-    {
-        return "0";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.h
index eca05833e02c6732bb63aa68eefd473604dd49a1..710df1a421e5ff684ac85b70839ff7cff513378e 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Long.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.cpp
index 1ac6a3c0bc490be4959d145b58d414aeef1f71f4..1cced6991fa157d23638241f1e012c2c0e7a4589 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.cpp
@@ -58,9 +58,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::String";
     }
-
-    std::string String::getDefaultFromString() const
-    {
-        return "";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.h
index b5da234237a140b681e47445487a9f2ce46cdbb5..54dedab7b228d2262097d0cbe59675c4f721eb39 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/String.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.cpp b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.cpp
index 1a0e19d856c85ece58c792b31df8ef1a87c10ae6..76ba1e55c0c2d7d65c12760e6c66ef725ffbbd5c 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.cpp
@@ -58,9 +58,4 @@ namespace armarx::aron::type
     {
         return "armarx::aron::type::Time";
     }
-
-    std::string Time::getDefaultFromString() const
-    {
-        return "0";
-    }
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.h b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.h
index d460e792132d6cb759b4457c82f40cceb1ef6aa3..bd92b965d9c280979732d1f8d54389153a13573f 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/primitive/Time.h
@@ -47,6 +47,5 @@ namespace armarx::aron::type
         /* virtual implementations */
         virtual std::string getShortName() const override;
         virtual std::string getFullName() const override;
-        std::string getDefaultFromString() const override;
     };
 }
diff --git a/source/RobotAPI/libraries/skills/provider/Skill.cpp b/source/RobotAPI/libraries/skills/provider/Skill.cpp
index 5cac4402ff144b92bde79a2464a50f7b48e8b4ad..fa68245928b32e12f1f948a786aa8b8af2b9f983 100644
--- a/source/RobotAPI/libraries/skills/provider/Skill.cpp
+++ b/source/RobotAPI/libraries/skills/provider/Skill.cpp
@@ -4,34 +4,85 @@ namespace armarx
 {
     namespace skills
     {
-        Skill::Skill()
+        Skill::Skill(const SkillDescription& desc):
+            description(desc)
         {
             // replace constructor if you want to have a specific logging tag
-            Logging::setTag("armarx::skills::Skill");
+            Logging::setTag("armarx::skills::" + description.skillName);
         }
 
-        Skill::Status Skill::execute(const aron::data::DictPtr& params, const CallbackT& callback)
+        std::thread Skill::installTimeoutCondition()
+        {
+            // start timeout check
+            return std::thread{ [&](){
+                    if (description.timeoutMs <= 0) return;
+                    long skillStartedAt = IceUtil::Time::now().toMilliSeconds();
+                    while(running)
+                    {
+                        auto now = IceUtil::Time::now().toMilliSeconds();
+                        if ((now - skillStartedAt) >= description.timeoutMs) notifyTimeoutReached();
+                        std::this_thread::sleep_for(std::chrono::milliseconds(100));
+                    }
+                }
+            };
+        }
+
+        void Skill::notifyTimeoutReached()
+        {
+            timeoutReached = true;
+            _notifyTimeoutReached();
+        }
+
+        void Skill::notifyStopped()
+        {
+            stopped = true;
+            _notifyStopped();
+        }
+
+        void Skill::_notifyTimeoutReached()
+        {
+
+        }
+
+        void Skill::_notifyStopped()
         {
-            (void) params;
 
-            ARMARX_WARNING_S << "You have to override this method!";
-            return Status::Succeeded;
         }
 
         void Skill::reset()
         {
             stopped = false;
             timeoutReached = false;
+
+            _reset();
         }
 
-        void Skill::notifyStopped()
+        void Skill::_reset()
         {
-            stopped = true;
+
         }
 
-        void Skill::notifyTimeoutReached()
+        Skill::Status Skill::execute(const aron::data::DictPtr& params, const CallbackT& callback)
         {
-            timeoutReached = true;
+            running = true;
+            started = IceUtil::Time::now().toMilliSeconds();
+
+            auto timeoutCheck = installTimeoutCondition();
+
+            auto ret = _execute(params, callback);
+
+            started = 0;
+            running = false;
+            timeoutCheck.join(); // safely wait for the timeoutcheck to return
+            return ret;
+        }
+
+        Skill::Status Skill::_execute(const aron::data::DictPtr& params, const CallbackT& callback)
+        {
+            (void) params;
+
+            ARMARX_WARNING_S << "You have to override this method!";
+            return Status::Succeeded;
         }
 
     }
diff --git a/source/RobotAPI/libraries/skills/provider/Skill.h b/source/RobotAPI/libraries/skills/provider/Skill.h
index 27a2c6089bdab93ad11a77fbcb8c9c25a50eebdf..a4bf8ba687d332e2598c728e7f77be053d93e884 100644
--- a/source/RobotAPI/libraries/skills/provider/Skill.h
+++ b/source/RobotAPI/libraries/skills/provider/Skill.h
@@ -13,6 +13,8 @@
 #include <RobotAPI/interface/skills/SkillManagerInterface.h>
 #include <RobotAPI/libraries/aron/core/data/variant/All.h>
 
+#include "SkillDescription.h"
+
 namespace armarx
 {
     namespace skills
@@ -26,22 +28,45 @@ namespace armarx
             {
                 Succeeded,
                 TimeoutReached,
+                Stopped,
                 Failed
             };
 
-            Skill();
+            Skill() = delete;
+            Skill(const SkillDescription&);
             virtual ~Skill() = default;
 
-            virtual void notifyStopped();
-            virtual void notifyTimeoutReached();
+            /// Execute Skill
+            Status execute(const aron::data::DictPtr& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; });
+
+            /// Reset all parameters before starting a skill.
+            void reset();
+
+            /// Set the notification bools
+            void notifyTimeoutReached();
+            void notifyStopped();
 
             /// Override this method with the actual implementation. The callback is for status updates to the calling instance
-            virtual Status execute(const aron::data::DictPtr& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; });
+            virtual Status _execute(const aron::data::DictPtr& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; });
+
+            /// Override if you have special members that needs to be resetted
+            virtual void _reset();
 
-            /// Reset all parameters before starting a skill. Override if you have special members that needs to be resetted
-            virtual void reset();
+            /// Override these methods if you want to do something special when notification comes
+            virtual void _notifyTimeoutReached();
+            virtual void _notifyStopped();
+
+        private:
+            /// install a condition as a seperate thread
+            std::thread installTimeoutCondition();
+
+        public:
+            const SkillDescription description;
+            std::atomic_bool running = false;
+            long started = 0;
 
         protected:
+            /// Use conditions during runtime this way
             std::atomic_bool stopped = false;
             std::atomic_bool timeoutReached = false;
         };
diff --git a/source/RobotAPI/libraries/skills/provider/SkillDescription.cpp b/source/RobotAPI/libraries/skills/provider/SkillDescription.cpp
index 844249f0e46f5075d044ed0bb4bb8cffc75b0846..5295057bec7d1ace202d9ac1245306542848d6f9 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillDescription.cpp
+++ b/source/RobotAPI/libraries/skills/provider/SkillDescription.cpp
@@ -7,10 +7,7 @@ namespace armarx
         provider::dto::SkillDescription SkillDescription::toIce() const
         {
             provider::dto::SkillDescription ret;
-            if (acceptedType)
-            {
-                ret.acceptedType = acceptedType->toObjectDTO();
-            }
+            ret.acceptedType = aron::type::Object::ToAronObjectDTO(acceptedType);
             ret.description = description;
             ret.skillName = skillName;
             ret.targets = targets;
diff --git a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
index 30bbcc86a9764465dedaa63b314aa3da4ae8c451..c471f140cc312952e960a922ea26be50996eb260 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
@@ -52,35 +52,40 @@ namespace armarx
         addPlugin(plugin);
     }
 
-    void SkillProviderComponentPluginUser::addSkill(const std::shared_ptr<skills::Skill>& skill, const skills::SkillDescription& desc)
+    void SkillProviderComponentPluginUser::addSkill(const std::shared_ptr<skills::Skill>& skill)
     {
+        if (!skill)
+        {
+            return;
+        }
+
         std::lock_guard l(skillsMutex);
-        std::string skillName = desc.skillName;
 
+        std::string skillName = skill->description.skillName;
         if (skillImplementations.find(skillName) != skillImplementations.end())
         {
-            ARMARX_WARNING << "Try to add a skill '" + skillName + "' which already exists in list. Ignore this skill.";
+            ARMARX_WARNING << "Try to add a skill '" + skillName + "' which already exists in list. Ignoring this skill.";
             return;
         }
 
-        ARMARX_DEBUG << "Adding skill " << skillName << " to list";
-        skills::detail::SkillImplementationWrapper s(desc, skill);
+        ARMARX_INFO << "Adding skill " << skillName;
+        skills::detail::SkillImplementationWrapper s(skill);
         skillImplementations.insert({skillName, s});
     }
 
     void SkillProviderComponentPluginUser::addSkill(const skills::helper::LambdaSkill::FunT& f, const skills::SkillDescription& desc)
     {
-        auto lambda = std::make_shared<skills::helper::LambdaSkill>(f);
-        addSkill(lambda, desc);
+        auto lambda = std::make_shared<skills::helper::LambdaSkill>(f, desc);
+        addSkill(lambda);
     }
 
     skills::provider::dto::SkillDescriptionMap SkillProviderComponentPluginUser::getSkills(const Ice::Current &current)
     {
         std::lock_guard l(skillsMutex);
         skills::provider::dto::SkillDescriptionMap skillDesciptions;
-        for (const auto& [key, skillImplementation] : skillImplementations)
+        for (const auto& [key, skillWrapper] : skillImplementations)
         {
-            skillDesciptions.insert({key, skillImplementation.description.toIce()});
+            skillDesciptions.insert({key, skillWrapper.skill->description.toIce()});
         }
         return skillDesciptions;
     }
@@ -88,10 +93,10 @@ namespace armarx
     skills::provider::dto::SkillStatusUpdate SkillProviderComponentPluginUser::getSkillExecutionStatus(const std::string& skill, const Ice::Current &current)
     {
         std::lock_guard l(skillsMutex);
-        auto& skillImplementation = skillImplementations.at(skill);
+        auto& skillWrapper = skillImplementations.at(skill);
 
-        std::lock_guard l2(skillImplementation.statusInfo.skillStatusMutex);
-        return skillImplementation.statusInfo.statusUpdate.toIce();
+        std::lock_guard l2(skillWrapper.skillStatusMutex);
+        return skillWrapper.statusUpdate.toIce();
     }
 
     void SkillProviderComponentPluginUser::executeSkill(const skills::provider::dto::SkillExecutionInfo& info, const Ice::Current &current)
@@ -100,38 +105,21 @@ namespace armarx
         std::string skillName = info.skillName;
         ARMARX_CHECK_EXPRESSION(skillImplementations.count(skillName) > 0);
 
-        auto& impl = skillImplementations.at(skillName);
-
-        if (impl.task.joinable())
+        auto& wrapper = skillImplementations.at(skillName);
+        if (wrapper.task.joinable())
         {
-            impl.task.join();
-        }
-        if (impl.timeoutCheck.joinable())
-        {
-            impl.timeoutCheck.join();
-        }
-        if (impl.stoppedCheck.joinable())
-        {
-            impl.stoppedCheck.join();
+            wrapper.task.join();
         }
 
         // update input params
-        impl.reset();
-        impl.statusInfo.statusUpdate.usedCallbackInterface = info.callbackInterface;
-        impl.statusInfo.statusUpdate.skillName = info.skillName;
-        impl.statusInfo.statusUpdate.providerName = getName();
-        if (info.params)
-        {
-            impl.statusInfo.statusUpdate.usedParameterization = std::make_shared<aron::data::Dict>(info.params);
-        }
-
-        // make sure thread is started
-        impl.statusInfo.started = true;
-
-        // recreate thread and execute skill
-        impl.timeoutCheck = std::thread{ [&](){ impl.constantlyCheckForTimeoutReached();}};
-        impl.stoppedCheck = std::thread{ [&](){ impl.constantlyCheckForStopped();}};
-        impl.task = std::thread{ [&] { impl.execute();}};
+        wrapper.reset();
+        wrapper.statusUpdate.usedCallbackInterface = info.callbackInterface;
+        wrapper.statusUpdate.skillName = info.skillName;
+        wrapper.statusUpdate.providerName = getName();
+        wrapper.statusUpdate.usedParameterization = aron::data::Dict::FromAronDictDTO(info.params);
+
+        // recreate thread and execute skill.
+        wrapper.task = std::thread{ [&] { wrapper.execute();}};
     }
 
     skills::provider::dto::SkillStatusUpdate SkillProviderComponentPluginUser::abortSkill(const std::string& skillName, const Ice::Current &current)
@@ -139,33 +127,16 @@ namespace armarx
         std::lock_guard l(skillsMutex);
         ARMARX_CHECK_EXPRESSION(skillImplementations.count(skillName) > 0);
 
-        auto& impl = skillImplementations.at(skillName);
-        auto& statusInfo = impl.statusInfo;
+        auto& wrapper = skillImplementations.at(skillName);
 
-        std::lock_guard l2(statusInfo.skillStatusMutex);
-        auto& statusUpdate = statusInfo.statusUpdate;
-
-        impl.statusInfo.stopped = true;
-        impl.statusInfo.started = false;
-        if (impl.task.joinable())
-        {
-            impl.task.join();
-        }
-        if (impl.timeoutCheck.joinable())
-        {
-            impl.timeoutCheck.join();
-        }
-        if (impl.stoppedCheck.joinable())
-        {
-            impl.stoppedCheck.join();
-        }
+        std::lock_guard l2(wrapper.skillStatusMutex);
 
-        if (statusUpdate.status != skills::provider::dto::Execution::Status::Succeeded &&
-                statusUpdate.status != skills::provider::dto::Execution::Status::Failed)
+        if (wrapper.skill->running)
         {
-            impl.statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Aborted;
+            wrapper.skill->notifyStopped();
+            wrapper.task.join();
         }
 
-        return statusUpdate.toIce();
+        return wrapper.statusUpdate.toIce();
     }
 }
diff --git a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
index 14b3ce55ec587254aa8d2627231266453ac9d4f3..7e370346cbd8d49f4ec2ac96e638ab85ea23fcea 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
+++ b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
@@ -54,7 +54,7 @@ namespace armarx
 
     protected:
         void addSkill(const skills::helper::LambdaSkill::FunT&, const skills::SkillDescription&);
-        void addSkill(const std::shared_ptr<skills::Skill>&, const skills::SkillDescription&);
+        void addSkill(const std::shared_ptr<skills::Skill>&);
 
     private:
         armarx::plugins::SkillProviderComponentPlugin* plugin = nullptr;
diff --git a/source/RobotAPI/libraries/skills/provider/SkillStatusUpdate.cpp b/source/RobotAPI/libraries/skills/provider/SkillStatusUpdate.cpp
index f19d037dc3c24993f2a87d651121e2855128041e..cfc9f6fd218acc22e618e5ab264078af053f71da 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillStatusUpdate.cpp
+++ b/source/RobotAPI/libraries/skills/provider/SkillStatusUpdate.cpp
@@ -9,13 +9,10 @@ namespace armarx
             provider::dto::SkillStatusUpdate ret;
             ret.providerName = providerName;
             ret.skillName = skillName;
-            if (data)
-            {
-                ret.data = data->toAronDictPtr();
-            }
+            ret.data = aron::data::Dict::ToAronDictDTO(data);
             ret.status = status;
             ret.usedCallbackInterface = usedCallbackInterface;
-            ret.usedParams = usedParameterization->toAronDictPtr();
+            ret.usedParams = aron::data::Dict::ToAronDictDTO(usedParameterization);
             return ret;
         }
     }
diff --git a/source/RobotAPI/libraries/skills/provider/SpecializedSkill.h b/source/RobotAPI/libraries/skills/provider/SpecializedSkill.h
index e3606ef526d18f1aa326c6ca60009b0b47de691d..a1b617a49700fc57f97e904c79de2882d3b6b690 100644
--- a/source/RobotAPI/libraries/skills/provider/SpecializedSkill.h
+++ b/source/RobotAPI/libraries/skills/provider/SpecializedSkill.h
@@ -2,6 +2,11 @@
 
 #include "Skill.h"
 
+#include <RobotAPI/libraries/aron/core/type/variant/container/Object.h>
+
+// Debug
+#include <RobotAPI/libraries/aron/converter/json/NLohmannJSONConverter.h>
+
 namespace armarx
 {
     namespace skills
@@ -13,8 +18,14 @@ namespace armarx
             using Skill::Skill;
             virtual ~SpecializedSkill() = default;
 
+            /// returns the accepted type of the skill
+            static armarx::aron::type::ObjectPtr GetAcceptedType()
+            {
+                return AronT::toAronType();
+            }
+
             /// Override this method with the actual implementation. The callback is for status updates to the calling instance
-            virtual Status execute(const AronT& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; })
+            virtual Status _execute(const AronT& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; })
             {
                 (void) params;
 
@@ -23,12 +34,13 @@ namespace armarx
             }
 
             /// Do not use anymore
-            Status execute(const aron::data::DictPtr& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; }) final
+            Status _execute(const aron::data::DictPtr& params, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; }) final
             {
                 AronT p;
+                //ARMARX_IMPORTANT << aron::converter::AronNlohmannJSONConverter::ConvertToNlohmannJSON(params).dump(2);
                 p.fromAron(params);
 
-                return execute(p, callback);
+                return _execute(p, callback);
             }
         };
     }
diff --git a/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.cpp b/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.cpp
index 4160489c075261afaf522f8c9b311ea349f7ebb6..9f9c573b80df17e055baa37737f3f1dc86e4997a 100644
--- a/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.cpp
+++ b/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.cpp
@@ -4,126 +4,96 @@ namespace armarx
 {
     namespace skills::detail
     {
-        void SkillImplementationWrapper::constantlyCheckForTimeoutReached() const
-        {
-            while(statusInfo.started)
-            {
-                if (isTimeoutReached())
-                {
-                    skill->notifyTimeoutReached();
-                    break; // only notify once?
-                }
-            }
-            std::this_thread::sleep_for(std::chrono::milliseconds(100));
-        }
-
-        void SkillImplementationWrapper::constantlyCheckForStopped() const
-        {
-            while(statusInfo.started)
-            {
-                if (statusInfo.stopped)
-                {
-                    skill->notifyStopped();
-                    break; // only notify once?
-                }
-            }
-            std::this_thread::sleep_for(std::chrono::milliseconds(100));
-        }
-
         void SkillImplementationWrapper::reset()
         {
-            std::lock_guard l(statusInfo.skillStatusMutex);
-            statusInfo.started = false;
-            statusInfo.stopped = false;
-            statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Idle;
-            statusInfo.statusUpdate.data = nullptr;
-            skillStarted = IceUtil::Time::now().toMilliSeconds();
+            ARMARX_CHECK_NOT_NULL(skill);
+            std::lock_guard l(skillStatusMutex);
+            statusUpdate.status = skills::provider::dto::Execution::Status::Idle;
+            statusUpdate.data = nullptr;
             skill->reset();
         }
 
         void SkillImplementationWrapper::execute()
         {
-            ARMARX_INFO_S << "Executing skill: " << description.skillName;
-            statusInfo.started = true;
+            ARMARX_CHECK_NOT_NULL(skill);
+            std::lock_guard l(executingMutex);
+
+            const std::string skillName = skill->description.skillName;
+            ARMARX_INFO_S << "Executing skill: " << skillName;
 
             // get params and setup variables
-            auto& aron_params = statusInfo.statusUpdate.usedParameterization;
-            if (not(aron_params) && description.acceptedType)
-            {
-                throw armarx::LocalException("The Skill '" + description.skillName + "' requires a type but no params are NULL.");
-            }
+            auto& aron_params = statusUpdate.usedParameterization;
 
             try
             {
-                // set scheduled
+                // Check params
+                if (not(aron_params) && skill->description.acceptedType)
                 {
-                    std::lock_guard l(statusInfo.skillStatusMutex);
-                    statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Scheduled;
-
-                    // do callback
-                    updateStatusCallback();
+                    throw armarx::LocalException("The Skill '" + skillName + "' requires a type but no params are NULL.");
                 }
 
-
-                // execute
+                // set scheduled
                 {
-                    std::lock_guard l(statusInfo.skillStatusMutex);
-                    statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Running;
-                    updateStatusCallback();
+                    std::lock_guard l(skillStatusMutex);
+                    statusUpdate.status = skills::provider::dto::Execution::Status::Scheduled;
+                    updateStatus();
                 }
 
-                auto result = skill->execute(aron_params, [&](const aron::data::DictPtr& update)
-                                {
-                                    statusInfo.statusUpdate.data = update;
-                                    updateStatusCallback();
-                                }
-                );
 
-                if (result == skills::Skill::Status::Failed)
+                // execute
                 {
-                    throw armarx::LocalException("The Skill '"+description.skillName+"' failed during execution.");
+                    std::lock_guard l(skillStatusMutex);
+                    statusUpdate.status = skills::provider::dto::Execution::Status::Running;
+                    updateStatus();
                 }
-                if (result == skills::Skill::Status::TimeoutReached)
+
+                auto execution_callback = [&](const aron::data::DictPtr& update)
                 {
-                    throw armarx::LocalException("The Skill '"+description.skillName+"' reached timeout during execution.");
-                }
+                    statusUpdate.data = update;
+                    updateStatus();
+                };
+                auto result = skill->execute(aron_params, execution_callback);
 
+                switch (result)
                 {
-                    std::lock_guard l(statusInfo.skillStatusMutex);
-                    statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Succeeded;
-                    updateStatusCallback();
+                    case skills::Skill::Status::Failed:
+                        throw armarx::LocalException("The Skill '" + skillName + "' failed during execution.");
+                        break;
+                    case skills::Skill::Status::TimeoutReached:
+                        throw armarx::LocalException("The Skill '" + skillName + "' reached timeout during execution.");
+                        break;
+                    case skills::Skill::Status::Stopped:
+                    {
+                        std::lock_guard l(skillStatusMutex);
+                        statusUpdate.status = skills::provider::dto::Execution::Status::Aborted;
+                        updateStatus();
+                        break;
+                    }
+                    default:
+                    {
+                        std::lock_guard l(skillStatusMutex);
+                        statusUpdate.status = skills::provider::dto::Execution::Status::Succeeded;
+                        updateStatus();
+                    }
                 }
             }
             catch (const std::exception& ex)
             {
-                ARMARX_WARNING_S << "Skill " << description.skillName << " died with exception:\n" << ex.what();
-
-                std::lock_guard l(statusInfo.skillStatusMutex);
-                statusInfo.statusUpdate.status = skills::provider::dto::Execution::Status::Failed;
-                updateStatusCallback();
-            }
-
-            statusInfo.started = false;
-        }
+                ARMARX_WARNING_S << "Skill " << skillName << " died with exception:\n" << ex.what();
 
-        bool SkillImplementationWrapper::isTimeoutReached() const
-        {
-            if (description.timeoutMs < 0)
-            {
-                return false;
+                std::lock_guard l(skillStatusMutex);
+                statusUpdate.status = skills::provider::dto::Execution::Status::Failed;
+                updateStatus();
             }
-
-            auto now = IceUtil::Time::now().toMilliSeconds();
-            return (now - skillStarted) >= description.timeoutMs;
         }
 
-        void SkillImplementationWrapper::updateStatusCallback() const
+        void SkillImplementationWrapper::updateStatus() const
         {
-            auto& callbackInterface = statusInfo.statusUpdate.usedCallbackInterface;
+            auto& callbackInterface = statusUpdate.usedCallbackInterface;
 
             if (callbackInterface)
             {
-                callbackInterface->updateStatusForSkill(statusInfo.statusUpdate.toIce());
+                callbackInterface->updateStatusForSkill(statusUpdate.toIce());
             }
         }
     }
diff --git a/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.h b/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.h
index 24a8637b44f634734e8ffba20809ecadf9a493ce..35910a968a66026b5eff1399b133484adef1437a 100644
--- a/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.h
+++ b/source/RobotAPI/libraries/skills/provider/detail/SkillImplementationWrapper.h
@@ -16,47 +16,32 @@ namespace armarx
             {
             public:
                 // fixed values. Do not change after skill instantiation
-                const SkillDescription description;
                 const std::shared_ptr<Skill> skill;
 
                 // Current execution status. Changes during execution
                 // The status also holds the used parameterization
-                struct StatusInfo
-                {
-                    mutable std::mutex skillStatusMutex;
-                    std::atomic_bool started;
-                    std::atomic_bool stopped;
-                    SkillStatusUpdate statusUpdate;
-                } statusInfo;
+                mutable std::mutex skillStatusMutex;
+                SkillStatusUpdate statusUpdate;
 
                 // Task information. task is recreated every time the skill restarts
+                mutable std::mutex executingMutex;
                 std::thread task;
-                std::thread timeoutCheck;
-                std::thread stoppedCheck;
 
-                SkillImplementationWrapper(const skills::SkillDescription& desc, const std::shared_ptr<skills::Skill> skill) :
-                    description(desc), skill(skill)
+                SkillImplementationWrapper(const std::shared_ptr<skills::Skill> skill) :
+                    skill(skill)
                 {
                     reset();
                 }
 
                 SkillImplementationWrapper(const SkillImplementationWrapper& s) :
-                    SkillImplementationWrapper(s.description, s.skill)
+                    SkillImplementationWrapper(s.skill)
                 {}
 
                 void execute();
                 void reset();
 
-                // checks for interrupts
-                void constantlyCheckForTimeoutReached() const;
-                void constantlyCheckForStopped() const;
-
             protected:
-                bool isTimeoutReached() const;
-                void updateStatusCallback() const;
-
-            private:
-                long skillStarted = 0;
+                void updateStatus() const;
             };
         }
     }
diff --git a/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.cpp b/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.cpp
index 9b761b403f51552235b690d601137ff1c11a002b..59d51cd16b66a4799f25e0503d2c987bea7ab4cc 100644
--- a/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.cpp
+++ b/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.cpp
@@ -5,7 +5,7 @@ namespace armarx
     namespace skills::helper
     {
 
-        Skill::Status LambdaSkill::execute(const aron::data::DictPtr& data, const CallbackT& callback)
+        Skill::Status LambdaSkill::_execute(const aron::data::DictPtr& data, const CallbackT& callback)
         {
             (void) callback;
             bool res = fun(data);
diff --git a/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.h b/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.h
index bb422b1bda029935f54ac94bd7cca0289ac799e0..27e1ab0aea43127441d7b4798207433bd7549783 100644
--- a/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.h
+++ b/source/RobotAPI/libraries/skills/provider/helper/LambdaSkillImplementation.h
@@ -12,9 +12,13 @@ namespace armarx
             using FunT = std::function<bool(const aron::data::DictPtr&)>;
 
             LambdaSkill() = delete;
-            LambdaSkill(const FunT& f) : fun(f) {};
+            LambdaSkill(const FunT& f, const SkillDescription& desc) :
+                Skill(desc),
+                fun(f)
+            {};
 
-            Skill::Status execute(const aron::data::DictPtr& data, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; }) override;
+        protected:
+            Skill::Status _execute(const aron::data::DictPtr& data, const CallbackT& callback = [](const aron::data::DictPtr& returnValue) { (void) returnValue; }) override;
 
         private:
             FunT fun;