diff --git a/source/RobotAPI/components/ArViz/CMakeLists.txt b/source/RobotAPI/components/ArViz/CMakeLists.txt
index 9638058676450ed6fcb7d8ff884cf7ebf8beb67e..734be2bc9cf9fa584fe9d76d30935863ea8d8544 100644
--- a/source/RobotAPI/components/ArViz/CMakeLists.txt
+++ b/source/RobotAPI/components/ArViz/CMakeLists.txt
@@ -71,6 +71,9 @@ set(SOURCES
     Coin/VisualizationRobot.cpp
     Coin/VisualizationPath.cpp
     Coin/VisualizationObject.cpp
+    Coin/VisualizationMesh.cpp
+    Coin/VisualizationEllipsoid.cpp
+    Coin/VisualizationCylindroid.cpp
 
     Coin/Visualizer.cpp
     Coin/RegisterVisualizationTypes.cpp
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.cpp b/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..6d2cc827a17e3b5e507ead7888d673cb10d849de
--- /dev/null
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.cpp
@@ -0,0 +1,63 @@
+/**
+ * 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      (  )
+ * @date       2024
+ * @copyright  http://www.gnu.org/licenses/gpl-2.0.txt
+ *             GNU General Public License
+ */
+ 
+ #include "VisualizationCylindroid.h"
+ 
+#include <Inventor/nodes/SoMaterial.h>
+ 
+ bool
+ armarx::viz::coin::VisualizationCylindroid::update(ElementType const& element)
+ {
+     auto color = element.color;
+     constexpr float conv = 1.0f / 255.0f;
+     const float r = color.r * conv;
+     const float g = color.g * conv;
+     const float b = color.b * conv;
+     const float a = color.a * conv;
+
+     VirtualRobot::VisualizationNodePtr cylindroid_node;
+     {
+         // Params.
+         SoMaterial* mat = new SoMaterial;
+         mat->diffuseColor.setValue(r, g, b);
+         mat->ambientColor.setValue(r, g, b);
+         mat->transparency.setValue(1. - a);
+
+         SoSeparator* res = new SoSeparator();
+         res->ref();
+         SoUnits* u = new SoUnits();
+         u->units = SoUnits::MILLIMETERS;
+         res->addChild(u);
+         res->addChild(VirtualRobot::CoinVisualizationFactory::CreateCylindroid(
+             element.axisLengths.e0, element.axisLengths.e1, element.height, mat));
+
+         cylindroid_node.reset(new VirtualRobot::CoinVisualizationNode(res));
+         res->unref();
+     }
+
+     SoNode* cylindroid = dynamic_cast<VirtualRobot::CoinVisualizationNode&>(*cylindroid_node)
+                              .getCoinVisualization();
+
+     node->removeAllChildren();
+     node->addChild(cylindroid);
+
+     return true;
+ }
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.h b/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.h
index 478f99c019e82321a860f7b6a4be18454f97064a..ded11d25008b2d2525294ac9d5bd4aa317bc2c16 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationCylindroid.h
@@ -15,43 +15,6 @@ namespace armarx::viz::coin
     {
         using ElementType = data::ElementCylindroid;
 
-        bool update(ElementType const& element)
-        {
-            auto color = element.color;
-            constexpr float conv = 1.0f / 255.0f;
-            const float r = color.r * conv;
-            const float g = color.g * conv;
-            const float b = color.b * conv;
-            const float a = color.a * conv;
-
-            VirtualRobot::VisualizationNodePtr cylindroid_node;
-            {
-                // Params.
-                SoMaterial* mat = new SoMaterial;
-                mat->diffuseColor.setValue(r, g, b);
-                mat->ambientColor.setValue(r, g, b);
-                mat->transparency.setValue(1. - a);
-
-                SoSeparator* res = new SoSeparator();
-                res->ref();
-                SoUnits* u = new SoUnits();
-                u->units = SoUnits::MILLIMETERS;
-                res->addChild(u);
-                res->addChild(VirtualRobot::CoinVisualizationFactory::CreateCylindroid(
-                                  element.axisLengths.e0, element.axisLengths.e1, element.height,
-                                  mat));
-
-                cylindroid_node.reset(new VirtualRobot::CoinVisualizationNode(res));
-                res->unref();
-            }
-
-            SoNode* cylindroid = dynamic_cast<VirtualRobot::CoinVisualizationNode&>(
-                                     *cylindroid_node).getCoinVisualization();
-
-            node->removeAllChildren();
-            node->addChild(cylindroid);
-
-            return true;
-        }
+        bool update(ElementType const& element);
     };
 }
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.cpp b/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..65fa3c22b1457ca322a83fe86e30463df13e34e3
--- /dev/null
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.cpp
@@ -0,0 +1,31 @@
+#include "VisualizationEllipsoid.h"
+
+#include <Inventor/nodes/SoComplexity.h>
+#include <Inventor/nodes/SoScale.h>
+#include <Inventor/nodes/SoSphere.h>
+
+armarx::viz::coin::VisualizationEllipsoid::VisualizationEllipsoid()
+{
+    complexity = new SoComplexity();
+    complexity->type.setValue(SoComplexity::OBJECT_SPACE);
+    complexity->value.setValue(1.0f);
+
+    scale = new SoScale;
+
+    sphere = new SoSphere();
+    // We create a unit sphere and create an ellipsoid through scaling
+    sphere->radius.setValue(1.0f);
+
+    node->addChild(complexity);
+    node->addChild(scale);
+    node->addChild(sphere);
+}
+
+bool
+armarx::viz::coin::VisualizationEllipsoid::update(ElementType const& element)
+{
+    scale->scaleFactor.setValue(
+        element.axisLengths.e0, element.axisLengths.e1, element.axisLengths.e2);
+
+    return true;
+}
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.h b/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.h
index e0c3e4db489cdbe6a6434616348229b68c552abc..e38337629eebaac5d26dfd893e43e605e57f574a 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationEllipsoid.h
@@ -4,9 +4,9 @@
 
 #include <RobotAPI/interface/ArViz/Elements.h>
 
