diff --git a/scenarios/AronComponentConfigExample/config/AronComponentConfigExample.cfg b/scenarios/AronComponentConfigExample/config/AronComponentConfigExample.cfg
index dcf2233099e0acef6a620567979cc71e1da2cc29..c5122a357453ce2b9cc050e4a8a5a862534e4002 100644
--- a/scenarios/AronComponentConfigExample/config/AronComponentConfigExample.cfg
+++ b/scenarios/AronComponentConfigExample/config/AronComponentConfigExample.cfg
@@ -60,152 +60,200 @@
 # ArmarX.ComponentConfigTest.RemoteGuiName = RemoteGuiProvider
 
 
-# ArmarX.ComponentConfigTest.boolMember:  
+# ArmarX.ComponentConfigTest.TestConfig.boolMember:  
 #  Attributes:
 #  - Default:            true
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ComponentConfigTest.boolMember = true
+# ArmarX.ComponentConfigTest.TestConfig.boolMember = true
 
 
-# ArmarX.ComponentConfigTest.floatMember:  
+# ArmarX.ComponentConfigTest.TestConfig.floatMember:  
 #  Attributes:
 #  - Default:            100
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.floatMember = 100
+# ArmarX.ComponentConfigTest.TestConfig.floatMember = 100
 
 
-# ArmarX.ComponentConfigTest.intMember:  
+# ArmarX.ComponentConfigTest.TestConfig.intMember:  
 #  Attributes:
 #  - Default:            1000
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.intMember = 1000
+# ArmarX.ComponentConfigTest.TestConfig.intMember = 1000
 
 
-# ArmarX.ComponentConfigTest.stringMember:  
+# ArmarX.ComponentConfigTest.TestConfig.orientation.header.agent:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.orientation.header.agent = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.orientation.header.frame:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.orientation.header.frame = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.pose.header.agent:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.pose.header.agent = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.pose.header.frame:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.pose.header.frame = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.position.header.agent:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.position.header.agent = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.position.header.frame:  
+#  Attributes:
+#  - Default:            ""
+#  - Case sensitivity:   yes
+#  - Required:           no
+# ArmarX.ComponentConfigTest.TestConfig.position.header.frame = ""
+
+
+# ArmarX.ComponentConfigTest.TestConfig.stringMember:  
 #  Attributes:
 #  - Default:            initial
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.stringMember = initial
+# ArmarX.ComponentConfigTest.TestConfig.stringMember = initial
 
 
-# ArmarX.ComponentConfigTest.subMember.boolMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.boolMember:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ComponentConfigTest.subMember.boolMember = false
+# ArmarX.ComponentConfigTest.TestConfig.subMember.boolMember = false
 
 
-# ArmarX.ComponentConfigTest.subMember.doubleMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.doubleMember:  
 #  Attributes:
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.doubleMember = 0
+# ArmarX.ComponentConfigTest.TestConfig.subMember.doubleMember = 0
 
 
-# ArmarX.ComponentConfigTest.subMember.floatMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.floatMember:  
 #  Attributes:
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.floatMember = 0
+# ArmarX.ComponentConfigTest.TestConfig.subMember.floatMember = 0
 
 
-# ArmarX.ComponentConfigTest.subMember.intMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.intMember:  
 #  Attributes:
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.intMember = 0
+# ArmarX.ComponentConfigTest.TestConfig.subMember.intMember = 0
 
 
-# ArmarX.ComponentConfigTest.subMember.stringMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.stringMember:  
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.stringMember = ""
+# ArmarX.ComponentConfigTest.TestConfig.subMember.stringMember = ""
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.boolMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.boolMember:  
 #  Attributes:
 #  - Default:            false
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {0, 1, false, no, true, yes}
-# ArmarX.ComponentConfigTest.subMember.subsubMember.boolMember = false
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.boolMember = false
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.enumMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.enumMember:  
 #  Attributes:
 #  - Default:            1
 #  - Case sensitivity:   yes
 #  - Required:           no
 #  - Possible values: {Bar, Baz, Foo, Qux}
-# ArmarX.ComponentConfigTest.subMember.subsubMember.enumMember = 1
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.enumMember = 1
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.floatMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.floatMember:  
 #  Attributes:
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.floatMember = 0
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.floatMember = 0
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.intDictMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intDictMember:  
 #  Attributes:
 #  - Default:            int1:1,int2:2
 #  - Case sensitivity:   yes
 #  - Required:           no
-ArmarX.ComponentConfigTest.subMember.subsubMember.intDictMember = int1:1,int2:2,int3:3,int5:4
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intDictMember = int1:1,int2:2
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.intListMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intListMember:  
 #  Attributes:
 #  - Default:            1, 2, 3, 4, 5, 6
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.intListMember = 1, 2, 3, 4, 5, 6
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intListMember = 1, 2, 3, 4, 5, 6
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.intMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intMember:  
 #  Attributes:
 #  - Default:            0
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.intMember = 0
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.intMember = 0
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringDictMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringDictMember:  
 #  Attributes:
 #  - Default:            string1:blub,string2:duh
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringDictMember = string1:blub,string2:duh
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringDictMember = string1:blub,string2:duh
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringListMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringListMember:  
 #  Attributes:
 #  - Default:            a, b, c, d, e
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringListMember = a, b, c, d, e
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringListMember = a, b, c, d, e
 
 
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringMember:  
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringMember:  
 #  Attributes:
 #  - Default:            ""
 #  - Case sensitivity:   yes
 #  - Required:           no
-# ArmarX.ComponentConfigTest.subMember.subsubMember.stringMember = ""
+# ArmarX.ComponentConfigTest.TestConfig.subMember.subsubMember.stringMember = ""
 
 
 # ArmarX.Config:  Comma-separated list of configuration files 
diff --git a/source/RobotAPI/applications/AronCodeGenerator/main.cpp b/source/RobotAPI/applications/AronCodeGenerator/main.cpp
index 8544c238abca345b587f78737198d6e5e51e7de6..05185cc8d7c1a244a9797668f91481a8d2357d5e 100644
--- a/source/RobotAPI/applications/AronCodeGenerator/main.cpp
+++ b/source/RobotAPI/applications/AronCodeGenerator/main.cpp
@@ -177,58 +177,95 @@ int main(int argc, char* argv[])
             }
         }
 
+        std::time_t current_time = std::time(0);
+        std::tm* now = std::localtime(&current_time);
+        std::string current_year = std::to_string(now->tm_year + 1900);
+
+        std::string fileDoc = std::string("* This file is part of ArmarX. \n") +
+"* \n" +
+"* Copyright (C) 2012-" + current_year + ", High Performance Humanoid Technologies (H2T), \n" +
+"* Karlsruhe Institute of Technology (KIT), all rights reserved. \n" +
+"* \n" +
+"* ArmarX is free software; you can redistribute it and/or modify \n" +
+"* it under the terms of the GNU General Public License version 2 as \n" +
+"* published by the Free Software Foundation. \n" +
+"* \n" +
+"* ArmarX is distributed in the hope that it will be useful, but \n" +
+"* WITHOUT ANY WARRANTY; without even the implied warranty of \n" +
+"* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the \n" +
+"* GNU General Public License for more details. \n" +
+"* \n" +
+"* You should have received a copy of the GNU General Public License \n" +
+"* along with this program. If not, see <http://www.gnu.org/licenses/>. \n" +
+"* \n" +
+"* @copyright  http://www.gnu.org/licenses/gpl-2.0.txt \n" +
+"*             GNU General Public License \n" +
+"* *********************************************************************** \n" +
+"* WARNING: This file is autogenerated. \n" +
+"* Original file: " + filename + " \n" +
+"* Please do not edit since your changes may be overwritten on the next generation \n" +
+"* If you have any questions please contact: Fabian Peller-Konrad (fabian dot peller-konrad at kit dot edu) \n" +
+"* ***********************************************************************";
+
+        auto w = CppWriterPtr(new CppWriter(true, fileDoc));
+        w->header.line();
+        w->header.line();
+
+        // Generate enums at top of generated header file
+        std::vector<MetaEnumPtr> enums = writer.getTypeEnums();
+        if (verbose)
+        {
+            std::cout << "Now exporting enums..." << std::endl;
+        }
+
+        w->body.line("/*************************************************************************");
+        w->body.line(" * ALL GENERATED ENUMS ***************************************************");
+        w->body.line(" ************************************************************************/");
+        MetaEnum::Write(enums, w);
+        w->body.line();
+        w->body.line();
+
+        std::string enum_file_generation_content = w->getString();
+
+        if (verbose)
+        {
+            std::cout << "Now exporting enums... done!" << std::endl;
+        }
+
+        if (enums.size() > 0 && enum_file_generation_content == "")
+        {
+            std::cerr << "\033[31m" << "Error code 11 - Found error in code generation. Aborting!" << "\033[0m" << std::endl;
+            exit(1);
+        }
+
+        // Generate all classes
         std::vector<MetaClassPtr> classes = writer.getTypeClasses();
         if (verbose)
         {
             std::cout << "Now exporting classes..." << std::endl;
         }
 
-        auto w = CppWriterPtr(new CppWriter());
+        w->body.line("/* ************************************************************************");
+        w->body.line(" * ALL GENERATED CLASSES *************************************************");
+        w->body.line(" * ***********************************************************************/");
         CppClass::Write(classes, w);
+        w->body.line();
+        w->body.line();
 
-        std::string new_file_content = w->getString();
+        std::string class_file_generation_content = simox::alg::remove_prefix(w->getString(), enum_file_generation_content);
 
         if (verbose)
         {
             std::cout << "Now exporting classes... done!" << std::endl;
         }
 
-        if (new_file_content == "")
+        if (classes.size() > 0 && class_file_generation_content == "")
         {
-            std::cerr << "Found error in code generation. Aborting!" << std::endl;
+            std::cerr << "\033[31m" << "Error code 21 - Found error in code generation. Aborting!" << "\033[0m" << std::endl;
             exit(1);
         }
 
-        std::string new_file_header = "\
-/* \n\
- * This file is part of ArmarX. \n\
- * \n\
- * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), \n\
- * Karlsruhe Institute of Technology (KIT), all rights reserved. \n\
- * \n\
- * ArmarX is free software; you can redistribute it and/or modify \n\
- * it under the terms of the GNU General Public License version 2 as \n\
- * published by the Free Software Foundation. \n\
- * \n\
- * ArmarX is distributed in the hope that it will be useful, but \n\
- * WITHOUT ANY WARRANTY; without even the implied warranty of \n\
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the \n\
- * GNU General Public License for more details. \n\
- * \n\
- * You should have received a copy of the GNU General Public License \n\
- * along with this program. If not, see <http://www.gnu.org/licenses/>. \n\
- * \n\
- * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt \n\
- *             GNU General Public License \n\
- ************************************************************************* \n\
- * WARNING: This file is autogenerated. \n\
- * Original file: " + filename + " \n\
- * Please do not edit since your changes may be overwritten on the next generation \n\
- * If you have any questions please contact: Fabian Peller-Konrad (fabian dot peller-konrad at kit dot edu) \n\
- ************************************************************************* \n\
- */\n\n\n";
-
-        std::string new_file_full_content = new_file_header + new_file_content;
+        std::string new_file_full_content = w->getString();
 
         std::string new_name_with_extension = input_file.filename().replace_extension("").string();
         new_name_with_extension += ".aron.generated.h";
@@ -247,7 +284,7 @@ int main(int argc, char* argv[])
                 {
                     if (verbose)
                     {
-                        std::cout << "File content not changed for <" + output_file.string() + ">" << std::endl;
+                        std::cout << "\033[31m" << "Error code 31 - File content not changed for <" + output_file.string() + ">" << "\033[0m" << std::endl;
                     }
                     exit(0);
                 }
@@ -261,12 +298,12 @@ int main(int argc, char* argv[])
 
         if (verbose)
         {
-            std::cout << "Finished generating <" + output_file.string() + ">. The new file ist called <" << output_file.string() << ">" << std::endl;
+            std::cout << "\033[32m" << "Finished generating <" + output_file.string() + ">. The new file ist called <" << output_file.string() << ">" << "\033[0m" << std::endl;
         }
     }
     catch (const cxxopts::OptionException& e)
     {
-        std::cerr << "Error in parsing cxxopts options: " << e.what() << std::endl;
+        std::cerr << "\033[31m" << "Error code 01 - Error in parsing cxxopts options: " << e.what() << "\033[0m" << std::endl;
         exit(1);
     }
     exit(0);
diff --git a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
index ae751bb1ac1bfb0ba8e51a4fc9fc11b28c0e3cf2..c9afa372dc20c08fc6e80ce2666214618d366286 100644
--- a/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
+++ b/source/RobotAPI/components/armem/addon/LegacyRobotStateMemoryAdapter/LegacyRobotStateMemoryAdapter.cpp
@@ -96,7 +96,7 @@ namespace armarx::armem
 
         armem::EntityUpdate entityUpdate;
         entityUpdate.entityID = propEntityID;
-        entityUpdate.timeCreated = Time(Duration::MicroSeconds(_timestampUpdateFirstModifiedInUs));  // we take the oldest timestamp
+        entityUpdate.referencedTime = Time(Duration::MicroSeconds(_timestampUpdateFirstModifiedInUs));  // we take the oldest timestamp
 
         entityUpdate.instancesData =
         {
@@ -128,7 +128,7 @@ namespace armarx::armem
 
             armem::EntityUpdate locUpdate;
             locUpdate.entityID = locEntityID;
-            locUpdate.timeCreated = Time(Duration::MicroSeconds(_timestampUpdateFirstModifiedInUs));
+            locUpdate.referencedTime = Time(Duration::MicroSeconds(_timestampUpdateFirstModifiedInUs));
             locUpdate.instancesData =
             {
                transform.toAron()
@@ -282,7 +282,7 @@ namespace armarx::armem
         entityUpdate.entityID.entityName = "Armar3";
 
         entityUpdate.instancesData = { desc.toAron() };
-        entityUpdate.timeCreated = armem::Time::Now();
+        entityUpdate.referencedTime = armem::Time::Now();
         auto res = memoryWriter.commit(c);
         if (!res.allSuccess())
         {
diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
index c072f6fce5ef567fafb8c804e479747a895e80c6..cde81dc6801e7205867c6ff6cd679c69a1db9d92 100644
--- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
+++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp
@@ -218,9 +218,9 @@ namespace armarx
         // Prepare the update with some empty instances.
         armem::EntityUpdate update;
         update.entityID = entityID;
-        update.timeCreated = armem::Time::Now();
+        update.referencedTime = armem::Time::Now();
 
-        double diff = (update.timeCreated - runStarted).toMilliSecondsDouble() / 1000;
+        double diff = (update.referencedTime - runStarted).toMilliSecondsDouble() / 1000;
 
         auto dict1 = std::make_shared<aron::data::Dict>();
         auto dict2 = std::make_shared<aron::data::Dict>();
@@ -265,7 +265,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = entityID;
-            update.timeCreated = armem::Time::Now() + armem::Duration::Seconds(i);
+            update.referencedTime = armem::Time::Now() + armem::Duration::Seconds(i);
             for (int j = 0; j < i; ++j)
             {
                 update.instancesData.push_back(std::make_shared<aron::data::Dict>());
@@ -387,7 +387,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("default");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             toAron(data.memoryID, armem::MemoryID());
@@ -401,7 +401,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("the answer");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             data.the_bool = true;
@@ -488,7 +488,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = linkedDataProviderID.withEntityName("yet_more_data");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::LinkedData data;
             data.yet_another_int = 42;
@@ -545,7 +545,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("id to the_answer");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             armem::toAron(data.memoryID, theAnswerSnapshotID);
@@ -556,7 +556,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("id to self");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             armem::toAron(data.memoryID, update.entityID.withTimestamp(time));
@@ -568,7 +568,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("id to previous snapshot");
-            update.timeCreated = time - armem::Duration::Seconds(1);  // 1 sec in the past
+            update.referencedTime = time - armem::Duration::Seconds(1);  // 1 sec in the past
 
             armem::example::ExampleData data;
             armem::toAron(data.memoryID, armem::MemoryID());  // First entry - invalid link
@@ -579,7 +579,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("id to previous snapshot");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             armem::toAron(data.memoryID, update.entityID.withTimestamp(time - armem::Duration::Seconds(1)));
@@ -634,7 +634,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("link to yet_more_data");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             armem::toAron(data.memoryID, armem::MemoryID());
@@ -686,7 +686,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("some_new_fancy_entity_id");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             auto currentFolder = std::filesystem::current_path();
             auto opencv_img = cv::imread((currentFolder / "images" / (std::to_string(imageCounter + 1) + ".jpg")).string());
@@ -708,7 +708,7 @@ namespace armarx
         {
             armem::EntityUpdate& update = commit.add();
             update.entityID = exampleDataProviderID.withEntityName("unexpected_data");
-            update.timeCreated = time;
+            update.referencedTime = time;
 
             armem::example::ExampleData data;
             toAron(data.memoryID, armem::MemoryID()); // ////1/1
diff --git a/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/ObjectInstanceToIndex.cpp b/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/ObjectInstanceToIndex.cpp
index fedf604b04009ee1b1b3ef18e36df93f7a57b6a4..23b426f37c9dc8942a621cde3b5746e6cdb52ae3 100644
--- a/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/ObjectInstanceToIndex.cpp
+++ b/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/ObjectInstanceToIndex.cpp
@@ -196,7 +196,7 @@ namespace armarx
 
                 armem::EntityUpdate& update = commit.add();
                 update.entityID = provSegID.withEntityName(instance.id().str());
-                update.timeCreated = instance.id().timestamp;
+                update.referencedTime = instance.id().timestamp;
                 update.instancesData = { spatial.toAron() };
 
                 return true;
diff --git a/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/impl/ObjectInstanceToIndex.cpp b/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/impl/ObjectInstanceToIndex.cpp
index 4498d01cec8f60ba81e864438671dc254b2bf5e9..34901591b175f4b5e09dcef339868bbe488d5b50 100644
--- a/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/impl/ObjectInstanceToIndex.cpp
+++ b/source/RobotAPI/components/armem/client/ObjectInstanceToIndex/impl/ObjectInstanceToIndex.cpp
@@ -75,7 +75,7 @@ namespace armarx::armem::objects
                 armem::EntityUpdate& update = commit.add();
                 update.entityID = indexSpatialProviderSegmentID.withEntityName(
                     objectInstanceID.getEntityID().str());
-                update.timeCreated = objectPose.timestamp;
+                update.referencedTime = objectPose.timestamp;
                 update.instancesData = {spatial.toAron()};
             }
 
@@ -114,7 +114,7 @@ namespace armarx::armem::objects
                 armem::EntityUpdate& update = commit.add();
                 update.entityID = indexNamedProviderSegmentID.withEntityName(
                     objectInstanceID.getEntityID().str());
-                update.timeCreated = objectPose.timestamp;
+                update.referencedTime = objectPose.timestamp;
                 update.instancesData = {named.toAron()};
             }
         }
diff --git a/source/RobotAPI/components/armem/client/RobotStatePredictionClientExample/RobotStatePredictionClient.cpp b/source/RobotAPI/components/armem/client/RobotStatePredictionClientExample/RobotStatePredictionClient.cpp
index 3d98d0f2717747a91f7a56c3e0c547cbb0088fbd..492c2c14214d5b1a31a8c0998843a5b799ab495b 100644
--- a/source/RobotAPI/components/armem/client/RobotStatePredictionClientExample/RobotStatePredictionClient.cpp
+++ b/source/RobotAPI/components/armem/client/RobotStatePredictionClientExample/RobotStatePredictionClient.cpp
@@ -163,7 +163,7 @@ namespace armarx::armem::robot_state
                 {
                     armem::EntityUpdate update;
                     update.entityID = entityID;
-                    update.timeCreated = predictedTime;
+                    update.referencedTime = predictedTime;
                     update.instancesData = {result.prediction};
                     coreSegment->update(update);
                 }
diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
index 77135658d4a93d47e0b4474002b589cf569de67f..981489f8621918a733208a0dc7c6c20d274ecfe9 100644
--- a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
+++ b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp
@@ -197,7 +197,7 @@ namespace armarx
                         .withProviderSegmentName(memoryID.providerSegmentName)
                         .withEntityName(memoryID.entityName);
                     update.entityID = newID;
-                    update.timeCreated = armem::Time::Now();
+                    update.referencedTime = armem::Time::Now();
                     update.instancesData = { instance->data() };
 
                     armem::Commit newCommit;
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.cpp
index 0f45fe1f7bbd22ff33afc7859f595ecdc952ab60..3e50e1069a5ff136d8a4eba9df1c1d982ebccc2e 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.cpp
@@ -43,25 +43,31 @@ namespace armarx::RobotUnitModule::details
             {
                 t = IceUtil::Time::seconds(0);
             }
+
             IceUtil::Time t;
+
             void
             start()
             {
                 t -= IceUtil::Time::now();
                 ++n;
             }
+
             void
             stop()
             {
                 t += IceUtil::Time::now();
             }
+
             double
             ms() const
             {
                 return t.toMilliSecondsDouble();
             }
+
             std::size_t n = 0;
         };
+
         DurationsEntry header;
         DurationsEntry header_csv;
         DurationsEntry header_stream;
@@ -389,7 +395,7 @@ namespace armarx::RobotUnitModule
         DataStreamingEntry& streamingEntry = rtDataStreamingEntry[receiver];
         getProperty(streamingEntry.rtStreamMaxClientErrors,
                     "RTLogging_StreamingDataMaxClientConnectionFailures");
-        
+
         getProperty(logAllEntries, "RTLogging_LogAllMessages");
 
         ARMARX_INFO << "start data streaming to " << receiver->ice_getIdentity().name
@@ -421,8 +427,8 @@ namespace armarx::RobotUnitModule
                     continue; //do not add to result and skipp during processing
                 }
                 auto& descrEntr = descr.entries[valData.fields.at(i).name];
-//formatter failes here!
 //*INDENT-OFF*
+// clang-format off
 #define make_case(Type, TName)                                                                     \
     (typeid(Type) == *valData.fields.at(i).type)                                                   \
     {                                                                                              \
@@ -433,27 +439,26 @@ namespace armarx::RobotUnitModule
         ++streamingEntry.num##TName##s;                                                            \
     }
                 if make_case (bool, Bool)
-                    else if make_case (Ice::Byte, Byte) else if make_case (Ice::Short, Short) else if make_case (Ice::Int, Int) else if make_case (
-                        Ice::Long,
-                        Long) else if make_case (Ice::Float,
-                                                 Float) else if make_case (Ice::Double,
-                                                                           Double) else if make_case (std::
-                                                                                                          uint16_t,
-                                                                                                      Long) else if make_case (std::
-                                                                                                                                   uint32_t,
-                                                                                                                               Long) else
-                    {
-                        ARMARX_CHECK_EXPRESSION(false)
-                            << "This code sould be unreachable! "
-                               "The type of "
-                            << valData.fields.at(i).name << " is not handled correctly!";
-                    }
+                else if make_case (Ice::Byte, Byte)
+                else if make_case (Ice::Short, Short)
+                else if make_case (Ice::Int, Int)
+                else if make_case (Ice::Long, Long)
+                else if make_case (Ice::Float, Float)
+                else if make_case (Ice::Double, Double)
+                else if make_case (std::uint16_t, Long)
+                else if make_case (std::uint32_t, Long)
+                else {
+                    ARMARX_CHECK_EXPRESSION(false)
+                                << "This code sould be unreachable! "
+                                   "The type of "
+                                << valData.fields.at(i).name << " is not handled correctly!";
+                }
 #undef make_case
-                //*INDENT-ON*
             }
             return result;
         };
-
+        //*INDENT-ON*
+        // clang-format on
         //get logged sensor device values
         {
             ARMARX_TRACE;
@@ -560,10 +565,14 @@ namespace armarx::RobotUnitModule
         //remove backlog entries
         const auto start_time_remove_backlog_entries = IceUtil::Time::now();
         {
-            while (!backlog.empty() &&
-                   backlog.front().writeTimestamp + rtLoggingBacklogRetentionTime < now)
+            if (rtLoggingBacklogEnabled)
             {
-                backlog.pop_front();
+                while (!backlog.empty() &&
+                       (backlog.front().writeTimestamp + rtLoggingBacklogRetentionTime < now or
+                        backlog.size() > rtLoggingBacklogMaxSize))
+                {
+                    backlog.pop_front();
+                }
             }
         }
         //log all
@@ -579,7 +588,7 @@ namespace armarx::RobotUnitModule
             }
 
 
-            if(logAllEntries)
+            if (logAllEntries)
             {
                 _module<ControlThreadDataBuffer>()
                     .getControlThreadOutputBuffer()
@@ -589,7 +598,9 @@ namespace armarx::RobotUnitModule
                             ARMARX_TRACE;
                             doLogging(dlogdurs, now, data, i, num);
                         });
-            }else { // only log newest entry
+            }
+            else
+            { // only log newest entry
                 _module<ControlThreadDataBuffer>()
                     .getControlThreadOutputBuffer()
                     .forLatestLoggingEntry(
@@ -599,7 +610,6 @@ namespace armarx::RobotUnitModule
                             doLogging(dlogdurs, now, data, i, num);
                         });
             }
-
         }
         ARMARX_DEBUG << ::deactivateSpam() << "the last " << backlog.size()
                      << " iterations are stored";
@@ -657,27 +667,45 @@ namespace armarx::RobotUnitModule
         }
         // clang-format off
         const auto end_time = IceUtil::Time::now();
-        const auto time_total = (end_time                   - now).toMilliSecondsDouble();
+        const auto time_total = (end_time - now).toMilliSecondsDouble();
         ARMARX_DEBUG << deactivateSpam(1)
                      << "rtlogging time required:        " << time_total << "ms\n"
-                     << "    time_remove_backlog_entries " << (start_time_log_all         - start_time_remove_backlog_entries).toMilliSecondsDouble() << "ms\n"
-                     << "    time_log_all                " << (start_time_flush_all_files - start_time_log_all).toMilliSecondsDouble()                << "ms\n"
-                     << "        header                  " << dlogdurs.header.ms()           << "ms\t(" << dlogdurs.header.n           << " calls)\n"
-                     << "            csv                 " << dlogdurs.header_csv.ms()       << "ms\t(" << dlogdurs.header_csv.n       << " calls)\n"
-                     << "            stream              " << dlogdurs.header_stream.ms()    << "ms\t(" << dlogdurs.header_stream.n    << " calls)\n"
-                     << "        sens                    " << dlogdurs.sens.ms()             << "ms\t(" << dlogdurs.sens.n             << " calls)\n"
-                     << "            csv                 " << dlogdurs.sens_csv.ms()         << "ms\t(" << dlogdurs.sens_csv.n         << " calls)\n"
-                     << "            stream              " << dlogdurs.sens_stream.ms()      << "ms\t(" << dlogdurs.sens_stream.n      << " calls)\n"
-                     << "                per elem        " << dlogdurs.sens_stream_elem.ms() << "ms\t(" << dlogdurs.sens_stream_elem.n << " calls)\n"
-                     << "        ctrl                    " << dlogdurs.ctrl.ms()             << "ms\t(" << dlogdurs.ctrl.n             << " calls)\n"
-                     << "            csv                 " << dlogdurs.ctrl_csv.ms()         << "ms\t(" << dlogdurs.ctrl_csv.n         << " calls)\n"
-                     << "            stream              " << dlogdurs.ctrl_stream.ms()      << "ms\t(" << dlogdurs.ctrl_stream.n      << " calls)\n"
-                     << "                per elem        " << dlogdurs.ctrl_stream_elem.ms() << "ms\t(" << dlogdurs.ctrl_stream_elem.n << " calls)\n"
-                     << "        backlog                 " << dlogdurs.backlog.ms()          << "ms\t(" << dlogdurs.backlog.n          << " calls)\n"
-                     << "        msg                     " << dlogdurs.msg.ms()              << "ms\t(" << dlogdurs.msg.n              << " calls)\n"
-                     << "    time_flush_all_files        " << (start_time_remove_entries  - start_time_flush_all_files).toMilliSecondsDouble()        << "ms\n"
-                     << "    time_remove_entries         " << (start_time_data_streaming  - start_time_remove_entries).toMilliSecondsDouble()         << "ms\n"
-                     << "    time_data_streaming         " << (end_time                   - start_time_data_streaming).toMilliSecondsDouble()         << "ms\n";
+                     << "    time_remove_backlog_entries "
+                     << (start_time_log_all - start_time_remove_backlog_entries).toMilliSecondsDouble() << "ms\n"
+                     << "    time_log_all                "
+                     << (start_time_flush_all_files - start_time_log_all).toMilliSecondsDouble() << "ms\n"
+                     << "        header                  " << dlogdurs.header.ms() << "ms\t(" << dlogdurs.header.n
+                     << " calls)\n"
+                     << "            csv                 " << dlogdurs.header_csv.ms() << "ms\t("
+                     << dlogdurs.header_csv.n << " calls)\n"
+                     << "            stream              " << dlogdurs.header_stream.ms() << "ms\t("
+                     << dlogdurs.header_stream.n << " calls)\n"
+                     << "        sens                    " << dlogdurs.sens.ms() << "ms\t(" << dlogdurs.sens.n
+                     << " calls)\n"
+                     << "            csv                 " << dlogdurs.sens_csv.ms() << "ms\t(" << dlogdurs.sens_csv.n
+                     << " calls)\n"
+                     << "            stream              " << dlogdurs.sens_stream.ms() << "ms\t("
+                     << dlogdurs.sens_stream.n << " calls)\n"
+                     << "                per elem        " << dlogdurs.sens_stream_elem.ms() << "ms\t("
+                     << dlogdurs.sens_stream_elem.n << " calls)\n"
+                     << "        ctrl                    " << dlogdurs.ctrl.ms() << "ms\t(" << dlogdurs.ctrl.n
+                     << " calls)\n"
+                     << "            csv                 " << dlogdurs.ctrl_csv.ms() << "ms\t(" << dlogdurs.ctrl_csv.n
+                     << " calls)\n"
+                     << "            stream              " << dlogdurs.ctrl_stream.ms() << "ms\t("
+                     << dlogdurs.ctrl_stream.n << " calls)\n"
+                     << "                per elem        " << dlogdurs.ctrl_stream_elem.ms() << "ms\t("
+                     << dlogdurs.ctrl_stream_elem.n << " calls)\n"
+                     << "        backlog                 " << dlogdurs.backlog.ms() << "ms\t(" << dlogdurs.backlog.n
+                     << " calls)\n"
+                     << "        msg                     " << dlogdurs.msg.ms() << "ms\t(" << dlogdurs.msg.n
+                     << " calls)\n"
+                     << "    time_flush_all_files        "
+                     << (start_time_remove_entries - start_time_flush_all_files).toMilliSecondsDouble() << "ms\n"
+                     << "    time_remove_entries         "
+                     << (start_time_data_streaming - start_time_remove_entries).toMilliSecondsDouble() << "ms\n"
+                     << "    time_data_streaming         "
+                     << (end_time - start_time_data_streaming).toMilliSecondsDouble() << "ms\n";
         // clang-format on
     }
 
@@ -723,432 +751,434 @@ namespace armarx::RobotUnitModule
         }
 
         // Process devices.
+        {// Sensors.
+         {ARMARX_TRACE;
+        durations.sens.start();
+        //sensors
+        for (std::size_t idxDev = 0; idxDev < data.sensors.size(); ++idxDev)
         {
-            // Sensors.
+            const SensorValueBase* val = data.sensors.at(idxDev);
+            //dimensions of sensor value (e.g. vel, tor, f_x, f_y, ...)
+            for (std::size_t idxField = 0; idxField < val->getNumberOfDataFields(); ++idxField)
             {
-                ARMARX_TRACE;
-                durations.sens.start();
-                //sensors
-                for (std::size_t idxDev = 0; idxDev < data.sensors.size(); ++idxDev)
+                if (!rtLoggingEntries.empty())
                 {
-                    const SensorValueBase* val = data.sensors.at(idxDev);
-                    //dimensions of sensor value (e.g. vel, tor, f_x, f_y, ...)
-                    for (std::size_t idxField = 0; idxField < val->getNumberOfDataFields(); ++idxField)
+                    durations.sens_csv.start();
+                    const auto str = val->getDataFieldAs<std::string>(idxField);
+                    for (auto& [_, entry] : rtLoggingEntries)
                     {
-                        if (!rtLoggingEntries.empty())
-                        {
-                            durations.sens_csv.start();
-                            const auto str = val->getDataFieldAs<std::string>(idxField);
-                            for (auto& [_, entry] : rtLoggingEntries)
-                            {
-                                if (entry->loggedSensorDeviceValues.at(idxDev).at(idxField))
-                                {
-                                    entry->stream << ";" << str;
-                                }
-                            }
-                            durations.sens_csv.stop();
-                        }
-                        if (!rtDataStreamingEntry.empty())
+                        if (entry->loggedSensorDeviceValues.at(idxDev).at(idxField))
                         {
-                            durations.sens_stream.start();
-                            for (auto& [_, data] : rtDataStreamingEntry)
-                            {
-                                durations.sens_stream_elem.start();
-                                data.processSens(*val, idxDev, idxField);
-                                durations.sens_stream_elem.stop();
-                            }
-                            durations.sens_stream.stop();
+                            entry->stream << ";" << str;
                         }
                     }
+                    durations.sens_csv.stop();
+                }
+                if (!rtDataStreamingEntry.empty())
+                {
+                    durations.sens_stream.start();
+                    for (auto& [_, rtStreamingEntry] : rtDataStreamingEntry)
+                    {
+                        durations.sens_stream_elem.start();
+                        rtStreamingEntry.processSens(*val, idxDev, idxField);
+                        durations.sens_stream_elem.stop();
+                    }
+                    durations.sens_stream.stop();
                 }
-                durations.sens.stop();
             }
+        }
+        durations.sens.stop();
+    }
 
-            // Controller.
+    // Controller.
+    {
+        durations.ctrl.start();
+        ARMARX_TRACE;
+        //joint controllers
+        for (std::size_t idxDev = 0; idxDev < data.control.size(); ++idxDev)
+        {
+            const auto& vals = data.control.at(idxDev);
+            //control value (e.g. v_platform)
+            for (std::size_t idxVal = 0; idxVal < vals.size(); ++idxVal)
             {
-                durations.ctrl.start();
-                ARMARX_TRACE;
-                //joint controllers
-                for (std::size_t idxDev = 0; idxDev < data.control.size(); ++idxDev)
+                const ControlTargetBase* val = vals.at(idxVal);
+                //dimensions of control value (e.g. v_platform_x, v_platform_y, v_platform_rotate)
+                for (std::size_t idxField = 0; idxField < val->getNumberOfDataFields(); ++idxField)
                 {
-                    const auto& vals = data.control.at(idxDev);
-                    //control value (e.g. v_platform)
-                    for (std::size_t idxVal = 0; idxVal < vals.size(); ++idxVal)
+                    if (!rtLoggingEntries.empty())
                     {
-                        const ControlTargetBase* val = vals.at(idxVal);
-                        //dimensions of control value (e.g. v_platform_x, v_platform_y, v_platform_rotate)
-                        for (std::size_t idxField = 0; idxField < val->getNumberOfDataFields(); ++idxField)
+                        durations.ctrl_csv.start();
+                        std::string str;
+                        val->getDataFieldAs(idxField, str); // expensive function
+                        for (auto& [_, entry] : rtLoggingEntries)
                         {
-                            if (!rtLoggingEntries.empty())
-                            {
-                                durations.ctrl_csv.start();
-                                std::string str;
-                                val->getDataFieldAs(idxField, str); // expensive function
-                                for (auto& [_, entry] : rtLoggingEntries)
-                                {
-                                    if (entry->loggedControlDeviceValues.at(idxDev).at(idxVal).at(idxField))
-                                    {
-                                        entry->stream << ";" << str;
-                                    }
-                                }
-                                durations.ctrl_csv.stop();
-                            }
-                            if (!rtDataStreamingEntry.empty())
+                            if (entry->loggedControlDeviceValues.at(idxDev).at(idxVal).at(idxField))
                             {
-                                durations.ctrl_stream.start();
-                                for (auto& [_, data] : rtDataStreamingEntry)
-                                {
-                                    durations.ctrl_stream_elem.start();
-                                    data.processCtrl(*val, idxDev, idxVal, idxField);
-                                    durations.ctrl_stream_elem.stop();
-                                }
-                                durations.ctrl_stream.stop();
+                                entry->stream << ";" << str;
                             }
                         }
+                        durations.ctrl_csv.stop();
+                    }
+                    if (!rtDataStreamingEntry.empty())
+                    {
+                        durations.ctrl_stream.start();
+                        for (auto& [_, rtStreamingEntry] : rtDataStreamingEntry)
+                        {
+                            durations.ctrl_stream_elem.start();
+                            rtStreamingEntry.processCtrl(*val, idxDev, idxVal, idxField);
+                            durations.ctrl_stream_elem.stop();
+                        }
+                        durations.ctrl_stream.stop();
                     }
                 }
-
-                durations.ctrl.stop();
             }
         }
 
-        //finish processing
+        durations.ctrl.stop();
+    }
+} // namespace armarx::RobotUnitModule
+
+//finish processing
+{
+    //store data to backlog
+    {
+        if (rtLoggingBacklogEnabled)
         {
-            //store data to backlog
-            {
-                durations.backlog.start();
-                ARMARX_TRACE;
-                if (data.writeTimestamp + rtLoggingBacklogRetentionTime >= now)
-                {
-                    backlog.emplace_back(data, true); //true for minimal copy
-                }
-                durations.backlog.stop();
-            }
-            //print + reset messages
+            durations.backlog.start();
+            ARMARX_TRACE;
+            if (data.writeTimestamp + rtLoggingBacklogRetentionTime >= now)
             {
-                durations.msg.start();
-                ARMARX_TRACE;
-                for (const ::armarx::detail::RtMessageLogEntryBase* ptr : data.messages.getEntries())
-                {
-                    if (!ptr)
-                    {
-                        break;
-                    }
-                    ptr->print(controlThreadId);
-                }
-                durations.msg.stop();
+                backlog.emplace_back(data, true); //true for minimal copy
             }
+            durations.backlog.stop();
         }
     }
-
-    bool
-    Logging::MatchName(const std::string& pattern, const std::string& name)
+    //print + reset messages
     {
+        durations.msg.start();
         ARMARX_TRACE;
-        if (pattern.empty())
-        {
-            return false;
-        }
-        static const std::regex pattern_regex{R"(^\^?[- ._*a-zA-Z0-9]+\$?$)"};
-        if (!std::regex_match(pattern, pattern_regex))
+        for (const ::armarx::detail::RtMessageLogEntryBase* ptr : data.messages.getEntries())
         {
-            throw InvalidArgumentException{"Pattern '" + pattern + "' is invalid"};
+            if (!ptr)
+            {
+                break;
+            }
+            ptr->print(controlThreadId);
         }
-        static const std::regex reg_dot{"[.]"};
-        static const std::regex reg_star{"[*]"};
-        const std::string rpl1 = std::regex_replace(pattern, reg_dot, "\\.");
-        const std::string rpl2 = std::regex_replace(rpl1, reg_star, ".*");
-        const std::regex key_regex{rpl2};
-        return std::regex_search(name, key_regex);
+        durations.msg.stop();
     }
+}
+}
 
-    void
-    Logging::_postOnInitRobotUnit()
+bool
+Logging::MatchName(const std::string& pattern, const std::string& name)
+{
+    ARMARX_TRACE;
+    if (pattern.empty())
     {
-        ARMARX_TRACE;
-        throwIfInControlThread(BOOST_CURRENT_FUNCTION);
-        rtLoggingTimestepMs = getProperty<std::size_t>("RTLogging_PeriodMs");
-        ARMARX_CHECK_LESS(0, rtLoggingTimestepMs) << "The property RTLoggingPeriodMs must not be 0";
+        return false;
+    }
+    static const std::regex pattern_regex{R"(^\^?[- ._*a-zA-Z0-9]+\$?$)"};
+    if (!std::regex_match(pattern, pattern_regex))
+    {
+        throw InvalidArgumentException{"Pattern '" + pattern + "' is invalid"};
+    }
+    static const std::regex reg_dot{"[.]"};
+    static const std::regex reg_star{"[*]"};
+    const std::string rpl1 = std::regex_replace(pattern, reg_dot, "\\.");
+    const std::string rpl2 = std::regex_replace(rpl1, reg_star, ".*");
+    const std::regex key_regex{rpl2};
+    return std::regex_search(name, key_regex);
+}
 
-        messageBufferSize = getProperty<std::size_t>("RTLogging_MessageBufferSize");
-        messageBufferMaxSize = getProperty<std::size_t>("RTLogging_MaxMessageBufferSize");
-        ARMARX_CHECK_LESS_EQUAL(messageBufferSize, messageBufferMaxSize);
+void
+Logging::_postOnInitRobotUnit()
+{
+    ARMARX_TRACE;
+    throwIfInControlThread(BOOST_CURRENT_FUNCTION);
+    rtLoggingTimestepMs = getProperty<std::size_t>("RTLogging_PeriodMs");
+    ARMARX_CHECK_LESS(0, rtLoggingTimestepMs) << "The property RTLoggingPeriodMs must not be 0";
 
-        messageBufferNumberEntries = getProperty<std::size_t>("RTLogging_MessageNumber");
-        messageBufferMaxNumberEntries = getProperty<std::size_t>("RTLogging_MaxMessageNumber");
-        ARMARX_CHECK_LESS_EQUAL(messageBufferNumberEntries, messageBufferMaxNumberEntries);
+    messageBufferSize = getProperty<std::size_t>("RTLogging_MessageBufferSize");
+    messageBufferMaxSize = getProperty<std::size_t>("RTLogging_MaxMessageBufferSize");
+    ARMARX_CHECK_LESS_EQUAL(messageBufferSize, messageBufferMaxSize);
 
-        rtLoggingBacklogRetentionTime =
-            IceUtil::Time::milliSeconds(getProperty<std::size_t>("RTLogging_KeepIterationsForMs"));
-        
-        ARMARX_CHECK_GREATER(getControlThreadTargetPeriod().toMicroSeconds(), 0);
-    }
+    messageBufferNumberEntries = getProperty<std::size_t>("RTLogging_MessageNumber");
+    messageBufferMaxNumberEntries = getProperty<std::size_t>("RTLogging_MaxMessageNumber");
+    ARMARX_CHECK_LESS_EQUAL(messageBufferNumberEntries, messageBufferMaxNumberEntries);
 
-    void
-    Logging::_postFinishDeviceInitialization()
+    rtLoggingBacklogRetentionTime =
+        IceUtil::Time::milliSeconds(getProperty<std::size_t>("RTLogging_KeepIterationsForMs"));
+    rtLoggingBacklogMaxSize = getProperty<std::size_t>("RTLogging_MaxBacklogSize");
+    rtLoggingBacklogEnabled = getProperty<bool>("RTLogging_EnableBacklog");
+    ARMARX_CHECK_GREATER(getControlThreadTargetPeriod().toMicroSeconds(), 0);
+}
+
+void
+Logging::_postFinishDeviceInitialization()
+{
+    ARMARX_TRACE;
+    throwIfInControlThread(BOOST_CURRENT_FUNCTION);
+    //init buffer
     {
         ARMARX_TRACE;
-        throwIfInControlThread(BOOST_CURRENT_FUNCTION);
-        //init buffer
-        {
-            ARMARX_TRACE;
-            std::size_t ctrlThreadPeriodUs =
-                static_cast<std::size_t>(getControlThreadTargetPeriod().toMicroSeconds());
-            std::size_t logThreadPeriodUs = rtLoggingTimestepMs * 1000;
-            std::size_t nBuffers = (logThreadPeriodUs / ctrlThreadPeriodUs + 1) * 100;
-
-            const auto bufferSize =
-                _module<ControlThreadDataBuffer>().getControlThreadOutputBuffer().initialize(
-                    nBuffers,
-                    _module<Devices>().getControlDevices(),
-                    _module<Devices>().getSensorDevices(),
-                    messageBufferSize,
-                    messageBufferNumberEntries,
-                    messageBufferMaxSize,
-                    messageBufferMaxNumberEntries);
-            ARMARX_INFO << "RTLogging activated. Using " << nBuffers << " buffers "
-                        << "(buffersize = " << bufferSize << " bytes)";
-        }
-        //init logging names + field types
-        {
-            ARMARX_TRACE;
-            const auto makeValueMetaData = [&](auto* val, const std::string& namePre)
-            {
-                ValueMetaData data;
-                const auto names = val->getDataFieldNames();
-                data.fields.resize(names.size());
+        std::size_t ctrlThreadPeriodUs =
+            static_cast<std::size_t>(getControlThreadTargetPeriod().toMicroSeconds());
+        std::size_t logThreadPeriodUs = rtLoggingTimestepMs * 1000;
+        std::size_t nBuffers = (logThreadPeriodUs / ctrlThreadPeriodUs + 1) * 100;
 
-                for (std::size_t fieldIdx = 0; fieldIdx < names.size(); ++fieldIdx)
-                {
-                    std::string const& fieldName = names[fieldIdx];
-                    data.fields.at(fieldIdx).name = namePre + '.' + fieldName;
-                    data.fields.at(fieldIdx).type = &(val->getDataFieldType(fieldIdx));
-                }
-                return data;
-            };
+        const auto bufferSize =
+            _module<ControlThreadDataBuffer>().getControlThreadOutputBuffer().initialize(
+                nBuffers,
+                _module<Devices>().getControlDevices(),
+                _module<Devices>().getSensorDevices(),
+                messageBufferSize,
+                messageBufferNumberEntries,
+                messageBufferMaxSize,
+                messageBufferMaxNumberEntries);
+        ARMARX_INFO << "RTLogging activated. Using " << nBuffers << " buffers "
+                    << "(buffersize = " << bufferSize << " bytes)";
+    }
+    //init logging names + field types
+    {
+        ARMARX_TRACE;
+        const auto makeValueMetaData = [&](auto* val, const std::string& namePre)
+        {
+            ValueMetaData data;
+            const auto names = val->getDataFieldNames();
+            data.fields.resize(names.size());
 
-            //sensorDevices
-            controlDeviceValueMetaData.reserve(_module<Devices>().getControlDevices().size());
-            for (const auto& cd : _module<Devices>().getControlDevices().values())
+            for (std::size_t fieldIdx = 0; fieldIdx < names.size(); ++fieldIdx)
             {
-                ARMARX_TRACE;
-                controlDeviceValueMetaData.emplace_back();
-                auto& dataForDev = controlDeviceValueMetaData.back();
-                dataForDev.reserve(cd->getJointControllers().size());
-                for (auto jointC : cd->getJointControllers())
-                {
-                    dataForDev.emplace_back(makeValueMetaData(jointC->getControlTarget(),
-                                                              "ctrl." + cd->getDeviceName() + "." +
-                                                                  jointC->getControlMode()));
-                }
+                std::string const& fieldName = names[fieldIdx];
+                data.fields.at(fieldIdx).name = namePre + '.' + fieldName;
+                data.fields.at(fieldIdx).type = &(val->getDataFieldType(fieldIdx));
             }
-            //sensorDevices
-            sensorDeviceValueMetaData.reserve(_module<Devices>().getSensorDevices().size());
-            for (const auto& sd : _module<Devices>().getSensorDevices().values())
+            return data;
+        };
+
+        //sensorDevices
+        controlDeviceValueMetaData.reserve(_module<Devices>().getControlDevices().size());
+        for (const auto& cd : _module<Devices>().getControlDevices().values())
+        {
+            ARMARX_TRACE;
+            controlDeviceValueMetaData.emplace_back();
+            auto& dataForDev = controlDeviceValueMetaData.back();
+            dataForDev.reserve(cd->getJointControllers().size());
+            for (auto jointC : cd->getJointControllers())
             {
-                ARMARX_TRACE;
-                sensorDeviceValueMetaData.emplace_back(
-                    makeValueMetaData(sd->getSensorValue(), "sens." + sd->getDeviceName()));
+                dataForDev.emplace_back(makeValueMetaData(jointC->getControlTarget(),
+                                                          "ctrl." + cd->getDeviceName() + "." +
+                                                              jointC->getControlMode()));
             }
         }
-        //start logging thread is done in rtinit
-        //maybe add the default log
+        //sensorDevices
+        sensorDeviceValueMetaData.reserve(_module<Devices>().getSensorDevices().size());
+        for (const auto& sd : _module<Devices>().getSensorDevices().values())
         {
             ARMARX_TRACE;
-            const auto loggingpath = getProperty<std::string>("RTLogging_DefaultLog").getValue();
-            if (!loggingpath.empty())
-            {
-                defaultLogHandle = startRtLogging(loggingpath, getLoggingNames());
-            }
+            sensorDeviceValueMetaData.emplace_back(
+                makeValueMetaData(sd->getSensorValue(), "sens." + sd->getDeviceName()));
         }
     }
-
-    void
-    Logging::DataStreamingEntry::clearResult()
+    //start logging thread is done in rtinit
+    //maybe add the default log
     {
         ARMARX_TRACE;
-        for (auto& e : result)
+        const auto loggingpath = getProperty<std::string>("RTLogging_DefaultLog").getValue();
+        if (!loggingpath.empty())
         {
-            entryBuffer.emplace_back(std::move(e));
+            defaultLogHandle = startRtLogging(loggingpath, getLoggingNames());
         }
-        result.clear();
     }
+}
 
-    RobotUnitDataStreaming::TimeStep
-    Logging::DataStreamingEntry::allocateResultElement() const
+void
+Logging::DataStreamingEntry::clearResult()
+{
+    ARMARX_TRACE;
+    for (auto& e : result)
     {
-        ARMARX_TRACE;
-        RobotUnitDataStreaming::TimeStep data;
-        data.bools.resize(numBools);
-        data.bytes.resize(numBytes);
-        data.shorts.resize(numShorts);
-        data.ints.resize(numInts);
-        data.longs.resize(numLongs);
-        data.floats.resize(numFloats);
-        data.doubles.resize(numDoubles);
-        return data;
+        entryBuffer.emplace_back(std::move(e));
     }
+    result.clear();
+}
 
-    RobotUnitDataStreaming::TimeStep
-    Logging::DataStreamingEntry::getResultElement()
+RobotUnitDataStreaming::TimeStep
+Logging::DataStreamingEntry::allocateResultElement() const
+{
+    ARMARX_TRACE;
+    RobotUnitDataStreaming::TimeStep data;
+    data.bools.resize(numBools);
+    data.bytes.resize(numBytes);
+    data.shorts.resize(numShorts);
+    data.ints.resize(numInts);
+    data.longs.resize(numLongs);
+    data.floats.resize(numFloats);
+    data.doubles.resize(numDoubles);
+    return data;
+}
+
+RobotUnitDataStreaming::TimeStep
+Logging::DataStreamingEntry::getResultElement()
+{
+    ARMARX_TRACE;
+    if (entryBuffer.empty())
     {
-        ARMARX_TRACE;
-        if (entryBuffer.empty())
-        {
-            return allocateResultElement();
-        }
-        auto e = std::move(entryBuffer.back());
-        entryBuffer.pop_back();
-        return e;
+        return allocateResultElement();
     }
+    auto e = std::move(entryBuffer.back());
+    entryBuffer.pop_back();
+    return e;
+}
 
-    void
-    Logging::DataStreamingEntry::processHeader(const ControlThreadOutputBuffer::Entry& e)
+void
+Logging::DataStreamingEntry::processHeader(const ControlThreadOutputBuffer::Entry& e)
+{
+    ARMARX_TRACE;
+    if (stopStreaming)
     {
-        ARMARX_TRACE;
-        if (stopStreaming)
-        {
-            return;
-        }
-        
-        auto& data = result.emplace_back(getResultElement());
-
-        data.iterationId = e.iteration;
-        data.timestampUSec = e.sensorValuesTimestamp.toMicroSeconds();
-        data.timesSinceLastIterationUSec = e.timeSinceLastIteration.toMicroSeconds();
+        return;
     }
 
-    void
-    WriteTo(const auto& dentr,
-            const Logging::DataStreamingEntry::OutVal& out,
-            const auto& val,
-            std::size_t fidx,
-            auto& data)
+    auto& data = result.emplace_back(getResultElement());
+
+    data.iterationId = e.iteration;
+    data.timestampUSec = e.sensorValuesTimestamp.toMicroSeconds();
+    data.timesSinceLastIterationUSec = e.timeSinceLastIteration.toMicroSeconds();
+}
+
+void
+WriteTo(const auto& dentr,
+        const Logging::DataStreamingEntry::OutVal& out,
+        const auto& val,
+        std::size_t fidx,
+        auto& data)
+{
+    ARMARX_TRACE;
+    using enum_t = Logging::DataStreamingEntry::ValueT;
+    try
     {
         ARMARX_TRACE;
-        using enum_t = Logging::DataStreamingEntry::ValueT;
-        try
-        {
-            ARMARX_TRACE;
-            switch (out.value)
-            {
-                case enum_t::Bool:
-                    bool b;
-                    val.getDataFieldAs(fidx, b);
-                    data.bools.at(out.idx) = b;
-                    return;
-                case enum_t::Byte:
-                    val.getDataFieldAs(fidx, data.bytes.at(out.idx));
-                    return;
-                case enum_t::Short:
-                    val.getDataFieldAs(fidx, data.shorts.at(out.idx));
-                    return;
-                case enum_t::Int:
-                    val.getDataFieldAs(fidx, data.ints.at(out.idx));
-                    return;
-                case enum_t::Long:
-                    val.getDataFieldAs(fidx, data.longs.at(out.idx));
-                    return;
-                case enum_t::Float:
-                    val.getDataFieldAs(fidx, data.floats.at(out.idx));
-                    return;
-                case enum_t::Double:
-                    val.getDataFieldAs(fidx, data.doubles.at(out.idx));
-                    return;
-                case enum_t::Skipped:
-                    return;
-            }
-        }
-        catch (...)
+        switch (out.value)
         {
-            ARMARX_ERROR << GetHandledExceptionString() << "\ntype " << static_cast<int>(out.value)
-                         << "\n"
-                         << VAROUT(data.bools.size()) << " " << VAROUT(dentr.numBools) << "\n"
-                         << VAROUT(data.bytes.size()) << " " << VAROUT(dentr.numBytes) << "\n"
-                         << VAROUT(data.shorts.size()) << " " << VAROUT(dentr.numShorts) << "\n"
-                         << VAROUT(data.ints.size()) << " " << VAROUT(dentr.numInts) << "\n"
-                         << VAROUT(data.longs.size()) << " " << VAROUT(dentr.numLongs) << "\n"
-                         << VAROUT(data.floats.size()) << " " << VAROUT(dentr.numFloats) << "\n"
-                         << VAROUT(data.doubles.size()) << " " << VAROUT(dentr.numDoubles);
-            throw;
+            case enum_t::Bool:
+                bool b;
+                val.getDataFieldAs(fidx, b);
+                data.bools.at(out.idx) = b;
+                return;
+            case enum_t::Byte:
+                val.getDataFieldAs(fidx, data.bytes.at(out.idx));
+                return;
+            case enum_t::Short:
+                val.getDataFieldAs(fidx, data.shorts.at(out.idx));
+                return;
+            case enum_t::Int:
+                val.getDataFieldAs(fidx, data.ints.at(out.idx));
+                return;
+            case enum_t::Long:
+                val.getDataFieldAs(fidx, data.longs.at(out.idx));
+                return;
+            case enum_t::Float:
+                val.getDataFieldAs(fidx, data.floats.at(out.idx));
+                return;
+            case enum_t::Double:
+                val.getDataFieldAs(fidx, data.doubles.at(out.idx));
+                return;
+            case enum_t::Skipped:
+                return;
         }
     }
+    catch (...)
+    {
+        ARMARX_ERROR << GetHandledExceptionString() << "\ntype " << static_cast<int>(out.value)
+                     << "\n"
+                     << VAROUT(data.bools.size()) << " " << VAROUT(dentr.numBools) << "\n"
+                     << VAROUT(data.bytes.size()) << " " << VAROUT(dentr.numBytes) << "\n"
+                     << VAROUT(data.shorts.size()) << " " << VAROUT(dentr.numShorts) << "\n"
+                     << VAROUT(data.ints.size()) << " " << VAROUT(dentr.numInts) << "\n"
+                     << VAROUT(data.longs.size()) << " " << VAROUT(dentr.numLongs) << "\n"
+                     << VAROUT(data.floats.size()) << " " << VAROUT(dentr.numFloats) << "\n"
+                     << VAROUT(data.doubles.size()) << " " << VAROUT(dentr.numDoubles);
+        throw;
+    }
+}
 
-    void
-    Logging::DataStreamingEntry::processCtrl(const ControlTargetBase& val,
-                                             std::size_t didx,
-                                             std::size_t vidx,
-                                             std::size_t fidx)
+void
+Logging::DataStreamingEntry::processCtrl(const ControlTargetBase& val,
+                                         std::size_t didx,
+                                         std::size_t vidx,
+                                         std::size_t fidx)
+{
+    ARMARX_TRACE;
+    if (stopStreaming)
     {
-        ARMARX_TRACE;
-        if (stopStreaming)
-        {
-            return;
-        }
-        auto& data = result.back();
-        const OutVal& o = ctrlDevs.at(didx).at(vidx).at(fidx);
-        WriteTo(*this, o, val, fidx, data);
+        return;
     }
+    auto& data = result.back();
+    const OutVal& o = ctrlDevs.at(didx).at(vidx).at(fidx);
+    WriteTo(*this, o, val, fidx, data);
+}
 
-    void
-    Logging::DataStreamingEntry::processSens(const SensorValueBase& val,
-                                             std::size_t didx,
-                                             std::size_t fidx)
+void
+Logging::DataStreamingEntry::processSens(const SensorValueBase& val,
+                                         std::size_t didx,
+                                         std::size_t fidx)
+{
+    ARMARX_TRACE;
+    if (stopStreaming)
     {
-        ARMARX_TRACE;
-        if (stopStreaming)
-        {
-            return;
-        }
-        auto& data = result.back();
-        const OutVal& o = sensDevs.at(didx).at(fidx);
-        WriteTo(*this, o, val, fidx, data);
+        return;
     }
+    auto& data = result.back();
+    const OutVal& o = sensDevs.at(didx).at(fidx);
+    WriteTo(*this, o, val, fidx, data);
+}
 
-    void
-    Logging::DataStreamingEntry::send(const RobotUnitDataStreaming::ReceiverPrx& r, std::uint64_t msgId)
+void
+Logging::DataStreamingEntry::send(const RobotUnitDataStreaming::ReceiverPrx& r, std::uint64_t msgId)
+{
+    ARMARX_TRACE;
+    const auto start_send = IceUtil::Time::now();
+    updateCalls.emplace_back(r->begin_update(result, static_cast<Ice::Long>(msgId)));
+    const auto start_clear = IceUtil::Time::now();
+    clearResult();
+    const auto end = IceUtil::Time::now();
+    ARMARX_DEBUG_S << "Logging::DataStreamingEntry::send"
+                   << "\n    update " << (start_clear - start_send).toMilliSecondsDouble() << "ms ("
+                   << result.size() << " timesteps)"
+                   << "\n    clear  " << (end - start_clear).toMilliSecondsDouble() << "ms";
+
+    //now execute all ready callbacks
+    std::size_t i = 0;
+    for (; i < updateCalls.size(); ++i)
     {
-        ARMARX_TRACE;
-        const auto start_send = IceUtil::Time::now();
-        updateCalls.emplace_back(r->begin_update(result, static_cast<Ice::Long>(msgId)));
-        const auto start_clear = IceUtil::Time::now();
-        clearResult();
-        const auto end = IceUtil::Time::now();
-        ARMARX_DEBUG_S << "Logging::DataStreamingEntry::send"
-                       << "\n    update " << (start_clear - start_send).toMilliSecondsDouble() << "ms ("
-                       << result.size() << " timesteps)"
-                       << "\n    clear  " << (end - start_clear).toMilliSecondsDouble() << "ms";
-
-        //now execute all ready callbacks
-        std::size_t i = 0;
-        for (; i < updateCalls.size(); ++i)
+        try
         {
-            try
-            {
-                if (!updateCalls.at(i)->isCompleted())
-                {
-                    break;
-                }
-                r->end_update(updateCalls.at(i));
-                connectionFailures = 0;
-            }
-            catch (...)
+            if (!updateCalls.at(i)->isCompleted())
             {
-                ARMARX_TRACE;
-                ++connectionFailures;
-                if (connectionFailures > rtStreamMaxClientErrors)
-                {
-                    stopStreaming = true;
-                    ARMARX_WARNING_S << "DataStreaming Receiver was not reachable for "
-                                     << connectionFailures << " iterations! Removing receiver";
-                    updateCalls.clear();
-                    break;
-                }
+                break;
             }
+            r->end_update(updateCalls.at(i));
+            connectionFailures = 0;
         }
-        if (!updateCalls.empty())
+        catch (...)
         {
-            updateCalls.erase(updateCalls.begin(), updateCalls.begin() + i);
+            ARMARX_TRACE;
+            ++connectionFailures;
+            if (connectionFailures > rtStreamMaxClientErrors)
+            {
+                stopStreaming = true;
+                ARMARX_WARNING_S << "DataStreaming Receiver was not reachable for "
+                                 << connectionFailures << " iterations! Removing receiver";
+                updateCalls.clear();
+                break;
+            }
         }
     }
+    if (!updateCalls.empty())
+    {
+        updateCalls.erase(updateCalls.begin(), updateCalls.begin() + i);
+    }
+}
 }
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.h
index bb6a625e3484fc843f4d27224a5801d416d91858..7529c75fd0182aa30c7c64ff994df15127b29009 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleLogging.h
@@ -71,10 +71,18 @@ namespace armarx::RobotUnitModule
                 "RTLogging_MaxMessageBufferSize", 16 * 1024 * 1024,
                 "Max number of bytes that can be logged in the control thread");
 