-#include <Inventor/nodes/SoComplexity.h>
-#include <Inventor/nodes/SoScale.h>
-#include <Inventor/nodes/SoSphere.h>
+class SoComplexity;
+class SoScale;
+class SoSphere;
 
 namespace armarx::viz::coin
 {
@@ -14,29 +14,9 @@ namespace armarx::viz::coin
     {
         using ElementType = data::ElementEllipsoid;
 
-        VisualizationEllipsoid()
-        {
-            complexity = new SoComplexity();
-            complexity->type.setValue(SoComplexity::OBJECT_SPACE);
-            complexity->value.setValue(1.0f);
+        VisualizationEllipsoid();
 
-            scale = new SoScale;
-
-            sphere = new SoSphere();
-            // We create a unit sphere and create an ellipsoid through scaling
-            sphere->radius.setValue(1.0f);
-
-            node->addChild(complexity);
-            node->addChild(scale);
-            node->addChild(sphere);
-        }
-
-        bool update(ElementType const& element)
-        {
-            scale->scaleFactor.setValue(element.axisLengths.e0, element.axisLengths.e1, element.axisLengths.e2);
-
-            return true;
-        }
+        bool update(ElementType const& element);
 
         SoMaterial* material = nullptr;
         SoComplexity* complexity = nullptr;
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.cpp b/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..90a5ae9eef31a378436424ab2f65579192e8da85
--- /dev/null
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.cpp
@@ -0,0 +1,113 @@
+#include "VisualizationMesh.h"
+
+#include <Inventor/nodes/SoCoordinate3.h>
+#include <Inventor/nodes/SoIndexedFaceSet.h>
+#include <Inventor/nodes/SoMaterial.h>
+#include <Inventor/nodes/SoMaterialBinding.h>
+#include <Inventor/nodes/SoNormal.h>
+#include <Inventor/nodes/SoShapeHints.h>
+
+namespace armarx::viz::coin
+{
+
+    VisualizationMesh::VisualizationMesh()
+    {
+        SoMaterialBinding* myBinding = new SoMaterialBinding;
+        myBinding->value = SoMaterialBinding::PER_VERTEX_INDEXED;
+
+        materials = new SoMaterial;
+        coords = new SoCoordinate3;
+
+        SoShapeHints* hints = new SoShapeHints;
+        // Disable back culling and enable two-sided lighting
+        hints->vertexOrdering = SoShapeHints::VertexOrdering::COUNTERCLOCKWISE;
+        hints->shapeType = SoShapeHints::ShapeType::UNKNOWN_SHAPE_TYPE;
+
+        faceSet = new SoIndexedFaceSet;
+
+        node->addChild(myBinding);
+        node->addChild(materials);
+        node->addChild(coords);
+        node->addChild(hints);
+        node->addChild(faceSet);
+    }
+
+    bool
+    VisualizationMesh::update(ElementType const& element)
+    {
+        int colorSize = (int)element.colors.size();
+        bool noColorsArray = colorSize == 0;
+        if (colorSize == 0)
+        {
+            colorSize = 1;
+        }
+        matColor.resize(colorSize);
+        transp.resize(colorSize);
+
+        const float conv = 1.0f / 255.0f;
+        if (noColorsArray)
+        {
+            auto color = element.color;
+            float r = color.r * conv;
+            float g = color.g * conv;
+            float b = color.b * conv;
+            float a = color.a * conv;
+            matColor[0].setValue(r, g, b);
+            transp[0] = 1.0f - a;
+        }
+        else
+        {
+            for (int i = 0; i < colorSize; i++)
+            {
+                auto color = element.colors[i];
+                float r = color.r * conv;
+                float g = color.g * conv;
+                float b = color.b * conv;
+                float a = color.a * conv;
+                matColor[i].setValue(r, g, b);
+                transp[i] = 1.0f - a;
+            }
+        }
+
+        // Define colors for the faces
+        materials->diffuseColor.setValuesPointer(colorSize, matColor.data());
+        materials->ambientColor.setValuesPointer(colorSize, matColor.data());
+        materials->transparency.setValuesPointer(colorSize, transp.data());
+
+        // define vertex array
+        int vertexSize = (int)element.vertices.size();
+        vertexPositions.resize(vertexSize);
+        for (int i = 0; i < vertexSize; i++)
+        {
+            auto v = element.vertices[i];
+            vertexPositions[i].setValue(v.e0, v.e1, v.e2);
+        }
+
+        // Define coordinates for vertices
+        coords->point.setValuesPointer(vertexSize, vertexPositions.data());
+
+        int facesSize = (int)element.faces.size();
+        faces.resize(facesSize * 4);
+        matInx.resize(facesSize * 4);
+
+        for (int i = 0; i < facesSize; i++)
+        {
+            auto& face = element.faces[i];
+
+            faces[i * 4 + 0] = face.v0;
+            faces[i * 4 + 1] = face.v1;
+            faces[i * 4 + 2] = face.v2;
+            faces[i * 4 + 3] = SO_END_FACE_INDEX;
+
+            matInx[i * 4 + 0] = face.c0;
+            matInx[i * 4 + 1] = face.c1;
+            matInx[i * 4 + 2] = face.c2;
+            matInx[i * 4 + 3] = SO_END_FACE_INDEX;
+        }
+
+        faceSet->coordIndex.setValuesPointer(faces.size(), faces.data());
+        faceSet->materialIndex.setValuesPointer(matInx.size(), matInx.data());
+
+        return true;
+    }
+} // namespace armarx::viz::coin
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.h b/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.h
index 120bb629a6ddb6008ebeb7780e31d4954441be4e..391fe0e140a2f5e907be36871a86837535a63321 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationMesh.h
@@ -4,11 +4,10 @@
 
 #include <RobotAPI/interface/ArViz/Elements.h>
 
-#include <Inventor/nodes/SoCoordinate3.h>
-#include <Inventor/nodes/SoIndexedFaceSet.h>
-#include <Inventor/nodes/SoMaterialBinding.h>
-#include <Inventor/nodes/SoNormal.h>
-#include <Inventor/nodes/SoShapeHints.h>
+#include <Inventor/SbColor.h>
+
+class SoCoordinate3;
+class SoIndexedFaceSet;
 
 namespace armarx::viz::coin
 {
@@ -16,105 +15,9 @@ namespace armarx::viz::coin
     {
         using ElementType = data::ElementMesh;
 
-        VisualizationMesh()
-        {
-            SoMaterialBinding* myBinding = new SoMaterialBinding;
-            myBinding->value = SoMaterialBinding::PER_VERTEX_INDEXED;
-
-            materials = new SoMaterial;
-            coords = new SoCoordinate3;
-
-            SoShapeHints* hints = new SoShapeHints;
-            // Disable back culling and enable two-sided lighting
-            hints->vertexOrdering = SoShapeHints::VertexOrdering::COUNTERCLOCKWISE;
-            hints->shapeType = SoShapeHints::ShapeType::UNKNOWN_SHAPE_TYPE;
-
-            faceSet = new SoIndexedFaceSet;
-
-            node->addChild(myBinding);
-            node->addChild(materials);
-            node->addChild(coords);
-            node->addChild(hints);
-            node->addChild(faceSet);
-        }
-
-        bool update(ElementType const& element)
-        {
-            int colorSize = (int)element.colors.size();
-            bool noColorsArray = colorSize == 0;
-            if (colorSize == 0)
-            {
-                colorSize = 1;
-            }
-            matColor.resize(colorSize);
-            transp.resize(colorSize);
-
-            const float conv = 1.0f / 255.0f;
-            if (noColorsArray)
-            {
-                auto color = element.color;
-                float r = color.r * conv;
-                float g = color.g * conv;
-                float b = color.b * conv;
-                float a = color.a * conv;
-                matColor[0].setValue(r, g, b);
-                transp[0] = 1.0f - a;
-            }
-            else
-            {
-                for (int i = 0; i < colorSize; i++)
-                {
-                    auto color = element.colors[i];
-                    float r = color.r * conv;
-                    float g = color.g * conv;
-                    float b = color.b * conv;
-                    float a = color.a * conv;
-                    matColor[i].setValue(r, g, b);
-                    transp[i] = 1.0f - a;
-                }
-            }
-
-            // Define colors for the faces
-            materials->diffuseColor.setValuesPointer(colorSize, matColor.data());
-            materials->ambientColor.setValuesPointer(colorSize, matColor.data());
-            materials->transparency.setValuesPointer(colorSize, transp.data());
-
-            // define vertex array
-            int vertexSize = (int)element.vertices.size();
-            vertexPositions.resize(vertexSize);
-            for (int i = 0; i < vertexSize; i++)
-            {
-                auto v = element.vertices[i];
-                vertexPositions[i].setValue(v.e0, v.e1, v.e2);
-            }
-
-            // Define coordinates for vertices
-            coords->point.setValuesPointer(vertexSize, vertexPositions.data());
-
-            int facesSize = (int)element.faces.size();
-            faces.resize(facesSize * 4);
-            matInx.resize(facesSize * 4);
-
-            for (int i = 0; i < facesSize; i++)
-            {
-                auto& face = element.faces[i];
-
-                faces[i * 4 + 0] = face.v0;
-                faces[i * 4 + 1] = face.v1;
-                faces[i * 4 + 2] = face.v2;
-                faces[i * 4 + 3] = SO_END_FACE_INDEX;
-
-                matInx[i * 4 + 0] = face.c0;
-                matInx[i * 4 + 1] = face.c1;
-                matInx[i * 4 + 2] = face.c2;
-                matInx[i * 4 + 3] = SO_END_FACE_INDEX;
-            }
-
-            faceSet->coordIndex.setValuesPointer(faces.size(), faces.data());
-            faceSet->materialIndex.setValuesPointer(matInx.size(), matInx.data());
+        VisualizationMesh();
 
-            return true;
-        }
+        bool update(ElementType const& element);
 
         SoMaterial* materials;
         SoCoordinate3* coords;
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationObject.cpp b/source/RobotAPI/components/ArViz/Coin/VisualizationObject.cpp
index 5f6b068fccb635c596f2534068e4516fec63693d..f27e344ca8ab1256bd618d1f86e5c2496abcbfd1 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationObject.cpp
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationObject.cpp
@@ -2,6 +2,9 @@
 
 #include <RobotAPI/libraries/ArmarXObjects/ObjectFinder.h>
 
+#include <Inventor/nodes/SoMaterial.h>
+#include <Inventor/SbColor.h>
+
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationPointCloud.h b/source/RobotAPI/components/ArViz/Coin/VisualizationPointCloud.h
index 5b4afb2bb562e0b52aac7bc954ed3f2526058c0f..16df986fe4ef3efa20e84d91392e1475440aed83 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationPointCloud.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationPointCloud.h
@@ -1,11 +1,13 @@
 #pragma once
 
+#include <cfloat>
 #include "ElementVisualizer.h"
 
 #include <RobotAPI/interface/ArViz/Elements.h>
 
 #include <Inventor/nodes/SoCoordinate3.h>
 #include <Inventor/nodes/SoDrawStyle.h>
+#include <Inventor/nodes/SoMaterial.h>
 #include <Inventor/nodes/SoMaterialBinding.h>
 #include <Inventor/nodes/SoPointSet.h>
 
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationPolygon.h b/source/RobotAPI/components/ArViz/Coin/VisualizationPolygon.h
index 7ea618b063125dce6507245847688ffe29f69e3d..5c185f4539f265fd1fba2f8807142df1052ba9c7 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationPolygon.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationPolygon.h
@@ -10,6 +10,7 @@
 #include <Inventor/nodes/SoDrawStyle.h>
 #include <Inventor/nodes/SoFaceSet.h>
 #include <Inventor/nodes/SoLineSet.h>
+#include <Inventor/nodes/SoMaterial.h>
 
 
 namespace armarx::viz::coin
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationPose.h b/source/RobotAPI/components/ArViz/Coin/VisualizationPose.h
index 490e192582f1b89baafdedaf12a03d5a0a55bc93..1e5e9719dbfbc546199417da57823d676fe50f2b 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationPose.h
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationPose.h
@@ -6,6 +6,7 @@
 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h>
 #include <Inventor/nodes/SoAsciiText.h>
 #include <Inventor/nodes/SoCube.h>
+#include <Inventor/nodes/SoMaterial.h>
 #include <Inventor/nodes/SoSeparator.h>
 #include <Inventor/nodes/SoTransform.h>
 #include <Inventor/nodes/SoTranslation.h>
diff --git a/source/RobotAPI/components/ArViz/Coin/VisualizationRobot.cpp b/source/RobotAPI/components/ArViz/Coin/VisualizationRobot.cpp
index 71dad203ab70fab4b411ad891b55b781b9fc7e39..68cfb856e64ef8c225436dec38e9a5a894c493dc 100644
--- a/source/RobotAPI/components/ArViz/Coin/VisualizationRobot.cpp
+++ b/source/RobotAPI/components/ArViz/Coin/VisualizationRobot.cpp
@@ -9,6 +9,8 @@
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
+#include <Inventor/SbColor.h>
+#include <Inventor/nodes/SoMaterial.h>
 
 namespace armarx::viz::coin
 {
diff --git a/source/RobotAPI/components/DebugDrawer/CMakeLists.txt b/source/RobotAPI/components/DebugDrawer/CMakeLists.txt
index 131cc850cb846c673d5147154acc3256c43d50c6..5322817c5cf5a12bcc1cc4f5da8ca8b7c0ecf5a5 100644
--- a/source/RobotAPI/components/DebugDrawer/CMakeLists.txt
+++ b/source/RobotAPI/components/DebugDrawer/CMakeLists.txt
@@ -5,6 +5,7 @@ set(COMPONENT_LIBS ArmarXCore RobotAPIInterfaces RobotAPICore)
 set(SOURCES
     DebugDrawerComponent.cpp
     DebugDrawerHelper.cpp
+    DebugDrawerUtils.cpp
     )
 set(HEADERS
     DebugDrawerComponent.h
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.cpp b/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.cpp
index 5cffdc6d755be9696f23479a64b4077380228046..928e2d47b22cfb858ed966a77a93d6e892f7673b 100644
--- a/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.cpp
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.cpp
@@ -30,6 +30,7 @@
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h>
 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
+#include <VirtualRobot/Visualization/VisualizationFactory.h>
 #include <Inventor/nodes/SoUnits.h>
 #include <Inventor/nodes/SoCube.h>
 #include <Inventor/nodes/SoMaterial.h>
@@ -51,6 +52,7 @@
 #include <Inventor/fields/SoMFVec3f.h>
 #include <Inventor/fields/SoMFColor.h>
 #include <Inventor/nodes/SoShapeHints.h>
+#include <Inventor/nodes/SoMatrixTransform.h>
 
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.h b/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.h
index 9b7c3709bc92be7256deae774a11b748be5ee14a..7b2e5af08f2b9399cb5a2b482af3870db0689820 100644
--- a/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.h
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerComponent.h
@@ -626,4 +626,3 @@ namespace armarx
     using DebugDrawerComponentPtr = IceInternal::Handle<DebugDrawerComponent>;
 
 }
-
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.cpp b/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.cpp
index e65fa6a4f4d0242b686656493ef93dba95cc5b36..e0293363b3b56891468b8c1a88950e6c7e09ae6e 100644
--- a/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.cpp
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.cpp
@@ -23,6 +23,8 @@
 
 #include "DebugDrawerHelper.h"
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/Robot.h>
 #include <VirtualRobot/math/Helpers.h>
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.h b/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.h
index 72a4ee76f56373b6e03697b76a9c45e07a3816dd..9da37492f73fd7b08310591a3ed294f6767acce7 100644
--- a/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.h
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerHelper.h
@@ -23,7 +23,7 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 #include <SimoxUtility/shapes/OrientedBox.h>
 #include <SimoxUtility/shapes/XYConstrainedOrientedBox.h>
 
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.cpp b/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..52b2a5872cec93b896e05e836d41ec32de6506c7
--- /dev/null
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.cpp
@@ -0,0 +1,49 @@
+#include "DebugDrawerUtils.h"
+
+#include <VirtualRobot/Visualization/TriMeshModel.h>
+
+armarx::DebugDrawerTriMesh
+armarx::DebugDrawerUtils::convertTriMesh(const VirtualRobot::TriMeshModel& trimesh)
+{
+    DebugDrawerTriMesh ddMesh;
+
+    auto addVertex = [&](const Eigen::Vector3f& v)
+    {
+        ddMesh.vertices.push_back({v(0), v(1), v(2)});
+        return (int)ddMesh.vertices.size() - 1;
+    };
+
+    auto addColor = [&](const VirtualRobot::VisualizationFactory::Color& c)
+    {
+        ddMesh.colors.push_back(DrawColor{c.r, c.g, c.b, c.transparency});
+        return (int)ddMesh.colors.size() - 1;
+    };
+    ddMesh.faces.reserve(trimesh.faces.size());
+    ddMesh.vertices.reserve(trimesh.vertices.size());
+    ddMesh.colors.reserve(trimesh.colors.size());
+
+    for (auto& f : trimesh.faces)
+    {
+        DebugDrawerFace f2;
+        f2.vertex1.vertexID = addVertex(trimesh.vertices.at(f.id1));
+        f2.vertex2.vertexID = addVertex(trimesh.vertices.at(f.id2));
+        f2.vertex3.vertexID = addVertex(trimesh.vertices.at(f.id3));
+        if (f.idNormal1 != UINT_MAX)
+        {
+            f2.vertex1.normalID = addVertex(trimesh.normals.at(f.idNormal1));
+            f2.vertex2.normalID = addVertex(trimesh.normals.at(f.idNormal2));
+            f2.vertex3.normalID = addVertex(trimesh.normals.at(f.idNormal3));
+        }
+        else
+        {
+            //                    f2.vertex1.normalID = f2.vertex2.normalID = f2.vertex3.normalID = addVertex(f.normal);
+            f2.normal = {f.normal.x(), f.normal.y(), f.normal.z()};
+        }
+        f2.vertex1.colorID = addColor(trimesh.colors.at(f.idColor1));
+        f2.vertex2.colorID = addColor(trimesh.colors.at(f.idColor2));
+        f2.vertex3.colorID = addColor(trimesh.colors.at(f.idColor3));
+
+        ddMesh.faces.push_back(f2);
+    }
+    return ddMesh;
+}
diff --git a/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.h b/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.h
index b50b0a9d98870ca210f1459e4445802d06f3e922..7d20ed5fc22362c478b143fe79984b1c90e7d253 100644
--- a/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.h
+++ b/source/RobotAPI/components/DebugDrawer/DebugDrawerUtils.h
@@ -23,58 +23,16 @@
  */
 #pragma once
 
-#include <VirtualRobot/Visualization/TriMeshModel.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 #include <RobotAPI/interface/visualization/DebugDrawerInterface.h>
+
 #include <Eigen/Core>
 namespace armarx
 {
     class DebugDrawerUtils
     {
     public:
-        static DebugDrawerTriMesh convertTriMesh(const VirtualRobot::TriMeshModel& trimesh)
-        {
-            DebugDrawerTriMesh ddMesh;
-
-            auto addVertex = [&](const Eigen::Vector3f & v)
-            {
-                ddMesh.vertices.push_back({v(0), v(1), v(2)});
-                return (int)ddMesh.vertices.size() - 1;
-            };
-
-            auto addColor = [&](const VirtualRobot::VisualizationFactory::Color & c)
-            {
-                ddMesh.colors.push_back(DrawColor {c.r, c.g, c.b, c.transparency});
-                return (int)ddMesh.colors.size() - 1;
-            };
-            ddMesh.faces.reserve(trimesh.faces.size());
-            ddMesh.vertices.reserve(trimesh.vertices.size());
-            ddMesh.colors.reserve(trimesh.colors.size());
-
-            for (auto& f : trimesh.faces)
-            {
-                DebugDrawerFace f2;
-                f2.vertex1.vertexID = addVertex(trimesh.vertices.at(f.id1));
-                f2.vertex2.vertexID = addVertex(trimesh.vertices.at(f.id2));
-                f2.vertex3.vertexID = addVertex(trimesh.vertices.at(f.id3));
-                if (f.idNormal1 != UINT_MAX)
-                {
-                    f2.vertex1.normalID = addVertex(trimesh.normals.at(f.idNormal1));
-                    f2.vertex2.normalID = addVertex(trimesh.normals.at(f.idNormal2));
-                    f2.vertex3.normalID = addVertex(trimesh.normals.at(f.idNormal3));
-                }
-                else
-                {
-                    //                    f2.vertex1.normalID = f2.vertex2.normalID = f2.vertex3.normalID = addVertex(f.normal);
-                    f2.normal = {f.normal.x(), f.normal.y(), f.normal.z()};
-                }
-                f2.vertex1.colorID = addColor(trimesh.colors.at(f.idColor1));
-                f2.vertex2.colorID = addColor(trimesh.colors.at(f.idColor2));
-                f2.vertex3.colorID = addColor(trimesh.colors.at(f.idColor3));
-
-                ddMesh.faces.push_back(f2);
-            }
-            return ddMesh;
-        }
-
+        static DebugDrawerTriMesh convertTriMesh(const VirtualRobot::TriMeshModel& trimesh);
     };
 }
diff --git a/source/RobotAPI/components/NaturalIKTest/NaturalIKTest.cpp b/source/RobotAPI/components/NaturalIKTest/NaturalIKTest.cpp
index 8eb4b47b27281850862e414d80654c61639e3ba7..17292ba93b00511d251c50a3241859c38ce127c4 100644
--- a/source/RobotAPI/components/NaturalIKTest/NaturalIKTest.cpp
+++ b/source/RobotAPI/components/NaturalIKTest/NaturalIKTest.cpp
@@ -28,6 +28,7 @@
 #include <ArmarXCore/core/time/TimeUtil.h>
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/math/Helpers.h>
 
diff --git a/source/RobotAPI/components/ObjectMemoryEditor/Editor.h b/source/RobotAPI/components/ObjectMemoryEditor/Editor.h
index e94e1a7cc2aa544650681583ca6a1aae11f9bef6..783675ba07f54dfe80ab569c8fe65a5b836ca23f 100644
--- a/source/RobotAPI/components/ObjectMemoryEditor/Editor.h
+++ b/source/RobotAPI/components/ObjectMemoryEditor/Editor.h
@@ -1,6 +1,7 @@
 #pragma once
 
 #include <list>
+#include <queue>
 
 #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
 #include <RobotAPI/libraries/ArmarXObjects/plugins/ObjectPoseClientPlugin.h>
diff --git a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
index d6ea24e6ecf3f421f62f2b8c904e7e15ff678c3b..7649e1f4ef73da60db7e7e14c3d95c1de004b9ff 100644
--- a/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
+++ b/source/RobotAPI/components/armem/server/GraspMemory/GraspMemory.h
@@ -2,7 +2,7 @@
 
 
 #include <memory>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/core/services/tasks/RunningTask.h>
diff --git a/source/RobotAPI/components/ik_demo/IkDemo.cpp b/source/RobotAPI/components/ik_demo/IkDemo.cpp
index 2d60ef2feeae53056890925f44a799a7ea8f5b10..4ff605566ffec008e8cbdd811554d070cbc3f36d 100644
--- a/source/RobotAPI/components/ik_demo/IkDemo.cpp
+++ b/source/RobotAPI/components/ik_demo/IkDemo.cpp
@@ -5,6 +5,7 @@
 #include <SimoxUtility/math/pose/invert.h>
 
 #include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/IK/CompositeDiffIK/CompositeDiffIK.h>
 #include <VirtualRobot/IK/CompositeDiffIK/ManipulabilityNullspaceGradient.h>
diff --git a/source/RobotAPI/components/units/HandUnit.cpp b/source/RobotAPI/components/units/HandUnit.cpp
index 237ea2180bd5ec2ed68e6750f0f360984f0884d7..28cbd6157b2f03757dd0c6f476a9ea61caa48bbb 100644
--- a/source/RobotAPI/components/units/HandUnit.cpp
+++ b/source/RobotAPI/components/units/HandUnit.cpp
@@ -28,6 +28,7 @@
 #include <vector>
 
 #include <VirtualRobot/EndEffector/EndEffector.h>
+#include <VirtualRobot/VirtualRobotException.h>
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
diff --git a/source/RobotAPI/components/units/KinematicUnit.cpp b/source/RobotAPI/components/units/KinematicUnit.cpp
index 5bac1a14bec7705c4cd2e03721c0beda91d545c5..c2e0dc1854b402f00beb894231cf44d1377ff75a 100644
--- a/source/RobotAPI/components/units/KinematicUnit.cpp
+++ b/source/RobotAPI/components/units/KinematicUnit.cpp
@@ -28,6 +28,7 @@
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/VirtualRobotException.h>
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/application/Application.h>
diff --git a/source/RobotAPI/components/units/KinematicUnit.h b/source/RobotAPI/components/units/KinematicUnit.h
index fb29aac629722ad2ae563dd33461544a6da48386..74146b034692247907da52d1cb5dfa4ee604d772 100644
--- a/source/RobotAPI/components/units/KinematicUnit.h
+++ b/source/RobotAPI/components/units/KinematicUnit.h
@@ -32,7 +32,8 @@
 
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 
-#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 #include <vector>
 
 namespace armarx
@@ -148,4 +149,3 @@ namespace armarx
         std::vector<std::string> armarXPackages;
     };
 }
-
diff --git a/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.cpp b/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.cpp
index d18722607d92879c22184fd8afc06a5ed0fa9bb9..5f51021681e02c7162cdc194372f199ac6e6408d 100644
--- a/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.cpp
+++ b/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.cpp
@@ -28,7 +28,6 @@
 #include <algorithm>
 #include <cmath>
 #include <limits>
-#include <numeric>
 
 // Eigen
 #include <Eigen/Core>
@@ -36,6 +35,8 @@
 
 // Simox
 #include <SimoxUtility/math.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/Safety.h>
 
 // ArmarX
 #include <ArmarXCore/observers/variant/Variant.h>
diff --git a/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.h b/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.h
index 1bc78b92b4ba4edd0811d7324d2a2f811aa2ee15..7ddf5b4a09a50db16e0c7ee68ab191d6738d9bb7 100644
--- a/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.h
+++ b/source/RobotAPI/components/units/ObstacleAwarePlatformUnit/ObstacleAwarePlatformUnit.h
@@ -25,9 +25,7 @@
 
 
 // STD/STL
-#include <deque>
 #include <string>
-#include <tuple>
 #include <mutex>
 #include <vector>
 
@@ -38,7 +36,7 @@
 #include <IceUtil/Time.h>
 
 // Simox
-#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/Safety.h>
 
 // ArmarX
diff --git a/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.cpp b/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.cpp
index 5ea5de5a0decff5792d66ea890a1e39729c5c4a0..8042b243406d074c7055b33502c6d022fee5deb0 100644
--- a/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.cpp
@@ -9,6 +9,15 @@
 #include <VirtualRobot/MathTools.h>
 
 
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/IK/IKSolver.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+
+#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
+#include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValue1DoFActuator.h>
+
 using namespace armarx;
 
 int
diff --git a/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.h b/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.h
index 0c0ed889cebc1671c436eee9226dc79457850a25..46704a4816bcca9a5265143d13ef3eda16fb66e9 100644
--- a/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.h
+++ b/source/RobotAPI/components/units/RobotUnit/ControllerParts/CartesianImpedanceController.h
@@ -1,13 +1,16 @@
 #pragma once
 
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <Eigen/Geometry>
+
+#include <VirtualRobot/VirtualRobot.h>
 
-#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
-#include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValue1DoFActuator.h>
 
 namespace armarx
 {
+    class SensorValue1DoFActuatorTorque;
+    class SensorValue1DoFActuatorVelocity;
+    class SensorValue1DoFActuatorPosition;
+
     class CartesianImpedanceController
     {
     public:
diff --git a/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.cpp b/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.cpp
index 0ed24cb2fb0459f76a6a373d9c1cd3768c733181..70f06887df16c47032960a8044755c461bb6a696 100644
--- a/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.cpp
@@ -22,6 +22,8 @@
 
 #include "DefaultWidgetDescriptions.h"
 
+#include <VirtualRobot/Robot.h>
+
 namespace armarx::WidgetDescription
 {
     StringComboBoxPtr
@@ -86,4 +88,34 @@ namespace armarx::WidgetDescription
         }
         return rns;
     }
+
+    StringComboBoxPtr
+    makeRNSComboBox(const VirtualRobot::RobotPtr& robot,
+                    std::string name,
+                    const std::set<std::string>& preferredSet,
+                    const std::string& mostPreferred)
+    {
+        return makeStringSelectionComboBox(
+            std::move(name), robot->getRobotNodeSetNames(), preferredSet, mostPreferred);
+    }
+
+    StringComboBoxPtr
+    makeRobotNodeComboBox(const VirtualRobot::RobotPtr& robot,
+                          std::string name,
+                          const std::set<std::string>& preferredSet,
+                          const std::string& mostPreferred)
+    {
+        return makeStringSelectionComboBox(
+            std::move(name), robot->getRobotNodeNames(), preferredSet, mostPreferred);
+    }
+
+    StringComboBoxPtr
+    makeStringSelectionComboBox(std::string name,
+                                std::vector<std::string> options,
+                                const std::string& mostPreferred,
+                                const std::set<std::string>& preferredSet)
+    {
+        return makeStringSelectionComboBox(
+            std::move(name), std::move(options), preferredSet, mostPreferred);
+    }
 } // namespace armarx::WidgetDescription
diff --git a/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.h b/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.h
index e276010f22b2d70b6b6b37fac642991020df968c..3da3c5b5451964d5c83e831489ff6406d048948c 100644
--- a/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.h
+++ b/source/RobotAPI/components/units/RobotUnit/DefaultWidgetDescriptions.h
@@ -25,7 +25,7 @@
 #include <set>
 #include <string>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXGui/interface/WidgetDescription.h>
 #include <ArmarXGui/libraries/DefaultWidgetDescriptions/DefaultWidgetDescriptions.h>
@@ -57,33 +57,18 @@ namespace armarx::WidgetDescription
                                                   const std::set<std::string>& preferredSet,
                                                   const std::string& mostPreferred);
 
-    inline StringComboBoxPtr
-    makeStringSelectionComboBox(std::string name,
-                                std::vector<std::string> options,
-                                const std::string& mostPreferred,
-                                const std::set<std::string>& preferredSet)
-    {
-        return makeStringSelectionComboBox(
-            std::move(name), std::move(options), preferredSet, mostPreferred);
-    }
+    StringComboBoxPtr makeStringSelectionComboBox(std::string name,
+                                                  std::vector<std::string> options,
+                                                  const std::string& mostPreferred,
+                                                  const std::set<std::string>& preferredSet);
 
-    inline StringComboBoxPtr
-    makeRNSComboBox(const VirtualRobot::RobotPtr& robot,
-                    std::string name = "RobotNodeSet",
-                    const std::set<std::string>& preferredSet = {},
-                    const std::string& mostPreferred = "")
-    {
-        return makeStringSelectionComboBox(
-            std::move(name), robot->getRobotNodeSetNames(), preferredSet, mostPreferred);
-    }
+    StringComboBoxPtr makeRNSComboBox(const VirtualRobot::RobotPtr& robot,
+                                      std::string name = "RobotNodeSet",
+                                      const std::set<std::string>& preferredSet = {},
+                                      const std::string& mostPreferred = "");
 
-    inline StringComboBoxPtr
-    makeRobotNodeComboBox(const VirtualRobot::RobotPtr& robot,
-                          std::string name = "RobotNode",
-                          const std::set<std::string>& preferredSet = {},
-                          const std::string& mostPreferred = "")
-    {
-        return makeStringSelectionComboBox(
-            std::move(name), robot->getRobotNodeNames(), preferredSet, mostPreferred);
-    }
+    StringComboBoxPtr makeRobotNodeComboBox(const VirtualRobot::RobotPtr& robot,
+                                            std::string name = "RobotNode",
+                                            const std::set<std::string>& preferredSet = {},
+                                            const std::string& mostPreferred = "");
 } // namespace armarx::WidgetDescription
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianNaturalPositionController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianNaturalPositionController.cpp
index 67e940d30ad6899cc9773c14c950f8207092f905..09338fd57c5de9986647bbd3333f33e7e7925125 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianNaturalPositionController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianNaturalPositionController.cpp
@@ -2,6 +2,7 @@
 
 #include <iomanip>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/math/Helpers.h>
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.cpp
index ec93568c8452b7268c5ad2212ddb9df954e8b9ce..26fa0111d4f48e868573fbffc3590da3e7233fd6 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.cpp
@@ -24,6 +24,8 @@
 #include "NJointCartesianTorqueController.h"
 
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.h
index 91326e4935517bb6b05457e2843615647a7fa05c..b02c292f635089f09c5553d56a6cf3aa5f3db985 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianTorqueController.h
@@ -23,9 +23,8 @@
  */
 #pragma once
 
+#include <VirtualRobot/VirtualRobot.h>
 
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
 
 #include <RobotAPI/interface/units/RobotUnit/NJointCartesianTorqueController.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.cpp
index 486eaa77564de408fcd7c57da71eb1c73e6e93f1..165da2d63db3e5e085eb1c02eb8b229b81a0fd66 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.cpp
@@ -24,10 +24,14 @@
 
 #include "NJointCartesianVelocityController.h"
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
+#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
+#include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValue1DoFActuator.h>
 
 #define DEFAULT_TCP_STRING "default TCP"
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.h
index 35f3a9375629e1a6b2d42c2d9205290b3d2fd4b1..1c0755674bd5ae042858d5138a053109ccbcbedd 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityController.h
@@ -24,17 +24,19 @@
 #pragma once
 
 
-#include <VirtualRobot/IK/DifferentialIK.h>
 #include <VirtualRobot/VirtualRobot.h>
 
-#include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerWithTripleBuffer.h>
-#include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValue1DoFActuator.h>
 #include <RobotAPI/interface/units/RobotUnit/NJointCartesianVelocityController.h>
 #include <RobotAPI/libraries/core/CartesianVelocityController.h>
 
 namespace armarx
 {
+    class ControlTarget1DoFActuatorVelocity;
+    class SensorValue1DoFActuatorTorque;
+    class SensorValue1DoFGravityTorque;
+
+
     TYPEDEF_PTRS_HANDLE(NJointCartesianVelocityController);
 
     TYPEDEF_PTRS_HANDLE(NJointCartesianVelocityControllerControlData);
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.cpp
index 90ef15b6185b7424ef70714af3eec4b16b6a0ba6..ea5ab7c70dbd998b8b0b4e3c549c2712f4649ea1 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.cpp
@@ -24,6 +24,8 @@
 #include "NJointCartesianVelocityControllerWithRamp.h"
 
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.h
index 40bba081c0c63eaa83edb2454c03dfb73ce2bfe3..34d99731e249308d5a6685c017b9e56031cdadb5 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianVelocityControllerWithRamp.h
@@ -23,9 +23,7 @@
  */
 #pragma once
 
-
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/interface/units/RobotUnit/NJointCartesianVelocityControllerWithRamp.h>
 #include <RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianWaypointController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianWaypointController.cpp
index 08870cfcc27981ee9e0e97f096563a35a1f51507..943f878897d4eb3e0e08b1fa8a23ae7b686397d3 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianWaypointController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointCartesianWaypointController.cpp
@@ -1,6 +1,8 @@
 #include "NJointCartesianWaypointController.h"
 
 #include <iomanip>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerBase.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerBase.h
index 3239c0e831c96536d442cba4531b2615a1bfe034..76cf0ca051ae2bf2d31b028f074460b6c31d0783 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerBase.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerBase.h
@@ -23,7 +23,6 @@
 #pragma once
 
 #include <atomic>
-#include <functional>
 #include <map>
 #include <mutex>
 #include <optional>
@@ -35,8 +34,10 @@
 #include <ArmarXCore/core/services/tasks/ThreadPool.h>
 #include <ArmarXCore/interface/core/ManagedIceObjectDefinitions.h>
 
-#include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
+// #include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
+
 #include <RobotAPI/interface/units/RobotUnit/NJointController.h>
+#include <RobotAPI/interface/units/RobotUnit/RobotUnitInterface.h>
 
 namespace IceProxy::armarx
 {
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp
index 2956bbcf81a23ed99c16ac0ee8dc7ab5b697ace0..c02af15ef7fc7888bf2995b4876ea8d92671f313 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.cpp
@@ -28,6 +28,7 @@
 #include <SimoxUtility/math/convert/mat3f_to_rpy.h>
 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
 #include <SimoxUtility/math/periodic/periodic_clamp.h>
+#include <VirtualRobot/Robot.h>
 
 #include "ArmarXCore/core/logging/Logging.h"
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.h
index f59f1b7bef8c52d860490b75f1dc8e2f9eb6462e..f13f66fe7770cb8f3b7f77791e6a73e696edf5ee 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.h
@@ -26,7 +26,8 @@
 
 #include <atomic>
 
-#include <VirtualRobot/Robot.h>
+
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.cpp
index cca564afe0ad449f947c3e5be351f9b7ce7952ba..1e827dcc163c5417515ebb006038f025950e9a51 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.cpp
@@ -27,6 +27,8 @@
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
+#include <VirtualRobot/Robot.h>
+
 namespace armarx
 {
     NJointControllerRegistration<NJointHolonomicPlatformRelativePositionController>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.h
index 62760e241a7b2a4c7b4457fa6669545d040dff63..ba3c5ba50962c864ff1e96ab8f4446aa2664e01b 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.h
@@ -26,7 +26,7 @@
 
 #include <atomic>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.cpp
index 892a1ae7e554387630efa35d048ee6cd44f02584..31870bd96e67c11bbe85aca9352f96d00b679152 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.cpp
@@ -22,6 +22,8 @@
 
 #include "NJointHolonomicPlatformUnitVelocityPassThroughController.h"
 
+#include <VirtualRobot/Robot.h>
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.h
index ef08635a5f8329e80020f47b1eb8b49b3a894b7a..c692e00dea00d7c5d3044054991ba6aaffd9ae39 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformUnitVelocityPassThroughController.h
@@ -22,7 +22,8 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerInterface.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.cpp
index 972f3abd1bb5d9a0ad34582c19033ae635e7ac80..e903a1a5d9e606b62b3f8ffba8f11d1fe9886d42 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.cpp
@@ -22,9 +22,14 @@
 
 #include "NJointHolonomicPlatformVelocityControllerWithRamp.h"
 
+#include <VirtualRobot/Robot.h>
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include "RobotAPI/components/units/RobotUnit/SensorValues/SensorValueBase.h"
+#include "RobotAPI/components/units/RobotUnit/SensorValues/SensorValueHolonomicPlatform.h"
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
+#include "../ControlTargets/ControlTargetHolonomicPlatformVelocity.h"
 
 namespace armarx
 {
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.h
index 8cd957b50d7911524c6e5d68a91ad4359213f145..795b16c8ef2f9d50717ec3ee42ea06d866305f3a 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerWithRamp.h
@@ -22,15 +22,16 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformVelocityControllerInterface.h>
 
-#include "../ControlTargets/ControlTargetHolonomicPlatformVelocity.h"
-#include "NJointControllerWithTripleBuffer.h"
+// #include "NJointControllerWithTripleBuffer.h"
 
 namespace armarx
 {
+    class ControlTargetHolonomicPlatformVelocity;
+    class SensorValueHolonomicPlatformVelocity;
 
     class Cartesian2DimVelocityRamp
     {
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.cpp
index e51de4dbdb2c7b903d83aeb462d9b9fd8f6a695d..be1af27f6be2ad526b49f178464c4a32bad31ce0 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.cpp
@@ -22,6 +22,8 @@
 
 #include "NJointKinematicUnitPassThroughController.h"
 
+#include <VirtualRobot/Robot.h>
+
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
 namespace armarx
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.h
index ab280b2245ff23cecbb5062969168dca312abc2f..9f38d25d491b275c944a988f76a36a32880890ab 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointKinematicUnitPassThroughController.h
@@ -24,7 +24,7 @@
 
 #include <atomic>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.cpp
index 12ca8b5a1ec6146599034643989c0a668704d888..1c3a68e75ac1131f46372a5bdaa68442b849788a 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.cpp
@@ -24,6 +24,8 @@
 #include "NJointTCPController.h"
 
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.h
index ecf1fc2666dded6b34c9f46850d1b00f7b0c09de..311df4838b1194c954f1ac1e23d4e754ff56434c 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTCPController.h
@@ -23,9 +23,8 @@
  */
 #pragma once
 
-
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/IKSolver.h>
 
 #include "../ControlTargets/ControlTarget1DoFActuator.h"
 #include "../SensorValues/SensorValue1DoFActuator.h"
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp
index e4b850fcaea1b866c2b6c6394d77934ffdfd5998..069b296afe87fddbe6493b91007089b66fdac58a 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp
@@ -25,6 +25,10 @@
 #include <SimoxUtility/math/convert/mat4f_to_pos.h>
 #include <SimoxUtility/math/convert/mat4f_to_quat.h>
 
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
+
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerRegistry.h>
 
 using namespace armarx;
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.h
index 42ce54179acab6ab646191155c259a8a05f1e38a..47706d9dcc9ccd835750cad1b51ee0a91a22ac03 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.h
@@ -22,8 +22,7 @@
 
 #pragma once
 
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/components/units/RobotUnit/ControlTargets/ControlTarget1DoFActuator.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerWithTripleBuffer.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.cpp
index 4e79acb8ff78a77e739ac8b2ee867ca8b64df701..e4a068265734fffb5255660be5302f1e935ada3b 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.cpp
@@ -1,6 +1,8 @@
 #include "NJointTrajectoryController.h"
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/TimeOptimalTrajectory/TimeOptimalTrajectory.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/time/TimeUtil.h>
 #include <ArmarXCore/interface/observers/ObserverInterface.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.h b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.h
index eb13d7c90f16f4fe14ce3b70b26928f569aa8343..95b90d9c7ab7219219b2ce944490a2b097cc3755 100644
--- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.h
+++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTrajectoryController.h
@@ -1,6 +1,6 @@
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXGui/interface/StaticPlotterInterface.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnit.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnit.cpp
index 29f4b175adc0de5bbbca50aa92730d8871c31947..2d3a8b5ea8c779fb063a0aa820f9aae418e5a0e4 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnit.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnit.cpp
@@ -29,4 +29,9 @@ namespace armarx
     {
     }
 
+    armarx::PropertyDefinitionsPtr
+    RobotUnit::createPropertyDefinitions()
+    {
+        return PropertyDefinitionsPtr(new RobotUnitPropertyDefinitions(getConfigIdentifier()));
+    }
 } // namespace armarx
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnit.h b/source/RobotAPI/components/units/RobotUnit/RobotUnit.h
index 0c97bcd05f4e4d6f4231839b23a99bcec8131c0d..b22844a4ec70de140442e173458c7ae5e01ad287 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnit.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnit.h
@@ -200,10 +200,6 @@ namespace armarx
         }
 
         /// @see PropertyUser::createPropertyDefinitions()
-        armarx::PropertyDefinitionsPtr
-        createPropertyDefinitions() override
-        {
-            return PropertyDefinitionsPtr(new RobotUnitPropertyDefinitions(getConfigIdentifier()));
-        }
+        armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
     };
 } // namespace armarx
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.cpp
index 732a0e2c479ed852a1162551f881c67c3fa36489..a2cc1aa25d67e8c84eed521cea12e9a4e55b279f 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.cpp
@@ -24,6 +24,8 @@
 
 #include <sstream>
 
+#include <VirtualRobot/Robot.h>
+
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/util/Preprocessor.h>
 #include <ArmarXCore/util/CPPUtility/trace.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.h
index b76f54dc8b0c5de7052552f202f62c9eefcce05a..29732afdeb43944f828b05287439fa856a178397 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleBase.h
@@ -30,7 +30,7 @@
 #include <boost/preprocessor/seq/for_each.hpp>
 #include <boost/preprocessor/variadic/to_seq.hpp>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/Component.h>
 #include <ArmarXCore/util/CPPUtility/Pointer.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThread.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThread.cpp
index 6f01acc17ee6c7cf5ede5925d4deffa68ceeca4e..6b65c43badf87a905fb0a60b3ffe87f40fe51998 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThread.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThread.cpp
@@ -23,6 +23,7 @@
 #include "RobotUnitModuleControlThread.h"
 
 #include <SimoxUtility/math/convert/pos_rpy_to_mat4f.h>
+#include <VirtualRobot/VirtualRobotException.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
 #include <ArmarXCore/core/time/TimeUtil.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.cpp
index 99b4a64e42605d0449e62145b869d8d64972aba7..d9e4084164fb2144b5d4bd2c823c11b6177154ae 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.cpp
@@ -24,6 +24,8 @@
 
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointControllerBase.h>
 
+#include <VirtualRobot/Robot.h>
+
 #include "RobotUnitModuleControllerManagement.h"
 #include "RobotUnitModuleDevices.h"
 
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.h
index 1833042321debe6dbd1487e9d5af4a673c670ac5..d9ed47b7b6775296ec52cefebb77b32aff989bad 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleControlThreadDataBuffer.h
@@ -22,7 +22,8 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 
 #include <ArmarXCore/core/util/TripleBuffer.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleDevices.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleDevices.h
index 0c7caccb3cf6fa840928c6a5907f483e21690d5a..4702668c566ab4413b621f66807209bcb38607d6 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleDevices.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleDevices.h
@@ -24,6 +24,10 @@
 
 #include <mutex>
 
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/Robot.h>
+
 #include "RobotAPI/components/units/RobotUnit/Devices/GlobalRobotPoseSensorDevice.h"
 #include <RobotAPI/interface/units/RobotUnit/RobotUnitInterface.h>
 
@@ -259,6 +263,8 @@ namespace armarx::RobotUnitModule
          * @param nodes The VirtualRobot's RobotNodes
          * @param sensors The \ref SensorValue "SensorValues"
          */
+
+         // TODO use base type for 'sensors' element
         template <class PtrT>
         void
         updateVirtualRobotFromSensorValues(const VirtualRobot::RobotPtr& robot,
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.cpp
index b2ae894908ffc85a0bc906254f93bc4a31f1f5c5..033d869628eb78f86dd723a8671feb26063df5a1 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.cpp
@@ -24,7 +24,9 @@
 
 #include <SimoxUtility/algorithm/string/string_tools.h>
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/VirtualRobotException.h>
 #include <VirtualRobot/XML/RobotIO.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.h
index c6e94bd515bea5a6f88597c935eb277c234a33d2..d3e1e68f7ff9da6ba782e7c9454c1faefcbb8c92 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleRobotData.h
@@ -22,7 +22,7 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/ArmarXManager.h>
 #include <ArmarXCore/core/services/tasks/TaskUtil.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.cpp b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.cpp
index 698df2657899773a1a111bd02ce561abd66308ef..1ebf5d476627e4503c355298b96d655ce11a19f0 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.cpp
@@ -27,8 +27,11 @@
 
 #include <SimoxUtility/algorithm/string/string_tools.h>
 #include <VirtualRobot/CollisionDetection/CollisionChecker.h>
+#include <VirtualRobot/CollisionDetection/CollisionModel.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/Obstacle.h>
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Robot.h>
 
 #include "ArmarXCore/core/logging/Logging.h"
 #include "ArmarXCore/core/time/Metronome.h"
diff --git a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.h b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.h
index fa7e690cd602045f3ed0883e81fb0e3956822b69..36798242c9e365fa26bc9a5db0dc93123da623aa 100644
--- a/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.h
+++ b/source/RobotAPI/components/units/RobotUnit/RobotUnitModules/RobotUnitModuleSelfCollisionChecker.h
@@ -24,7 +24,7 @@
 
 #include <thread>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 
diff --git a/source/RobotAPI/components/units/RobotUnit/SensorValues/SensorValueForceTorque.h b/source/RobotAPI/components/units/RobotUnit/SensorValues/SensorValueForceTorque.h
index 776bb731d7ab5115953fb6cb044c0f385ce6e7a2..707800ad73868e83a5b49a0d159121beb8eb20c7 100644
--- a/source/RobotAPI/components/units/RobotUnit/SensorValues/SensorValueForceTorque.h
+++ b/source/RobotAPI/components/units/RobotUnit/SensorValues/SensorValueForceTorque.h
@@ -23,7 +23,8 @@
 
 #include <RobotAPI/libraries/core/Pose.h>
 
-#include "Eigen/Core"
+#include <Eigen/Core>
+
 #include "SensorValueBase.h"
 
 namespace armarx
diff --git a/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.cpp b/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.cpp
index debb6a1a7d61f2cc348dd8214dea4f5e512bdf1e..2dc836d8968f0c52974e8b1431a86bc2abea2e2c 100644
--- a/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.cpp
@@ -25,6 +25,7 @@
 #include <Eigen/Geometry>
 
 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
+#include <VirtualRobot/MathTools.h>
 
 #include <RobotAPI/components/units/RobotUnit/Devices/GlobalRobotPoseSensorDevice.h>
 #include <RobotAPI/interface/core/GeometryBase.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.h b/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.h
index c40aa7e4460792dae1ae0e8f5519edb80766a31f..bc679526a8af3080a27de60f98f6ae39b4e0dac4 100644
--- a/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.h
+++ b/source/RobotAPI/components/units/RobotUnit/Units/LocalizationSubUnit.h
@@ -26,7 +26,6 @@
 
 #include <Eigen/Core>
 
-#include <VirtualRobot/MathTools.h>
 
 #include <RobotAPI/components/units/SensorActorUnit.h>
 #include <RobotAPI/interface/core/RobotState.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp
index c7e7348c57092485ddc70a1e5a18487b091cd358..4186fa390c094c673efe2fcf12509c9efedec2f2 100644
--- a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.cpp
@@ -25,6 +25,7 @@
 #include <Eigen/Geometry>
 
 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
+#include <VirtualRobot/MathTools.h>
 
 #include <RobotAPI/components/units/RobotUnit/Devices/GlobalRobotPoseSensorDevice.h>
 #include <RobotAPI/interface/core/GeometryBase.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h
index dd41099f1f79411eb23fcd7e484b9c57b7cd42a8..dc081d781946ac3fe52efb56db4aef88329f9dd6 100644
--- a/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h
+++ b/source/RobotAPI/components/units/RobotUnit/Units/PlatformSubUnit.h
@@ -26,8 +26,6 @@
 
 #include <Eigen/Core>
 
-#include <VirtualRobot/MathTools.h>
-
 #include <RobotAPI/components/units/PlatformUnit.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformGlobalPositionController.h>
 #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointHolonomicPlatformRelativePositionController.h>
diff --git a/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.cpp b/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.cpp
index 79d076f9b2aa7202f4ad649f76090b034da2f6db..bc22d972c5bf6eb3830fc5f3a1b7e8ef12949dfc 100644
--- a/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.cpp
+++ b/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.cpp
@@ -28,6 +28,10 @@
 
 #include <RobotAPI/components/units/RobotUnit/RobotUnit.h>
 
+
+#include <VirtualRobot/Dynamics/Dynamics.h>
+#include <VirtualRobot/RobotNodeSet.h>
+
 namespace armarx
 {
 
diff --git a/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.h b/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.h
index edcf445b56cc0354889cce4475147aabf1605c2b..e49736123c26cf94e184d78f0445e4f46cf23754 100644
--- a/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.h
+++ b/source/RobotAPI/components/units/RobotUnit/util/DynamicsHelper.h
@@ -24,8 +24,8 @@
 #pragma once
 #include <Eigen/Core>
 
+#include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/Dynamics/Dynamics.h>
-#include <VirtualRobot/RobotNodeSet.h>
 
 #include <RobotAPI/components/units/RobotUnit/SensorValues/SensorValue1DoFActuator.h>
 
diff --git a/source/RobotAPI/components/units/TCPControlUnit.cpp b/source/RobotAPI/components/units/TCPControlUnit.cpp
index 4f79878eef58dbe407b744780f8b50203ca26a04..08557d8a0649565caf404908ed2fb979ac095d9f 100644
--- a/source/RobotAPI/components/units/TCPControlUnit.cpp
+++ b/source/RobotAPI/components/units/TCPControlUnit.cpp
@@ -28,10 +28,12 @@
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
 #include <ArmarXCore/core/time/TimeUtil.h>
 #include <VirtualRobot/RobotConfig.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/MathTools.h>
 
 #include <SimoxUtility/algorithm/string/string_tools.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
 
 #include <Eigen/Core>
 
diff --git a/source/RobotAPI/components/units/TCPControlUnit.h b/source/RobotAPI/components/units/TCPControlUnit.h
index 8b373d10178d0975bbf78831b08859c15781f9b6..8811a63dd792a7186c12cd8d2cd05d55220655ca 100644
--- a/source/RobotAPI/components/units/TCPControlUnit.h
+++ b/source/RobotAPI/components/units/TCPControlUnit.h
@@ -27,7 +27,9 @@
 #include <ArmarXCore/core/services/tasks/PeriodicTask.h>
 #include <ArmarXCore/core/Component.h>
 
+#include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/IK/DifferentialIK.h>
+
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 #include <ArmarXCore/interface/observers/ObserverInterface.h>
 
@@ -280,4 +282,3 @@ namespace armarx
     using EDifferentialIKPtr = std::shared_ptr<EDifferentialIK>;
 
 }
-
diff --git a/source/RobotAPI/gui-plugins/FTSensorCalibrationGui/FTSensorCalibrationGuiWidgetController.cpp b/source/RobotAPI/gui-plugins/FTSensorCalibrationGui/FTSensorCalibrationGuiWidgetController.cpp
index 288e480893d5f9865a83781fcde00ed799d7ccf7..6cc8d730eec3f7c083e46ff1f5c6b77300cce16f 100644
--- a/source/RobotAPI/gui-plugins/FTSensorCalibrationGui/FTSensorCalibrationGuiWidgetController.cpp
+++ b/source/RobotAPI/gui-plugins/FTSensorCalibrationGui/FTSensorCalibrationGuiWidgetController.cpp
@@ -22,6 +22,7 @@
 #include <string>
 
 #include <QRegExp>
+#include <VirtualRobot/RobotNodeSet.h>
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 #include <ArmarXCore/core/util/FileSystemPathBuilder.h>
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
index 440815d7d495c3a7a0e57acdde433e4a3a1d672f..a5c4e264d190647807344cfdca73a812ac6b3f57 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
@@ -44,6 +44,13 @@
 #include <RobotAPI/interface/core/NameValueMap.h>
 #include <RobotAPI/interface/units/KinematicUnitInterface.h>
 
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Visualization/VisualizationFactory.h>
+#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
+
+
 #include "KinematicUnitConfigDialog.h"
 
 // Qt headers
@@ -993,7 +1000,7 @@ namespace armarx
         if (robot != NULL)
         {
             ARMARX_VERBOSE << "getting coin visualization" << flush;
-            coinVisualization = robot->getVisualization<VirtualRobot::CoinVisualization>();
+            coinVisualization = robot->getVisualization();
 
             if (!coinVisualization || !coinVisualization->getCoinVisualization())
             {
diff --git a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
index 1c94c93057f2a7ff961809c63aab383df6b5623e..f569285ac3ba1ccefd86a88d4e7cfa2db47865eb 100644
--- a/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
@@ -40,19 +40,15 @@
 #include <QToolBar>
 
 
-#include <VirtualRobot/Robot.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/Visualization/VisualizationFactory.h>
-#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
-
 #include <Inventor/sensors/SoTimerSensor.h>
 #include <Inventor/nodes/SoNode.h>
 #include <Inventor/nodes/SoSeparator.h>
 #include <Inventor/nodes/SoEventCallback.h>
 #include <Inventor/Qt/viewers/SoQtExaminerViewer.h>
 #include <Inventor/Qt/SoQt.h>
+
 #include <QStyledItemDelegate>
+
 #include <ArmarXCore/core/util/IceReportSkipper.h>
 
 #include <VirtualRobot/VirtualRobot.h>
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
index bbd260410802a01a317945a6893194ccaddfb91e..d13aaf8d1234f45d5fa17e0dbec4d066f3b4e32c 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.cpp
@@ -33,8 +33,14 @@
 
 #include <RobotAPI/libraries/core/FramedPose.h>
 
+#include <VirtualRobot/MathTools.h>
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/CollisionDetection/CollisionModel.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Visualization/VisualizationFactory.h>
+#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
 
 // Qt headers
 #include <Qt>
@@ -389,7 +395,7 @@ void RobotViewerWidgetController::setRobotVisu(bool colModel)
         v = VirtualRobot::SceneObject::Collision;
     }
 
-    CoinVisualizationPtr robotViewerVisualization = robot->getVisualization<CoinVisualization>(v);
+    CoinVisualizationPtr robotViewerVisualization = robot->getVisualization(v);
 
     if (robotViewerVisualization)
     {
diff --git a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
index 48a161aa9eed86e54d45d7cf58a753b258880005..ebb76786af86a2dff64ea0880547a376a5ae1d06 100644
--- a/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
+++ b/source/RobotAPI/gui-plugins/RobotViewerPlugin/RobotViewerGuiPlugin.h
@@ -37,12 +37,7 @@
 /* Qt headers */
 #include <QMainWindow>
 
-
-#include <VirtualRobot/Robot.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/Visualization/VisualizationFactory.h>
-#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <Inventor/sensors/SoTimerSensor.h>
 
@@ -186,4 +181,3 @@ namespace armarx
     };
     using RobotViewerGuiPluginPtr = std::shared_ptr<RobotViewerWidgetController>;
 }
-
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
index 80b861c28d248f67d375eb5b4e3860f354d660f5..be74b8d21b39b76d9847876d2b806e9c43c74f75 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
@@ -27,7 +27,10 @@
 #include <VirtualRobot/XML/RobotIO.h>
 #include <VirtualRobot/LinkedCoordinate.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
-
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
 
 // C++ includes
 #include <sstream>
diff --git a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
index e3a78e725f07cf73ac8fc10d478c3abf914ee7f6..bcbfc2e079c91bd5db1f114bfa4902b3cd99b954 100644
--- a/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
+++ b/source/RobotAPI/gui-plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
@@ -29,11 +29,10 @@
 // ArmarX includes
 #include <RobotAPI/interface/units/TCPMoverUnitInterface.h>
 #include <RobotAPI/interface/units/TCPControlUnit.h>
+
 /** VirtualRobot headers **/
-#include <VirtualRobot/Robot.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 #include <ArmarXGui/libraries/ArmarXGuiBase/widgets/IceProxyFinder.h>
 
 #include <ArmarXGui/libraries/ArmarXGuiBase/ArmarXComponentWidgetController.h>
@@ -151,4 +150,3 @@ namespace armarx
         QPointer<TCPMoverConfigDialog> configDialog;
     };
 }
-
diff --git a/source/RobotAPI/libraries/ArmarXObjects/ObjectPose.cpp b/source/RobotAPI/libraries/ArmarXObjects/ObjectPose.cpp
index 82dc134ee4b958981cf1ebe5d74047f49eb62a2a..4bb9a4a1d7078a761b8ac79c99464e1766d8d9fb 100644
--- a/source/RobotAPI/libraries/ArmarXObjects/ObjectPose.cpp
+++ b/source/RobotAPI/libraries/ArmarXObjects/ObjectPose.cpp
@@ -3,6 +3,7 @@
 #include <SimoxUtility/math/pose/invert.h>
 #include <SimoxUtility/math/pose/pose.h>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/RobotConfig.h>
 
diff --git a/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.cpp b/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.cpp
index ffb42a45b44248c318516b6e74fea570e5db0bd6..af5dec6f77b98de2ea386a39ffa4f5335f118e04 100644
--- a/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.cpp
@@ -23,6 +23,7 @@
 
 #include "BimanualGraspCandidateHelper.h"
 #include <VirtualRobot/math/Helpers.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
diff --git a/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.h b/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.h
index 1b2e9b10cf81e17240e09af578468a12c13c4b40..9a861d414a7d35a13e500cc1365a99d8096a40ca 100644
--- a/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.h
+++ b/source/RobotAPI/libraries/GraspingUtility/BimanualGraspCandidateHelper.h
@@ -27,7 +27,7 @@
 #include <RobotAPI/interface/units/GraspCandidateProviderInterface.h>
 #include <RobotAPI/libraries/core/Pose.h>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <memory>
 
diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.cpp b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.cpp
index cba726500972e01f8f6ccf34fece40cbad4b2d4a..b8eafe669d406b838852dd10a9ab7a65aca10aec 100644
--- a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.cpp
@@ -23,6 +23,7 @@
 
 #include "GraspCandidateHelper.h"
 #include <VirtualRobot/math/Helpers.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.h b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.h
index 0fa9fe1ea3d713e090dda9d3a529050e1b9f82d1..d47e00f3f922ec170d28ceb484b5a1539658e0f6 100644
--- a/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.h
+++ b/source/RobotAPI/libraries/GraspingUtility/GraspCandidateHelper.h
@@ -26,7 +26,7 @@
 #include <RobotAPI/interface/units/GraspCandidateProviderInterface.h>
 #include <RobotAPI/libraries/core/Pose.h>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <memory>
 
diff --git a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp
index e20c92b7599c0fde9ae42500beba8677a696f4ba..efa9b038a15f3a446af7063f05ccb93cf31b45de 100644
--- a/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/GraspTrajectory.cpp
@@ -30,6 +30,7 @@
 
 #include <SimoxUtility/json/eigen_conversion.h>
 #include <SimoxUtility/json/json.hpp>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/math/Helpers.h>
 
 #include "ArmarXCore/core/logging/Logging.h"
diff --git a/source/RobotAPI/libraries/GraspingUtility/box_to_grasp_candidates.cpp b/source/RobotAPI/libraries/GraspingUtility/box_to_grasp_candidates.cpp
index b01b2c6e976d2f3d2f3e882668236cea36943c69..00a84074915aa9a7979ae47e08548c60d145de21 100644
--- a/source/RobotAPI/libraries/GraspingUtility/box_to_grasp_candidates.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/box_to_grasp_candidates.cpp
@@ -4,6 +4,8 @@
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
+#include <VirtualRobot/Robot.h>
+
 #include "box_to_grasp_candidates.h"
 
 namespace armarx
diff --git a/source/RobotAPI/libraries/GraspingUtility/grasp_candidate_drawer.cpp b/source/RobotAPI/libraries/GraspingUtility/grasp_candidate_drawer.cpp
index 9888dccad9687c74234e5a0e6ee2b59a4511e141..f24952192f6174ece60745d1855f7985fcbc232e 100644
--- a/source/RobotAPI/libraries/GraspingUtility/grasp_candidate_drawer.cpp
+++ b/source/RobotAPI/libraries/GraspingUtility/grasp_candidate_drawer.cpp
@@ -1,4 +1,5 @@
 #include <SimoxUtility/math/pose/pose.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
 
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
diff --git a/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.cpp b/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.cpp
index 8072390200cb2696c0a51bde1f7ca6807a76659d..38b5f30cd0d88591fa518fcb11fab3df7357424e 100644
--- a/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.cpp
+++ b/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.cpp
@@ -25,6 +25,10 @@
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
 #include <RobotAPI/libraries/core/FramedPose.h>
 
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/XML/RobotIO.h>
+
 #include "RobotStateComponentPlugin.h"
 
 
diff --git a/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h b/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h
index af85178be6aaa8e98da1e19e8c76dc0019bc237f..c385948dbea9cb9cf87755874eed4b9c847d3285 100644
--- a/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h
+++ b/source/RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h
@@ -24,7 +24,7 @@
 
 #include <mutex>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
 #include <ArmarXCore/core/ComponentPlugin.h>
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.cpp b/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.cpp
index 0cbf7e730f56186618f92c0a74be2b5dc5ad0f5a..16308fdfe7da160f2691d894c24d5f6a33bc84ce 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.cpp
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.cpp
@@ -26,6 +26,7 @@
 
 // Simox
 #include <SimoxUtility/math.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
 
 
 armarx::ObstacleAvoidingPlatformUnitHelper::ObstacleAvoidingPlatformUnitHelper(
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.h b/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.h
index 85d7543c956369817a0bb4df0c3dbda9fd22a576..d372ee8da0badc3114a8b60971e88a950e970c54 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.h
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/ObstacleAvoidingPlatformUnitHelper.h
@@ -28,7 +28,7 @@
 #include <Eigen/Core>
 
 // Simox
-#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 // RobotAPI
 #include <RobotAPI/components/units/ObstacleAvoidingPlatformUnit/ObstacleAvoidingPlatformUnit.h>
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.cpp b/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.cpp
index b5fe191b9674e89b0105679a22ddc6fdd459b0e5..7fbe6b3f88261e2815f1b8ca11a397c00968424d 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.cpp
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.cpp
@@ -27,8 +27,11 @@
 
 #include <RobotAPI/libraries/core/CartesianVelocityController.h>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/MathTools.h>
+#include <VirtualRobot/Robot.h>
 
 namespace armarx
 {
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.h b/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.h
index 40d1640eab8b5019577e0289cd1c8b19d5f932e8..279242ca5638f3643674bdcc13cabcba593b24d7 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.h
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/PositionControllerHelper.h
@@ -27,7 +27,8 @@
 
 #include "VelocityControllerHelper.h"
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/JacobiProvider.h>
 
 #include <RobotAPI/libraries/core/CartesianPositionController.h>
 #include <RobotAPI/libraries/core/Pose.h>
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.cpp b/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.cpp
index cf5eb9b333563c0850e9e4fa5f7b618041958f63..602cda54231704749972b62390cf0323efe043b2 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.cpp
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.cpp
@@ -31,6 +31,11 @@
 #include <ArmarXCore/util/CPPUtility/trace.h>
 // #include <ArmarXCore/core/system/ArmarXDataPath.cpp>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/Visualization/TriMeshModel.h>
+
 #include <Eigen/Dense>
 #include <algorithm>
 
diff --git a/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.h b/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.h
index c1fa9b4d74194e7fd4b8c2a5748d81ef4ccfdcbd..86e01df9c63b146cf3d37d1b44768b4fa76b3166 100644
--- a/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.h
+++ b/source/RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.h
@@ -25,9 +25,7 @@
 
 #include <RobotAPI/interface/core/RobotState.h>
 
-#include <VirtualRobot/Robot.h>
 #include <VirtualRobot/VirtualRobot.h>
-#include <VirtualRobot/Visualization/TriMeshModel.h>
 
 namespace armarx
 {
diff --git a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
index e18c49fcbbefa6a08196536a49705a55adf87866..2ae44a2916d7dceedeb06a6699b3aaa582bc3cef 100644
--- a/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
+++ b/source/RobotAPI/libraries/armem_grasping/server/KnownGraspProviderSegment.cpp
@@ -1,7 +1,9 @@
 #include "KnownGraspProviderSegment.h"
 
 #include <SimoxUtility/algorithm/string/string_tools.h>
+#include <VirtualRobot/Grasping/Grasp.h>
 #include <VirtualRobot/Grasping/GraspSet.h>
+#include <VirtualRobot/ManipulationObject.h>
 #include <VirtualRobot/XML/ObjectIO.h>
 
 #include <ArmarXCore/core/exceptions/LocalException.h>
diff --git a/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.cpp b/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.cpp
index 764cbdcc8e3a0cbeab1b6dd7b0027f1fcc30f2e9..9f69b93009bed3d41c34e0d99d2952443e399671 100644
--- a/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.cpp
+++ b/source/RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.cpp
@@ -3,6 +3,7 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/Robot.h>
 #include <SimoxUtility/algorithm/string/string_tools.h>
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
index 130e229fb4f9d988726307a183218f0e7a5b852c..505d2b44b59d52ff9515adeea173b1684e3aaf74 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.cpp
@@ -6,6 +6,7 @@
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/PackagePath.h>
 #include <ArmarXCore/core/logging/Logging.h>
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
index 571838aa3104abbbc89f1834d50f7f8c2a73ca41..83a17cf03a6059ce9effddc40f5777a191a0a37f 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h
@@ -21,7 +21,6 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
 #include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotWriter.h b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotWriter.h
index 0bae7b6e9d12bf287307ec5f774bc95389ca216c..b0a9552b82a11d0f44e6d3d7c75c297169bf7bff 100644
--- a/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotWriter.h
+++ b/source/RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotWriter.h
@@ -21,9 +21,7 @@
 
 #pragma once
 
-#include <VirtualRobot/Robot.h>
 #include <VirtualRobot/VirtualRobot.h>
-#include <VirtualRobot/XML/RobotIO.h>
 
 #include "RobotAPI/libraries/armem/core/forward_declarations.h"
 
diff --git a/source/RobotAPI/libraries/armem_robot_state/server/common/Visu.cpp b/source/RobotAPI/libraries/armem_robot_state/server/common/Visu.cpp
index 8a6af77010b1105ae66fc81a03a35cbdc1b87cdb..2627328d9a0f7efb5270b7b3dbf9a803d6a66c5e 100644
--- a/source/RobotAPI/libraries/armem_robot_state/server/common/Visu.cpp
+++ b/source/RobotAPI/libraries/armem_robot_state/server/common/Visu.cpp
@@ -10,6 +10,7 @@
 #include <SimoxUtility/algorithm/string/string_tools.h>
 #include <SimoxUtility/math/pose.h>
 #include <SimoxUtility/math/rescale.h>
+#include <VirtualRobot/Nodes/Sensor.h>
 #include <VirtualRobot/XML/RobotIO.h>
 
 #include <ArmarXCore/core/logging/Logging.h>
diff --git a/source/RobotAPI/libraries/armem_vision/types.h b/source/RobotAPI/libraries/armem_vision/types.h
index 1a6b6b7d69eb52cc7857744dfb774564ac984720..1ddd16d87b8cd65665d97f9ea7985c4145cf97d3 100644
--- a/source/RobotAPI/libraries/armem_vision/types.h
+++ b/source/RobotAPI/libraries/armem_vision/types.h
@@ -21,9 +21,9 @@
 
 #pragma once
 
-#include <vector>
 
-#include <VirtualRobot/MathTools.h>
+#include <Eigen/Core>
+#include <Eigen/Geometry>
 
 #include <RobotAPI/interface/units/LaserScannerUnit.h>
 #include <RobotAPI/libraries/armem/core/Time.h>
diff --git a/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.cpp b/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.cpp
index 18f34713915af784e3883b0a78d1112a14eda644..1804cb7326160912cdf214aebb8f887c79f4d4c2 100644
--- a/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.cpp
+++ b/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.cpp
@@ -24,6 +24,12 @@
 #include "CartesianFeedForwardPositionController.h"
 #include <RobotAPI/libraries/core/math/MathUtils.h>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/math/AbstractFunctionR1R6.h>
+
 namespace armarx
 {
     CartesianFeedForwardPositionController::CartesianFeedForwardPositionController(const VirtualRobot::RobotNodePtr& tcp)
diff --git a/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.h b/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.h
index 4c2704aca4a0bb8a0edb2779a32dd3d7b135692c..c40a394645c3b8c188315720b9e672e4b4e5ea00 100644
--- a/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.h
+++ b/source/RobotAPI/libraries/core/CartesianFeedForwardPositionController.h
@@ -23,11 +23,11 @@
 
 #pragma once
 
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/math/MathForwardDefinitions.h>
+#include <VirtualRobot/IK/IKSolver.h>
+
 #include <Eigen/Dense>
-#include <VirtualRobot/math/AbstractFunctionR1R6.h>
 
 namespace armarx
 {
diff --git a/source/RobotAPI/libraries/core/CartesianNaturalPositionController.cpp b/source/RobotAPI/libraries/core/CartesianNaturalPositionController.cpp
index b1f6850fbf3cd8067a0903c8a6973561f2418c9d..5c45b8873d933c7d53728603c703af3e4ed0141a 100644
--- a/source/RobotAPI/libraries/core/CartesianNaturalPositionController.cpp
+++ b/source/RobotAPI/libraries/core/CartesianNaturalPositionController.cpp
@@ -29,8 +29,10 @@
 
 #include "CartesianNaturalPositionController.h"
 
+#include <VirtualRobot/Nodes/RobotNode.h>
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/MathTools.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
 
 namespace armarx
 {
diff --git a/source/RobotAPI/libraries/core/CartesianPositionController.cpp b/source/RobotAPI/libraries/core/CartesianPositionController.cpp
index c34d94957311c775b378bcda7e0dda17f38fe1c3..a2d75227f2cf8739a62bdd34a7301a2baca5c6e8 100644
--- a/source/RobotAPI/libraries/core/CartesianPositionController.cpp
+++ b/source/RobotAPI/libraries/core/CartesianPositionController.cpp
@@ -23,6 +23,12 @@
 
 #include "CartesianPositionController.h"
 
+
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
+
 #include <RobotAPI/libraries/core/math/MathUtils.h>
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
diff --git a/source/RobotAPI/libraries/core/CartesianPositionController.h b/source/RobotAPI/libraries/core/CartesianPositionController.h
index d4f3a688376c1ee470572e6ed1963be41aa2d9c0..df4272087876ef431d2c49ed7800bc1a57d3992d 100644
--- a/source/RobotAPI/libraries/core/CartesianPositionController.h
+++ b/source/RobotAPI/libraries/core/CartesianPositionController.h
@@ -23,9 +23,9 @@
 
 #pragma once
 
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/IKSolver.h>
+
 #include <Eigen/Dense>
 
 #include <RobotAPI/interface/core/CartesianPositionControllerConfig.h>
@@ -128,4 +128,3 @@ namespace armarx
 
     typedef IceInternal::Handle<CartesianPositionControllerConfig> CartesianPositionControllerConfigPtr;
 }
-
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityController.cpp b/source/RobotAPI/libraries/core/CartesianVelocityController.cpp
index 93d3df8e907c5086e00a470d9f4e9bdfe3dfb37f..636104a3993a63b694445d19c1492303280e24bf 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityController.cpp
+++ b/source/RobotAPI/libraries/core/CartesianVelocityController.cpp
@@ -28,8 +28,11 @@
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 #include <ArmarXCore/core/logging/Logging.h>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/Robot.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
 
 #include <Eigen/Core>
 
@@ -306,5 +309,3 @@ void CartesianVelocityController::setJointCosts(const std::vector<float>& jointC
         _jointCosts(i) = jointCosts.at(i);
     }
 }
-
-
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityController.h b/source/RobotAPI/libraries/core/CartesianVelocityController.h
index 3e37d44f53308858b756f84423cf06cd65995404..0454957fb9cbf3c765c9a794e8d401321251730c 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityController.h
+++ b/source/RobotAPI/libraries/core/CartesianVelocityController.h
@@ -23,8 +23,8 @@
 
 #pragma once
 
-#include <VirtualRobot/IK/DifferentialIK.h>
 #include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/JacobiProvider.h>
 
 #include <Eigen/Core>
 
@@ -75,4 +75,3 @@ namespace armarx
         Eigen::VectorXf _jointCosts;
     };
 }
-
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.cpp b/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.cpp
index ee06ab837f18e01764757e98e9aa372fc63e785f..6c9d30d58dc25d3a6a58021ad7f763776041cd04 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.cpp
+++ b/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.cpp
@@ -23,6 +23,10 @@
 
 #include "CartesianVelocityControllerWithRamp.h"
 
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+
 #include <ArmarXCore/core/logging/Logging.h>
 
 namespace armarx
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.h b/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.h
index 1a73b84900971b6cafe810bedd219998362a29a4..3b6b93dc9ba6336acb6e1df39d9c14c6abf59f35 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.h
+++ b/source/RobotAPI/libraries/core/CartesianVelocityControllerWithRamp.h
@@ -28,9 +28,8 @@
 #include "JointVelocityRamp.h"
 
 #include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/IKSolver.h>
 
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
 #include <Eigen/Dense>
 
 
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityRamp.cpp b/source/RobotAPI/libraries/core/CartesianVelocityRamp.cpp
index e904576b730b5eb9e4d2927cc2819685af7e0b4c..eb5646dac877f1f3632c94b9f4bf64c1d441a765 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityRamp.cpp
+++ b/source/RobotAPI/libraries/core/CartesianVelocityRamp.cpp
@@ -25,6 +25,9 @@
 
 #include <ArmarXCore/core/logging/Logging.h>
 
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/Robot.h>
+
 namespace armarx
 {
     CartesianVelocityRamp::CartesianVelocityRamp()
@@ -88,4 +91,3 @@ namespace armarx
         return maxOrientationAcceleration;
     }
 }
-
diff --git a/source/RobotAPI/libraries/core/CartesianVelocityRamp.h b/source/RobotAPI/libraries/core/CartesianVelocityRamp.h
index b4d5aac333e20e488831c44567f093cafa8dad95..573dfe2b293450fb5dd98be649a982aef81d3842 100644
--- a/source/RobotAPI/libraries/core/CartesianVelocityRamp.h
+++ b/source/RobotAPI/libraries/core/CartesianVelocityRamp.h
@@ -23,8 +23,9 @@
 
 #pragma once
 
-#include <VirtualRobot/IK/DifferentialIK.h>
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/IKSolver.h>
+
 #include <Eigen/Dense>
 
 namespace armarx
diff --git a/source/RobotAPI/libraries/core/CartesianWaypointController.cpp b/source/RobotAPI/libraries/core/CartesianWaypointController.cpp
index 917877b7a5ce1556ece46a9d8353b274dba87465..34c1902c05f8cbc63435dcb1cd35a1735b4e2c39 100644
--- a/source/RobotAPI/libraries/core/CartesianWaypointController.cpp
+++ b/source/RobotAPI/libraries/core/CartesianWaypointController.cpp
@@ -31,6 +31,7 @@
 
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/MathTools.h>
+#include <VirtualRobot/Robot.h>
 #include <cfloat>
 #include <ArmarXCore/util/CPPUtility/trace.h>
 
diff --git a/source/RobotAPI/libraries/core/CartesianWaypointController.h b/source/RobotAPI/libraries/core/CartesianWaypointController.h
index b87ae11f3a1bd3341261eb95d638dafd511add6b..d6fb2f7bc2038ac64dfc260346662b1441baaddc 100644
--- a/source/RobotAPI/libraries/core/CartesianWaypointController.h
+++ b/source/RobotAPI/libraries/core/CartesianWaypointController.h
@@ -27,7 +27,7 @@
 
 #include <Eigen/Dense>
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/libraries/core/CartesianPositionController.h>
 #include <RobotAPI/libraries/core/Pose.h>
diff --git a/source/RobotAPI/libraries/core/FramedOrientedPoint.cpp b/source/RobotAPI/libraries/core/FramedOrientedPoint.cpp
index 67391514fcba1a51f62ab4488aa1d5f4d54a4a1e..9c42823f12c1bb88cc4581d67a5f8d88d50a385c 100644
--- a/source/RobotAPI/libraries/core/FramedOrientedPoint.cpp
+++ b/source/RobotAPI/libraries/core/FramedOrientedPoint.cpp
@@ -22,7 +22,6 @@
 
 #include <VirtualRobot/Robot.h>
 #include <VirtualRobot/LinkedCoordinate.h>
-#include <VirtualRobot/LinkedCoordinate.h>
 #include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h>
diff --git a/source/RobotAPI/libraries/core/FramedOrientedPoint.h b/source/RobotAPI/libraries/core/FramedOrientedPoint.h
index 3504cad3a5450c0a8d2e19722f66676995319ac4..22aff2d36db3a88dc92b0237534eb1a867439ebf 100644
--- a/source/RobotAPI/libraries/core/FramedOrientedPoint.h
+++ b/source/RobotAPI/libraries/core/FramedOrientedPoint.h
@@ -23,9 +23,6 @@
 
 #include "OrientedPoint.h"
 
-#include <VirtualRobot/Robot.h>
-#include <VirtualRobot/LinkedCoordinate.h>
-#include <VirtualRobot/LinkedCoordinate.h>
 #include <VirtualRobot/VirtualRobot.h>
 
 #include <RobotAPI/interface/core/RobotState.h>
@@ -105,4 +102,3 @@ namespace armarx
 
     };
 }
-
diff --git a/source/RobotAPI/libraries/core/RobotPool.cpp b/source/RobotAPI/libraries/core/RobotPool.cpp
index 0b6d58afe038069766bcd96751fcccadfd7056ec..731646d134359076c163f2aa002f2e80946079d0 100644
--- a/source/RobotAPI/libraries/core/RobotPool.cpp
+++ b/source/RobotAPI/libraries/core/RobotPool.cpp
@@ -24,6 +24,7 @@
 #include "RobotPool.h"
 
 #include <VirtualRobot/CollisionDetection/CollisionChecker.h>
+#include <VirtualRobot/Robot.h>
 
 #include <ArmarXCore/core/logging/Logging.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
diff --git a/source/RobotAPI/libraries/core/RobotPool.h b/source/RobotAPI/libraries/core/RobotPool.h
index 4d6db6fc1ed2ba14a1f3c9bffe2b7557deaf0508..c65afe3036082809c3f0d36674f40f674d69cc52 100644
--- a/source/RobotAPI/libraries/core/RobotPool.h
+++ b/source/RobotAPI/libraries/core/RobotPool.h
@@ -23,9 +23,10 @@
  */
 #pragma once
 
-#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <mutex>
+#include <map>
 
 namespace armarx
 {
@@ -60,5 +61,3 @@ namespace armarx
     };
     using RobotPoolPtr = std::shared_ptr<RobotPool>;
 }
-
-
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
index 4f0f563e7960efbb4cc8055f2c198803105b841e..4383ae2e53fafb87f6713bd0a341a380e073cf54 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.cpp
@@ -31,7 +31,14 @@
 #include <VirtualRobot/Nodes/RobotNodePrismaticFactory.h>
 #include <VirtualRobot/Nodes/RobotNodeRevoluteFactory.h>
 #include <VirtualRobot/CollisionDetection/CollisionChecker.h>
-
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <RobotAPI/interface/core/RobotState.h>
+#include <VirtualRobot/Nodes/RobotNodeRevolute.h>
+#include <VirtualRobot/Nodes/RobotNodePrismatic.h>
+#include <VirtualRobot/Nodes/RobotNodeFixed.h>
+#include <VirtualRobot/XML/RobotIO.h>
 
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
index 734db7407354682df6fa45c866acdb0e9c8c0a6f..c976c53411a43af5837a52fb8d58926401db4bee 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobot.h
@@ -23,15 +23,15 @@
  */
 #pragma once
 
-#include <VirtualRobot/VirtualRobot.h>
 #include <VirtualRobot/Robot.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <RobotAPI/interface/core/RobotState.h>
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/XML/RobotIO.h>
+
+#include <VirtualRobot/Nodes/RobotNodeFixed.h>
 #include <VirtualRobot/Nodes/RobotNodeRevolute.h>
 #include <VirtualRobot/Nodes/RobotNodePrismatic.h>