+            defineOptionalProperty<bool>(
+                "RTLogging_EnableBacklog", true,
+                "Enable/Disable the backlog (SensorValues, ControlTargets, Messages) that is kept"
+                "and can be dumped in case of an error.");
             defineOptionalProperty<std::size_t>(
                 "RTLogging_KeepIterationsForMs", 60 * 1000,
                 "All logging data (SensorValues, ControlTargets, Messages) is kept for this duration "
                 "and can be dumped in case of an error.");
+            defineOptionalProperty<std::size_t>(
+                "RTLogging_MaxBacklogSize", 5000,
+                "Maximum size of the backlog (SensorValues, ControlTargets, Messages) that is kept"
+                "and can be dumped in case of an error.");
 
             defineOptionalProperty<std::size_t>(
                 "RTLogging_StreamingDataMaxClientConnectionFailures", 10,
@@ -301,8 +309,12 @@ namespace armarx::RobotUnitModule
         std::size_t messageBufferMaxNumberEntries {0};
         /// @brief The logging thread's period
         std::size_t rtLoggingTimestepMs {0};
-        /// @brief The time an entry shold remain in the backlog.
+        /// @brief The time an entry should remain in the backlog.
         IceUtil::Time rtLoggingBacklogRetentionTime;
+        /// @brief The maximum number of entries in the backlog.
+        std::size_t rtLoggingBacklogMaxSize;
+        /// @brief Enable/disable the backlog.
+        bool rtLoggingBacklogEnabled;
 
         /// @brief 
         bool logAllEntries = true;
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModulePublisher.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModulePublisher.cpp
index c07f2d42c7d1d17def0b67a8c4866fe21384284e..243950a7c5a15f376f1f5c7b09b8b99fac0ea2d2 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModulePublisher.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModulePublisher.cpp
@@ -31,6 +31,9 @@
 #include <RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
+#include "ArmarXCore/core/exceptions/local/ExpressionException.h"
+#include "ArmarXCore/core/logging/Logging.h"
+#include "ArmarXCore/core/util/StringHelpers.h"
 #include <ArmarXCore/core/ArmarXObjectScheduler.h>
 
 namespace armarx::RobotUnitModule
@@ -312,6 +315,7 @@ namespace armarx::RobotUnitModule
                 SensorDeviceStatus status;
                 status.deviceName = DevicesAttorneyForPublisher::GetSensorDeviceName(this, sensidx);
 
+                ARMARX_TRACE;
                 if (observerPublishSensorValues && publishToObserver)
                 {
                     for (const auto& pair : variants)
diff --git a/source/RobotAPI/components/units/RobotUnit/util/ControlThreadOutputBuffer.cpp b/source/RobotAPI/components/units/RobotUnit/util/ControlThreadOutputBuffer.cpp
index 26a7dd83ddcfd736b85cc4466686c9ea93c02809..1327e8e353890c42fb2200c253e42ff03325be35 100644
--- a/source/RobotAPI/components/units/RobotUnit/util/ControlThreadOutputBuffer.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/util/ControlThreadOutputBuffer.cpp
@@ -445,11 +445,13 @@ namespace armarx
         messages {other.messages, minimize},
         buffer(other.buffer.size(), 0)
     {
+        ARMARX_TRACE;
         void* place = buffer.data();
         std::size_t space = buffer.size();
 
         auto getAlignedPlace = [&space, &place, this](std::size_t bytes, std::size_t alignment)
         {
+            ARMARX_TRACE;
             ARMARX_CHECK_EXPRESSION(std::align(alignment, bytes, place, space));
             ARMARX_CHECK_LESS(bytes, space);
             const auto resultPlace = place;
@@ -463,6 +465,7 @@ namespace armarx
         sensors.reserve(other.sensors.size());
         for (const SensorValueBase* sv : other.sensors)
         {
+            ARMARX_TRACE;
             sensors.emplace_back(sv->_placementCopyConstruct(getAlignedPlace(sv->_sizeof(), sv->_alignof())));
         }
 
@@ -470,6 +473,7 @@ namespace armarx
         control.reserve(other.control.size());
         for (const auto& cdctargs : other.control)
         {
+            ARMARX_TRACE;
             control.emplace_back();
             auto& ctargs = control.back();
             ctargs.reserve(cdctargs.size());
diff --git a/source/RobotAPI/interface/armem/commit.ice b/source/RobotAPI/interface/armem/commit.ice
index 17260a2136d2cc4c24d1ecd06f5f77ecbcb7f8c0..4a7008293fbe1bd2080ebf808f1bd28621792303 100644
--- a/source/RobotAPI/interface/armem/commit.ice
+++ b/source/RobotAPI/interface/armem/commit.ice
@@ -34,7 +34,7 @@ module armarx
             {
                 armem::data::MemoryID entityID;
                 aron::data::dto::AronDictSeq instancesData;
-                armarx::core::time::dto::DateTime timeCreated;
+                armarx::core::time::dto::DateTime referencedTime;
 
                 float confidence = 1.0;
                 armarx::core::time::dto::DateTime timeSent;
diff --git a/source/RobotAPI/interface/armem/memory.ice b/source/RobotAPI/interface/armem/memory.ice
index 617f7043f76019a2c474f588127dbcbd9c4f3991..63801dd4da540ae46fef76e993a862e4979409c7 100644
--- a/source/RobotAPI/interface/armem/memory.ice
+++ b/source/RobotAPI/interface/armem/memory.ice
@@ -38,9 +38,11 @@ module armarx
             /// Ice Twin of `armarx::armem::EntityInstanceMetadata`.
             class EntityInstanceMetadata
             {
-                armarx::core::time::dto::DateTime timeCreated;
-                armarx::core::time::dto::DateTime timeSent;
-                armarx::core::time::dto::DateTime timeArrived;
+                armarx::core::time::dto::DateTime referencedTime;
+                armarx::core::time::dto::DateTime sentTime;
+                armarx::core::time::dto::DateTime arrivedTime;
+                armarx::core::time::dto::DateTime lastAccessedTime;
+                long accessed = 0;
 
                 float confidence = 1.0;
             };
diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateWriter.cpp b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateWriter.cpp
index 76200b0ab1772d68cd30482e577ae870e711af10..7aa20ba28af1b49404118cfedb3abd006d784738 100644
--- a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateWriter.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateWriter.cpp
@@ -170,7 +170,7 @@ namespace armarx::armem
         armem::EntityUpdate update;
         update.entityID = entityID;
         update.instancesData = instances;
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
diff --git a/source/RobotAPI/libraries/armem/client/Writer.cpp b/source/RobotAPI/libraries/armem/client/Writer.cpp
index 3c4edce62f6cbc0b2d2dc908e673fbe06afe6f53..e9b06f66e1e297296a2f47c39cdf6474c0015795 100644
--- a/source/RobotAPI/libraries/armem/client/Writer.cpp
+++ b/source/RobotAPI/libraries/armem/client/Writer.cpp
@@ -84,12 +84,12 @@ namespace armarx::armem::client
     EntityUpdateResult Writer::commit(
         const MemoryID& entityID,
         const std::vector<aron::data::DictPtr>& instancesData,
-        Time timeCreated)
+        Time referencedTime)
     {
         EntityUpdate update;
         update.entityID = entityID;
         update.instancesData = instancesData;
-        update.timeCreated = timeCreated;
+        update.referencedTime = referencedTime;
         return commit(update);
     }
 
diff --git a/source/RobotAPI/libraries/armem/client/Writer.h b/source/RobotAPI/libraries/armem/client/Writer.h
index 1d898bf6e3bc7382e4a4a22318507a3b29ee2cd7..6c4b223ce12e0ee80cd5564e2d2d3ad688661cbc 100644
--- a/source/RobotAPI/libraries/armem/client/Writer.h
+++ b/source/RobotAPI/libraries/armem/client/Writer.h
@@ -49,7 +49,7 @@ namespace armarx::armem::client
         EntityUpdateResult commit(
             const MemoryID& entityID,
             const std::vector<aron::data::DictPtr>& instancesData,
-            Time timeCreated);
+            Time referencedTime);
 
         // with bare-ice types
         data::CommitResult commit(const data::Commit& commit);
diff --git a/source/RobotAPI/libraries/armem/core/Commit.cpp b/source/RobotAPI/libraries/armem/core/Commit.cpp
index 3c311d2249c3dc7ebe6baee5779c9337b6e19a01..341d160ec7852bb9d397d283289a4944c1f98409 100644
--- a/source/RobotAPI/libraries/armem/core/Commit.cpp
+++ b/source/RobotAPI/libraries/armem/core/Commit.cpp
@@ -14,7 +14,7 @@ namespace armarx::armem
     {
         return os << "Entity update: "
                << "\n- success:    \t" << rhs.entityID
-               << "\n- timestamp:  \t" << toDateTimeMilliSeconds(rhs.timeCreated)
+               << "\n- timestamp:  \t" << toDateTimeMilliSeconds(rhs.referencedTime)
                << "\n- #instances: \t" << rhs.instancesData.size()
                << "\n"
                ;
@@ -25,7 +25,7 @@ namespace armarx::armem
         return os << "Entity update result: "
                << "\n- success:       \t" << (rhs.success ? "true" : "false")
                << "\n- snapshotID:    \t" << rhs.snapshotID
-               << "\n- time arrived:  \t" << toDateTimeMilliSeconds(rhs.timeArrived)
+               << "\n- time arrived:  \t" << toDateTimeMilliSeconds(rhs.arrivedTime)
                << "\n- error message: \t" << rhs.errorMessage
                << "\n"
                ;
diff --git a/source/RobotAPI/libraries/armem/core/Commit.h b/source/RobotAPI/libraries/armem/core/Commit.h
index 8a1da207528940d0db22dd004faae5b15e3d07f3..81d0413849549af39abb5f2733e76d53565a6f3b 100644
--- a/source/RobotAPI/libraries/armem/core/Commit.h
+++ b/source/RobotAPI/libraries/armem/core/Commit.h
@@ -36,7 +36,7 @@ namespace armarx::armem
          * @brief Time when this entity update was created (e.g. time of image recording).
          * This is the key of the entity's history.
          */
-        Time timeCreated = Time::Invalid();
+        Time referencedTime = Time::Invalid();
 
 
         // OPTIONAL
@@ -52,14 +52,14 @@ namespace armarx::armem
          *
          * Set automatically when sending the commit.
          */
-        Time timeSent = Time::Invalid();
+        Time sentTime = Time::Invalid();
 
         /**
          * @brief Time when this update arrived at the memory server.
          *
          * Set by memory server on arrival.
          */
-        Time timeArrived = Time::Invalid();
+        Time arrivedTime = Time::Invalid();
 
 
         friend std::ostream& operator<<(std::ostream& os, const EntityUpdate& rhs);
@@ -74,7 +74,7 @@ namespace armarx::armem
         bool success = false;
 
         MemoryID snapshotID;
-        Time timeArrived = Time::Invalid();
+        Time arrivedTime = Time::Invalid();
 
         std::string errorMessage;
 
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityBase.h b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
index 9c9a8c88a535eb919029c16305f2af72e999423d..7b6972a93bf7dcad9d804a03136869472b364082 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityBase.h
@@ -552,11 +552,11 @@ namespace armarx::armem::base
 
             EntitySnapshotT* snapshot;
 
-            auto it = this->_container.find(update.timeCreated);
+            auto it = this->_container.find(update.referencedTime);
             if (it == this->_container.end())
             {
                 // Insert into history.
-                snapshot = &addSnapshot(update.timeCreated);
+                snapshot = &addSnapshot(update.referencedTime);
                 // ret.removedSnapshots = this->truncate();
                 ret.entityUpdateType = UpdateType::InsertedNew;
             }
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
index 1cc2e9544d00ce96d65658acaf853c670418bdce..a2cabd58bd92564c68374f0bf61ab06ef5990135 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.cpp
@@ -3,11 +3,17 @@
 
 namespace armarx::armem::base
 {
+    void EntityInstanceMetadata::access() const
+    {
+        numAccessed++;
+        lastAccessedTime = armarx::core::time::DateTime::Now();
+    }
+
     bool EntityInstanceMetadata::operator==(const EntityInstanceMetadata& other) const
     {
-        return timeCreated == other.timeCreated
-               && timeSent == other.timeSent
-               && timeArrived == other.timeArrived
+        return referencedTime == other.referencedTime
+               && sentTime == other.sentTime
+               && arrivedTime == other.arrivedTime
                && std::abs(confidence - other.confidence) < 1e-6f;
     }
 }
@@ -16,10 +22,11 @@ namespace armarx::armem::base
 std::ostream& armarx::armem::base::operator<<(std::ostream& os, const EntityInstanceMetadata& d)
 {
     os << "EntityInstanceMetadata: "
-       << "\n- t_create =   \t" << armem::toStringMicroSeconds(d.timeCreated) << " us"
-       << "\n- t_sent =     \t" << armem::toStringMicroSeconds(d.timeSent) << " us"
-       << "\n- t_arrived =  \t" << armem::toStringMicroSeconds(d.timeArrived) << " us"
-       << "\n- confidence = \t" << d.confidence << " us"
+       << "\n - t_referenced = \t" << armem::toStringMicroSeconds(d.referencedTime) << " us"
+       << "\n - t_sent       = \t" << armem::toStringMicroSeconds(d.sentTime) << " us"
+       << "\n - t_arrived    = \t" << armem::toStringMicroSeconds(d.arrivedTime) << " us"
+       << "\n - t_accessed   = \t" << armem::toStringMicroSeconds(d.lastAccessedTime) << " us (" << d.numAccessed << ")"
+       << "\n - confidence   = \t" << d.confidence << " us"
        ;
     return os;
 }
diff --git a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
index 9ec1376516decfb9b5215477421902f387ccb92e..0bd03af1448d99536640c0b9f4a2f83036afc307 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntityInstanceBase.h
@@ -14,6 +14,16 @@ namespace armarx::armem::base
      */
     struct NoData
     {
+        virtual ~NoData() = default;
+
+        bool operator==(const NoData& other)
+        {
+            return true;
+        }
+        bool operator!=(const NoData& other)
+        {
+            return false;
+        }
     };
 
 
@@ -22,22 +32,34 @@ namespace armarx::armem::base
      */
     struct EntityInstanceMetadata
     {
-        /// Time when this value was created.
-        Time timeCreated;
+
+        virtual ~EntityInstanceMetadata() = default;
+
+        /**
+         * @brief Time this instance refers to.
+         *
+         * For example, the physical time point when an image was captured.
+         * If the image is processed, the result should have the same
+         * referencedTime as the image.
+         */
+        Time referencedTime = Time::Invalid();
+
         /// Time when this value was sent to the memory.
-        Time timeSent;
+        Time sentTime = Time::Invalid();
         /// Time when this value has arrived at the memory.
-        Time timeArrived;
+        Time arrivedTime = Time::Invalid();
 
         /// An optional confidence, may be used for things like decay.
         float confidence = 1.0;
 
-        /// An optional value indicating the last access
-        Time lastAccessed = Time::Invalid();
+        /// An optional value indicating the time of last access.
+        mutable Time lastAccessedTime = Time::Invalid();
 
-        /// A counter how often the instance has been accessed
-        unsigned long accessed = 0;
+        /// A counter how often the instance has been accessed.
+        mutable unsigned long numAccessed = 0;
 
+        /// Called whenever the entity instance this metadata belongs to is accessed (e.g. queried).
+        void access() const;
 
         bool operator==(const EntityInstanceMetadata& other) const;
         inline bool operator!=(const EntityInstanceMetadata& other) const
@@ -91,11 +113,11 @@ namespace armarx::armem::base
 
         // Data
 
-        EntityInstanceMetadata& metadata()
+        MetadataT& metadata()
         {
             return _metadata;
         }
-        const EntityInstanceMetadata& metadata() const
+        const MetadataT& metadata() const
         {
             return _metadata;
         }
diff --git a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
index c983dd8dec8a9a351b0a4cd1efc9d00320f59a1c..b7048a6328990d6be2152c0559466cf1ff142b9e 100644
--- a/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
+++ b/source/RobotAPI/libraries/armem/core/base/EntitySnapshotBase.h
@@ -223,7 +223,7 @@ namespace armarx::armem::base
 
         void update(const EntityUpdate& update)
         {
-            detail::throwIfNotEqual(time(), update.timeCreated);
+            detail::throwIfNotEqual(time(), update.referencedTime);
 
             this->_container.clear();
             for (int index = 0; index < int(update.instancesData.size()); ++index)
diff --git a/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
index 6ec40abd7ec808b8aca5aaf3cb4a93a5772e17b1..42620f2d928b91f7941600315a9970b16111618c 100644
--- a/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/base/ice_conversions.cpp
@@ -56,16 +56,20 @@ namespace armarx::armem
     void base::toIce(data::EntityInstanceMetadata& ice, const EntityInstanceMetadata& metadata)
     {
         ice.confidence = metadata.confidence;
-        toIce(ice.timeArrived, metadata.timeArrived);
-        toIce(ice.timeCreated, metadata.timeCreated);
-        toIce(ice.timeSent, metadata.timeSent);
+        toIce(ice.arrivedTime, metadata.arrivedTime);
+        toIce(ice.referencedTime, metadata.referencedTime);
+        toIce(ice.sentTime, metadata.sentTime);
+        toIce(ice.lastAccessedTime, metadata.lastAccessedTime);
+        ice.accessed = metadata.numAccessed;
     }
     void base::fromIce(const data::EntityInstanceMetadata& ice, EntityInstanceMetadata& metadata)
     {
         metadata.confidence = ice.confidence;
-        fromIce(ice.timeArrived, metadata.timeArrived);
-        fromIce(ice.timeCreated, metadata.timeCreated);
-        fromIce(ice.timeSent, metadata.timeSent);
+        fromIce(ice.arrivedTime, metadata.arrivedTime);
+        fromIce(ice.referencedTime, metadata.referencedTime);
+        fromIce(ice.sentTime, metadata.sentTime);
+        fromIce(ice.lastAccessedTime, metadata.lastAccessedTime);
+        metadata.numAccessed = ice.accessed;
     }
 
 
diff --git a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
index dfd25e3ba39ca2bc9a18be1b45684d004255297f..5e1ace16263e1bcdd11a760e8aba7c5216afc36d 100644
--- a/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/ice_conversions.cpp
@@ -87,10 +87,10 @@ namespace armarx
         std::transform(ice.instancesData.begin(), ice.instancesData.end(), std::back_inserter(update.instancesData),
                        aron::data::Dict::FromAronDictDTO);
 
-        fromIce(ice.timeCreated, update.timeCreated);
+        fromIce(ice.referencedTime, update.referencedTime);
 
         update.confidence = ice.confidence;
-        fromIce(ice.timeSent, update.timeSent);
+        fromIce(ice.timeSent, update.sentTime);
     }
 
     void armem::toIce(data::EntityUpdate& ice, const EntityUpdate& update)
@@ -102,17 +102,17 @@ namespace armarx
         std::transform(update.instancesData.begin(), update.instancesData.end(), std::back_inserter(ice.instancesData),
                        aron::data::Dict::ToAronDictDTO);
 
-        toIce(ice.timeCreated, update.timeCreated);
+        toIce(ice.referencedTime, update.referencedTime);
 
         ice.confidence = update.confidence;
-        toIce(ice.timeSent, update.timeSent);
+        toIce(ice.timeSent, update.sentTime);
     }
 
     void armem::fromIce(const data::EntityUpdateResult& ice, EntityUpdateResult& result)
     {
         result.success = ice.success;
         fromIce(ice.snapshotID, result.snapshotID);
-        fromIce(ice.timeArrived, result.timeArrived);
+        fromIce(ice.timeArrived, result.arrivedTime);
         result.errorMessage = ice.errorMessage;
     }
 
@@ -120,7 +120,7 @@ namespace armarx
     {
         ice.success = result.success;
         toIce(ice.snapshotID, result.snapshotID);
-        toIce(ice.timeArrived, result.timeArrived);
+        toIce(ice.timeArrived, result.arrivedTime);
         ice.errorMessage = result.errorMessage;
     }
 
@@ -137,7 +137,7 @@ namespace armarx
     void armem::fromIce(const data::EntityUpdate& ice, EntityUpdate& update, Time timeArrived)
     {
         fromIce(ice, update);
-        update.timeArrived = timeArrived;
+        update.arrivedTime = timeArrived;
     }
 
     void armem::fromIce(const actions::data::MenuPtr& ice, actions::Menu& menu)
diff --git a/source/RobotAPI/libraries/armem/core/operations.cpp b/source/RobotAPI/libraries/armem/core/operations.cpp
index 51729c613b6d10e5903a92818d9e1b4fa507fa11..5ac621a9ec9bd0e1ca9bf3ef6a6ca0e16ceb5d49 100644
--- a/source/RobotAPI/libraries/armem/core/operations.cpp
+++ b/source/RobotAPI/libraries/armem/core/operations.cpp
@@ -25,7 +25,7 @@ namespace armarx
     {
         EntityUpdate up;
         up.entityID = snapshot.id().getEntityID();
-        up.timeCreated = snapshot.time();
+        up.referencedTime = snapshot.time();
         up.instancesData = getAronData(snapshot);
         return up;
     }
diff --git a/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
index 6a23899d1903460ef3cda2075dba196274401c6b..e2ceb0f2ac5e77f23d0a8a330b9b7837699691fa 100644
--- a/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/aron_conversions.cpp
@@ -6,7 +6,7 @@
 namespace armarx::armem
 {
     constexpr const char* DATA_WRAPPER_TIME_STORED_FIELD     = "__WRITER_METADATA__TIME_STORED";
-    constexpr const char* DATA_WRAPPER_TIME_CREATED_FIELD    = "__ENTITY_METADATA__TIME_CREATED";
+    constexpr const char* DATA_WRAPPER_TIME_REFERENCED_FIELD = "__ENTITY_METADATA__TIME_REFERENCED";
     constexpr const char* DATA_WRAPPER_TIME_SENT_FIELD       = "__ENTITY_METADATA__TIME_SENT";
     constexpr const char* DATA_WRAPPER_TIME_ARRIVED_FIELD    = "__ENTITY_METADATA__TIME_ARRIVED";
     constexpr const char* DATA_WRAPPER_CONFIDENCE_FIELD      = "__ENTITY_METADATA__CONFIDENCE";
@@ -22,14 +22,14 @@ 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(Duration::MicroSeconds(timeCreated->toAronLongDTO()->value));
+    auto referencedTime = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_REFERENCED_FIELD));
+    m.referencedTime = Time(Duration::MicroSeconds(referencedTime->toAronLongDTO()->value));
 
     auto timeSent = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_SENT_FIELD));
-    m.timeSent = Time(Duration::MicroSeconds(timeSent->toAronLongDTO()->value));
+    m.sentTime = Time(Duration::MicroSeconds(timeSent->toAronLongDTO()->value));
 
     auto timeArrived = aron::data::Long::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_TIME_ARRIVED_FIELD));
-    m.timeArrived = Time(Duration::MicroSeconds(timeArrived->toAronLongDTO()->value));
+    m.arrivedTime = Time(Duration::MicroSeconds(timeArrived->toAronLongDTO()->value));
 
     auto confidence = aron::data::Double::DynamicCastAndCheck(metadata->getElement(DATA_WRAPPER_CONFIDENCE_FIELD));
     m.confidence = static_cast<float>(confidence->toAronDoubleDTO()->value);
@@ -46,16 +46,16 @@ void armarx::armem::to_aron(aron::data::DictPtr& metadata, aron::data::DictPtr&
     metadata->addElement(DATA_WRAPPER_TIME_STORED_FIELD, timeWrapped);
 
     const wm::EntityInstanceMetadata& m = e.metadata();
-    auto timeCreated = std::make_shared<aron::data::Long>(armarx::aron::Path(std::vector<std::string>{DATA_WRAPPER_TIME_CREATED_FIELD}));
-    timeCreated->setValue(m.timeCreated.toMicroSecondsSinceEpoch());
-    metadata->addElement(DATA_WRAPPER_TIME_CREATED_FIELD, timeCreated);
+    auto referencedTime = std::make_shared<aron::data::Long>(armarx::aron::Path(std::vector<std::string>{DATA_WRAPPER_TIME_REFERENCED_FIELD}));
+    referencedTime->setValue(m.referencedTime.toMicroSecondsSinceEpoch());
+    metadata->addElement(DATA_WRAPPER_TIME_REFERENCED_FIELD, referencedTime);
 
     auto timeSent = std::make_shared<aron::data::Long>(armarx::aron::Path(std::vector<std::string>{DATA_WRAPPER_TIME_SENT_FIELD}));
-    timeSent->setValue(m.timeSent.toMicroSecondsSinceEpoch());
+    timeSent->setValue(m.sentTime.toMicroSecondsSinceEpoch());
     metadata->addElement(DATA_WRAPPER_TIME_SENT_FIELD, timeSent);
 
     auto timeArrived = std::make_shared<aron::data::Long>(armarx::aron::Path(std::vector<std::string>{DATA_WRAPPER_TIME_ARRIVED_FIELD}));
-    timeArrived->setValue(m.timeArrived.toMicroSecondsSinceEpoch());
+    timeArrived->setValue(m.arrivedTime.toMicroSecondsSinceEpoch());
     metadata->addElement(DATA_WRAPPER_TIME_ARRIVED_FIELD, timeArrived);
 
     auto confidence = std::make_shared<aron::data::Double>(armarx::aron::Path(std::vector<std::string>{DATA_WRAPPER_CONFIDENCE_FIELD}));
diff --git a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
index 0758020be61e3326c6b870b8bffae8d06e318a79..bfc408ac99a98a5bf1826f37334e1c331196ed1b 100644
--- a/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
+++ b/source/RobotAPI/libraries/armem/core/wm/memory_definitions.cpp
@@ -37,9 +37,9 @@ namespace armarx::armem::wm
 
         this->_metadata.confidence = update.confidence;
 
-        this->_metadata.timeCreated = update.timeCreated;
-        this->_metadata.timeSent = update.timeSent;
-        this->_metadata.timeArrived = update.timeArrived;
+        this->_metadata.referencedTime = update.referencedTime;
+        this->_metadata.sentTime = update.sentTime;
+        this->_metadata.arrivedTime = update.arrivedTime;
     }
 
 }
diff --git a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
index 06096a9960aab2b13c694492b2eb1d022a6d9728..858f715c4ec5728edbf646e587cd4f02d5958798 100644
--- a/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
+++ b/source/RobotAPI/libraries/armem/server/MemoryToIceAdapter.cpp
@@ -187,7 +187,7 @@ namespace armarx::armem::server
 
                 result.success = true;
                 result.snapshotID = updateResult.id;