-#include <VirtualRobot/Nodes/RobotNodeFixed.h>
-#include <VirtualRobot/XML/RobotIO.h>
+
+#include <RobotAPI/interface/core/RobotState.h>
 
 #include <mutex>
 
@@ -262,4 +262,3 @@ namespace armarx
 
     using RemoteRobotPtr = std::shared_ptr<RemoteRobot>;
 }
-
diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
index 28bb76573e925f3f6135ba0f3d75be2aa060d9f4..6e402e30031d962e4e755e50cd2bd63b0131fe8d 100644
--- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
+++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp
@@ -29,6 +29,7 @@
 #include <ArmarXCore/interface/core/BasicTypes.h>
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/VirtualRobot.h>
 
 
diff --git a/source/RobotAPI/libraries/core/test/CartesianVelocityControllerTest.cpp b/source/RobotAPI/libraries/core/test/CartesianVelocityControllerTest.cpp
index 683ad38f8e45e9d49ffdf0b425bb3569eef4d499..9c2f0fc609d47dfae5993d61d4d887be05e82b5b 100644
--- a/source/RobotAPI/libraries/core/test/CartesianVelocityControllerTest.cpp
+++ b/source/RobotAPI/libraries/core/test/CartesianVelocityControllerTest.cpp
@@ -23,9 +23,15 @@
 #define BOOST_TEST_MODULE RobotAPI::CartesianVelocityController::Test
 #define ARMARX_BOOST_TEST
 #include <RobotAPI/Test.h>