-                result.timeArrived = update.timeArrived;
+                result.arrivedTime = update.arrivedTime;
 
                 for (const auto& snapshot : updateResult.removedSnapshots)
                 {
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/ltm/detail/EntityQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/ltm/detail/EntityQueryProcessorBase.h
index 70250e824baba3192db3c1ee009f6ef3b75f51bc..5d3f9b0ed7e2128be282661107886986c6edc1da 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/ltm/detail/EntityQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/ltm/detail/EntityQueryProcessorBase.h
@@ -29,6 +29,7 @@ namespace armarx::armem::server::query_proc::ltm::detail
 
 
     protected:
+        // default addResultSnapshot method. Always copies the data
         void addResultSnapshot(ResultEntityT& result, const EntitySnapshotT& snapshot) const override
         {
             ResultSnapshotT s;
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/wm/detail/EntityQueryProcessorBase.h b/source/RobotAPI/libraries/armem/server/query_proc/wm/detail/EntityQueryProcessorBase.h
index faa3fe544af4dedb4e4226123a1d422a2a1ed200..5fbd2300c13561d64075720d399bc0e4c87633f0 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/wm/detail/EntityQueryProcessorBase.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/wm/detail/EntityQueryProcessorBase.h
@@ -2,6 +2,7 @@
 
 #include "../../base/EntityQueryProcessorBase.h"
 
+#include <ArmarXCore/core/logging/Logging.h>
 
 namespace armarx::armem::server::query_proc::wm::detail
 {
@@ -32,7 +33,12 @@ namespace armarx::armem::server::query_proc::wm::detail
     protected:
         void addResultSnapshot(ResultEntityT& result, const EntitySnapshotT& snapshot) const override
         {
-            result.addSnapshot(snapshot);
+            snapshot.forEachInstance([](const typename EntitySnapshotT::EntityInstanceT& instance)
+            {
+                instance.metadata().access();
+            });
+            EntitySnapshotT copy = snapshot;
+            result.addSnapshot(std::move(copy));
         }
     };
 }
diff --git a/source/RobotAPI/libraries/armem/server/query_proc/wm/wm.h b/source/RobotAPI/libraries/armem/server/query_proc/wm/wm.h
index 27e88e82881deb7ba6f47249d385867b134b9621..312a39896aa717fb8d17115dfe4c0c904a524181 100644
--- a/source/RobotAPI/libraries/armem/server/query_proc/wm/wm.h
+++ b/source/RobotAPI/libraries/armem/server/query_proc/wm/wm.h
@@ -53,15 +53,21 @@ namespace armarx::armem::server::query_proc::wm::detail
             bool withData = (dataMode == armem::query::DataMode::WithData);
             if (withData)
             {
-                result.addSnapshot(server::wm::EntitySnapshot{ snapshot });
+                Base::addResultSnapshot(result, snapshot);
             }
             else
             {
+                // 1. access real data
+                snapshot.forEachInstance([](const server::wm::EntityInstance& i)
+                {
+                    i.metadata().access();
+                });
+
+                // 2. create copy and remove data from copy
                 server::wm::EntitySnapshot copy = snapshot;
                 copy.forEachInstance([](server::wm::EntityInstance & i)
                 {
                     i.data() = nullptr;
-                    return true;
                 });
                 result.addSnapshot(std::move(copy));
             }
diff --git a/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp b/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
index edaa7bb5c5d92b57b0edf3918d1674db34337680..fd326aa038d122cb76a26ad34825dcab4f85b933 100644
--- a/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
+++ b/source/RobotAPI/libraries/armem/server/test/ArMemLTMTest.cpp
@@ -123,7 +123,7 @@ namespace ArMemLTMTest
                 }
                 update.entityID = armem::MemoryID::fromString(memoryName + "/TestCoreSegment/TestProvider/TestEntity");
                 update.instancesData = q;
-                update.timeCreated = armem::Time::Now();
+                update.referencedTime = armem::Time::Now();
                 BOOST_CHECK_NO_THROW(providerSegment.update(update));
                 BOOST_CHECK_EQUAL(providerSegment.size(), 1);
             }
diff --git a/source/RobotAPI/libraries/armem/server/test/ArMemMemoryTest.cpp b/source/RobotAPI/libraries/armem/server/test/ArMemMemoryTest.cpp
index 8c3052e7d3abebf761431789865f4d0f46633cc7..70a0a2839f7f575d02d876a2721c3b3a6c73b58c 100644
--- a/source/RobotAPI/libraries/armem/server/test/ArMemMemoryTest.cpp
+++ b/source/RobotAPI/libraries/armem/server/test/ArMemMemoryTest.cpp
@@ -653,7 +653,7 @@ struct CopyMoveCtorsOpsTest : public CopyMoveCtorsOpsTestBase
         {
             armem::EntityUpdate update;
             update.entityID = armem::MemoryID("M", "C", "P", "E", armem::Time(armem::Duration::MicroSeconds(123000)), 0);
-            update.timeCreated = update.entityID.timestamp;
+            update.referencedTime = update.entityID.timestamp;
             update.instancesData.emplace_back();
             in.update(update);
         }
@@ -814,7 +814,7 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
         std::make_shared<aron::data::Dict>(),
         std::make_shared<aron::data::Dict>()
     };
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(1000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(1000));
     BOOST_CHECK_NO_THROW(providerSegment.update(update));
 
     BOOST_CHECK_EQUAL(providerSegment.size(), 1);
@@ -824,25 +824,25 @@ BOOST_AUTO_TEST_CASE(test_segment_setup)
     wm::Entity& entity = providerSegment.getEntity("image");
     BOOST_CHECK_EQUAL(entity.name(), "image");
     BOOST_CHECK_EQUAL(entity.size(), 1);
-    BOOST_CHECK(entity.hasSnapshot(update.timeCreated));
+    BOOST_CHECK(entity.hasSnapshot(update.referencedTime));
 
-    wm::EntitySnapshot& entitySnapshot = entity.getSnapshot(update.timeCreated);
+    wm::EntitySnapshot& entitySnapshot = entity.getSnapshot(update.referencedTime);
     BOOST_CHECK_EQUAL(entitySnapshot.size(), update.instancesData.size());
 
 
     // Another update (on memory).
 
     update.instancesData = { std::make_shared<aron::data::Dict>() };
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(2000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(2000));
     memory.update(update);
     BOOST_CHECK_EQUAL(entity.size(), 2);
-    BOOST_CHECK(entity.hasSnapshot(update.timeCreated));
-    BOOST_CHECK_EQUAL(entity.getSnapshot(update.timeCreated).size(), update.instancesData.size());
+    BOOST_CHECK(entity.hasSnapshot(update.referencedTime));
+    BOOST_CHECK_EQUAL(entity.getSnapshot(update.referencedTime).size(), update.instancesData.size());
 
 
     // A third update (on entity).
     update.instancesData = { std::make_shared<aron::data::Dict>() };
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(3000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(3000));
     entity.update(update);
     BOOST_CHECK_EQUAL(entity.size(), 3);
 
@@ -858,11 +858,11 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_entity)
     update.entityID.entityName = entity.name();
 
     // With unlimited history.
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(1000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(1000));
     entity.update(update);
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(2000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(2000));
     entity.update(update);
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(3000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(3000));
     entity.update(update);
     BOOST_CHECK_EQUAL(entity.size(), 3);
 
@@ -874,7 +874,7 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_entity)
     BOOST_CHECK(entity.hasSnapshot(armem::Time(armem::Duration::MilliSeconds(3000))));
 
 
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(4000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(4000));
     entity.update(update);
     BOOST_CHECK_EQUAL(entity.size(), 2);
     BOOST_CHECK(not entity.hasSnapshot(armem::Time(armem::Duration::MilliSeconds(2000))));
@@ -884,7 +884,7 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_entity)
     // Disable maximum history size.
     entity.setMaxHistorySize(-1);
 
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(5000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(5000));
     entity.update(update);
     BOOST_CHECK_EQUAL(entity.size(), 3);
     BOOST_CHECK(entity.hasSnapshot(armem::Time(armem::Duration::MilliSeconds(3000))));
@@ -907,15 +907,15 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     {
         update.entityID.entityName = name;
 
-        update.timeCreated = armem::Time(armem::Duration::MilliSeconds(1000));
+        update.referencedTime = armem::Time(armem::Duration::MilliSeconds(1000));
         providerSegment.update(update);
-        update.timeCreated = armem::Time(armem::Duration::MilliSeconds(2000));
+        update.referencedTime = armem::Time(armem::Duration::MilliSeconds(2000));
         providerSegment.update(update);
-        update.timeCreated = armem::Time(armem::Duration::MilliSeconds(3000));
+        update.referencedTime = armem::Time(armem::Duration::MilliSeconds(3000));
         providerSegment.update(update);
     }
     update.entityID.entityName = entityNames.back();
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(4000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(4000));
     providerSegment.update(update);
 
     BOOST_CHECK_EQUAL(providerSegment.getEntity("A").size(), 3);
@@ -939,11 +939,11 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     providerSegment.setMaxHistorySize(2);
 
     update.entityID.entityName = "C";
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(1000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(1000));
     providerSegment.update(update);
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(2000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(2000));
     providerSegment.update(update);
-    update.timeCreated = armem::Time(armem::Duration::MilliSeconds(3000));
+    update.referencedTime = armem::Time(armem::Duration::MilliSeconds(3000));
     providerSegment.update(update);
 
     // Check correctly inherited history size.
@@ -958,7 +958,7 @@ BOOST_AUTO_TEST_CASE(test_history_size_in_provider_segment)
     for (const std::string& name : entityNames)
     {
         update.entityID.entityName = name;
-        update.timeCreated = armem::Time(armem::Duration::MilliSeconds(5000));
+        update.referencedTime = armem::Time(armem::Duration::MilliSeconds(5000));
         providerSegment.update(update);
         BOOST_CHECK_EQUAL(providerSegment.getEntity(name).getMaxHistorySize(), -1);
         BOOST_CHECK_EQUAL(providerSegment.getEntity(name).size(), 3);
diff --git a/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
index f1b5b362318e577dda941c1dd8fff97dd3cf72d7..bf97734a52d7d9db9198101307270c23d8b07383 100644
--- a/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
+++ b/source/RobotAPI/libraries/armem/test/ArMemForEachTest.cpp
@@ -75,7 +75,7 @@ BOOST_AUTO_TEST_CASE(test_forEach)
 
                     EntityUpdate update;
                     update.entityID = eid;
-                    update.timeCreated = sid.timestamp;
+                    update.referencedTime = sid.timestamp;
                     for (size_t i = 0; i <= s; ++i)
                     {
                         const MemoryID iid = sid.withInstanceIndex(int(i));
diff --git a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
index e5c40a12dbb73b0cef3569eb12d80fb1980f95f2..00bd50a3d4721765f2287482bd31f09540d480a3 100644
--- a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
+++ b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
@@ -127,7 +127,7 @@ namespace armarx::armem::grasping::segment
             {
                 EntityUpdate& update = commit.add();
                 update.entityID = providerID.withEntityName(info.id().str());
-                update.entityID.timestamp = update.timeArrived = update.timeCreated = update.timeSent = now;
+                update.entityID.timestamp = update.arrivedTime = update.referencedTime = update.sentTime = now;
 
                 update.instancesData =
                 {
diff --git a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
index b9c789398b0d8ce5c6fb17e0c2cb44fb5bc5b531..4fdda00748d1201e84181c80e3054938c0143348 100644
--- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
+++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp
@@ -391,7 +391,7 @@ namespace armarx::armem::gui
                 entityUpdate.entityID = memId;
                 entityUpdate.confidence = 1.0;
                 entityUpdate.instancesData = {aron};
-                entityUpdate.timeCreated = now;
+                entityUpdate.referencedTime = now;
                 it->second.commit(comm);
             }
         }
diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
index e2d04e0449c190acacf502bb0b847d785e7f85cd..1c7a40faed6b57b15bcd0a4ddd8677b103e8670d 100644
--- a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
+++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp
@@ -50,6 +50,7 @@ namespace armarx::armem::gui::instance
         treeItemMetadata->addChild(new QTreeWidgetItem({"Time Created"}));
         treeItemMetadata->addChild(new QTreeWidgetItem({"Time Sent"}));
         treeItemMetadata->addChild(new QTreeWidgetItem({"Time Arrived"}));
+        treeItemMetadata->addChild(new QTreeWidgetItem({"Time Last Accessed"}));
 
         QList<QTreeWidgetItem*> items = {treeItemInstanceID, treeItemMetadata};
         tree->insertTopLevelItems(0, items);
@@ -110,9 +111,10 @@ namespace armarx::armem::gui::instance
         std::vector<std::string> items =
         {
             std::to_string(metadata.confidence),
-            armem::toDateTimeMilliSeconds(metadata.timeCreated),
-            armem::toDateTimeMilliSeconds(metadata.timeSent),
-            armem::toDateTimeMilliSeconds(metadata.timeArrived)
+            armem::toDateTimeMilliSeconds(metadata.referencedTime),
+            armem::toDateTimeMilliSeconds(metadata.sentTime),
+            armem::toDateTimeMilliSeconds(metadata.arrivedTime),
+            armem::toDateTimeMilliSeconds(metadata.lastAccessedTime) + " (" + std::to_string(metadata.numAccessed) + " times total)"
         };
         ARMARX_CHECK_EQUAL(static_cast<size_t>(treeItemMetadata->childCount()), items.size());
         int i = 0;
diff --git a/source/RobotAPI/libraries/armem_laser_scans/client/common/Writer.cpp b/source/RobotAPI/libraries/armem_laser_scans/client/common/Writer.cpp
index 08f456b165d08e52c9c3ce0aed649aa96ec8f863..9a7aa7e5aa8a97032bd5ab9dcbe245b693a52cc3 100644
--- a/source/RobotAPI/libraries/armem_laser_scans/client/common/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_laser_scans/client/common/Writer.cpp
@@ -83,7 +83,7 @@ namespace armarx::armem::laser_scans::client
         dict->addElement("scan", toAron(laserScan));
 
         update.instancesData = {dict};
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
diff --git a/source/RobotAPI/libraries/armem_motions/server/MotionSegment.cpp b/source/RobotAPI/libraries/armem_motions/server/MotionSegment.cpp
index 8e9621c5a711816c2e84762d9a9d59f10f333f03..76c811b3f05438c5d880da647afc54eb461dd114 100644
--- a/source/RobotAPI/libraries/armem_motions/server/MotionSegment.cpp
+++ b/source/RobotAPI/libraries/armem_motions/server/MotionSegment.cpp
@@ -76,9 +76,9 @@ namespace armarx::armem::server::motions::mdb::segment
                     auto& snapshot = entity.addSnapshot(op->createdDate);
 
                     armem::wm::EntityInstance& instance = snapshot.addInstance();
-                    instance.metadata().timeCreated = op->createdDate;
-                    instance.metadata().timeSent = Time::Now();
-                    instance.metadata().timeArrived = Time::Now();
+                    instance.metadata().referencedTime = op->createdDate;
+                    instance.metadata().sentTime = Time::Now();
+                    instance.metadata().arrivedTime = Time::Now();
                     instance.metadata().confidence = 1.0;
                     instance.data() = op->toAron();
                 }
diff --git a/source/RobotAPI/libraries/armem_mps/server/MotionPrimitives/Segment.cpp b/source/RobotAPI/libraries/armem_mps/server/MotionPrimitives/Segment.cpp
index a45cd788ff673d0e5a9c78e5a92940d0d2daf3c9..23b68572384fb24b7b4f28729fe1041f60d8c307 100644
--- a/source/RobotAPI/libraries/armem_mps/server/MotionPrimitives/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_mps/server/MotionPrimitives/Segment.cpp
@@ -87,9 +87,9 @@ namespace armarx::armem::server::motions::mps::segment
             ss << "Found valid instance at: " << pathToInfoJson << ". The motionID is: ";
 
             armem::wm::EntityInstance instance;
-            instance.metadata().timeCreated = armem::Time::Now();  //op->createdDate;
-            instance.metadata().timeSent = armem::Time::Now();
-            instance.metadata().timeArrived = armem::Time::Now();
+            instance.metadata().referencedTime = armem::Time::Now();  //op->createdDate;
+            instance.metadata().sentTime = armem::Time::Now();
+            instance.metadata().arrivedTime = armem::Time::Now();
             instance.metadata().confidence = 1.0;
 
             if(taskspace)
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
index fbce08b6323e1a1235bd000aadbd4e73ff6cbf8c..80c3168c5fc5e7c893c2813082171e5cd9c6319b 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/Writer.cpp
@@ -154,7 +154,7 @@ namespace armarx::armem::articulated_object
         toAron(aronArticulatedObjectDescription, obj.description);
 
         update.instancesData = {aronArticulatedObjectDescription.toAron()};
-        update.timeCreated   = timestamp;
+        update.referencedTime   = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
@@ -233,7 +233,7 @@ namespace armarx::armem::articulated_object
         objectInstance.pose.objectID = cs;
 
         update.instancesData = {objectInstance.toAron()};
-        update.timeCreated   = timestamp;
+        update.referencedTime   = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
diff --git a/source/RobotAPI/libraries/armem_objects/client/attachment/Writer.cpp b/source/RobotAPI/libraries/armem_objects/client/attachment/Writer.cpp
index 69f5806c2bb6dc4cbfae1f196d4f967c04ab9a12..9a59562ec531ce44644b4bda5ed2a8e9a0c6ac3e 100644
--- a/source/RobotAPI/libraries/armem_objects/client/attachment/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/attachment/Writer.cpp
@@ -82,7 +82,7 @@ namespace armarx::armem::attachment
         toAron(aronAttachment, attachment);
 
         update.instancesData = {aronAttachment.toAron()};
-        update.timeCreated   = timestamp;
+        update.referencedTime   = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
@@ -126,7 +126,7 @@ namespace armarx::armem::attachment
         toAron(aronAttachment, attachment);
 
         update.instancesData = {aronAttachment.toAron()};
-        update.timeCreated   = timestamp;
+        update.referencedTime   = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
diff --git a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectWriter.cpp b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectWriter.cpp
index 84b1e4613b8b4bbe8a72938949d503276500e407..8ee596b27069f82c9ff19d63efcd40e7cc819699 100644
--- a/source/RobotAPI/libraries/armem_objects/client/instance/ObjectWriter.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/instance/ObjectWriter.cpp
@@ -64,8 +64,8 @@ namespace armarx::armem::obj::instance
         e.entityID.coreSegmentName = properties.coreSegmentName;
         e.entityID.providerSegmentName = provider;
         e.entityID.entityName = inst.pose.objectID.dataset + "/" + inst.pose.objectID.className + "/" + inst.pose.objectID.instanceName;
-        e.timeCreated = t;
-        e.timeSent = armem::Time::Now();
+        e.referencedTime = t;
+        e.sentTime = armem::Time::Now();
         e.instancesData = { inst.toAron() };
 
         auto res = memoryWriter.commit(c);
diff --git a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
index 4dcf3262724cd6a9626a967f9582d4514a478d89..c841afc4dc6afe2629802871399944a0ef39da04 100644
--- a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp
@@ -95,7 +95,7 @@ namespace armarx::armem::server::obj::clazz
 
             EntityUpdate& update = commit.add();
             update.entityID = providerID.withEntityName(info.id().str());
-            update.timeArrived = update.timeCreated = update.timeSent = now;
+            update.arrivedTime = update.referencedTime = update.sentTime = now;
 
             arondto::ObjectClass objectClass = objectClassFromInfo(info);
             update.instancesData =
diff --git a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
index c17ce69020b2b7f2c363219339754919fc805723..b0726c001d978f7f98e5517e69248c6a9b4fd47f 100644
--- a/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_objects/server/instance/Segment.cpp
@@ -335,8 +335,8 @@ namespace armarx::armem::server::obj::instance
                                             providerName.empty() ? pose.providerName : providerName);
 
             update.entityID = providerID.withEntityName(pose.objectID.str());
-            update.timeArrived = now;
-            update.timeCreated = pose.timestamp;
+            update.arrivedTime = now;
+            update.referencedTime = pose.timestamp;
             update.confidence = pose.confidence;
 
             arondto::ObjectInstance dto;
@@ -781,7 +781,7 @@ namespace armarx::armem::server::obj::instance
             armem::Commit commit;
             armem::EntityUpdate & update = commit.add();
             update.entityID = objectEntity->id();
-            update.timeCreated = now;
+            update.referencedTime = now;
             {
                 arondto::ObjectInstance updated = data;
                 toAron(updated.pose.attachment, info);
@@ -889,7 +889,7 @@ namespace armarx::armem::server::obj::instance
         armem::Commit commit;
         armem::EntityUpdate & update = commit.add();
         update.entityID = entity.id();
-        update.timeCreated = now;
+        update.referencedTime = now;
         {
             arondto::ObjectInstance updated;
             if (commitAttachedPose and data.pose.attachmentValid)
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotWriter.cpp b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotWriter.cpp
index 579a335212beaeedcf61e2b77e279461345375f1..cfa84fb3f50ad95db2f82b29114cd2606250a2c4 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/RobotWriter.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/RobotWriter.cpp
@@ -85,7 +85,7 @@ namespace armarx::armem::robot_state
         toAron(aronDescription, description);
 
         update.instancesData = {aronDescription.toAron()};
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
@@ -129,7 +129,7 @@ namespace armarx::armem::robot_state
         }
 
         update.instancesData = {aronTransform.toAron()};
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
@@ -163,7 +163,7 @@ namespace armarx::armem::robot_state
         aronProprioception.joints.position = jointMap;
 
         update.instancesData = {aronProprioception.toAron()};
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
         armem::EntityUpdateResult updateResult = memoryWriter.commit(update);
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
index 932f55b0a6ea2ff74762a62ffa74f88d0ff18422..9f93ae53156e0da1e126ed7cc922905eb2f0796b 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/localization/TransformWriter.cpp
@@ -98,7 +98,7 @@ namespace armarx::armem::client::robot_state::localization
 
         armem::EntityUpdate update;
         update.entityID = entityID;
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         arondto::Transform aronTransform;
         toAron(aronTransform, transform);
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp b/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
index af2381c78d334e62ea39eb22978492ad66a32f1a..7a8f6ae0369050000b2a1b8f4df57ec4de4f050a 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/description/Segment.cpp
@@ -58,7 +58,7 @@ namespace armarx::armem::server::robot_state::description
 
         EntityUpdate update;
         update.entityID = providerID.withEntityName("description");
-        update.timeArrived = update.timeCreated = update.timeSent = now;
+        update.arrivedTime = update.referencedTime = update.sentTime = now;
 
         arondto::RobotDescription dto;
         robot::toAron(dto, robotDescription);
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
index 3fbf097937386a7d4973b55a22f76419d3f5d5eb..a503bae532af41ee91809d394c22cd74f4aab071 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/localization/Segment.cpp
@@ -187,7 +187,7 @@ namespace armarx::armem::server::robot_state::localization
 
         EntityUpdate update;
         update.entityID = providerID.withEntityName(transform.header.parentFrame + "," + transform.header.frame);
-        update.timeArrived = update.timeCreated = update.timeSent = timestamp;
+        update.arrivedTime = update.referencedTime = update.sentTime = timestamp;
 
         arondto::Transform aronTransform;
         toAron(aronTransform, transform);
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/proprioception/RobotStateWriter.cpp b/source/RobotAPI/libraries/armem_robot_state/server/proprioception/RobotStateWriter.cpp
index 847ec98c82966408545a50bf9d7fa93fc7081d9f..0c5ac1284fba2003474b9f885682de280a5b4403 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/proprioception/RobotStateWriter.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/proprioception/RobotStateWriter.cpp
@@ -159,7 +159,7 @@ namespace armarx::armem::server::robot_state::proprioception
             up.entityID = properties.robotUnitProviderID.withEntityName(
                 properties.robotUnitProviderID.providerSegmentName);
             up.entityID.coreSegmentName =::armarx::armem::robot_state::constants::proprioceptionCoreSegment;
-            up.timeCreated = data.timestamp;
+            up.referencedTime = data.timestamp;
             up.instancesData = {data.proprioception};
         }
 
@@ -169,7 +169,7 @@ namespace armarx::armem::server::robot_state::proprioception
             up.entityID = properties.robotUnitProviderID.withEntityName(
                 properties.robotUnitProviderID.providerSegmentName);
             up.entityID.coreSegmentName = ::armarx::armem::robot_state::constants::exteroceptionCoreSegment;
-            up.timeCreated = data.timestamp;
+            up.referencedTime = data.timestamp;
             up.instancesData = {data.exteroception};
         }
 
diff --git a/source/RobotAPI/libraries/armem_skills/CMakeLists.txt b/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
index dc960e9b30ad37fd54a9652f37083ff99fc47dd1..6e1e52fe32d7fcb877685c1f66489ca570f19bc2 100644
--- a/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
+++ b/source/RobotAPI/libraries/armem_skills/CMakeLists.txt
@@ -13,10 +13,8 @@ armarx_add_library(
         RobotAPI::armem_server
         RobotAPI::skills
         aronjsonconverter
-<<<<<<< Updated upstream
-=======
+        aroncommonconverter
         aronaronconverter
->>>>>>> Stashed changes
     SOURCES  
         ./aron_conversions.cpp
 
diff --git a/source/RobotAPI/libraries/armem_skills/aron/Skill.xml b/source/RobotAPI/libraries/armem_skills/aron/Skill.xml
index 84b9840794dbd1a618b51e5219732924949c1b8e..abd89ebd82a7d30d19c1945444d1dd8f5d650bfd 100644
--- a/source/RobotAPI/libraries/armem_skills/aron/Skill.xml
+++ b/source/RobotAPI/libraries/armem_skills/aron/Skill.xml
@@ -31,11 +31,11 @@ The memory should look like the following:
             </ObjectChild>
 
             <ObjectChild key='timeoutMs'>
-                <long />
+                <int64 />
             </ObjectChild>
 
             <ObjectChild key='acceptedType'>
-                <string /> <!-- TODO REPLACE! -->
+                <AnyObject shared_ptr="1" />
             </ObjectChild>
 
         </Object>
diff --git a/source/RobotAPI/libraries/armem_skills/server/segment/SkillEventSegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/SkillEventSegment.cpp
index 51c72a4caa79ca48823dc06670d90989cf2c2d07..1fa0989e8938206462674f93d9646f48b065123f 100644
--- a/source/RobotAPI/libraries/armem_skills/server/segment/SkillEventSegment.cpp
+++ b/source/RobotAPI/libraries/armem_skills/server/segment/SkillEventSegment.cpp
@@ -54,7 +54,7 @@ namespace armarx::skills::segment
         armem::Commit comm;
         auto& entityUpdate = comm.add();
         entityUpdate.confidence = 1.0;
-        entityUpdate.timeCreated = armem::Time::Now();
+        entityUpdate.referencedTime = armem::Time::Now();
         entityUpdate.instancesData = { aron };
         entityUpdate.entityID = commitId;
 
diff --git a/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
index f8333282e1c09b206ef8829cbda44c64bde470ec..818f3d13bb4315ebf69909c744c042b1ac268a39 100644
--- a/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
+++ b/source/RobotAPI/libraries/armem_skills/server/segment/SkillExecutionRequestSegment.cpp
@@ -66,7 +66,7 @@ namespace armarx::skills::segment
             entityUpdate.entityID = skillExecutionMemID;
             entityUpdate.instancesData = { aron };
             entityUpdate.confidence = 1.0;
-            entityUpdate.timeCreated = armem::Time::Now();
+            entityUpdate.referencedTime = armem::Time::Now();
         }
 
         {
@@ -79,7 +79,7 @@ namespace armarx::skills::segment
             entityUpdate.entityID = skillExecutionMemID;
             entityUpdate.instancesData = { aron };
             entityUpdate.confidence = 1.0;
-            entityUpdate.timeCreated = armem::Time::Now();
+            entityUpdate.referencedTime = armem::Time::Now();
         }
 
 
diff --git a/source/RobotAPI/libraries/armem_skills/server/segment/StatechartListenerSegment.cpp b/source/RobotAPI/libraries/armem_skills/server/segment/StatechartListenerSegment.cpp
index 46629f7cd066751e6286cb38cb081f5442b6b869..b2c5a53472a39c9dcf02f65323ff189caa3ae7b6 100644
--- a/source/RobotAPI/libraries/armem_skills/server/segment/StatechartListenerSegment.cpp
+++ b/source/RobotAPI/libraries/armem_skills/server/segment/StatechartListenerSegment.cpp
@@ -31,7 +31,7 @@ namespace armarx::skills::segment
         armem::EntityUpdate update;
         update.entityID = segmentPtr->id().withEntityName(entityName);
 
-        update.timeCreated = transitionTime;
+        update.referencedTime = transitionTime;
         skills::arondto::Statechart::Transition data;
         armem::toAron(data, t);
         update.instancesData.push_back(data.toAron());
diff --git a/source/RobotAPI/libraries/armem_system_state/server/CPUSegment.cpp b/source/RobotAPI/libraries/armem_system_state/server/CPUSegment.cpp
index fa392c615789ffac9e8ae2b9fd70eda0052e6d27..9886fdbe2b73326ca8b614ab0ed039d52e4e2b6e 100644
--- a/source/RobotAPI/libraries/armem_system_state/server/CPUSegment.cpp
+++ b/source/RobotAPI/libraries/armem_system_state/server/CPUSegment.cpp
@@ -63,7 +63,7 @@ namespace armarx::armem::server::systemstate::segment
         EntityUpdate update;
         update.entityID = providerId.withEntityName("CurrentCpuLoad");
         update.confidence = 1.0;
-        update.timeCreated = armem::Time::Now();
+        update.referencedTime = armem::Time::Now();
         update.instancesData = { data };
 
         segmentPtr->update(update);
diff --git a/source/RobotAPI/libraries/armem_system_state/server/RAMSegment.cpp b/source/RobotAPI/libraries/armem_system_state/server/RAMSegment.cpp
index f02b8f4fa263687d52336012322ca640ecd84f1d..a201c4731c14a211cfb670608f8839acf19482d1 100644
--- a/source/RobotAPI/libraries/armem_system_state/server/RAMSegment.cpp
+++ b/source/RobotAPI/libraries/armem_system_state/server/RAMSegment.cpp
@@ -54,7 +54,7 @@ namespace armarx::armem::server::systemstate::segment
         EntityUpdate update;
         update.entityID = providerId.withEntityName("CurrentMemoryLoad");
         update.confidence = 1.0;
-        update.timeCreated = armem::Time::Now();
+        update.referencedTime = armem::Time::Now();
         update.instancesData = { data };
 
         segmentPtr->update(update);
diff --git a/source/RobotAPI/libraries/armem_vision/client/laser_scanner_features/Writer.cpp b/source/RobotAPI/libraries/armem_vision/client/laser_scanner_features/Writer.cpp
index 0b24561dd5507efeef77793a5285b5a3eb2b00c9..8ae7ba4379288420d3578d7f30ae9bc9c58c559d 100644
--- a/source/RobotAPI/libraries/armem_vision/client/laser_scanner_features/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/laser_scanner_features/Writer.cpp
@@ -91,7 +91,7 @@ namespace armarx::armem::vision::laser_scanner_features::client
         ARMARX_TRACE;
 
         update.instancesData = {dto.toAron()};
-        update.timeCreated = timestamp;
+        update.referencedTime = timestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << timestamp;
 
diff --git a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
index e781a2582e511b59f3ebefe9cde4a35d425da60a..a682162553005783d3ad74e42d78bffefbc09ae2 100644
--- a/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
+++ b/source/RobotAPI/libraries/armem_vision/client/occupancy_grid/Writer.cpp
@@ -41,7 +41,7 @@ namespace armarx::armem::vision::occupancy_grid::client
         dict->addElement("grid", toAron(grid.grid));
 
         update.instancesData = {dict};
-        update.timeCreated   = iceTimestamp;
+        update.referencedTime   = iceTimestamp;
 
         ARMARX_DEBUG << "Committing " << update << " at time " << iceTimestamp;
         armem::EntityUpdateResult updateResult = memoryWriter().commit(update);
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/CodeWriter.h b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/CodeWriter.h
index 942d036f3e6ed88f012ccd2577c703bd85ac2c26..0e17ccc1ee4938bd81ae462e8a2b069669c25826 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/CodeWriter.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/CodeWriter.h
@@ -31,7 +31,8 @@
 #include <typeindex>
 
 // ArmarX
-#include <ArmarXCore/libraries/cppgen/MetaClass.h>
+#include <ArmarXCore/libraries/cppgen/CppEnum.h>
+#include <ArmarXCore/libraries/cppgen/CppClass.h>
 
 #include <RobotAPI/libraries/aron/core/type/variant/All.h>
 
@@ -61,18 +62,32 @@ namespace armarx::aron::codegenerator
             return typeClasses;
         }
 
+        std::vector<MetaEnumPtr> getTypeEnums() const // TODO: Create Meta Enum class to abstract away cpp details
+        {
+            return typeEnums;
+        }
+
     protected:
         virtual void addSpecificReaderMethods() = 0;
         virtual void addSpecificWriterMethods() = 0;
 
     protected:
         std::vector<MetaClassPtr> typeClasses;
+        std::vector<MetaEnumPtr> typeEnums;
 
         std::string producerName;
-        std::vector<codegenerator::WriterInfo> dataWriters;
-        std::vector<codegenerator::ReaderInfo> dataReaders;
-        std::vector<codegenerator::StaticReaderInfo> staticDataReaders;
-        std::vector<codegenerator::WriterInfo> initialTypeWriters;
+        std::vector<codegenerator::WriterInfo> dictDataWriters;
+        std::vector<codegenerator::WriterInfo> intEnumDataWriters;
+
+        std::vector<codegenerator::ReaderInfo> dictDataReaders;
+        std::vector<codegenerator::ReaderInfo> intEnumDataReaders;
+
+        std::vector<codegenerator::StaticReaderInfo> staticDictDataReaders;
+        std::vector<codegenerator::StaticReaderInfo> staticIntEnumDataReaders;
+
+        std::vector<codegenerator::WriterInfo> initialDictTypeWriters;
+        std::vector<codegenerator::WriterInfo> initialIntEnumTypeWriters;
+
         std::vector<std::string> additionalIncludes;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.cpp
index 85c6403e5e4452848c31ffbc3f59aa39c3fe46ee..c65402434f631f9d26f34c15b6f12d818e1b4a43 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.cpp
@@ -32,6 +32,45 @@
 
 namespace armarx::aron::codegenerator::cpp
 {
+
+    // Function to convert camel case
+    // string to snake case string
+    std::string camelToSnake(const std::string& str)
+    {
+
+        // Empty String
+        std::string result = "";
+
+        // Append first character(in lower case)
+        // to result string
+        char c = std::tolower(str[0]);
+        result+=(char(c));
+
+        // Traverse the string from
+        // ist index to last index
+        for (unsigned int i = 1; i < str.length(); i++) {
+
+            char ch = str[i];
+
+            // Check if the character is upper case
+            // then append '_' and such character
+            // (in lower case) to result string
+            if (std::isupper(ch)) {
+                result = result + '_';
+                result+=char(std::tolower(ch));
+            }
+
+            // If the character is lower case then
+            // add such character into result string
+            else {
+                result = result + ch;
+            }
+        }
+
+        // return the result
+        return result;
+    }
+
     Writer::Writer(const std::string& producerName, const std::vector<std::string>& additionalIncludesFromXMLFile) :
         CodeWriter(producerName, additionalIncludesFromXMLFile)
     {
@@ -41,90 +80,182 @@ namespace armarx::aron::codegenerator::cpp
 
     void Writer::addSpecificWriterMethods()
     {
-        // The toAron Serializer is visible by default
-        {
-            codegenerator::WriterInfo toAron;
-            toAron.methodName = "toAron";
-            toAron.returnType = "armarx::aron::data::DictPtr";
-            toAron.writerClassType = "armarx::aron::data::writer::VariantWriter";
-            toAron.include = "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
-            toAron.enforceConversion = "armarx::aron::data::Dict::DynamicCastAndCheck";
-            dataWriters.push_back(toAron);
-        }
-
-        {
-            codegenerator::WriterInfo toAronDTO;
-            toAronDTO.methodName = "toAronDTO";
-            toAronDTO.returnType = "armarx::aron::data::dto::DictPtr";
-            toAronDTO.writerClassType = "armarx::aron::data::writer::VariantWriter";
-            toAronDTO.include = "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
-            toAronDTO.enforceConversion = "armarx::aron::data::Dict::DynamicCastAndCheck";
-            toAronDTO.enforceMemberAccess = "->toAronDictDTO()";
-            dataWriters.push_back(toAronDTO);
-        }
-
+        // DictData stuff
         {
-            // The toAron Serializer is visible by default
-            codegenerator::WriterInfo ToAronType;
-            ToAronType.methodName = "ToAronType";
-            ToAronType.returnType = "armarx::aron::type::ObjectPtr";
-            ToAronType.writerClassType = "armarx::aron::type::writer::VariantWriter";
-            ToAronType.include = "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
-            ToAronType.enforceConversion = "armarx::aron::type::Object::DynamicCastAndCheck";
-            initialTypeWriters.push_back(ToAronType);
+            {
+                codegenerator::WriterInfo toAron;
+                toAron.methodName = "toAron";
+                toAron.returnType = "armarx::aron::data::DictPtr";
+                toAron.writerClassType = "armarx::aron::data::writer::VariantWriter";
+                toAron.include =
+                    "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
+                toAron.enforceConversion = "armarx::aron::data::Dict::DynamicCastAndCheck";
+                toAron.override = true;
+                dictDataWriters.push_back(toAron);
+            }
+            {
+                codegenerator::WriterInfo toAronDTO;
+                toAronDTO.methodName = "toAronDTO";
+                toAronDTO.returnType = "armarx::aron::data::dto::DictPtr";
+                toAronDTO.writerClassType = "armarx::aron::data::writer::VariantWriter";
+                toAronDTO.include =
+                    "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
+                toAronDTO.enforceConversion = "armarx::aron::data::Dict::DynamicCastAndCheck";
+                toAronDTO.enforceMemberAccess = "->toAronDictDTO()";
+                toAronDTO.override = true;
+                dictDataWriters.push_back(toAronDTO);
+            }
+            {
+                // The toAron Serializer is visible by default
+                codegenerator::WriterInfo ToAronType;
+                ToAronType.methodName = "ToAronType";
+                ToAronType.returnType = "armarx::aron::type::ObjectPtr";
+                ToAronType.writerClassType = "armarx::aron::type::writer::VariantWriter";
+                ToAronType.include =
+                    "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
+                ToAronType.enforceConversion = "armarx::aron::type::Object::DynamicCastAndCheck";
+                initialDictTypeWriters.push_back(ToAronType);
+            }
+            {
+                // The toAron Serializer is visible by default
+                codegenerator::WriterInfo ToAronTypeDTO;
+                ToAronTypeDTO.methodName = "ToAronTypeDTO";
+                ToAronTypeDTO.returnType = "armarx::aron::type::dto::AronObjectPtr";
+                ToAronTypeDTO.writerClassType = "armarx::aron::type::writer::VariantWriter";
+                ToAronTypeDTO.include =
+                    "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
+                ToAronTypeDTO.enforceConversion = "armarx::aron::type::Object::DynamicCastAndCheck";
+                ToAronTypeDTO.enforceMemberAccess = "->toAronObjectDTO()";
+                initialDictTypeWriters.push_back(ToAronTypeDTO);
+            }
         }
 
+        // IntEnum stuff
         {
-            // The toAron Serializer is visible by default
-            codegenerator::WriterInfo ToAronTypeDTO;
-            ToAronTypeDTO.methodName = "ToAronTypeDTO";
-            ToAronTypeDTO.returnType = "armarx::aron::type::dto::AronObjectPtr";
-            ToAronTypeDTO.writerClassType = "armarx::aron::type::writer::VariantWriter";
-            ToAronTypeDTO.include = "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
-            ToAronTypeDTO.enforceConversion = "armarx::aron::type::Object::DynamicCastAndCheck";
-            ToAronTypeDTO.enforceMemberAccess = "->toAronObjectDTO()";
-            initialTypeWriters.push_back(ToAronTypeDTO);
+            {
+                codegenerator::WriterInfo toAron;
+                toAron.methodName = "toAron";
+                toAron.returnType = "armarx::aron::data::IntPtr";
+                toAron.writerClassType = "armarx::aron::data::writer::VariantWriter";
+                toAron.include =
+                    "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
+                toAron.enforceConversion = "armarx::aron::data::Int::DynamicCastAndCheck";
+                toAron.override = true;
+                intEnumDataWriters.push_back(toAron);
+            }
+            {
+                codegenerator::WriterInfo toAronDTO;
+                toAronDTO.methodName = "toAronDTO";
+                toAronDTO.returnType = "armarx::aron::data::dto::AronIntPtr";
+                toAronDTO.writerClassType = "armarx::aron::data::writer::VariantWriter";
+                toAronDTO.include =
+                    "<RobotAPI/libraries/aron/core/data/rw/writer/variant/VariantWriter.h>";
+                toAronDTO.enforceConversion = "armarx::aron::data::Int::DynamicCastAndCheck";
+                toAronDTO.enforceMemberAccess = "->toAronIntDTO()";
+                toAronDTO.override = true;
+                intEnumDataWriters.push_back(toAronDTO);
+            }
+            {
+                // The toAron Serializer is visible by default
+                codegenerator::WriterInfo ToAronType;
+                ToAronType.methodName = "ToAronType";
+                ToAronType.returnType = "armarx::aron::type::IntEnumPtr";
+                ToAronType.writerClassType = "armarx::aron::type::writer::VariantWriter";
+                ToAronType.include =
+                    "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
+                ToAronType.enforceConversion = "armarx::aron::type::IntEnum::DynamicCastAndCheck";
+                initialIntEnumTypeWriters.push_back(ToAronType);
+            }
+            {
+                // The toAron Serializer is visible by default
+                codegenerator::WriterInfo ToAronTypeDTO;
+                ToAronTypeDTO.methodName = "ToAronTypeDTO";
+                ToAronTypeDTO.returnType = "armarx::aron::type::dto::IntEnumPtr";
+                ToAronTypeDTO.writerClassType = "armarx::aron::type::writer::VariantWriter";
+                ToAronTypeDTO.include =
+                    "<RobotAPI/libraries/aron/core/type/rw/writer/variant/VariantWriter.h>";
+                ToAronTypeDTO.enforceConversion = "armarx::aron::type::IntEnum::DynamicCastAndCheck";
+                ToAronTypeDTO.enforceMemberAccess = "->toIntEnumDTO()";
+                initialIntEnumTypeWriters.push_back(ToAronTypeDTO);
+            }
         }
     }
 
     void Writer::addSpecificReaderMethods()
     {
-        // The static FromAron Deserializer
+        // Dict stuff
         {
-            codegenerator::StaticReaderInfo fromAron;
-            fromAron.methodName = "FromAron";
-            fromAron.argumentType = "armarx::aron::data::DictPtr";
-            fromAron.returnType = OWN_TYPE_NAME;
-            staticDataReaders.push_back(fromAron);
-        }
-
-        {
-            codegenerator::StaticReaderInfo fromAronDTO;
-            fromAronDTO.methodName = "FromAron";
-            fromAronDTO.argumentType = "armarx::aron::data::dto::DictPtr";
-            fromAronDTO.returnType = OWN_TYPE_NAME;
-            staticDataReaders.push_back(fromAronDTO);
-        }
-
-
-        // The fromAron Deserializer is visible by default
-        {
-            codegenerator::ReaderInfo fromAron;
-            fromAron.methodName = "fromAron";
-            fromAron.argumentType = "armarx::aron::data::DictPtr";
-            fromAron.readerClassType = "armarx::aron::data::reader::VariantReader";
-            fromAron.include = "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
-            dataReaders.push_back(fromAron);
+            {
+                codegenerator::StaticReaderInfo fromAron;
+                fromAron.methodName = "FromAron";
+                fromAron.argumentType = "armarx::aron::data::DictPtr";
+                fromAron.returnType = OWN_TYPE_NAME;
+                staticDictDataReaders.push_back(fromAron);
+            }
+            {
+                codegenerator::StaticReaderInfo fromAronDTO;
+                fromAronDTO.methodName = "FromAron";
+                fromAronDTO.argumentType = "armarx::aron::data::dto::DictPtr";
+                fromAronDTO.returnType = OWN_TYPE_NAME;
+                staticDictDataReaders.push_back(fromAronDTO);
+            }
+            {
+                codegenerator::ReaderInfo fromAron;
+                fromAron.methodName = "fromAron";
+                fromAron.argumentType = "armarx::aron::data::DictPtr";
+                fromAron.readerClassType = "armarx::aron::data::reader::VariantReader";
+                fromAron.include = "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
+                fromAron.override = true;
+                dictDataReaders.push_back(fromAron);
+            }
+            {
+                codegenerator::ReaderInfo fromAronDTO;
+                fromAronDTO.methodName = "fromAron";
+                fromAronDTO.argumentType = "armarx::aron::data::dto::DictPtr";
+                fromAronDTO.readerClassType = "armarx::aron::data::reader::VariantReader";
+                fromAronDTO.include = "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
+                fromAronDTO.enforceConversion = "std::make_shared<armarx::aron::data::Dict>";
+                fromAronDTO.override = true;
+                dictDataReaders.push_back(fromAronDTO);
+            }
         }
 
+        // IntEnum stuff
         {
-            codegenerator::ReaderInfo fromAronDTO;
-            fromAronDTO.methodName = "fromAron";
-            fromAronDTO.argumentType = "armarx::aron::data::dto::DictPtr";
-            fromAronDTO.readerClassType = "armarx::aron::data::reader::VariantReader";
-            fromAronDTO.include = "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
-            fromAronDTO.enforceConversion = "std::make_shared<armarx::aron::data::Dict>";
-            dataReaders.push_back(fromAronDTO);
+            {
+                codegenerator::StaticReaderInfo fromAron;
+                fromAron.methodName = "FromAron";
+                fromAron.argumentType = "armarx::aron::data::IntPtr";
+                fromAron.returnType = OWN_TYPE_NAME;
+                staticIntEnumDataReaders.push_back(fromAron);
+            }
+            {
+                codegenerator::StaticReaderInfo fromAronDTO;
+                fromAronDTO.methodName = "FromAron";
+                fromAronDTO.argumentType = "armarx::aron::data::dto::AronIntPtr";
+                fromAronDTO.returnType = OWN_TYPE_NAME;
+                staticIntEnumDataReaders.push_back(fromAronDTO);
+            }
+            {
+                codegenerator::ReaderInfo fromAron;
+                fromAron.methodName = "fromAron";
+                fromAron.argumentType = "armarx::aron::data::IntPtr";
+                fromAron.readerClassType = "armarx::aron::data::reader::VariantReader";
+                fromAron.include = "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
+                fromAron.override = true;
+                intEnumDataReaders.push_back(fromAron);
+            }
+            {
+                codegenerator::ReaderInfo fromAronDTO;
+                fromAronDTO.methodName = "fromAron";
+                fromAronDTO.argumentType = "armarx::aron::data::dto::AronIntPtr";
+                fromAronDTO.readerClassType = "armarx::aron::data::reader::VariantReader";
+                fromAronDTO.include =
+                    "<RobotAPI/libraries/aron/core/data/rw/reader/variant/VariantReader.h>";
+                fromAronDTO.enforceConversion = "std::make_shared<armarx::aron::data::Int>";
+                fromAronDTO.override = true;
+                intEnumDataReaders.push_back(fromAronDTO);
+            }
         }
     }
 
@@ -151,7 +282,7 @@ namespace armarx::aron::codegenerator::cpp
                 std::vector<std::string> tmpl_requires;
                 for (auto& t : type->getTemplates())
                 {
-                    tmpl_requires.push_back("armarx::aron::cpp::isAronGeneratedClass<" + t + ">");
+                    tmpl_requires.push_back("armarx::aron::cpp::isAronGeneratedObject<" + t + ">");
                     tmpl.push_back("class " + t);
                 }
                 std::string templateDef = "template <" + simox::alg::join(tmpl, ", ") + ">";
@@ -167,11 +298,11 @@ namespace armarx::aron::codegenerator::cpp
             }
             else
             {
-                c->addInherit("public armarx::aron::cpp::AronGeneratedClass");
+                c->addInherit("public armarx::aron::cpp::AronGeneratedObject<" + generator.getFullClassCppTypename() + ">");
             }
 
             // Writermethods
-            for (codegenerator::WriterInfo info : dataWriters)
+            for (codegenerator::WriterInfo info : dictDataWriters)
             {
                 if (info.returnType == OWN_TYPE_NAME)
                 {
@@ -182,13 +313,14 @@ namespace armarx::aron::codegenerator::cpp
                 {
                     c->addInclude(info.include);
                 }
+
                 CppMethodPtr convert = generator.toSpecializedDataWriterMethod(info);
-                c->addMethod(convert);
+                c->addPublicMethod(convert);
             }
 
             // Add methods to set the member variables
             // also resolve the original class name if the return type is set to special
-            for (codegenerator::StaticReaderInfo info : staticDataReaders)
+            for (codegenerator::StaticReaderInfo info : staticDictDataReaders)
             {
                 if (info.returnType == OWN_TYPE_NAME)
                 {
@@ -200,11 +332,11 @@ namespace armarx::aron::codegenerator::cpp
                 }
 
                 CppMethodPtr convert = generator.toSpecializedStaticDataReaderMethod(info);
-                c->addMethod(convert);
+                c->addPublicMethod(convert);
             }
 
             // Add methods to set the member variables
-            for (codegenerator::ReaderInfo info : dataReaders)
+            for (codegenerator::ReaderInfo info : dictDataReaders)
             {
                 if (info.argumentType == OWN_TYPE_NAME)
                 {
@@ -215,12 +347,13 @@ namespace armarx::aron::codegenerator::cpp
                 {
                     c->addInclude(info.include);
                 }
+
                 CppMethodPtr convert = generator.toSpecializedDataReaderMethod(info);
-                c->addMethod(convert);
+                c->addPublicMethod(convert);
             }
 
             // Typewritermethods
-            for (codegenerator::WriterInfo info : initialTypeWriters)
+            for (codegenerator::WriterInfo info : initialDictTypeWriters)
             {
                 if (info.returnType == OWN_TYPE_NAME)
                 {
@@ -232,7 +365,7 @@ namespace armarx::aron::codegenerator::cpp
                     c->addInclude(info.include);
                 }
                 CppMethodPtr convert = generator.toSpecializedTypeWriterMethod(info);
-                c->addMethod(convert);
+                c->addPublicMethod(convert);
             }
 
             typeClasses.push_back(c);
@@ -247,40 +380,139 @@ namespace armarx::aron::codegenerator::cpp
             ARMARX_CHECK_NOT_NULL(nav);
 
             generator::IntEnumClass generator(*nav);
+
+            // Create enum class and add to enums
+            CppEnumPtr enumrepresentation = setupEnumPtr(publicGenerateIntEnumType, generator);
+            typeEnums.push_back(enumrepresentation);
+
+            // Generate aron wrapper class and add to classes
             CppClassPtr c = setupBasicCppClass(publicGenerateIntEnumType, generator);
+            c->addInclude("<RobotAPI/libraries/aron/core/data/variant/primitive/Int.h>");
+
             setupMemberFields(c, publicGenerateIntEnumType.doc_values, generator);
 
-            c->addInherit("public armarx::aron::cpp::AronGeneratedClass");
+            c->addInherit("public armarx::aron::cpp::AronGeneratedIntEnum<" + generator.getFullClassCppTypename() + ">");
 
             // ctor
-            c->addCtor(generator.toInnerEnumCtor(c->getName()));
-
-            // Specific methods
-            CppEnumPtr enumrepresentation = generator.toInnerEnumDefinition();
-            c->addInnerEnum(enumrepresentation);
+            c->addCtor(generator.toEnumCtor(c->getName()));
 
             CppMethodPtr toString = generator.toToStringMethod();
-            c->addMethod(toString);
+            c->addPublicMethod(toString);
 
             CppMethodPtr fromString = generator.toFromStringMethod();
-            c->addMethod(fromString);
+            c->addPublicMethod(fromString);
 
             CppMethodPtr intConversion = generator.toIntMethod();
-            c->addMethod(intConversion);
+            c->addPublicMethod(intConversion);
 
             CppMethodPtr enumAssignment = generator.toEnumAssignmentMethod();
-            c->addMethod(enumAssignment);
+            c->addPublicMethod(enumAssignment);
 
             CppMethodPtr enumAssignment2 = generator.toCopyAssignmentMethod();
-            c->addMethod(enumAssignment2);
+            c->addPublicMethod(enumAssignment2);
 
             CppMethodPtr enumAssignment3 = generator.toIntAssignmentMethod();
-            c->addMethod(enumAssignment3);
+            c->addPublicMethod(enumAssignment3);
+
+            // Writermethods
+            for (codegenerator::WriterInfo info : intEnumDataWriters)
+            {
+                if (info.returnType == OWN_TYPE_NAME)
+                {
+                    info.returnType = generator.getFullClassCppTypename();
+                }
+
+                if (!info.include.empty())
+                {
+                    c->addInclude(info.include);
+                }
+
+                CppMethodPtr convert = generator.toSpecializedDataWriterMethod(info);
+                c->addPublicMethod(convert);
+            }
+
+            // Add methods to set the member variables
+            // also resolve the original class name if the return type is set to special
+            for (codegenerator::StaticReaderInfo info : staticIntEnumDataReaders)
+            {
+                if (info.returnType == OWN_TYPE_NAME)
+                {
+                    info.returnType = generator.getFullClassCppTypename();
+                }
+                if (info.argumentType == OWN_TYPE_NAME)
+                {
+                    info.argumentType = generator.getFullClassCppTypename();
+                }
+
+                CppMethodPtr convert = generator.toSpecializedStaticDataReaderMethod(info);
+                c->addPublicMethod(convert);
+            }
+
+            // Add methods to set the member variables
+            for (codegenerator::ReaderInfo info : intEnumDataReaders)
+            {
+                if (info.argumentType == OWN_TYPE_NAME)
+                {
+                    info.argumentType = generator.getFullClassCppTypename();
+                }
+
+                if (!info.include.empty())
+                {
+                    c->addInclude(info.include);
+                }
+                CppMethodPtr convert = generator.toSpecializedDataReaderMethod(info);
+                c->addPublicMethod(convert);
+            }
+
+            // Typewritermethods
+            for (codegenerator::WriterInfo info : initialIntEnumTypeWriters)
+            {
+                if (info.returnType == OWN_TYPE_NAME)
+                {
+                    info.returnType = generator.getFullClassCppTypename();
+                }
+
+                if (!info.include.empty())
+                {
+                    c->addInclude(info.include);
+                }
+                CppMethodPtr convert = generator.toSpecializedTypeWriterMethod(info);
+                c->addPublicMethod(convert);
+            }
 
             typeClasses.push_back(c);
         }
     }
 
+    CppEnumPtr Writer::setupEnumPtr(const typereader::GenerateInfo& info, const generator::IntEnumClass& gen) const
+    {
+        const auto& type = gen.getType();
+        if (type.getMaybe() != type::Maybe::NONE)
+        {
+            // Should not happen since we check the maybe flag on creation of the generator. However, better to double check
+            throw error::ValueNotValidException(__PRETTY_FUNCTION__, "Somehow the maybe flag of a top level object declaration is set. This is not valid!", std::to_string((int) type.getMaybe()) + " aka " + type::defaultconversion::string::Maybe2String.at(type.getMaybe()), type.getPath());
+        }
+
+        const std::string classCppTypename = gen.getClassCppTypename();
+
+        std::vector<std::string> namespaces = info.getNamespaces();
+        std::string rawObjectName = info.getNameWithoutNamespace();
+        namespaces.push_back(simox::alg::to_lower(camelToSnake(rawObjectName)) + "_details");
+
+        std::string enumdoc = "The enum definition of the enum of the auogenerated class '" + gen.getFullClassCppTypename() + "'.";
+        CppEnumPtr e = std::make_shared<CppEnum>(namespaces, "Enum");
+        auto enumFields = gen.toEnumFields();
+
+        ARMARX_CHECK(enumFields.size() > 0);
+
+        for (const auto& field : enumFields)
+        {
+            e->addField(field);
+        }
+
+        return e;
+    }
+
     CppClassPtr Writer::setupBasicCppClass(const typereader::GenerateInfo& info, const Generator& gen) const
     {
         const auto& type = gen.getType();
@@ -308,7 +540,6 @@ namespace armarx::aron::codegenerator::cpp
         }
 
         c->addClassDoc(classDoc);
-        c->setPragmaOnceIncludeGuard(true);
 
         // add generator includes (e.g. coming from dto types)
         for (const auto& s : gen.getRequiredIncludes())
@@ -328,48 +559,50 @@ namespace armarx::aron::codegenerator::cpp
             }
         }
 
-        // add aron includes
+        // always add aron includes
         c->addInclude("<RobotAPI/libraries/aron/core/aron_conversions.h>");
         c->addInclude("<RobotAPI/libraries/aron/core/rw.h>");
         c->addInclude("<RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedClass.h>");
+        c->addInclude("<RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedObject.h>");
+        c->addInclude("<RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedIntEnum.h>");
 
         // ctor
         c->addCtor(gen.toCtor(c->getName()));
         c->addCtor(gen.toCopyCtor(c->getName()));
 
         // dtor
-        c->addMethod(gen.toDtor(c->getName()));
+        c->addPublicMethod(gen.toDtor(c->getName()));
 
         // Generic methods
         //std::cout << "Generate equals method" << std::endl;
         CppMethodPtr equals = gen.toEqualsMethod();
-        c->addMethod(equals);
+        c->addPublicMethod(equals);
 
         //std::cout << "Generate reset method" << std::endl;
         CppMethodPtr resetHard = gen.toResetHardMethod();
-        c->addMethod(resetHard);
+        c->addPublicMethod(resetHard);
 
         //std::cout << "Generate init method" << std::endl;
         CppMethodPtr resetSoft = gen.toResetSoftMethod();
-        c->addMethod(resetSoft);
+        c->addPublicMethod(resetSoft);
 
         //std::cout << "Generate writeInit method" << std::endl;
         CppMethodPtr writeType = gen.toWriteTypeMethod();
-        c->addMethod(writeType);
+        c->addPublicMethod(writeType);
 
         //std::cout << "Generate write method" << std::endl;
         CppMethodPtr write = gen.toWriteMethod();
-        c->addMethod(write);
+        c->addPublicMethod(write);
 
         //std::cout << "Generate read method" << std::endl;
         CppMethodPtr read = gen.toReadMethod();