+
 #include <ArmarXCore/core/test/IceTestHelper.h>
 #include <ArmarXCore/core/system/ArmarXDataPath.h>
+
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/XML/RobotIO.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/IK/IKSolver.h>
+
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include "../CartesianVelocityController.h"
 
diff --git a/source/RobotAPI/libraries/core/test/CartesianVelocityControllerWithRampTest.cpp b/source/RobotAPI/libraries/core/test/CartesianVelocityControllerWithRampTest.cpp
index 5ffd4e0aed928a3e9292cabbb25087cf91758b6f..a4dcccdcec0d71c592dd0198f91e0e7beb2ebac7 100644
--- a/source/RobotAPI/libraries/core/test/CartesianVelocityControllerWithRampTest.cpp
+++ b/source/RobotAPI/libraries/core/test/CartesianVelocityControllerWithRampTest.cpp
@@ -20,6 +20,7 @@
 *             GNU General Public License
 */
 
+#include <VirtualRobot/IK/DifferentialIK.h>
 #define BOOST_TEST_MODULE RobotAPI::CartesianVelocityController::Test
 #define ARMARX_BOOST_TEST
 #include <RobotAPI/Test.h>
diff --git a/source/RobotAPI/libraries/diffik/CompositeDiffIK.cpp b/source/RobotAPI/libraries/diffik/CompositeDiffIK.cpp
index d8d4f0f6d09f30d964146f9428d26efb6de81d52..833e6a399e5e3ca64ad8e7441eb6aa78f5c0a99e 100644
--- a/source/RobotAPI/libraries/diffik/CompositeDiffIK.cpp
+++ b/source/RobotAPI/libraries/diffik/CompositeDiffIK.cpp
@@ -24,9 +24,13 @@
 #include "CompositeDiffIK.h"
 #include <VirtualRobot/Robot.h>
 #include <ArmarXCore/core/exceptions/Exception.h>