-        c->addMethod(read);
+        c->addPublicMethod(read);
         return c;
     }
 
     void Writer::setupMemberFields(CppClassPtr& c, const std::map<std::string, std::string>& doc_members, const generator::ObjectClass& o) const
     {
-        auto publicFields = o.getPublicVariableDeclarations("");
+        auto publicFields = o.getPublicVariableDeclarations(c->getName());
         for (const auto& f : publicFields)
         {
             if (auto it = doc_members.find(f->getName()); it != doc_members.end())
@@ -382,7 +615,7 @@ namespace armarx::aron::codegenerator::cpp
 
     void Writer::setupMemberFields(CppClassPtr& c, const std::map<std::string, std::string>& doc_members, const generator::IntEnumClass& o) const
     {
-        auto publicFields = o.getPublicVariableDeclarations("");
+        auto publicFields = o.getPublicVariableDeclarations(camelToSnake(c->getName()));
         for (const auto& f : publicFields)
         {
             if (auto it = doc_members.find(f->getName()); it != doc_members.end())
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.h b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.h
index 9405f63952de447de96a97e68fb3614bfec47807..3aa93f1775c7fe460935552c9eb078f8ae45ad0c 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/Writer.h
@@ -59,6 +59,8 @@ namespace armarx::aron::codegenerator::cpp
         virtual void addSpecificReaderMethods() override;
 
         CppClassPtr setupBasicCppClass(const typereader::GenerateInfo& info, const Generator& gen) const;
+        CppEnumPtr setupEnumPtr(const typereader::GenerateInfo& info, const generator::IntEnumClass& gen) const;
+
         void setupMemberFields(CppClassPtr&, const std::map<std::string, std::string>& doc_members, const generator::ObjectClass&) const;
         void setupMemberFields(CppClassPtr&, const std::map<std::string, std::string>& doc_members, const generator::IntEnumClass&) const;
 
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/Generator.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/Generator.cpp
index be87200f51f745b314ef7f3f7c2a67beb18d332a..d3c61320d0bd8d1f57fd03531edf1f79df5754f2 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/Generator.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/Generator.cpp
@@ -317,7 +317,7 @@ namespace armarx::aron::codegenerator::cpp
         doc << "@brief " << info.methodName << "() - This method returns a new data from the member data types using a writer implementation. \n";
         doc << "@return - the result of the writer implementation";
 
-        CppMethodPtr m = CppMethodPtr(new CppMethod(info.returnType + " " + info.methodName + "() const", doc.str()));
+        CppMethodPtr m = CppMethodPtr(new CppMethod(info.returnType + " " + info.methodName + "() const" + (info.override ? " override" : ""), doc.str()));
         m->addLine(info.writerClassType + " writer;");
         m->addLine("return " + info.enforceConversion + "(this->write(writer))" + info.enforceMemberAccess + ";");
 
@@ -331,7 +331,7 @@ namespace armarx::aron::codegenerator::cpp
         doc << "@brief " << info.methodName << " - This method sets the struct members to new values given in a reader implementation. \n";
         doc << "@return - nothing";
 
-        CppMethodPtr m = CppMethodPtr(new CppMethod("void " + info.methodName + "(const " + info.argumentType + "& input)", doc.str()));
+        CppMethodPtr m = CppMethodPtr(new CppMethod("void " + info.methodName + "(const " + info.argumentType + "& input)" + (info.override ? " override" : ""), doc.str()));
         m->addLine(info.readerClassType + " reader;");
         m->addLine("this->read(reader, " + info.enforceConversion + "(input)" + info.enforceMemberAccess + ");");
 
@@ -395,9 +395,9 @@ namespace armarx::aron::codegenerator::cpp
         return {field};
     }
 
-    std::pair<std::vector<std::pair<std::string, std::string>>, bool> Generator::getCtorInitializers(const std::string&) const
+    std::pair<std::vector<std::pair<std::string, std::string>>, bool> Generator::getCtorInitializers(const std::string& name) const
     {
-        return {{}, false};
+        return {{{name, "{}"}}, false};
     }
 
     CppBlockPtr Generator::getCtorBlock(const std::string&) const
@@ -408,7 +408,7 @@ namespace armarx::aron::codegenerator::cpp
     std::pair<std::vector<std::pair<std::string, std::string>>, bool> Generator::getCopyCtorInitializers(const std::string& name) const
     {
         const auto& t = getType();
-        if (t.getMaybe() == type::Maybe::UNIQUE_PTR || t.getMaybe() == type::Maybe::RAW_PTR)
+        if (t.getMaybe() == type::Maybe::UNIQUE_PTR) // unique ptrs cant be copied
         {
             return {{{name, ARON_OTHER_ACCESSOR + "." + name + " ? " + resolveMaybeGenerator("*" + ARON_OTHER_ACCESSOR + "." + name) + " : nullptr"}}, true};
         }
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
index 569d5be67dfd601cf09157655ff0542f022680ae..d0bf18091c9fd3310b1d0d9de98ff7c6c259eff3 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/Matrix.cpp
@@ -31,6 +31,7 @@ namespace armarx::aron::codegenerator::cpp::generator
 {
     const std::map<type::matrix::ElementType, std::tuple<std::string, int, std::string>> ElementType2Cpp =
     {
+        // TODO: rename to float32 etc. but keep backward compability
         {type::matrix::INT16, {"short", 2, "::armarx::aron::type::matrix::INT16"}},
         {type::matrix::INT32, {"int", 4, "::armarx::aron::type::matrix::INT32"}},
         {type::matrix::INT64, {"long", 8, "::armarx::aron::type::matrix::INT64"}},
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/PointCloud.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/PointCloud.cpp
index 78e42fe0850ee5f0ec665fe8c69eac4a70138317..1fe84d735e74cd59f63801c0096ac19cbe1e9f9f 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/PointCloud.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/ndarray/PointCloud.cpp
@@ -102,7 +102,19 @@ namespace armarx::aron::codegenerator::cpp::generator
         block_if_data->addLine("std::vector<int> " + dims + ";");
         block_if_data->addLine("std::vector<unsigned char> " + data + ";");
         block_if_data->addLine("" + ARON_READER_ACCESSOR + ".readNDArray("+variantAccessor+", "+dims+", "+type+", "+data+"); // of " + cppAccessor);
-        block_if_data->addLine(cppAccessor + " = " + getInstantiatedCppTypename() + "(" + dims + "[0], " + dims + "[1]);");
+
+        block_if_data->addLine("ARMARX_CHECK_AND_THROW(" + dims + ".size() == 3, ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, \"Received wrong dimensions for member '"+cppAccessor+"'.\"));");
+        block_if_data->addLine("ARMARX_CHECK_AND_THROW(" + type + " == \"" + std::get<0>(VoxelType2Cpp.at(this->type.getVoxelType())) + "\", ::armarx::aron::error::AronException(__PRETTY_FUNCTION__, \"Received wrong type for member '"+cppAccessor+"'.\"));");
+
+        // assign is not availablePCL for PCL 1.8
+        // block_if_data->addLine(cppAccessor + nextEl() + "assign(" + dims + "[0], " + dims + "[1], " + std::get<0>(VoxelType2Cpp.at(this->type.getVoxelType())) + "());");
+        block_if_data->addLine(cppAccessor + nextEl() + "clear();");
+        // resize(width, height , value) is not available either
+        // block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + "[0], " + dims + "[1], " + std::get<0>(VoxelType2Cpp.at(this->type.getVoxelType())) + "()));");
+        block_if_data->addLine(cppAccessor + nextEl() + "resize(" + dims + "[0] * " + dims + "[1]);");
+        block_if_data->addLine(cppAccessor + nextEl() + "width = " + dims + "[0];");
+        block_if_data->addLine(cppAccessor + nextEl() + "height = " + dims + "[1];");
+
         block_if_data->addLine("std::memcpy(reinterpret_cast<unsigned char*>(" + cppAccessor + nextEl() + "points.data()), "+data+".data(), "+data+".size());");
         return resolveMaybeReadBlock(block_if_data, cppAccessor, variantAccessor);
     }
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.cpp
index f5463258db1423ba317c428b2d604907b913755a..0cddfd33161dcd0bf5f398fa87f4c0a88ec0a447 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.cpp
@@ -44,7 +44,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         }
     }
 
-    std::vector<CppFieldPtr> IntEnumClass::getPublicVariableDeclarations(const std::string&) const
+    std::vector<CppFieldPtr> IntEnumClass::getPublicVariableDeclarations(const std::string& className) const
     {
         std::vector<CppFieldPtr> fields;
         std::stringstream enum_to_name;
@@ -52,6 +52,11 @@ namespace armarx::aron::codegenerator::cpp::generator
         std::stringstream enum_to_value;
         std::stringstream value_to_enum;
 
+        // add legacy typedef
+        fields.push_back(std::make_shared<CppField>("using", std::string(IMPL_ENUM), simox::alg::to_lower(className) + "_details::Enum", "Legacy typedef of enum"));
+
+        ARMARX_CHECK(type.getAcceptedValueMap().size() > 0);
+
         enum_to_name << "{" << std::endl;
         name_to_enum << "{" << std::endl;
         enum_to_value << "{" << std::endl;
@@ -78,7 +83,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         fields.push_back(std::make_shared<CppField>("static inline const std::map<" + std::string(IMPL_ENUM) + ", int>", "EnumToValueMap", enum_to_value.str(), "Mapping enum values to a int value"));
         fields.push_back(std::make_shared<CppField>("static inline const std::map<int, " + std::string(IMPL_ENUM) + ">", "ValueToEnumMap", value_to_enum.str(), "Mapping int values to a enum"));
 
-        fields.push_back(std::make_shared<CppField>(std::string(IMPL_ENUM), "value", "", "The current value of the enum object"));
+        fields.push_back(std::make_shared<CppField>(std::string(IMPL_ENUM), "value", type.getAcceptedValueNames()[0], "The current value of the enum object"));
 
         return fields;
     }
@@ -159,12 +164,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         return c;
     }*/
 
-    std::pair<std::vector<std::pair<std::string, std::string>>, bool> IntEnumClass::getCopyCtorInitializers(const std::string&) const
-    {
-        return {{{"value", ARON_OTHER_ACCESSOR + ".value"}}, false};
-    }
-
-    CppCtorPtr IntEnumClass::toInnerEnumCtor(const std::string& name) const
+    CppCtorPtr IntEnumClass::toEnumCtor(const std::string& name) const
     {
         CppCtorPtr c = std::make_shared<CppCtor>(name + "(const " + std::string(IMPL_ENUM) + " e)");
         std::vector<std::pair<std::string, std::string>> initList = {{"value", "e"}};
@@ -173,12 +173,12 @@ namespace armarx::aron::codegenerator::cpp::generator
         return c;
     }
 
-    CppEnumPtr IntEnumClass::toInnerEnumDefinition() const
+    std::vector<CppEnumFieldPtr> IntEnumClass::toEnumFields() const
     {
-        CppEnumPtr e = std::make_shared<CppEnum>(std::string(IMPL_ENUM), "The internal enum definition of the enum of this autogenerated class.");
+        std::vector<CppEnumFieldPtr> e;
         for (const auto& [key, value] : type.getAcceptedValueMap())
         {
-            e->addField(std::make_shared<CppEnumField>(key));
+            e.push_back(std::make_shared<CppEnumField>(key));
         }
         return e;
     }
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.h b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.h
index 10d6ca0c14d8100e71d78944f24fd3f46870b8e1..fb5e22671ba678ea69072e7b97fee54dbdd395e9 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/IntEnumClass.h
@@ -43,8 +43,6 @@ namespace armarx::aron::codegenerator::cpp::generator
         // virtual implementations
         std::vector<CppFieldPtr> getPublicVariableDeclarations(const std::string&) const final;
 
-        std::pair<std::vector<std::pair<std::string, std::string>>, bool> getCopyCtorInitializers(const std::string&) const final;
-
         CppBlockPtr getResetHardBlock(const std::string& cppAccessor) const final;
         CppBlockPtr getResetSoftBlock(const std::string& cppAccessor) const final;
         CppBlockPtr getWriteTypeBlock(const std::string& typeAccessor, const std::string& cppAccessor, const Path&, std::string& variantAccessor) const final;
@@ -54,8 +52,8 @@ namespace armarx::aron::codegenerator::cpp::generator
 
         // TODO: Move some of those methods to upper class for enums (if we want to support multiple enums)
         //CppCtorPtr toCopyCtor(const std::string&) const;
-        CppCtorPtr toInnerEnumCtor(const std::string&) const;
-        CppEnumPtr toInnerEnumDefinition() const;
+        std::vector<CppEnumFieldPtr> toEnumFields() const;
+        CppCtorPtr toEnumCtor(const std::string&) const;
         CppMethodPtr toIntMethod() const;
         CppMethodPtr toCopyAssignmentMethod() const;
         CppMethodPtr toEnumAssignmentMethod() const;
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/ObjectClass.cpp b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/ObjectClass.cpp
index e3af89daa12ecc2de2f4fe60d9269dd48f729c9a..605c7b8655db3accb2dd1999d7c62e1cfc48730e 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/ObjectClass.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/codewriter/cpp/generator/toplevel/ObjectClass.cpp
@@ -47,7 +47,7 @@ namespace armarx::aron::codegenerator::cpp::generator
     std::vector<std::string> ObjectClass::getRequiredIncludes() const
     {
         std::vector<std::string> ret;
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             (void) key;
             auto child_s = FromAronType(*child);
@@ -59,7 +59,7 @@ namespace armarx::aron::codegenerator::cpp::generator
     std::vector<CppFieldPtr> ObjectClass::getPublicVariableDeclarations(const std::string&) const
     {
         std::vector<CppFieldPtr> fields;
-        for (const auto& [key, member] : type.getMemberTypes())
+        for (const auto& [key, member] : type.getDirectMemberTypes())
         {
             auto member_s = FromAronType(*member);
             std::vector<CppFieldPtr> member_fields = member_s->getPublicVariableDeclarations(key);
@@ -77,7 +77,7 @@ namespace armarx::aron::codegenerator::cpp::generator
             block_if_data->addLine(extends_s->getFullInstantiatedCppTypename() + "::resetSoft();");
         }
 
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             auto child_s = FromAronType(*child);
             CppBlockPtr b2 = child_s->getResetSoftBlock(key);
@@ -95,7 +95,7 @@ namespace armarx::aron::codegenerator::cpp::generator
             block_if_data->addLine(extends_s->getFullInstantiatedCppTypename() + "::resetHard();");
         }
 
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             const auto child_s = FromAronType(*child);
             CppBlockPtr b2 = child_s->getResetHardBlock(key);
@@ -127,7 +127,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         }
 
         b->addLine("// members of " + this->getFullInstantiatedCppTypename());
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             const auto child_s = FromAronType(*child);
             std::string child_return_variant;
@@ -176,7 +176,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         }
 
         block_if_data->addLine("// members of " + this->getFullInstantiatedCppTypename());
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             const auto child_s = FromAronType(*child);
             std::string child_return_variant;
@@ -210,7 +210,7 @@ namespace armarx::aron::codegenerator::cpp::generator
 
         block_if_data->addLine("" + ARON_READER_ACCESSOR + ".readDict("+variantAccessor+", "+OBJECT_MEMBERS_ACCESSOR+"); // of top level object " + getInstantiatedCppTypename());
 
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             const auto child_s = FromAronType(*child);
             std::string child_accessor = OBJECT_MEMBERS_ACCESSOR + "_" + key + "_iterator";
@@ -230,7 +230,7 @@ namespace armarx::aron::codegenerator::cpp::generator
             block_if_data->addLine("if (not (" + extends_s->getFullInstantiatedCppTypename() + "::operator== (" + otherInstanceAccessor + ")))");
             block_if_data->addLineAsBlock("return false;");
         }
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             auto child_s = FromAronType(*child);
             CppBlockPtr b2 = child_s->getEqualsBlock(key, otherInstanceAccessor + "." + key);
@@ -250,7 +250,7 @@ namespace armarx::aron::codegenerator::cpp::generator
         }
 
         bool anyComplex = false;
-        for (const auto& [key, child] : type.getMemberTypes())
+        for (const auto& [key, child] : type.getDirectMemberTypes())
         {
             auto child_s = FromAronType(*child);
             auto initList = child_s->getCopyCtorInitializers(key);
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/ReaderInfo.h b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/ReaderInfo.h
index 3bda10de7b14849fe6e18da11f7201704c2f3670..486a57879e42fa1eaced1d76231bf63f181a7312 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/ReaderInfo.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/ReaderInfo.h
@@ -37,6 +37,7 @@ namespace armarx::aron::codegenerator
         std::string include;
         std::string enforceConversion = "";
         std::string enforceMemberAccess = "";
+        bool override = false;
     };
 
 
diff --git a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/WriterInfo.h b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/WriterInfo.h
index 1989ac5de9e93ee5ddda8ac66cfa1e65edeab98b..c7dc87033b6fe87356e2b79a42b477ed8bd37b3d 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/WriterInfo.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/codegenerator/helper/WriterInfo.h
@@ -37,5 +37,6 @@ namespace armarx::aron::codegenerator
         std::string include;
         std::string enforceConversion = "";
         std::string enforceMemberAccess = "";
+        bool override = false;
     };
 }
diff --git a/source/RobotAPI/libraries/aron/codegeneration/test/CMakeLists.txt b/source/RobotAPI/libraries/aron/codegeneration/test/CMakeLists.txt
index d7add84ada2fcafe2c8bf8f9f9a8d2c40e663c7d..3b05caec20fae2d7a43b406f043e4c2da703923c 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/test/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/codegeneration/test/CMakeLists.txt
@@ -106,6 +106,24 @@ armarx_add_test(
         ${Simox_INCLUDE_DIR}
 )
 
+######################
+# ARON CONVERSION TEST
+######################
+armarx_add_test(
+    TEST_NAME
+        aronConversionTest
+    TEST_FILE
+        aronConversionTest.cpp
+    LIBS
+        SimoxUtility  # Simox::SimoxUtility
+        ArmarXCore
+        RobotAPI::aron
+    ARON_FILES
+        aron/HumanPoseTest.xml
+    INCLUDE_DIRECTORIES
+        ${Simox_INCLUDE_DIR}
+)
+
 ######################
 # ARON JSON EXPORT TEST
 ######################
diff --git a/source/RobotAPI/libraries/aron/codegeneration/test/aronConversionTest.cpp b/source/RobotAPI/libraries/aron/codegeneration/test/aronConversionTest.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..636f9bde6472fb9596a0a1a07d6343f3690da808
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/codegeneration/test/aronConversionTest.cpp
@@ -0,0 +1,97 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @package    RobotAPI::ArmarXObjects::aron
+ * @author     Simon Ottenhaus ( simon dot ottenhaus at kit dot edu )
+ * @date       2019
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#define BOOST_TEST_MODULE RobotAPI::ArmarXLibraries::aron
+
+#define ARMARX_BOOST_TEST
+
+// STD/STL
+#include <iostream>
+#include <cstdlib>
+#include <ctime>
+#include <numeric>
+
+// Test
+#include <RobotAPI/Test.h>
+
+// Aron
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/codegeneration/test/aron/HumanPoseTest.aron.generated.h>
+
+
+using namespace armarx;
+using namespace aron;
+
+namespace armarx
+{
+    class HumanPoseBO
+    {
+    public:
+        std::vector<float> jointValues;
+        bool reached;
+
+        HumanPoseBO() = default;
+
+        void fromAron(const HumanPoseTest& aron)
+        {
+            jointValues = aron.jointValues;
+            reached = aron.reached;
+        }
+
+        HumanPoseTest toAron()
+        {
+            HumanPoseTest aron;
+            aron.jointValues = jointValues;
+            aron.reached = reached;
+            return aron;
+        }
+    };
+
+    void fromAron(const HumanPoseTest& aron, HumanPoseBO& bo)
+    {
+        bo.jointValues = aron.jointValues;
+        bo.reached = aron.reached;
+    }
+
+    void toAron(HumanPoseTest& aron, const HumanPoseBO& bo)
+    {
+        aron.jointValues = bo.jointValues;
+        aron.reached = bo.reached;
+    }
+
+    BOOST_AUTO_TEST_CASE(AronAssignmentTest)
+    {
+        armarx::HumanPoseTest aron;
+        aron.jointValues = {1,2,3,4};
+        aron.reached = true;
+
+        HumanPoseBO bo;
+        aron.to(bo);
+
+        BOOST_CHECK((aron.jointValues == bo.jointValues));
+
+        HumanPoseBO bo2;
+        aron.to(bo, &fromAron);
+
+        BOOST_CHECK((aron.jointValues == bo2.jointValues));
+    }
+}
diff --git a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Data.h b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Data.h
index a2b724af0ceb6a029c76db86341e8445c725eebc..bc557478142396f30a2d92191b469e2f7fcf438f 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Data.h
+++ b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Data.h
@@ -24,12 +24,13 @@
 #pragma once
 
 // STD/STL
-#include <memory>
 #include <map>
+#include <memory>
 #include <optional>
 
 // ArmarX
 #include <SimoxUtility/xml.h>