+
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+
 #include <cfloat>
 
 using namespace armarx;
@@ -458,3 +462,21 @@ Eigen::VectorXf CompositeDiffIK::NullspaceJointLimitAvoidance::getGradient(Param
     }
     return r.cwiseProduct(weight);
 }
+
+Eigen::Matrix4f
+armarx::CompositeDiffIK::Target::getPoseError() const
+{
+    return tcp->getPoseInRootFrame().inverse() * target;
+}
+
+Eigen::Vector3f
+armarx::CompositeDiffIK::Target::getPosError() const
+{
+    return (tcp->getPoseInRootFrame().inverse() * target).topRightCorner<3, 1>();
+}
+
+auto
+armarx::CompositeDiffIK::Target::getOriError() const
+{
+    return simox::math::delta_angle(tcp->getPoseInRootFrame(), target);
+}
diff --git a/source/RobotAPI/libraries/diffik/CompositeDiffIK.h b/source/RobotAPI/libraries/diffik/CompositeDiffIK.h
index 2736bfff337a33de477c224e34e63a81daf4b048..2963293f63fa644a2769d57d6b3262b77320dc99 100644
--- a/source/RobotAPI/libraries/diffik/CompositeDiffIK.h
+++ b/source/RobotAPI/libraries/diffik/CompositeDiffIK.h
@@ -22,11 +22,11 @@
  */
 
 #pragma once