+
 #include <ArmarXCore/core/rapidxml/wrapper/RapidXmlReader.h>
 
 /**
@@ -97,10 +98,10 @@ namespace armarx::aron::typereader::xml
         const std::string QUATERNION_TAG = "quaternion";
         const std::string IMAGE_TAG = "image";
         const std::string POINT_CLOUD_TAG = "pointcloud";
-        const std::string INT_TAG = "int";
-        const std::string LONG_TAG = "long";
-        const std::string FLOAT_TAG = "float";
-        const std::string DOUBLE_TAG = "double";
+        const std::string INT_TAG = "int32";
+        const std::string LONG_TAG = "int64";
+        const std::string FLOAT_TAG = "float32";
+        const std::string DOUBLE_TAG = "float64";
         const std::string STRING_TAG = "string";
         const std::string BOOL_TAG = "bool";
         const std::string ANY_OBJECT_TAG = "anyobject";
@@ -108,33 +109,88 @@ namespace armarx::aron::typereader::xml
         // others
         const std::vector<std::string> WHATEVER_VALUES = {"?"};
 
-        // Replacements ({tagName, {replacementsTag, additionalAronDTOXMLIncludePackagePath}})
-        const std::map<std::string, std::pair<std::string, std::pair<std::string, std::string>>> REPLACEMENTS =
+        struct Replacement
         {
-            {"position",    {"<matrix rows='3' cols='1' type='float32' />", {}}},
-            {"pose",        {"<matrix rows='4' cols='4' type='float32' />", {}}},
-            {"orientation", {"<quaternion type='float32' />",               {}}},
-
-            // You can also add replacements for arondtos here!
-            // structure: {xml-identifier, {replacement, auto-include}}
-            {"datetime",            {"<armarx::arondto::DateTime />",             {"RobotAPI", "libraries/aron/common/aron/time.xml"}}},
-            {"time",                {"<armarx::arondto::DateTime />",             {"RobotAPI", "libraries/aron/common/aron/time.xml"}}},
-            {"duration",            {"<armarx::arondto::Duration />",             {"RobotAPI", "libraries/aron/common/aron/time.xml"}}},
-            {"framedposition",      {"<armarx::arondto::FramedPosition />",       {"RobotAPI", "libraries/aron/common/aron/framed.xml"}}},
-            {"framedorientation",   {"<armarx::arondto::FramedOrientation />",    {"RobotAPI", "libraries/aron/common/aron/framed.xml"}}},
-            {"framedpose",          {"<armarx::arondto::FramedPose />",           {"RobotAPI", "libraries/aron/common/aron/framed.xml"}}}
+            std::string replacementTag;
+            std::pair<std::string, std::string> additionalAronDTOXMLIncludePackagePath;
+            std::string deprecatedWarning;
         };
-    }
 
+        // Replacements ({tagName, {replacementsTag, additionalAronDTOXMLIncludePackagePath}, deprecationwarning})
+        const std::map<std::string, Replacement> REPLACEMENTS = {
+            {"int",
+             {"<int32 />", {}, "The <int />-tag is deprecated. Please use <int32 /> instead."}},
+            {"long",
+             {"<int64 />", {}, "The <long />-tag is deprecated. Please use <int64 /> instead."}},
+            {"float",
+             {"<float32 />",
+              {},
+              "The <float />-tag is deprecated. Please use <float32 /> instead."}},
+            {"double",
+             {"<float64 />",
+              {},
+              "The <double />-tag is deprecated. Please use <float64 /> instead."}},
+
+            // should that be deprecated?
+            {"position", {"<matrix rows='3' cols='1' type='float32' />", {}, ""}},
+            {"pose", {"<matrix rows='4' cols='4' type='float32' />", {}, ""}},
+            {"orientation", {"<quaternion type='float32' />", {}, ""}},
+
+            // values similar to eigen
+            {"quaternionf", {"<quaternion type='float32' />", {}, ""}},
+            {"quaterniond", {"<quaternion type='float64' />", {}, ""}},
+            {"vector2f", {"<matrix rows='2' cols='1' type='float32' />", {}, ""}},
+            {"vector2d", {"<matrix rows='2' cols='1' type='float64' />", {}, ""}},
+            {"vector3f", {"<matrix rows='3' cols='1' type='float32' />", {}, ""}},
+            {"vector3d", {"<matrix rows='3' cols='1' type='float64' />", {}, ""}},
+            {"vector4f", {"<matrix rows='4' cols='1' type='float32' />", {}, ""}},
+            {"vector4d", {"<matrix rows='4' cols='1' type='float64' />", {}, ""}},
+            {"matrix2f", {"<matrix rows='2' cols='2' type='float32' />", {}, ""}},
+            {"matrix2d", {"<matrix rows='2' cols='2' type='float64' />", {}, ""}},
+            {"matrix3f", {"<matrix rows='3' cols='3' type='float32' />", {}, ""}},
+            {"matrix3d", {"<matrix rows='3' cols='3' type='float64' />", {}, ""}},
+            {"matrix4f", {"<matrix rows='4' cols='4' type='float32' />", {}, ""}},
+            {"matrix4d", {"<matrix rows='4' cols='4' type='float64' />", {}, ""}},
+
+            // You can also add replacements for arondtos here!
+            // structure: {xml-identifier, {replacement, auto-include}, deprecationwarning}
+            {"datetime",
+             {"<armarx::arondto::DateTime />",
+              {"RobotAPI", "libraries/aron/common/aron/time.xml"},
+              ""}},
+            {"time",
+             {"<armarx::arondto::DateTime />",
+              {"RobotAPI", "libraries/aron/common/aron/time.xml"},
+              ""}},
+            {"duration",
+             {"<armarx::arondto::Duration />",
+              {"RobotAPI", "libraries/aron/common/aron/time.xml"},
+              ""}},
+            {"framedposition",
+             {"<armarx::arondto::FramedPosition />",
+              {"RobotAPI", "libraries/aron/common/aron/framed.xml"},
+              ""}},
+            {"framedorientation",
+             {"<armarx::arondto::FramedOrientation />",
+              {"RobotAPI", "libraries/aron/common/aron/framed.xml"},
+              ""}},
+            {"framedpose",
+             {"<armarx::arondto::FramedPose />",
+              {"RobotAPI", "libraries/aron/common/aron/framed.xml"},
+              ""}}};
+    } // namespace constantes
 
     namespace util
     {
-        std::optional<RapidXmlReaderNode> GetFirstNodeWithTag(const RapidXmlReaderNode& node, const std::string& name);
+        std::optional<RapidXmlReaderNode> GetFirstNodeWithTag(const RapidXmlReaderNode& node,
+                                                              const std::string& name);
 
         void EnforceAttribute(const RapidXmlReaderNode& node, const std::string& att);
         bool HasAttribute(const RapidXmlReaderNode& node, const std::string& att);
         std::string GetAttribute(const RapidXmlReaderNode& node, const std::string& att);
-        std::string GetAttributeWithDefault(const RapidXmlReaderNode& node, const std::string& att, const std::string& def);
+        std::string GetAttributeWithDefault(const RapidXmlReaderNode& node,
+                                            const std::string& att,
+                                            const std::string& def);
         bool AttributeIsTrue(const RapidXmlReaderNode& node, const std::string& att);
 
         bool HasTagName(const RapidXmlReaderNode& node, const std::string& name);
@@ -147,5 +203,5 @@ namespace armarx::aron::typereader::xml
         void EnforceChildSize(const RapidXmlReaderNode& node, const size_t size);
         void EnforceChildSizeGreaterEqual(const RapidXmlReaderNode& node, const size_t size);
         void EnforceChildSizeGreater(const RapidXmlReaderNode& node, const size_t size);
-    }
-}
+    } // namespace util
+} // namespace armarx::aron::typereader::xml
diff --git a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Factory.cpp b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Factory.cpp
index 9b17f8aa6ec6cfb67dbb14ccaae3e97eb9b5c111..8409c87ba128e86bab38cf78f0994d34f35844fe 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Factory.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Factory.cpp
@@ -30,11 +30,16 @@
 #include "Factory.h"
 
 // ArmarX
+#include <ArmarXCore/core/time/DateTime.h>
 #include <RobotAPI/libraries/aron/core/type/variant/All.h>
 #include "Data.h"
 
 namespace armarx::aron::typereader::xml
 {
+    void printDeprecationWarning(const std::string& warning)
+    {
+        std::cout << "\033[1;33mAron deprecation warning: " << warning << "\033[0m" << std::endl;
+    }
 
     type::VariantPtr ReaderFactory::create(const RapidXmlReaderNode& node, const Path& path)
     {
@@ -65,8 +70,14 @@ namespace armarx::aron::typereader::xml
         // check for replacement
         if (auto it = constantes::REPLACEMENTS.find(simox::alg::to_lower(nodeToUse.name())); it != constantes::REPLACEMENTS.end())
         {
+            auto replacement = it->second;
+            if (!replacement.deprecatedWarning.empty())
+            {
+                printDeprecationWarning(replacement.deprecatedWarning);
+            }
+
             // We make the system believe there is another string in the xml
-            RapidXmlReaderPtr reader = RapidXmlReader::FromXmlString(it->second.first);
+            RapidXmlReaderPtr reader = RapidXmlReader::FromXmlString(replacement.replacementTag);
             nodeToUse = reader->getRoot();
         }
 
diff --git a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Reader.cpp b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Reader.cpp
index 0ca73e5b6e72da48d81babbd19efb49cc0c929e3..7e9c71cbecf3c5dd9d8952135b61625a84ce1a27 100644
--- a/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Reader.cpp
+++ b/source/RobotAPI/libraries/aron/codegeneration/typereader/xml/Reader.cpp
@@ -350,10 +350,12 @@ namespace armarx::aron::typereader::xml
         std::vector<std::pair<std::string, std::string>> ret;
         for (const auto& repl : constantes::REPLACEMENTS)
         {
-            if (not repl.second.second.first.empty() && not repl.second.second.second.empty() && util::HasTagName(node, repl.first))
+            auto replacement = repl.second;
+
+            if (not replacement.additionalAronDTOXMLIncludePackagePath.first.empty() && not replacement.additionalAronDTOXMLIncludePackagePath.second.empty() && util::HasTagName(node, repl.first))
             {
                 // we found a string that will be replaced so we might need to add a default include
-                ret.push_back(repl.second.second);
+                ret.push_back(replacement.additionalAronDTOXMLIncludePackagePath);
                 break;
             }
         }
diff --git a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..77743613df7297b67273debdbcb0c71c0d346dff
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.cpp
@@ -0,0 +1,151 @@
+#include "DatatypeConverter.h"
+
+namespace armarx::aron::converter
+{
+    void DatatypeConverter::visitAronVariant(const type::ObjectPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
+        dict->addElement(typeMemberName, type);
+
+        for (const auto& [key, child] : el->getMemberTypes())
+        {
+            DatatypeConverter converter;
+            aron::type::visit(converter, child);
+
+            dict->addElement(key, converter.latest);
+        }
+
+        latest = dict;
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::DictPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
+        dict->addElement(typeMemberName, type);
+
+        auto acceptedType = el->getAcceptedType();
+        DatatypeConverter converter;
+        aron::type::visit(converter, acceptedType);
+        dict->addElement(acceptedTypeMemberName, converter.latest);
+
+        latest = dict;
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::ListPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
+        dict->addElement(typeMemberName, type);
+
+        auto acceptedType = el->getAcceptedType();
+        DatatypeConverter converter;
+        aron::type::visit(converter, acceptedType);
+        dict->addElement(acceptedTypeMemberName, converter.latest);
+
+        latest = dict;
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::PairPtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
+        dict->addElement(typeMemberName, type);
+
+        auto acceptedType1 = el->getFirstAcceptedType();
+        DatatypeConverter converter1;
+        aron::type::visit(converter1, acceptedType1);
+        dict->addElement(firstAcceptedTypeMemberName, converter1.latest);
+
+        auto acceptedType2 = el->getSecondAcceptedType();
+        DatatypeConverter converter2;
+        aron::type::visit(converter2, acceptedType2);
+        dict->addElement(secondAcceptedTypeMemberName, converter2.latest);
+
+        latest = dict;
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::TuplePtr& el)
+    {
+        auto dict = aron::make_dict(el->getPath());
+        auto type = aron::make_string(el->getFullName(), Path(el->getPath(), {typeMemberName}));
+        dict->addElement(typeMemberName, type);
+
+        int i = 0;
+        for (const auto& child : el->getAcceptedTypes())
+        {
+            DatatypeConverter converter;
+            aron::type::visit(converter, child);
+
+            dict->addElement(acceptedTypeMemberName + "_" + std::to_string(i++), converter.latest);
+        }
+
+        latest = dict;
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::MatrixPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::NDArrayPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::QuaternionPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::PointCloudPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::ImagePtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::IntEnumPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::IntPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::LongPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::FloatPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::DoublePtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::BoolPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::StringPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+
+    void DatatypeConverter::visitAronVariant(const type::AnyObjectPtr& el)
+    {
+        latest = aron::make_string(el->getFullName(), el->getPath());
+    }
+}
diff --git a/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
new file mode 100644
index 0000000000000000000000000000000000000000..34201b359d763ac81901135b475fd875714ab05c
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/converter/common/DatatypeConverter.h
@@ -0,0 +1,62 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Peller ( fabian dot peller at kit dot edu )
+ * @date       2023
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include <algorithm>
+#include <vector>
+
+#include <RobotAPI/libraries/aron/core/data/variant/All.h>
+#include <RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h>
+
+namespace armarx::aron::converter
+{
+    class DatatypeConverter :
+        public aron::type::ConstVariantVisitor
+    {
+        const std::string typeMemberName = "_aron_type";
+        const std::string acceptedTypeMemberName = "_aron_accepted_type";
+        const std::string firstAcceptedTypeMemberName = "_aron_first_accepted_type";
+        const std::string secondAcceptedTypeMemberName = "_aron_second_accepted_type";
+
+        void visitAronVariant(const type::ObjectPtr&) override;
+        void visitAronVariant(const type::DictPtr&) override;
+        void visitAronVariant(const type::ListPtr&) override;
+        void visitAronVariant(const type::PairPtr&) override;
+        void visitAronVariant(const type::TuplePtr&) override;
+        void visitAronVariant(const type::MatrixPtr&) override;
+        void visitAronVariant(const type::NDArrayPtr&) override;
+        void visitAronVariant(const type::QuaternionPtr&) override;
+        void visitAronVariant(const type::PointCloudPtr&) override;
+        void visitAronVariant(const type::ImagePtr&) override;
+        void visitAronVariant(const type::IntEnumPtr&) override;
+        void visitAronVariant(const type::IntPtr&) override;
+        void visitAronVariant(const type::LongPtr&) override;
+        void visitAronVariant(const type::FloatPtr&) override;
+        void visitAronVariant(const type::DoublePtr&) override;
+        void visitAronVariant(const type::BoolPtr&) override;
+        void visitAronVariant(const type::StringPtr&) override;
+        void visitAronVariant(const type::AnyObjectPtr&) override;
+
+    public:
+        aron::data::VariantPtr latest;
+    };
+}
diff --git a/source/RobotAPI/libraries/aron/core/CMakeLists.txt b/source/RobotAPI/libraries/aron/core/CMakeLists.txt
index e17910e7f15989afc0c99c8284469074c1f88f34..2fb890b86fb3c9e1bd26bee37f879922c3d6bcd5 100644
--- a/source/RobotAPI/libraries/aron/core/CMakeLists.txt
+++ b/source/RobotAPI/libraries/aron/core/CMakeLists.txt
@@ -107,6 +107,8 @@ set(LIB_HEADERS
     Path.h
 
     codegeneration/cpp/AronGeneratedClass.h
+    codegeneration/cpp/AronGeneratedObject.h
+    codegeneration/cpp/AronGeneratedIntEnum.h
 
     aron_conversions.h
     rw.h
diff --git a/source/RobotAPI/libraries/aron/core/Path.cpp b/source/RobotAPI/libraries/aron/core/Path.cpp
index 8218b431b035ec878ef1a1165ed8c6cbf8b07ba5..8d15ca0c810a94fb2972c451ca87cf01758088f7 100644
--- a/source/RobotAPI/libraries/aron/core/Path.cpp
+++ b/source/RobotAPI/libraries/aron/core/Path.cpp
@@ -29,27 +29,21 @@
 
 namespace armarx::aron
 {
-    Path::Path() :
-        rootIdentifier("_ARON"),
-        delimeter("->")
+    Path::Path() : rootIdentifier(DEFAULT_ROOT_IDENTIFIER), delimeter(DEFAULT_DELIMETER)
     {
     }
 
     Path::Path(const std::vector<std::string>& p) :
-        path(p)
+        rootIdentifier(DEFAULT_ROOT_IDENTIFIER), delimeter(DEFAULT_DELIMETER), path(p)
     {
     }
 
     Path::Path(const Path& p) :
-        rootIdentifier(p.getRootIdentifier()),
-        delimeter(p.getDelimeter()),
-        path(p.getPath())
+        rootIdentifier(p.getRootIdentifier()), delimeter(p.getDelimeter()), path(p.getPath())
     {
-
     }
 
-    Path::Path(const Path& pa, const std::vector<std::string>& p) :
-        Path(pa)
+    Path::Path(const Path& pa, const std::vector<std::string>& p) : Path(pa)
     {
         for (const std::string& s : p)
         {
@@ -57,65 +51,78 @@ namespace armarx::aron
         }
     }
 
-    void Path::setRootIdentifier(const std::string& s)
+    void
+    Path::setRootIdentifier(const std::string& s)
     {
         rootIdentifier = s;
     }
 
-    std::string Path::getRootIdentifier() const
+    std::string
+    Path::getRootIdentifier() const
     {
         return rootIdentifier;
     }
 
-    void Path::setDelimeter(const std::string& d)
+    void
+    Path::setDelimeter(const std::string& d)
     {
         delimeter = d;
     }
 
-    std::string Path::getDelimeter() const
+    std::string
+    Path::getDelimeter() const
     {
         return delimeter;
     }
 
-    void Path::append(const std::string& str)
+    void
+    Path::append(const std::string& str)
     {
         path.push_back(str);
     }
 
-    std::vector<std::string> Path::getPath() const
+    std::vector<std::string>
+    Path::getPath() const
     {
         return path;
     }
 
-    std::string Path::getLastElement() const
+    std::string
+    Path::getLastElement() const
     {
         if (!hasElement())
         {
-            throw error::AronException(__PRETTY_FUNCTION__, "Try to access last element of empty vector.");
+            throw error::AronException(__PRETTY_FUNCTION__,
+                                       "Try to access last element of empty vector.");
         }
         return path.back();
     }
 
-    std::string Path::getFirstElement() const
+    std::string
+    Path::getFirstElement() const
     {
         if (!hasElement())
         {
-            throw error::AronException(__PRETTY_FUNCTION__, "Try to access last element of empty vector.");
+            throw error::AronException(__PRETTY_FUNCTION__,
+                                       "Try to access last element of empty vector.");
         }
         return path[0];
     }
 
-    bool Path::hasElement() const
+    bool
+    Path::hasElement() const
     {
         return path.size() > 0;
     }
 
-    size_t Path::size() const
+    size_t
+    Path::size() const
     {
         return path.size();
     }
 
-    std::string Path::toString() const
+    std::string
+    Path::toString() const
     {
         std::stringstream ss;
         ss << rootIdentifier;
@@ -126,7 +133,10 @@ namespace armarx::aron
         return ss.str();
     }
 
-    Path Path::FromString(const std::string& s, const std::string& rootIdentifier, const std::string& delimeter)
+    Path
+    Path::FromString(const std::string& s,
+                     const std::string& rootIdentifier,
+                     const std::string& delimeter)
     {
         std::vector<std::string> elements = simox::alg::split(s, delimeter);
         if (elements.size())
@@ -136,7 +146,8 @@ namespace armarx::aron
         return Path(elements);
     }
 
-    Path Path::withIndex(int i, bool escape) const
+    Path
+    Path::withIndex(int i, bool escape) const
     {
         std::string el = std::to_string(i);
         if (escape)
@@ -146,7 +157,8 @@ namespace armarx::aron
         return Path(*this, {el});
     }
 
-    Path Path::withElement(const std::string& s, bool escape) const
+    Path
+    Path::withElement(const std::string& s, bool escape) const
     {
         std::string el = s;
         if (escape)
@@ -156,7 +168,8 @@ namespace armarx::aron
         return Path(*this, {el});
     }
 
-    Path Path::withAcceptedType(bool escape) const
+    Path
+    Path::withAcceptedType(bool escape) const
     {
         std::string el = "::accepted_type";
         if (escape)
@@ -166,7 +179,8 @@ namespace armarx::aron
         return Path(*this, {el});
     }
 
-    Path Path::withAcceptedTypeIndex(int i, bool escape) const
+    Path
+    Path::withAcceptedTypeIndex(int i, bool escape) const
     {
         std::string el = "::accepted_type_" + std::to_string(i);
         if (escape)
@@ -176,7 +190,8 @@ namespace armarx::aron
         return Path(*this, {el});
     }
 
-    Path Path::withDetachedLastElement() const
+    Path
+    Path::withDetachedLastElement() const
     {
         std::vector<std::string> p = path;
         p.pop_back();
@@ -186,7 +201,8 @@ namespace armarx::aron
         return ret;
     }
 
-    Path Path::withDetachedFirstElement() const
+    Path
+    Path::withDetachedFirstElement() const
     {
         std::vector<std::string> p = path;
         p.erase(p.begin());
@@ -196,7 +212,8 @@ namespace armarx::aron
         return ret;
     }
 
-    Path Path::getWithoutPrefix(const Path& pref) const
+    Path
+    Path::getWithoutPrefix(const Path& pref) const
     {
         unsigned int firstWithoutMatch = 0;
         for (const std::string& el : pref.getPath())
@@ -210,11 +227,12 @@ namespace armarx::aron
                 firstWithoutMatch++;
             }
         }
-        std::vector<std::string> elementsWithoutPrefix(path.begin() + firstWithoutMatch, path.end());
+        std::vector<std::string> elementsWithoutPrefix(path.begin() + firstWithoutMatch,
+                                                       path.end());
 
         auto ret = Path(elementsWithoutPrefix);
         ret.setRootIdentifier(rootIdentifier);
         ret.setDelimeter(delimeter);
         return ret;
     }
-}
+} // namespace armarx::aron
diff --git a/source/RobotAPI/libraries/aron/core/Path.h b/source/RobotAPI/libraries/aron/core/Path.h
index a9ffffc8a993e39ec70d980a5e8cc50df49a42c1..a88a00d84317ee20526d06334ebac5e829020591 100644
--- a/source/RobotAPI/libraries/aron/core/Path.h
+++ b/source/RobotAPI/libraries/aron/core/Path.h
@@ -24,8 +24,8 @@
 #pragma once
 
 // STD/STL
-#include<vector>
-#include<string>
+#include <string>
+#include <vector>
 
 namespace armarx::aron
 {
@@ -36,10 +36,13 @@ namespace armarx::aron
     class Path
     {
     public:
+        static const constexpr char* DEFAULT_ROOT_IDENTIFIER = "_ARON";
+        static const constexpr char* DEFAULT_DELIMETER = "->";
+
         /// default constructor
         Path();
 
-        /// constructor, taking a list of strings (a path)
+        /// default constructor, taking a list of strings (a path)
         Path(const std::vector<std::string>&);
 
         /// copy constructor
@@ -48,7 +51,7 @@ namespace armarx::aron
         /// append constructor
         Path(const Path&, const std::vector<std::string>&);
 
-        /// comparison operator
+        /// copy operator
         Path& operator=(const armarx::aron::Path&) = default;
 
         std::vector<std::string> getPath() const;
@@ -69,7 +72,9 @@ namespace armarx::aron
         std::string getDelimeter() const;
 
         std::string toString() const;
-        static Path FromString(const std::string&, const std::string& rootIdentifier = "_ARON", const std::string& delimeter = "->");
+        static Path FromString(const std::string&,
+                               const std::string& rootIdentifier = DEFAULT_ROOT_IDENTIFIER,
+                               const std::string& delimeter = DEFAULT_DELIMETER);
 
         Path withDetachedFirstElement() const;
         Path withDetachedLastElement() const;
@@ -83,4 +88,4 @@ namespace armarx::aron
         std::string delimeter;
         std::vector<std::string> path;
     };
-}
+} // namespace armarx::aron
diff --git a/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedIntEnum.h b/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedIntEnum.h
new file mode 100644
index 0000000000000000000000000000000000000000..f173775dabfd4faf404ea47564f3e74183e32de8
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedIntEnum.h
@@ -0,0 +1,68 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
+ * Karlsruhe Institute of Technology (KIT), all rights reserved.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Peller-Konrad (fabian dot peller-konrad at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "AronGeneratedClass.h"
+
+
+namespace armarx::aron::cpp
+{
+    class AronGeneratedIntEnumBase : public AronGeneratedClass
+    {
+    public:
+        AronGeneratedIntEnumBase() = default;
+        virtual ~AronGeneratedIntEnumBase() = default;
+
+        /// Convert the current bo to an aron variant data dict
+        virtual armarx::aron::data::IntPtr toAron() const = 0;
+
+        /// Convert the current bo to the ice representation of an aron variant data dict
+        virtual armarx::aron::data::dto::AronIntPtr toAronDTO() const = 0;
+
+        /// Set all members of the current bo according to the aron variant data dict
+        virtual void fromAron(const armarx::aron::data::IntPtr& input) = 0;
+
+        /// Set all members of the current bo according to the ice representation of an aron variant data dict
+        virtual void fromAron(const armarx::aron::data::dto::AronIntPtr& input) = 0;
+    };
+
+    template <class Derived>
+    class AronGeneratedIntEnum :
+            public AronGeneratedIntEnumBase
+    {
+    public:
+
+    };
+
+    template <class T>
+    concept isAronGeneratedIntEnum = std::is_base_of<AronGeneratedIntEnumBase, T>::value;
+}
+
+namespace armarx::aron::codegenerator::cpp
+{
+    using AronGeneratedIntEnumBase = aron::cpp::AronGeneratedIntEnumBase;
+
+    template <class Derived>
+    using AronGeneratedIntEnum = aron::cpp::AronGeneratedIntEnum<Derived>;
+}
diff --git a/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedObject.h b/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedObject.h
new file mode 100644
index 0000000000000000000000000000000000000000..17d94831b41120c40dbb56932427e003fe3de1fd
--- /dev/null
+++ b/source/RobotAPI/libraries/aron/core/codegeneration/cpp/AronGeneratedObject.h
@@ -0,0 +1,111 @@
+/*
+ * This file is part of ArmarX.
+ *
+ * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T),
+ * Karlsruhe Institute of Technology (KIT), all rights reserved.
+ *
+ * ArmarX is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * ArmarX is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @author     Fabian Peller-Konrad (fabian dot peller-konrad at kit dot edu)
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+
+#pragma once
+
+#include "AronGeneratedClass.h"
+
+
+namespace armarx::aron::cpp
+{
+
+    class AronGeneratedObjectBase :
+            public AronGeneratedClass
+    {
+    public:
+        AronGeneratedObjectBase() = default;
+        virtual ~AronGeneratedObjectBase() = default;
+
+        /// Convert the current bo to an aron variant data dict
+        virtual armarx::aron::data::DictPtr toAron() const = 0;
+
+        /// Convert the current bo to the ice representation of an aron variant data dict
+        virtual armarx::aron::data::dto::DictPtr toAronDTO() const = 0;
+
+        /// Set all members of the current bo according to the aron variant data dict
+        virtual void fromAron(const armarx::aron::data::DictPtr& input) = 0;
+
+        /// Set all members of the current bo according to the ice representation of an aron variant data dict
+        virtual void fromAron(const armarx::aron::data::dto::DictPtr& input) = 0;
+    };
+
+    template <class Derived>
+    class AronGeneratedObject :
+        public AronGeneratedObjectBase
+    {
+    public:
+        AronGeneratedObject() = default;
+        virtual ~AronGeneratedObject() = default;
+
+        template <class T>
+        void to(T& t) const
+        {
+            const Derived* d = dynamic_cast<const Derived*>(this);
+            if (d)
+            {
+                t.fromAron(*d);
+            }
+        }
+
+        template <class T>
+        void from(const T& t)
+        {
+            Derived* d = dynamic_cast<Derived*>(this);
+            if (d)
+            {
+                t.toAron(*d);
+            }
+        }
+
+        template <class T>
+        void to(T& t, void(*fromAron)(const Derived&, T&)) const
+        {
+            const Derived* d = dynamic_cast<const Derived*>(this);
+            if (d)
+            {
+                fromAron(*d, t);
+            }
+        }
+
+        template <class T>
+        void from(const T& t, void(*toAron)(Derived&, const T&))
+        {
+            Derived* d = dynamic_cast<Derived*>(this);
+            if (d)
+            {
+                toAron(*d, t);
+            }
+        }
+    };
+
+    template <class T>
+    concept isAronGeneratedObject = std::is_base_of<AronGeneratedObjectBase, T>::value;
+}
+
+namespace armarx::aron::codegenerator::cpp
+{
+    using AronGeneratedObjectBase = aron::cpp::AronGeneratedObjectBase;
+
+    template <class Derived>
+    using AronGeneratedObject = aron::cpp::AronGeneratedObject<Derived>;
+}
diff --git a/source/RobotAPI/libraries/aron/core/data/visitor/RecursiveVisitor.h b/source/RobotAPI/libraries/aron/core/data/visitor/RecursiveVisitor.h
index 60cb4be0ff236ae6369f1c53adb743e96a8e31da..b9a817f59a692b2b1e288391ff9f7e438eb42002 100644
--- a/source/RobotAPI/libraries/aron/core/data/visitor/RecursiveVisitor.h
+++ b/source/RobotAPI/libraries/aron/core/data/visitor/RecursiveVisitor.h
@@ -57,7 +57,17 @@ namespace armarx::aron::data
         virtual void visitDouble(Input& element) {};
         virtual void visitBool(Input& element) {};
         virtual void visitString(Input& element) {};
-        virtual void visitUnknown(Input& element) { throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor."); }
+        virtual void visitUnknown(Input& element)
+        {
+            if (!element)
+            {
+                throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor. The element was NULL.");
+            }
+            else
+            {
+                throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor. The element was set but descriptor was undefined.");
+            }
+        }
         virtual ~RecursiveVisitor() = default;
     };
 
@@ -108,8 +118,16 @@ namespace armarx::aron::data
         virtual void visitBool(DataInput& elementData, TypeInput& elementType) {};
         virtual void visitString(DataInput& elementData, TypeInput& elementType) {};
         virtual void visitAnyObject(DataInput& elementData, TypeInput& elementType) {};
-        virtual void visitUnknown(DataInput& elementData, TypeInput& elementType) {
-            throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor.");
+        virtual void visitUnknown(DataInput& elementData, TypeInput& elementType)
+        {
+            if (!elementData)
+            {
+                throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor. The element was NULL.");
+            }
+            else
+            {
+                throw error::AronException(__PRETTY_FUNCTION__, "Unknown type in visitor. The element was set but descriptor was undefined.");
+            }
         }
         virtual ~RecursiveTypedVisitor() = default;
     };
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 482c762d1426fef9c589a5c49e1ef14689cb6dcd..edaeccf90a02ec918fdbc90733a8209616e0bc1b 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.cpp
@@ -80,6 +80,16 @@ namespace armarx::aron::type
         return "armarx::aron::type::Dict<" + acceptedType->getFullName() + ">";
     }
 
+    std::string Dict::GetFullNamePrefix()
+    {
+        return "armarx::aron::type::Dict";
+    }
+
+    std::string Dict::GetNamePrefix()
+    {
+        return "Dict";
+    }
+
     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 4dfdd35e238b39b729d67c583ec9378fc19f5c0e..7ebbf72eaa7a7582d9b33157279b857c14756540 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Dict.h
@@ -59,6 +59,9 @@ namespace armarx::aron::type
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
+        static std::string GetFullNamePrefix();
+        static std::string GetNamePrefix();
+
     private:
         // members
         VariantPtr acceptedType;
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 7ee464bc121f8059dcd075dc29752e32be9761d4..958596b7e60f201e565d7082d2e26c7107d7ce05 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/List.cpp
@@ -80,6 +80,16 @@ namespace armarx::aron::type
         return "armarx::aron::type::List<" + acceptedType->getFullName() + ">";
     }
 
+    std::string List::GetFullNamePrefix()
+    {
+        return "armarx::aron::type::List";
+    }
+
+    std::string List::GetNamePrefix()
+    {
+        return "List";
+    }
+
     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 532146e010bf8217c4669649ee2da9771c0623ec..67db861e299cc4031f560fbaa6507b20f1f3fbc5 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/List.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/List.h
@@ -58,6 +58,9 @@ namespace armarx::aron::type
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
+        static std::string GetFullNamePrefix();
+        static std::string GetNamePrefix();
+
     private:
         // members
         VariantPtr acceptedType;
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 526cc9f053d5e7bbf1e96c5f38bbe1f49a52cfbe..f6d7d259a33220799098537cf1320d1a965bc4f7 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.cpp
@@ -54,15 +54,19 @@ namespace armarx::aron::type
         {
             memberTypes[key] = FromAronDTO(*t, path.withElement(key));
         }
+        if (o.parent)
+        {
+            extends = FromAronObjectDTO(o.parent);
+        }
     }
 
-    ObjectPtr Object::FromAronObjectDTO(const type::dto::AronObjectPtr& aron)
+    ObjectPtr Object::FromAronObjectDTO(const type::dto::AronObjectPtr& aron, const aron::Path& path)
     {
         if (!aron)
         {
             return nullptr;
         }
-        return std::make_shared<Object>(*aron);
+        return std::make_shared<Object>(*aron, path);
     }
 
     type::dto::AronObjectPtr Object::ToAronObjectDTO(const ObjectPtr& aron)
@@ -141,6 +145,7 @@ namespace armarx::aron::type
         ARMARX_CHECK_NOT_NULL(p);
         type::dto::AronObjectPtr ex = p->toAronObjectDTO();
         ARMARX_CHECK_NOT_NULL(ex);
+        aron->parent = ex;
         extends = p;
     }
 
@@ -266,6 +271,16 @@ namespace armarx::aron::type
         return "armarx::aron::type::Object<" + this->aron->objectName + (extends ? (" : " + extends->getFullName()) : "") + ">";
     }
 
+    std::string Object::GetFullNamePrefix()
+    {
+        return "armarx::aron::type::Object";
+    }
+
+    std::string Object::GetNamePrefix()
+    {
+        return "Object";
+    }
+
     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 9924c2cbd5e53a633122fa665b970cbc28bd6043..0f452d4b8070424af81d7d371e65acec54a4fdae 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Object.h
@@ -48,7 +48,8 @@ namespace armarx::aron::type
         Object(const std::string&, const std::vector<std::string>& templates = {}, const std::vector<std::string>& templateInstantiations = {}, 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 ObjectPtr FromAronObjectDTO(const type::dto::AronObjectPtr&,
+                                           const aron::Path& path = aron::Path());
         static type::dto::AronObjectPtr ToAronObjectDTO(const ObjectPtr&);
 
         // public member functions
@@ -86,6 +87,9 @@ namespace armarx::aron::type
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
+        static std::string GetFullNamePrefix();
+        static std::string GetNamePrefix();
+
     private:
         // members
         std::shared_ptr<Object> extends;
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 40b3cac3beb89df0323e08ffc681bde47ff29881..c147bd3dd3ab17a66b9e0068e6d3e044c663e67d 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.cpp
@@ -115,6 +115,16 @@ namespace armarx::aron::type
         return "armarx::aron::type::Pair<" + acceptedType1->getFullName() + ", " + acceptedType2->getFullName() + ">";
     }
 
+    std::string Pair::GetFullNamePrefix()
+    {
+        return "armarx::aron::type::Pair";
+    }
+
+    std::string Pair::GetNamePrefix()
+    {
+        return "Pair";
+    }
+
     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 a63f6819406ce2b328e97a4026aeae21127d7b09..e8bb11cd6fa82d711d87b39cf50b1dcfbd6f71fd 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Pair.h
@@ -62,6 +62,9 @@ namespace armarx::aron::type
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
+        static std::string GetFullNamePrefix();
+        static std::string GetNamePrefix();
+
     private:
         // members
         VariantPtr acceptedType1;
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 51d45e3975bb162460fd06893e91f388ac52b9f1..cdcd605f2d475d4e8e83ab1d25a25914cc32e99a 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.cpp
@@ -112,6 +112,16 @@ namespace armarx::aron::type
         return "armarx::aron::type::Tuple<" + simox::alg::to_string(names, ", ") + ">";
     }
 
+    std::string Tuple::GetFullNamePrefix()
+    {
+        return "armarx::aron::type::Tuple";
+    }
+
+    std::string Tuple::GetNamePrefix()
+    {
+        return "Tuple";
+    }
+
     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 3281584c15d6b4bb3e50c83ce598634a2bbec324..070bed6264c8a2d9c19751d1b7866794e6e3bfb8 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/container/Tuple.h
@@ -60,6 +60,9 @@ namespace armarx::aron::type
         std::vector<VariantPtr> getChildren() const override;
         size_t childrenSize() const override;
 
+        static std::string GetFullNamePrefix();
+        static std::string GetNamePrefix();
+
     private:
         std::vector<VariantPtr> acceptedTypes;
     };
diff --git a/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h b/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
index ce0d34761f476da47b41db3afc6af464e7ac3146..a15811e6330d35b4d879202bf45859d5cc0e95ff 100644
--- a/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
+++ b/source/RobotAPI/libraries/aron/core/type/variant/forward_declarations.h
@@ -31,5 +31,7 @@ namespace armarx::aron::type
     using StringPtr = std::shared_ptr<class String>;
     using BoolPtr = std::shared_ptr<class Bool>;
 
+    using AnyObjectPtr = std::shared_ptr<class AnyObject>;
+
 }
 
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h b/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
index a2f46088a7b0f2261f67fac9931597cd97934f2b..0a132de3166df5d582652f07295fa084ecc05c9b 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/RecursiveVisitor.h
@@ -151,9 +151,6 @@ namespace armarx::aron::type
         virtual void visitMatrix(Input&) {};
         virtual void visitNDArray(Input&) {};
         virtual void visitQuaternion(Input&) {};
-        virtual void visitOrientation(Input&) {};
-        virtual void visitPosition(Input&) {};
-        virtual void visitPose(Input&) {};
         virtual void visitImage(Input&) {};
         virtual void visitPointCloud(Input&) {};
         virtual void visitIntEnum(Input&) {};
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
index d2b1c19a07e2b04fbf1e547d1cc39859793c90cc..72e02863e6ca67aea5be0b20ed9999a091893292 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.cpp
@@ -147,6 +147,12 @@ namespace armarx::aron::type
         visitAronVariant(aron);
     }
 
+    void ConstVariantVisitor::visitAnyObject(Input& i)
+    {
+        auto aron = type::AnyObject::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
     void ConstVariantVisitor::visitAronVariant(const type::ObjectPtr&) {}
     void ConstVariantVisitor::visitAronVariant(const type::DictPtr&) {}
     void ConstVariantVisitor::visitAronVariant(const type::PairPtr&) {}
@@ -164,6 +170,7 @@ namespace armarx::aron::type
     void ConstVariantVisitor::visitAronVariant(const type::DoublePtr&) {}
     void ConstVariantVisitor::visitAronVariant(const type::BoolPtr&) {}
     void ConstVariantVisitor::visitAronVariant(const type::StringPtr&) {}
+    void ConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&) {}
 
     /****************************************************************************
      * RecursiveVariantVisitor
@@ -227,4 +234,166 @@ namespace armarx::aron::type
     {
         return GetTupleAcceptedTypes(t);
     }
+
+    void RecursiveConstVariantVisitor::visitObjectOnEnter(Input& i)
+    {
+        auto aron = type::Object::DynamicCastAndCheck(i);
+        visitAronVariantEnter(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitObjectOnExit(Input& i)
+    {
+        auto aron = type::Object::DynamicCastAndCheck(i);
+        visitAronVariantExit(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitDictOnEnter(Input& i)
+    {
+        auto aron = type::Dict::DynamicCastAndCheck(i);
+        visitAronVariantEnter(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitDictOnExit(Input& i)
+    {
+        auto aron = type::Dict::DynamicCastAndCheck(i);
+        visitAronVariantExit(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitPairOnEnter(Input& i)
+    {
+        auto aron = type::Pair::DynamicCastAndCheck(i);
+        visitAronVariantEnter(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitPairOnExit(Input& i)
+    {
+        auto aron = type::Pair::DynamicCastAndCheck(i);
+        visitAronVariantExit(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitTupleOnEnter(Input& i)
+    {
+        auto aron = type::Tuple::DynamicCastAndCheck(i);
+        visitAronVariantEnter(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitTupleOnExit(Input& i)
+    {
+        auto aron = type::Tuple::DynamicCastAndCheck(i);
+        visitAronVariantExit(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitListOnEnter(Input& i)
+    {
+        auto aron = type::List::DynamicCastAndCheck(i);
+        visitAronVariantEnter(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitListOnExit(Input& i)
+    {
+        auto aron = type::List::DynamicCastAndCheck(i);
+        visitAronVariantExit(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitMatrix(Input& i)
+    {
+        auto aron = type::Matrix::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitNDArray(Input& i)
+    {
+        auto aron = type::NDArray::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitQuaternion(Input & i)
+    {
+        auto aron = type::Quaternion::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitImage(Input& i)
+    {
+        auto aron = type::Image::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitPointCloud(Input& i)
+    {
+        auto aron = type::PointCloud::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitIntEnum(Input& i)
+    {
+        auto aron = type::IntEnum::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitInt(Input& i)
+    {
+        auto aron = type::Int::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitLong(Input& i)
+    {
+        auto aron = type::Long::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitFloat(Input& i)
+    {
+        auto aron = type::Float::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitDouble(Input& i)
+    {
+        auto aron = type::Double::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitBool(Input& i)
+    {
+        auto aron = type::Bool::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitString(Input& i)
+    {
+        auto aron = type::String::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitAnyObject(Input& i)
+    {
+        auto aron = type::AnyObject::DynamicCastAndCheck(i);
+        visitAronVariant(aron);
+    }
+
+    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ObjectPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::ObjectPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::DictPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::DictPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::PairPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::PairPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::TuplePtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::TuplePtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantEnter(const type::ListPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariantExit(const type::ListPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::NDArrayPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::MatrixPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::QuaternionPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::ImagePtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::PointCloudPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::IntEnumPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::IntPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::LongPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::FloatPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::DoublePtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::BoolPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::StringPtr&) {}
+    void RecursiveConstVariantVisitor::visitAronVariant(const type::AnyObjectPtr&) {}
 }
diff --git a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
index e7e87fa45974a37ded813f3bfc156417238e5a02..fccfae04aff6b10bca173d3b096001af51dd6782 100644
--- a/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
+++ b/source/RobotAPI/libraries/aron/core/type/visitor/variant/VariantVisitor.h
@@ -60,6 +60,7 @@ namespace armarx::aron::type
         void visitDouble(Input&) override;
         void visitBool(Input&) override;
         void visitString(Input&) override;
+        void visitAnyObject(Input&) override;
 
         // Use these if you do not want to cast manually
         virtual void visitAronVariant(const type::ObjectPtr&);
@@ -79,6 +80,7 @@ namespace armarx::aron::type
         virtual void visitAronVariant(const type::DoublePtr&);
         virtual void visitAronVariant(const type::BoolPtr&);
         virtual void visitAronVariant(const type::StringPtr&);
+        virtual void visitAronVariant(const type::AnyObjectPtr&);
     };
 
     /**
@@ -98,6 +100,57 @@ namespace armarx::aron::type
         static TupleElements GetTupleAcceptedTypes(Input& t);
         TupleElements getTupleAcceptedTypes(Input& t) override;
 
+        void visitObjectOnEnter(Input&) override;
+        void visitObjectOnExit(Input&) override;
+        void visitDictOnEnter(Input&) override;
+        void visitDictOnExit(Input&) override;
+        void visitPairOnEnter(Input&) override;
+        void visitPairOnExit(Input&) override;
+        void visitTupleOnEnter(Input&) override;
+        void visitTupleOnExit(Input&) override;
+        void visitListOnEnter(Input&) override;
+        void visitListOnExit(Input&) override;
+
+        void visitMatrix(Input&) override;
+        void visitNDArray(Input&) override;
+        void visitQuaternion(Input&) override;
+        void visitImage(Input&) override;
+        void visitPointCloud(Input&) override;
+        void visitIntEnum(Input&) override;
+        void visitInt(Input&) override;
+        void visitLong(Input&) override;
+        void visitFloat(Input&) override;
+        void visitDouble(Input&) override;
+        void visitBool(Input&) override;
+        void visitString(Input&) override;
+        void visitAnyObject(Input&) override;
+
+
+        // Use these if you do not want to cast manually
+        virtual void visitAronVariantEnter(const type::ObjectPtr&);
+        virtual void visitAronVariantExit(const type::ObjectPtr&);
+        virtual void visitAronVariantEnter(const type::DictPtr&);
+        virtual void visitAronVariantExit(const type::DictPtr&);
+        virtual void visitAronVariantEnter(const type::ListPtr&);
+        virtual void visitAronVariantExit(const type::ListPtr&);
+        virtual void visitAronVariantEnter(const type::PairPtr&);
+        virtual void visitAronVariantExit(const type::PairPtr&);
+        virtual void visitAronVariantEnter(const type::TuplePtr&);
+        virtual void visitAronVariantExit(const type::TuplePtr&);
+        virtual void visitAronVariant(const type::MatrixPtr&);
+        virtual void visitAronVariant(const type::NDArrayPtr&);
+        virtual void visitAronVariant(const type::QuaternionPtr&);
+        virtual void visitAronVariant(const type::PointCloudPtr&);
+        virtual void visitAronVariant(const type::ImagePtr&);
+        virtual void visitAronVariant(const type::IntEnumPtr&);
+        virtual void visitAronVariant(const type::IntPtr&);
+        virtual void visitAronVariant(const type::LongPtr&);
+        virtual void visitAronVariant(const type::FloatPtr&);
+        virtual void visitAronVariant(const type::DoublePtr&);
+        virtual void visitAronVariant(const type::BoolPtr&);
+        virtual void visitAronVariant(const type::StringPtr&);
+        virtual void visitAronVariant(const type::AnyObjectPtr&);
+
         virtual ~RecursiveConstVariantVisitor() = default;
     };
 }
diff --git a/source/RobotAPI/libraries/aron_component_config/ComponentPlugin.h b/source/RobotAPI/libraries/aron_component_config/ComponentPlugin.h
index 288462223d51f039e7b38316c0e24a6f2037801f..08e496d77a9d28f09ade6599f692a89ec06cdbc4 100644
--- a/source/RobotAPI/libraries/aron_component_config/ComponentPlugin.h
+++ b/source/RobotAPI/libraries/aron_component_config/ComponentPlugin.h
@@ -50,7 +50,7 @@ namespace armarx::plugins
         {
             ARMARX_TRACE;
             armarx::aron::component_config::PropertyDefinitionGetterVisitor vis(
-                parent<armarx::PropertyUser>());
+                parent<armarx::PropertyUser>(), prefix());
             auto data = std::static_pointer_cast<armarx::aron::data::Variant>(
                 config_.getUpToDateReadBuffer().toAron());
             auto type = config_.getUpToDateReadBuffer().ToAronType();
@@ -65,7 +65,7 @@ namespace armarx::plugins
         postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties) override
         {
             ARMARX_TRACE;
-            armarx::aron::component_config::PropertyDefinitionSetterVisitor vis(properties);
+            armarx::aron::component_config::PropertyDefinitionSetterVisitor vis(properties, prefix());
             const auto& config = config_.getUpToDateReadBuffer();
             armarx::aron::data::visitRecursive(vis, config.toAron(), config.ToAronType());
             ComponentPlugin::postCreatePropertyDefinitions(properties);
diff --git a/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.cpp b/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.cpp
index ee7d67c73021d5f72b5e3e266d24938b092fea0e..03b4c0f270a1b552034022b4fed16b341085be0f 100644
--- a/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.cpp
+++ b/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.cpp
@@ -157,8 +157,8 @@ namespace armarx::aron::component_config
     }
 
     PropertyDefinitionGetterVisitor::PropertyDefinitionGetterVisitor(
-        const armarx::PropertyUser& defs) :
-        property_user_(std::experimental::make_observer(&defs)), in_list_(false)
+        const armarx::PropertyUser& defs, const std::string& global_namespace):
+        property_user_(std::experimental::make_observer(&defs)), global_namespace_(global_namespace), in_list_(false)
     {
     }
 
@@ -246,16 +246,16 @@ namespace armarx::aron::component_config
                                                         const std::shared_ptr<type::Variant>& j)
     {
         INPUT_GUARD(i);
-        auto t = type::Object::DynamicCastAndCheck(j);
         if (global_namespace_.empty())
         {
+            auto t = type::Object::DynamicCastAndCheck(j);
             global_namespace_ = t->getObjectNameWithoutNamespace() + ".";
         }
     }
 
     PropertyDefinitionSetterVisitor::PropertyDefinitionSetterVisitor(
-        const PropertyDefinitionsPtr& defs) :
-        property_definitions_(std::experimental::make_observer(defs.get()))
+        const PropertyDefinitionsPtr& defs, const std::string& global_namespace) :
+        property_definitions_(std::experimental::make_observer(defs.get())), global_namespace_(global_namespace)
     {
     }
 
diff --git a/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.h b/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.h
index 3d48904146e5e7e5d01b90015df70d40db3a7b98..a9c1d5823bd8589acaea27b4f27928b4668ef853 100644
--- a/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.h
+++ b/source/RobotAPI/libraries/aron_component_config/PropertyDefinitionVisitors.h
@@ -34,7 +34,7 @@ namespace armarx::aron::component_config
     class PropertyDefinitionSetterVisitor : public aron::data::RecursiveConstTypedVariantVisitor
     {
     public:
-        explicit PropertyDefinitionSetterVisitor(const armarx::PropertyDefinitionsPtr& defs);
+        explicit PropertyDefinitionSetterVisitor(const armarx::PropertyDefinitionsPtr& defs, const std::string& global_namespace = "");
 
         void visitAronVariant(const data::IntPtr&, const type::IntEnumPtr&) override;
 
@@ -61,7 +61,7 @@ namespace armarx::aron::component_config
 
     private:
         std::experimental::observer_ptr<PropertyDefinitionContainer> property_definitions_;
-        std::string global_namespace_{""};
+        std::string global_namespace_;
         std::atomic<bool> in_list_{false};
     };
 
@@ -69,7 +69,7 @@ namespace armarx::aron::component_config
         public aron::data::RecursiveTypedVisitor<data::VariantPtr, const type::VariantPtr>
     {
     public:
-        explicit PropertyDefinitionGetterVisitor(const armarx::PropertyUser& defs);
+        explicit PropertyDefinitionGetterVisitor(const armarx::PropertyUser& defs, const std::string& global_namespace = "");
 
         type::Descriptor getDescriptor(DataInput& o, TypeInput& t) override;
 
@@ -109,7 +109,7 @@ namespace armarx::aron::component_config
 
     private:
         std::experimental::observer_ptr<const armarx::PropertyUser> property_user_;
-        std::string global_namespace_{""};
+        std::string global_namespace_;
         std::atomic<bool> in_list_;
     };
 
diff --git a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
index a53e04a2a92d5062dcb8785ca94301c44fc7865c..c76da14105facaf03ff55742b22ac968fe1fd196 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.cpp
@@ -6,24 +6,26 @@
 
 namespace armarx::plugins
 {
-    void SkillProviderComponentPlugin::preOnInitComponent()
+    void
+    SkillProviderComponentPlugin::preOnInitComponent()
     {
-
     }
 
-    void SkillProviderComponentPlugin::preOnConnectComponent()
+    void
+    SkillProviderComponentPlugin::preOnConnectComponent()
     {
         auto& p = parent<SkillProviderComponentPluginUser>();
         p.getProxy(myPrx, -1);
     }
 
-    void SkillProviderComponentPlugin::postOnConnectComponent()
+    void
+    SkillProviderComponentPlugin::postOnConnectComponent()
     {
         auto& p = parent<SkillProviderComponentPluginUser>();
         const std::string providerName = p.getName();
 
         // update skill ownership
-        for (auto& [skillName, impl] : p.skillImplementations)
+        for (auto& [skillName, impl] : skillImplementations)
         {
             impl.skill->manager = manager;
             impl.skill->providerName = providerName;
@@ -38,10 +40,11 @@ namespace armarx::plugins
         i.providedSkills = p.getSkillDescriptions();
         manager->addProvider(i);
 
-        p.connected = true;
+        connected = true;
     }
 
-    void SkillProviderComponentPlugin::preOnDisconnectComponent()
+    void
+    SkillProviderComponentPlugin::preOnDisconnectComponent()
     {
         auto& p = parent<SkillProviderComponentPluginUser>();
         std::string providerName = p.getName();
@@ -49,22 +52,27 @@ namespace armarx::plugins
         manager->removeProvider(providerName);
     }
 
-    void SkillProviderComponentPlugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties)
+    void
+    SkillProviderComponentPlugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties)
     {
         std::string prefix = "skill.";
-        properties->component(manager, "SkillMemory", prefix + "SkillManager", "The name of the SkillManager (or SkillMemory) proxy this provider belongs to.");
+        properties->component(
+            manager,
+            "SkillMemory",
+            prefix + "SkillManager",
+            "The name of the SkillManager (or SkillMemory) proxy this provider belongs to.");
     }
-}
-
 
-namespace armarx
-{
-    SkillProviderComponentPluginUser::SkillProviderComponentPluginUser()
+    void
+    SkillProviderComponentPlugin::addSkill(const skills::LambdaSkill::FunT& f,
+                                           const skills::SkillDescription& desc)
     {
-        addPlugin(plugin);
+        auto lambda = std::make_unique<skills::LambdaSkill>(f, desc);
+        addSkill(std::move(lambda));
     }
 
-    void SkillProviderComponentPluginUser::addSkill(std::unique_ptr<skills::Skill>&& skill)
+    void
+    SkillProviderComponentPlugin::addSkill(std::unique_ptr<skills::Skill>&& skill)
     {
         if (!skill)
         {
@@ -74,70 +82,119 @@ namespace armarx
         std::string skillName = skill->description.skillName;
         if (connected) // TODO: fix so that skills can be added anytime!!!
         {
-            ARMARX_WARNING << "The SkillProvider already registered to a manager. The skill '" + skillName + "' therefore cannot be added anymore. Please only add skills in the onInit method.";
+            ARMARX_WARNING << "The SkillProvider already registered to a manager. The skill '" +
+                                  skillName +
+                                  "' therefore cannot be added anymore. Please only add skills in "
+                                  "the onInit method.";
             return;
         }
 
         // lock skills map
-        std::unique_lock l(skillsMutex);
+        const std::unique_lock l(skillsMutex);
         if (skillImplementations.find(skillName) != skillImplementations.end())
         {
-            ARMARX_WARNING << "Try to add a skill '" + skillName + "' which already exists in list. Ignoring this skill.";
+            ARMARX_WARNING << "Try to add a skill '" + skillName +
+                                  "' which already exists in list. Ignoring this skill.";
             return;
         }
 
         ARMARX_INFO << "Adding skill and set owning provider name" << skillName;
         auto s = skillImplementations.emplace(skillName, std::move(skill));
-        s.first->second.statusUpdate.skillId = skills::SkillID(getName(), skillName);
+        s.first->second.statusUpdate.skillId = skills::SkillID(parent().getName(), skillName);
     }
 
-    void SkillProviderComponentPluginUser::addSkill(const skills::LambdaSkill::FunT& f, const skills::SkillDescription& desc)
+    skills::detail::SkillImplementationWrapper&
+    SkillProviderComponentPlugin::getSkill(const std::string& name)
     {
-        auto lambda = std::make_unique<skills::LambdaSkill>(f, desc);
-        addSkill(std::move(lambda));
+        ARMARX_CHECK_GREATER(skillImplementations.count(name), 0)
+            << "Skill '" + name + "' not found.";
+        const std::unique_lock l(skillsMutex);
+        return skillImplementations.at(name);
     }
 
-    skills::provider::dto::SkillDescription SkillProviderComponentPluginUser::getSkillDescription(const std::string& name, const Ice::Current &)
+    skills::provider::dto::SkillStatusUpdateMap
+    SkillProviderComponentPlugin::getSkillExecutionStatuses() const
     {
-        std::shared_lock l(skillsMutex);
-        const auto& skillWrapper = skillImplementations.at(name);
-        return skillWrapper.skill->description.toIce();
+        skills::provider::dto::SkillStatusUpdateMap skillUpdates;
+        const std::unique_lock l(skillsMutex);
+        for (const auto& [key, impl] : skillImplementations)
+        {
+            const std::shared_lock l2(impl.skillStatusMutex);
+            skillUpdates.insert({key, impl.statusUpdate.toIce()});
+        }
+        return skillUpdates;
     }
 
-    skills::provider::dto::SkillDescriptionMap SkillProviderComponentPluginUser::getSkillDescriptions(const Ice::Current &)
+    skills::provider::dto::SkillDescriptionMap
+    SkillProviderComponentPlugin::getSkillDescriptions() const
     {
-        std::shared_lock l(skillsMutex);
         skills::provider::dto::SkillDescriptionMap skillDesciptions;
-        for (const auto& [key, skillWrapper] : skillImplementations)
+        const std::unique_lock l(skillsMutex);
+        for (const auto& [key, impl] : skillImplementations)
         {
-            skillDesciptions.insert({key, skillWrapper.skill->description.toIce()});
+            skillDesciptions.insert({key, impl.skill->description.toIce()});
         }
         return skillDesciptions;
     }
 
-    skills::provider::dto::SkillStatusUpdate SkillProviderComponentPluginUser::getSkillExecutionStatus(const std::string& skill, const Ice::Current &)
+} // namespace armarx::plugins
+
+namespace armarx
+{
+    SkillProviderComponentPluginUser::SkillProviderComponentPluginUser()
+    {
+        addPlugin(plugin);
+    }
+
+    void
+    SkillProviderComponentPluginUser::addSkill(std::unique_ptr<skills::Skill>&& skill)
     {
-        std::shared_lock l(skillsMutex);
-        auto& skillWrapper = skillImplementations.at(skill);
+        plugin->addSkill(std::move(skill));
+    }
+
+    void
+    SkillProviderComponentPluginUser::addSkill(const skills::LambdaSkill::FunT& f,
+                                               const skills::SkillDescription& desc)
+    {
+        plugin->addSkill(f, desc);
+    }
+
+    skills::provider::dto::SkillDescription
+    SkillProviderComponentPluginUser::getSkillDescription(const std::string& name,
+                                                          const Ice::Current& /*unused*/)
+    {
+
+        const auto& skillWrapper = plugin->getSkill(name);
+        return skillWrapper.skill->description.toIce();
+    }
+
+    skills::provider::dto::SkillDescriptionMap
+    SkillProviderComponentPluginUser::getSkillDescriptions(const Ice::Current& /*unused*/)
+    {
+        return plugin->getSkillDescriptions();
+    }
 