+
 #include <SimoxUtility/math/distance/delta_angle.h>
 
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/IK/DifferentialIK.h>
+#include <VirtualRobot/VirtualRobot.h>
+
 #include <RobotAPI/libraries/core/CartesianPositionController.h>
 #include <RobotAPI/libraries/core/CartesianVelocityController.h>
 
@@ -150,18 +150,9 @@ namespace armarx
 
             std::vector<TargetStep> ikSteps;
 
-            Eigen::Matrix4f getPoseError() const
-            {
-                return tcp->getPoseInRootFrame().inverse() * target;
-            }
-            Eigen::Vector3f getPosError() const
-            {
-                return (tcp->getPoseInRootFrame().inverse() * target).topRightCorner<3, 1>();
-            }
-            auto getOriError() const
-            {
-                return simox::math::delta_angle(tcp->getPoseInRootFrame(), target);
-            }
+            Eigen::Matrix4f getPoseError() const;
+            Eigen::Vector3f getPosError() const;
+            auto getOriError() const;
         };
         typedef std::shared_ptr<Target> TargetPtr;
 
diff --git a/source/RobotAPI/libraries/diffik/GraspTrajectory.cpp b/source/RobotAPI/libraries/diffik/GraspTrajectory.cpp
index 3e6cdff5c28a7a27494e222ce78517abe3d8a5f5..ae7aace621b852c4d077aebd52afb0289da09d6e 100644
--- a/source/RobotAPI/libraries/diffik/GraspTrajectory.cpp
+++ b/source/RobotAPI/libraries/diffik/GraspTrajectory.cpp
@@ -25,6 +25,9 @@
 
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 
+#include <VirtualRobot/math/AbstractFunctionR1R6.h>
+#include <VirtualRobot/math/Helpers.h>
+
 using namespace armarx;
 
 
diff --git a/source/RobotAPI/libraries/diffik/GraspTrajectory.h b/source/RobotAPI/libraries/diffik/GraspTrajectory.h
index 8cc0a7cad1046733e4e7d52a4fe2d69eff28b660..777ed4066e29dd153284021272039e8cb37d61cc 100644
--- a/source/RobotAPI/libraries/diffik/GraspTrajectory.h
+++ b/source/RobotAPI/libraries/diffik/GraspTrajectory.h
@@ -38,9 +38,6 @@
 #include <ArmarXCore/core/system/cmake/CMakePackageFinder.h>
 #include <ArmarXCore/interface/serialization/Eigen.h>
 
-#include <VirtualRobot/math/AbstractFunctionR1R6.h>
-#include <VirtualRobot/math/Helpers.h>
-
 #include <Eigen/Core>
 
 #include <vector>
diff --git a/source/RobotAPI/libraries/diffik/NaturalDiffIK.cpp b/source/RobotAPI/libraries/diffik/NaturalDiffIK.cpp
index e7497443b1aded8914af5cc0400f4bf00ee89ffe..802f1e01c139423de6a09eec82eb986e77951247 100644
--- a/source/RobotAPI/libraries/diffik/NaturalDiffIK.cpp
+++ b/source/RobotAPI/libraries/diffik/NaturalDiffIK.cpp
@@ -24,6 +24,11 @@
 
 #include "NaturalDiffIK.h"
 
+
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+
 #include <RobotAPI/libraries/core/CartesianPositionController.h>
 #include <RobotAPI/libraries/core/CartesianVelocityController.h>
 
diff --git a/source/RobotAPI/libraries/diffik/NaturalDiffIK.h b/source/RobotAPI/libraries/diffik/NaturalDiffIK.h
index 0bdafb506e4cf6a22203b9b88cde2eccacba32d6..dbbd1e1172e271887392f8cfd6433b0578b2d0d6 100644
--- a/source/RobotAPI/libraries/diffik/NaturalDiffIK.h
+++ b/source/RobotAPI/libraries/diffik/NaturalDiffIK.h
@@ -23,10 +23,8 @@
 
 #pragma once
 
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
-#include <VirtualRobot/IK/DifferentialIK.h>
-
+#include <VirtualRobot/VirtualRobot.h>
+#include <VirtualRobot/IK/IKSolver.h>
 
 namespace armarx
 {
diff --git a/source/RobotAPI/libraries/diffik/SimpleDiffIK.cpp b/source/RobotAPI/libraries/diffik/SimpleDiffIK.cpp
index c3f1a32dbaa1001d06762522080ef5367c072b70..ef6a4d91b9d916ea46725f5db6e98b58bd0ef5b9 100644
--- a/source/RobotAPI/libraries/diffik/SimpleDiffIK.cpp
+++ b/source/RobotAPI/libraries/diffik/SimpleDiffIK.cpp
@@ -23,6 +23,9 @@
 
 #include "SimpleDiffIK.h"
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+
 #include <RobotAPI/libraries/core/CartesianPositionController.h>
 #include <RobotAPI/libraries/core/CartesianVelocityController.h>
 
@@ -171,4 +174,21 @@ namespace armarx
         return r;
     }
 
-}
+    void
+    SimpleDiffIK::Reachability::aggregate(const Result& result)
+    {
+        ikResults.emplace_back(result);
+        reachable = reachable && result.reached;
+        minimumJointLimitMargin = std::min(minimumJointLimitMargin, result.minimumJointLimitMargin);
+        if (jointLimitMargins.rows() == 0)
+        {
+            jointLimitMargins = result.jointLimitMargins;
+        }
+        else
+        {
+            jointLimitMargins = jointLimitMargins.cwiseMin(result.jointLimitMargins);
+        }
+        maxPosError = std::max(maxPosError, result.posError);
+        maxOriError = std::max(maxOriError, result.oriError);
+    }
+} // namespace armarx
diff --git a/source/RobotAPI/libraries/diffik/SimpleDiffIK.h b/source/RobotAPI/libraries/diffik/SimpleDiffIK.h
index d71ebbee9157cd27e643860fa68287d362d2524a..583fef2a8fec427dbde267d28fb5863ba9da7942 100644
--- a/source/RobotAPI/libraries/diffik/SimpleDiffIK.h
+++ b/source/RobotAPI/libraries/diffik/SimpleDiffIK.h
@@ -25,8 +25,7 @@
 
 #include "DiffIKProvider.h"
 
-#include <VirtualRobot/Nodes/RobotNode.h>
-#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/VirtualRobot.h>
 
 #include <memory>
 
@@ -88,22 +87,7 @@ namespace armarx
             float maxOriError = 0;
             std::vector<Result> ikResults;
 
-            void aggregate(const Result& result)
-            {
-                ikResults.emplace_back(result);
-                reachable = reachable && result.reached;
-                minimumJointLimitMargin = std::min(minimumJointLimitMargin, result.minimumJointLimitMargin);
-                if (jointLimitMargins.rows() == 0)
-                {
-                    jointLimitMargins = result.jointLimitMargins;
-                }
-                else
-                {
-                    jointLimitMargins = jointLimitMargins.cwiseMin(result.jointLimitMargins);
-                }
-                maxPosError = std::max(maxPosError, result.posError);
-                maxOriError = std::max(maxOriError, result.oriError);
-            }
+            void aggregate(const Result& result);
         };
 
         static Result CalculateDiffIK(const Eigen::Matrix4f targetPose, VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr tcp = VirtualRobot::RobotNodePtr(), Parameters params = Parameters());
diff --git a/source/RobotAPI/libraries/natik/CartesianNaturalPositionControllerProxy.cpp b/source/RobotAPI/libraries/natik/CartesianNaturalPositionControllerProxy.cpp
index 7a57d550daa7a14141bd3ddfc3e93193df11b394..bb532f39331aeb2ec1c599a918f88dad373b5314 100644
--- a/source/RobotAPI/libraries/natik/CartesianNaturalPositionControllerProxy.cpp
+++ b/source/RobotAPI/libraries/natik/CartesianNaturalPositionControllerProxy.cpp
@@ -27,6 +27,8 @@
 #include <ArmarXCore/core/exceptions/local/ExpressionException.h>
 //#include <RobotAPI/libraries/aron/core/navigator/Navigator.h>
 
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/math/Helpers.h>
 #include <VirtualRobot/MathTools.h>
 
@@ -530,5 +532,3 @@ CartesianNaturalPositionControllerProxy::ScopedJointValueRestore::~ScopedJointVa
     //ARMARX_IMPORTANT << "restoring joint values";
     rns->setJointValues(jointValues);
 }
-
-
diff --git a/source/RobotAPI/libraries/natik/NaturalIK.cpp b/source/RobotAPI/libraries/natik/NaturalIK.cpp
index 76bd6e75e6301cb29a80b608d8fd6fb2b7303b46..6a561959d34228fe6b64a436e74e713891ffcb47 100644
--- a/source/RobotAPI/libraries/natik/NaturalIK.cpp
+++ b/source/RobotAPI/libraries/natik/NaturalIK.cpp
@@ -23,11 +23,15 @@
 
 #include "NaturalIK.h"
 #include <ArmarXCore/core/exceptions/Exception.h>
+
 #include <SimoxUtility/math/convert/deg_to_rad.h>
 #include <SimoxUtility/math/convert/rad_to_deg.h>
-#include <ArmarXCore/core/logging/Logging.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
 #include <VirtualRobot/math/Helpers.h>
 
+#include <ArmarXCore/core/logging/Logging.h>
+
 using namespace armarx;
 
 NaturalIK::NaturalIK(std::string side, Eigen::Vector3f shoulderPos, float scale)
diff --git a/source/RobotAPI/libraries/natik/NaturalIK.h b/source/RobotAPI/libraries/natik/NaturalIK.h
index 7e1ecb940cc7adb84c0091e4e1f3427923559c74..e71511d9bd4ffef7f64b6fc4c9a86d22d49eb07d 100644
--- a/source/RobotAPI/libraries/natik/NaturalIK.h
+++ b/source/RobotAPI/libraries/natik/NaturalIK.h
@@ -26,7 +26,9 @@
 #include <memory>
 
 //#include <RobotAPI/libraries/core/SimpleDiffIK.h>
-#include <VirtualRobot/Nodes/RobotNode.h>
+
+#include <VirtualRobot/VirtualRobot.h>
+
 #include <RobotAPI/libraries/diffik/DiffIKProvider.h>
 #include <RobotAPI/libraries/diffik/NaturalDiffIK.h>
 #include <optional>
diff --git a/source/RobotAPI/libraries/obstacle_avoidance/CollisionModelHelper.cpp b/source/RobotAPI/libraries/obstacle_avoidance/CollisionModelHelper.cpp
index 05a230a8e02ffab13ae9c2970a817889e56e2982..b8165c4ba086e82aec64611efac92f7da4fea376 100644
--- a/source/RobotAPI/libraries/obstacle_avoidance/CollisionModelHelper.cpp
+++ b/source/RobotAPI/libraries/obstacle_avoidance/CollisionModelHelper.cpp
@@ -22,6 +22,7 @@
 
 #include "CollisionModelHelper.h"
 
+#include <VirtualRobot/CollisionDetection/CollisionModel.h>
 #include <VirtualRobot/ManipulationObject.h>
 #include <VirtualRobot/SceneObjectSet.h>
 #include <VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h>
diff --git a/source/RobotAPI/statecharts/RobotNameHelperTestGroup/TestGetNames.cpp b/source/RobotAPI/statecharts/RobotNameHelperTestGroup/TestGetNames.cpp
index df07b365c25f2f744246fd517d02e1a76e573adb..95ee1853bb68ffe504777330e996b1c5078ace25 100644
--- a/source/RobotAPI/statecharts/RobotNameHelperTestGroup/TestGetNames.cpp
+++ b/source/RobotAPI/statecharts/RobotNameHelperTestGroup/TestGetNames.cpp
@@ -21,6 +21,7 @@
  */
 
 #include "TestGetNames.h"
+#include <VirtualRobot/RobotNodeSet.h>
 
 #include <RobotAPI/libraries/RobotStatechartHelpers/RobotNameHelper.h>
 
@@ -208,4 +209,3 @@ XMLStateFactoryBasePtr TestGetNames::CreateInstance(XMLStateConstructorParams st
 {
     return XMLStateFactoryBasePtr(new TestGetNames(stateData));
 }
-