-        std::shared_lock l2(skillWrapper.skillStatusMutex);
+    skills::provider::dto::SkillStatusUpdate
+    SkillProviderComponentPluginUser::getSkillExecutionStatus(const std::string& skill,
+                                                              const Ice::Current& /*unused*/)
+    {
+        auto& skillWrapper = plugin->getSkill(skill);
+
+        const std::shared_lock l(skillWrapper.skillStatusMutex);
         return skillWrapper.statusUpdate.toIce();
     }
 
-    skills::provider::dto::SkillStatusUpdateMap SkillProviderComponentPluginUser::getSkillExecutionStatuses(const Ice::Current &)
+    skills::provider::dto::SkillStatusUpdateMap
+    SkillProviderComponentPluginUser::getSkillExecutionStatuses(const Ice::Current& /*unused*/)
     {
-        std::shared_lock l(skillsMutex);
-        skills::provider::dto::SkillStatusUpdateMap skillUpdates;
-        for (const auto& [key, skillWrapper] : skillImplementations)
-        {
-            std::shared_lock l2(skillWrapper.skillStatusMutex);
-            skillUpdates.insert({key, skillWrapper.statusUpdate.toIce()});
-        }
-        return skillUpdates;
+        return plugin->getSkillExecutionStatuses();
     }
 
     // Please not that this method waits until the skill can be scheduled!
-    skills::provider::dto::SkillStatusUpdate SkillProviderComponentPluginUser::executeSkill(const skills::provider::dto::SkillExecutionRequest& info, const Ice::Current &)
+    skills::provider::dto::SkillStatusUpdate
+    SkillProviderComponentPluginUser::executeSkill(
+        const skills::provider::dto::SkillExecutionRequest& info,
+        const Ice::Current& /*unused*/)
     {
         // The skill will be executed in a different thread
         std::thread execution;
@@ -149,19 +206,17 @@ namespace armarx
 
         skills::provider::dto::SkillStatusUpdate ret;
         {
-            std::shared_lock l(skillsMutex);
-            std::string skillName = info.skillName;
-            ARMARX_CHECK_EXPRESSION(skillImplementations.count(skillName) > 0) << "\nThe names are: " << VAROUT(skillName) << ", " << VAROUT(getName());
-
-            // get reference of the wrapper
-            auto& wrapper = skillImplementations.at(skillName);
+            const std::string skillName = info.skillName;
+            auto& wrapper = plugin->getSkill(skillName);
 
             // async start execution. But we wait for the execution to finish at the end of this method
-            execution = std::thread([&ret, &wrapper, &info, &usedParameterization](){
-                // execute waits until the previous execution finishes.
-                auto x = wrapper.setupAndExecuteSkill(info.executorName, usedParameterization);
-                ret = x.toIce();
-            });
+            execution = std::thread(
+                [&ret, &wrapper, &info, &usedParameterization]()
+                {
+                    // execute waits until the previous execution finishes.
+                    auto x = wrapper.setupAndExecuteSkill(info.executorName, usedParameterization);
+                    ret = x.toIce();
+                });
         } // release lock. We don't know how long the skill needs to finish and we have to release the lock for being able to abort the execution
 
         if (execution.joinable())
@@ -171,12 +226,16 @@ namespace armarx
         return ret;
     }
 
-    void SkillProviderComponentPluginUser::abortSkill(const std::string& skillName, const Ice::Current &)
+    void
+    SkillProviderComponentPluginUser::abortSkill(const std::string& skillName, const Ice::Current& /*unused*/)
     {
-        std::shared_lock l(skillsMutex);
-        ARMARX_CHECK_EXPRESSION(skillImplementations.count(skillName) > 0);
-
-        auto& wrapper = skillImplementations.at(skillName);
+        auto& wrapper = plugin->getSkill(skillName);
         wrapper.skill->notifySkillToStopASAP();
     }
-}
+
+    const std::experimental::observer_ptr<plugins::SkillProviderComponentPlugin>&
+    SkillProviderComponentPluginUser::getSkillProviderPlugin() const
+    {
+        return plugin;
+    }
+} // namespace armarx
diff --git a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
index d6d8a49a944aa190c47152aced4065bd15a19885..6b74dd1e2479068ca920dde2b8f2ec102b0d7646 100644
--- a/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
+++ b/source/RobotAPI/libraries/skills/provider/SkillProviderComponentPlugin.h
@@ -1,29 +1,32 @@
 #pragma once
 
-#include <shared_mutex>
+#include <functional>
 #include <queue>
+#include <shared_mutex>
 #include <thread>
-#include <functional>
 #include <type_traits>
+#include <experimental/memory>
 
 #include <ArmarXCore/core/ComponentPlugin.h>
 #include <ArmarXCore/core/ManagedIceObject.h>
-
 #include <ArmarXCore/core/services/tasks/RunningTask.h>
 
 #include <RobotAPI/interface/skills/SkillManagerInterface.h>
 #include <RobotAPI/libraries/aron/core/data/variant/container/Dict.h>
 
 // Include all types of skills
-#include "Skill.h"
-#include "SpecializedSkill.h"
 #include "LambdaSkill.h"
 #include "PeriodicSkill.h"
 #include "PeriodicSpecializedSkill.h"
+#include "Skill.h"
+#include "SpecializedSkill.h"
 
 // Helper wrapper for execution
 #include "detail/SkillImplementationWrapper.h"
-
+namespace armarx
+{
+    class SkillProviderComponentPluginUser; // forward declaration
+}
 namespace armarx::plugins
 {
     class SkillProviderComponentPlugin : public ComponentPlugin
@@ -40,53 +43,82 @@ namespace armarx::plugins
 
         void preOnDisconnectComponent() override;
 
+        void addSkill(const skills::LambdaSkill::FunT&, const skills::SkillDescription&);
+        void addSkill(std::unique_ptr<skills::Skill>&&);
+
+        template <typename T>
+        T*
+        addSkill()
+        {
+            static_assert(std::is_base_of<skills::Skill, T>::value,
+                          "T must be derived from skills::Skill!");
+            static_assert(std::is_default_constructible<T>::value,
+                          "T must be default constructible!");
+
+            auto skill = std::make_unique<T>();
+            auto* skillPtr = skill.get();
+            addSkill(std::move(skill));
+            return static_cast<T*>(skillPtr);
+        }
+
     private:
+        skills::detail::SkillImplementationWrapper& getSkill(const std::string& name);
+        skills::provider::dto::SkillStatusUpdateMap getSkillExecutionStatuses() const;
+        skills::provider::dto::SkillDescriptionMap getSkillDescriptions() const;
+
         skills::manager::dti::SkillManagerInterfacePrx manager;
         skills::provider::dti::SkillProviderInterfacePrx myPrx;
+
+        mutable std::shared_mutex skillsMutex;
+
+        bool connected = false;
+        std::map<std::string, skills::detail::SkillImplementationWrapper> skillImplementations;
+
+        friend class armarx::SkillProviderComponentPluginUser;
     };
-}
+} // namespace armarx::plugins
 
 namespace armarx
 {
     class SkillProviderComponentPluginUser :
-            virtual public ManagedIceObject,
-            virtual public skills::provider::dti::SkillProviderInterface
+        virtual public ManagedIceObject,
+        virtual public skills::provider::dti::SkillProviderInterface
     {
     public:
         SkillProviderComponentPluginUser();
 
-        skills::provider::dto::SkillDescription getSkillDescription(const std::string&, const Ice::Current &current = Ice::Current()) override;
-        skills::provider::dto::SkillDescriptionMap getSkillDescriptions(const Ice::Current &current = Ice::Current()) override;
-        skills::provider::dto::SkillStatusUpdate getSkillExecutionStatus(const std::string& skill, const Ice::Current &current = Ice::Current()) override;
-        skills::provider::dto::SkillStatusUpdateMap getSkillExecutionStatuses(const Ice::Current &current = Ice::Current()) override;
-
-        skills::provider::dto::SkillStatusUpdate executeSkill(const skills::provider::dto::SkillExecutionRequest& executionInfo, const Ice::Current &current = Ice::Current()) override;
-        void abortSkill(const std::string& name, const Ice::Current &current = Ice::Current()) override;
+        skills::provider::dto::SkillDescription
+        getSkillDescription(const std::string&,
+                            const Ice::Current& current = Ice::Current()) override;
+        skills::provider::dto::SkillDescriptionMap
+        getSkillDescriptions(const Ice::Current& current = Ice::Current()) override;
+        skills::provider::dto::SkillStatusUpdate
+        getSkillExecutionStatus(const std::string& skill,
+                                const Ice::Current& current = Ice::Current()) override;
+        skills::provider::dto::SkillStatusUpdateMap
+        getSkillExecutionStatuses(const Ice::Current& current = Ice::Current()) override;
+
+        skills::provider::dto::SkillStatusUpdate
+        executeSkill(const skills::provider::dto::SkillExecutionRequest& executionInfo,
+                     const Ice::Current& current = Ice::Current()) override;
+        void abortSkill(const std::string& name,
+                        const Ice::Current& current = Ice::Current()) override;
+
+        const std::experimental::observer_ptr<plugins::SkillProviderComponentPlugin>&
+        getSkillProviderPlugin() const;
 
     protected:
         void addSkill(const skills::LambdaSkill::FunT&, const skills::SkillDescription&);
         void addSkill(std::unique_ptr<skills::Skill>&&);
 
-        template<typename T>
-        T* addSkill()
+        template <typename T>
+        T*
+        addSkill()
         {
-            static_assert(std::is_base_of<skills::Skill, T>::value, "T must be derived from skills::Skill!");
-            static_assert(std::is_default_constructible<T>::value, "T must be default constructible!");
-
-            auto skill = std::make_unique<T>();
-            auto* skillPtr = skill.get();
-            addSkill(std::move(skill));
-            return static_cast<T*>(skillPtr);
+            return plugin->addSkill<T>();
         }
 
     private:
-        armarx::plugins::SkillProviderComponentPlugin* plugin = nullptr;
-
-    protected:
-        mutable std::shared_mutex skillsMutex;
-
-    public:
-        bool connected = false;
-        std::map<std::string, skills::detail::SkillImplementationWrapper> skillImplementations;
+        std::experimental::observer_ptr<plugins::SkillProviderComponentPlugin> plugin = nullptr;
     };
-}
+} // namespace armarx