From 55ac2e795175623e8a4e9cce47b640ed8983b419 Mon Sep 17 00:00:00 2001
From: Meixner <andre.meixner@kit.edu>
Date: Tue, 27 Dec 2022 21:30:12 +0100
Subject: [PATCH] Fixed methods in RobotFactory to reduce the robot model and
 created a better one; Updated primitive model approximation; Fixed some
 errors in RobotViewer included with the last commits

---
 VirtualRobot/RobotFactory.cpp                 | 263 +++++++++++++++---
 VirtualRobot/RobotFactory.h                   |  26 +-
 VirtualRobot/SceneObject.cpp                  |  40 +++
 VirtualRobot/SceneObject.h                    |   6 +
 .../CoinVisualizationFactory.cpp              |   7 +-
 .../CoinVisualizationFactory.h                |   2 +-
 .../Visualization/VisualizationFactory.h      |   2 +-
 VirtualRobot/XML/RobotIO.cpp                  |   5 +-
 .../examples/RobotViewer/RobotViewer.ui       |   3 -
 .../examples/RobotViewer/showRobotWindow.cpp  |  14 +-
 10 files changed, 310 insertions(+), 58 deletions(-)

diff --git a/VirtualRobot/RobotFactory.cpp b/VirtualRobot/RobotFactory.cpp
index d8a2af0d9..aa22124d5 100644
--- a/VirtualRobot/RobotFactory.cpp
+++ b/VirtualRobot/RobotFactory.cpp
@@ -13,6 +13,8 @@
 #include "Visualization//VisualizationFactory.h"
 #include "VirtualRobotException.h"
 
+#include <SimoxUtility/math/pose/invert.h>
+
 #include <algorithm>
 #include <cassert>
 #include <deque>
@@ -321,6 +323,7 @@ namespace VirtualRobot
         RobotNodePtr newRN = rnf->createRobotNode(robot, name, v, c, 0, 0, 0, transformation, Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero(), p);
         rn->attachChild(newRN);
         newRN->initialize(rn);
+        newRN->primitiveApproximation = o->getPrimitiveApproximation().clone();
         return true;
     }
 
@@ -656,15 +659,9 @@ namespace VirtualRobot
     {
         THROW_VR_EXCEPTION_IF(!robot, "NULL data");
         THROW_VR_EXCEPTION_IF(!nodeA, "NULL data");
-        auto rnf = RobotNodeFixedFactory::createInstance(nullptr);
-        SceneObject::Physics p;
-        VisualizationNodePtr v;
-        CollisionModelPtr c;
-
         if (nodeA == nodeB)
         {
-            RobotNodePtr newRN = rnf->createRobotNode(robot, nodeA->getName() + "_non_trafo", v, c, 0, 0, 0, Eigen::Matrix4f::Identity(), Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero(), p);
-            return newRN;
+            return RobotNodePtr();
         }
 
         std::vector<RobotNodePtr> childNodes;
@@ -684,7 +681,7 @@ namespace VirtualRobot
         {
             Eigen::Matrix4f startPose = nodeA->getGlobalPose();
             Eigen::Matrix4f goalPose = nodeB->getParent()->getGlobalPose();
-            storeTrafo = goalPose * startPose.inverse();
+            storeTrafo = simox::math::inverted_pose(startPose) * goalPose;
         }
 
         RobotNodePtr res = createUnitedRobotNode(robot, childNodes, nodeA, nodeAClone, Eigen::Matrix4f::Identity(), childSensorNodes);
@@ -751,7 +748,7 @@ namespace VirtualRobot
             v = vf->createUnitedVisualization(visus)->clone();
             if (parent)
             {
-                Eigen::Matrix4f invTr = parent->getGlobalPose().inverse();
+                Eigen::Matrix4f invTr = simox::math::inverted_pose(parent->getGlobalPose());
                 vf->applyDisplacement(v, invTr);
             }
         }
@@ -761,7 +758,7 @@ namespace VirtualRobot
             VisualizationNodePtr colVisu = vf->createUnitedVisualization(colVisus)->clone();
             if (parent)
             {
-                Eigen::Matrix4f invTr = parent->getGlobalPose().inverse();
+                Eigen::Matrix4f invTr = simox::math::inverted_pose(parent->getGlobalPose());
                 vf->applyDisplacement(colVisu, invTr);
             }
             c.reset(new CollisionModel(colVisu, nodes[0]->getName()));
@@ -773,20 +770,57 @@ namespace VirtualRobot
 
         newRN->initialize(parentClone);
 
+        const Eigen::Matrix4f trafoToNewRN = parent ? parent->getGlobalPose() * trafo : trafo;
+
+        // add primitive models
+        for (const auto& node : nodes)
+        {
+            const auto& primitiveApproximation = node->getPrimitiveApproximation();
+            const Eigen::Matrix4f localTransformation = simox::math::inverted_pose(trafoToNewRN) * node->getGlobalPose();
+            newRN->getPrimitiveApproximation().join(primitiveApproximation.clone().localTransformation(localTransformation));
+        }
+
         // attach sensors
         for (const auto& sensor : sensors)
         {
             SensorPtr s = sensor->clone(newRN);
-            Eigen::Matrix4f trafoToNewRN = parent ? parent->getGlobalPose() * trafo : trafo;
-            Eigen::Matrix4f t = trafoToNewRN.inverse() * sensor->getGlobalPose();
+            Eigen::Matrix4f t = simox::math::inverted_pose(trafoToNewRN) * sensor->getGlobalPose();
             s->setRobotNodeToSensorTransformation(t);
         }
 
         return newRN;
     }
 
+    void RobotFactory::cloneRNS(const Robot& from, RobotPtr to)
+    {
+        for (const auto& rns : from.getRobotNodeSets())
+        {
+            bool hasNodes = true;
+            for (const auto& nodeName : rns->getNodeNames())
+            {
+                if (!to->hasRobotNode(nodeName))
+                {
+                    hasNodes = false;
+                    break;
+                }
+            }
+            const auto &tcp = rns->getTCP();
+            if (hasNodes && (!tcp || to->hasRobotNode(tcp->getName())))
+            {
+                if (const auto& kinRoot = rns->getKinematicRoot())
+                {
+                    if (!to->hasRobotNode(kinRoot->getName()))
+                    {
+                        rns->clone(to, to->getRootNode());
+                        continue;
+                    }
+                }
+                rns->clone(to);
+            }
+        }
+    }
 
-    RobotPtr RobotFactory::cloneSubSet(RobotPtr robot, RobotNodeSetPtr rns, const std::string& name)
+    RobotPtr RobotFactory::cloneSubSet(RobotPtr robot, RobotNodeSetPtr rns, const std::string& name, bool addTCP)
     {
         THROW_VR_EXCEPTION_IF(!robot, "NULL data");
         THROW_VR_EXCEPTION_IF(!rns, "NULL data");
@@ -796,8 +830,8 @@ namespace VirtualRobot
         THROW_VR_EXCEPTION_IF(nodes.size() == 0, "0 data");
 
         // ensure tcp is part of nodes
-        //if (rns->getTCP() && !rns->hasRobotNode(rns->getTCP()))
-        //    nodes.push_back(rns->getTCP());
+        if (addTCP && rns->getTCP() && !rns->hasRobotNode(rns->getTCP()))
+            nodes.push_back(rns->getTCP());
 
         // ensure kinemtic root is part of nodes
         if (rns->getKinematicRoot() && !rns->hasRobotNode(rns->getKinematicRoot()))
@@ -904,7 +938,13 @@ namespace VirtualRobot
             }
         }
 
+        cloneRNS(*robot.get(), result);
+
         result->setGlobalPose(robot->getGlobalPose());
+        if(robot->getHumanMapping().has_value())
+        {
+            result->registerHumanMapping(robot->getHumanMapping().value());
+        }
         return result;
     }
 
@@ -931,41 +971,194 @@ namespace VirtualRobot
 
         cloneRecursiveUnite(result, currentNode, currentNodeClone, uniteWithAllChildren);
 
-        // clone RNS
-        std::vector<RobotNodeSetPtr> rnsets = robot->getRobotNodeSets();
-        for (auto rns : rnsets)
+        cloneRNS(*robot.get(), result);
+
+        result->setGlobalPose(robot->getGlobalPose());
+        if(robot->getHumanMapping().has_value())
         {
-            bool ok = true;
-            for (const auto& j : uniteWithAllChildren)
+            result->registerHumanMapping(robot->getHumanMapping().value());
+        }
+        return result;
+    }
+
+    RobotPtr RobotFactory::createReducedModel(Robot &robot, const std::vector<std::string> &actuatedJointNames,
+                                              const std::vector<std::string> &otherNodeNames)
+    {
+        std::set<std::string> joint_set(actuatedJointNames.begin(), actuatedJointNames.end());
+        std::set<std::string> other_set(otherNodeNames.begin(), otherNodeNames.end());
+
+        // Check joint nodes and set robot joints to default value
+        std::map<std::string, float> joint_values;
+        for (const auto& joint_name : actuatedJointNames)
+        {
+            if (robot.hasRobotNode(joint_name))
             {
-                RobotNodePtr rn = robot->getRobotNode(j);
-                std::vector<RobotNodePtr> allChildren;
-                rn->collectAllRobotNodes(allChildren);
-                for (auto& k : allChildren)
+                auto node = robot.getRobotNode(joint_name);
+                if (!node->isJoint())
                 {
-                    if (k == rn)
+                    VR_WARNING << "Robot node " << joint_name << " is not a joint node";
+                    return nullptr;
+                }
+                joint_values[joint_name] = node->getJointValue();
+                // Set joints do default starting value
+                node->setJointValueNoUpdate(0.);
+            }
+            else
+            {
+                VR_WARNING << "Robot does not contain node " << joint_name;
+                return nullptr;
+            }
+        }
+        robot.updatePose();
+
+        RobotPtr reducedModel = std::make_shared<LocalRobot>("Reduced_" + robot.getName(), robot.getType());
+
+        struct Node
+        {
+            RobotNodePtr node;
+            RobotNodePtr node_cloned = nullptr;
+            bool is_actuated_joint = false;
+            RobotNodePtr parentNode_cloned = nullptr;
+            std::vector<RobotNodePtr> childNodes = std::vector<RobotNodePtr>();
+        };
+        std::queue<Node> nodes;
+        nodes.push(Node { .node = robot.getRootNode() });
+
+        std::function<void(RobotNodePtr, Node&)> collect;
+        collect = [joint_set, other_set, &collect, &nodes](RobotNodePtr currentNode, Node& node) -> void
+        {
+            for (const auto &child : currentNode->getChildren())
+            {
+                if (const auto& childNode = std::dynamic_pointer_cast<RobotNode>(child))
+                {
+                    const bool is_actuated_joint = joint_set.count(childNode->getName()) > 0;
+                    if (!is_actuated_joint && other_set.count(childNode->getName()) == 0)
                     {
-                        continue;
+                        node.childNodes.push_back(childNode);
+                        collect(childNode, node);
                     }
-                    if (rns->hasRobotNode(k->getName()) || rns->getTCP() == k)
+                    else
                     {
-                        ok = false;
-                        break;
+                        nodes.push(Node { .node = childNode, .is_actuated_joint=is_actuated_joint, .parentNode_cloned = node.node_cloned });
                     }
                 }
             }
-            if (ok)
+        };
+
+        const auto fixed_node_factory = RobotNodeFixedFactory::createInstance(nullptr);
+        while(!nodes.empty())
+        {
+            auto n = nodes.front();
+            nodes.pop();
+
+            // If node is a joint but is not part of the joints it will be converted to a fixed transformation node
+            if (!n.is_actuated_joint && n.node->isJoint())
+            {
+                n.node_cloned = fixed_node_factory->createRobotNode(reducedModel, n.node->getName(),
+                                                                    n.node->getVisualization() ? n.node->getVisualization()->clone() : nullptr,
+                                                                    n.node->getCollisionModel() ? n.node->getCollisionModel()->clone() : nullptr,
+                                                                    0.f, 0.f, 0.f,
+                                                                    n.node->getLocalTransformation(),
+                                                                    Eigen::Vector3f::Zero(), Eigen::Vector3f::Zero(),
+                                                                    n.node->getPhysics());
+                n.node_cloned->primitiveApproximation = n.node->getPrimitiveApproximation().clone();
+                if (n.parentNode_cloned)
+                {
+                    n.node_cloned->initialize(n.parentNode_cloned);
+                }
+                n.node_cloned->basePath = n.node->basePath;
+            }
+            else
             {
-                rns->clone(result);
+                n.node_cloned = n.node->clone(reducedModel, false, n.parentNode_cloned);
+            }
+            // Probably will not be valid anymore after reducing robot as models will be missing
+            n.node_cloned->visualizationModelXML = std::string();
+            n.node_cloned->collisionModelXML = std::string();
+
+            collect(n.node, n);
+
+            if (!n.parentNode_cloned)
+            {
+                reducedModel->setRootNode(n.node_cloned);
+            }
+            else
+            {
+                Eigen::Matrix4f localTransformation = simox::math::inverted_pose(n.parentNode_cloned->getGlobalPose()) * n.node->getGlobalPose();
+                n.node_cloned->setLocalTransformation(localTransformation);
+                n.node_cloned->updateTransformationMatrices();
+            }
+
+            const VisualizationFactoryPtr vf = VisualizationFactory::first(NULL);
+            std::vector<VisualizationNodePtr> visus;
+            std::vector<VisualizationNodePtr> colVisus;
+            for (const auto& childNode : n.childNodes)
+            {
+                if (childNode->getVisualization())
+                {
+                    visus.push_back(childNode->getVisualization());
+                }
+                if (childNode->getCollisionModel() && childNode->getCollisionModel()->getVisualization())
+                {
+                    colVisus.push_back(childNode->getCollisionModel()->getVisualization());
+                }
+                n.node_cloned->physics.massKg += childNode->getMass(); // TODO fix physics somehow
+            }
+            const Eigen::Matrix4f globalPoseInv = simox::math::inverted_pose(n.node_cloned->getGlobalPose());
+            if (!visus.empty())
+            {
+                if (const auto visu = n.node->getVisualization())
+                {
+                    visus.insert(visus.begin(), visu->clone());
+                }
+                auto v = vf->createUnitedVisualization(visus);
+                if (n.parentNode_cloned)
+                {
+                    vf->applyDisplacement(v, globalPoseInv);
+                }
+                n.node_cloned->setVisualization(v);
+            }
+            if (!colVisus.empty())
+            {
+                if (const auto colModel = n.node->getCollisionModel())
+                {
+                    if (const auto vis = colModel->getVisualization())
+                    {
+                        colVisus.insert(colVisus.begin(), vis->clone());
+                    }
+                }
+                auto colVisu = vf->createUnitedVisualization(colVisus);
+                if (n.parentNode_cloned)
+                {
+                    vf->applyDisplacement(colVisu, globalPoseInv);
+                }
+                n.node_cloned->setCollisionModel(std::make_shared<CollisionModel>(colVisu, n.node->getName()));
+            }
+
+            for (const auto& childNode : n.childNodes)
+            {
+                const auto& primitiveApproximation = childNode->getPrimitiveApproximation();
+                n.node_cloned->getPrimitiveApproximation().join(primitiveApproximation.clone().localTransformation(globalPoseInv * childNode->getGlobalPose()));
+
+                // attach sensors
+                for (const auto& sensor : childNode->getSensors())
+                {
+                    SensorPtr s = sensor->clone(n.node_cloned);
+                    s->setRobotNodeToSensorTransformation(globalPoseInv * sensor->getGlobalPose());
+                }
             }
         }
 
-        result->setGlobalPose(robot->getGlobalPose());
-        if(robot->getHumanMapping().has_value())
+        reducedModel->setGlobalPose(robot.getGlobalPose());
+        reducedModel->setJointValues(joint_values);
+
+        cloneRNS(robot, reducedModel);
+
+        if(robot.getHumanMapping().has_value())
         {
-            result->registerHumanMapping(robot->getHumanMapping().value());
+            reducedModel->registerHumanMapping(robot.getHumanMapping().value());
         }
-        return result;
+        return reducedModel;
     }
 
     void RobotFactory::cloneRecursiveUnite(RobotPtr robot, RobotNodePtr currentNode, RobotNodePtr currentNodeClone, std::vector<std::string> uniteWithAllChildren)
diff --git a/VirtualRobot/RobotFactory.h b/VirtualRobot/RobotFactory.h
index c97ed648f..0b5303446 100644
--- a/VirtualRobot/RobotFactory.h
+++ b/VirtualRobot/RobotFactory.h
@@ -79,22 +79,45 @@ namespace VirtualRobot
         */
         static RobotPtr clone(RobotPtr robot, const std::string& name, CollisionCheckerPtr collisionChecker = CollisionCheckerPtr(), float scaling = 1.0f);
 
+        /*!
+         * \brief Clones all nodesets from one robot to another that fullfill the condition that all nodes are contained in the other robot
+         * \param from The nodesets copied from
+         * \param to The nodesets copied to
+         */
+        static void cloneRNS(const Robot& from, RobotPtr to);
+
         /*!
         Clones the robot, but only leave the defined joints active. ALl other joints are accumulated and set to one model which is fixed (may result in faster updates)
+        The human mapping is cloned but it is not guranteed that all joints are still contained in the robot.
         \param robot The robot to clone
         \param rns The robot node set of active joints. The joints must be given as an ordered set, i.e. node i must be located before node i+1 in the kinematic structure of the robot.
         \param name The new name
+        \param addTCP Wheter the tcp of the robot node set should also be added
         */
-        static RobotPtr cloneSubSet(RobotPtr robot, RobotNodeSetPtr rns, const std::string& name);
+        static RobotPtr cloneSubSet(RobotPtr robot, RobotNodeSetPtr rns, const std::string& name, bool addTCP = false);
 
         /*!
             Creates a robot clone with reduced structure.
+            The human mapping is cloned but it is not guranteed that all joints are still contained in the robot.
             \param robot The robot to clone.
             \param uniteWithAllChildren List of RobotNodeNames. Each listed robot ndoe is united with all of its children to one fixed RobotNode.
                                         This means that all related coordinate systems and joints will not be present in the clone. The visualizations are united.
         */
         static RobotPtr cloneUniteSubsets(RobotPtr robot, const std::string& name, std::vector<std::string> uniteWithAllChildren);
 
+        /*!
+         * Creates a cloned robot model that only include the given nodes by joining nodes together.
+         * The human mapping is cloned but it is not guranteed that all joints are still contained in the robot.
+         * Physics parameters such as segment inertia or information about whether to ignore collision between nodes are not (yet) updated correctly.
+         * \param robot The original robot
+         * \param actuatedJointNames The actuated joint nodes
+         * \param otherNodeNames Other robot nodes that should be contained with a fixed transformation (given current pose if actuated joint as these are converted to RobotNodeFixed)
+         * \return The reduced robot model or nullptr (if actuatedJointNames contains not only joint nodes that are in robot)
+         */
+        static VirtualRobot::RobotPtr
+        createReducedModel(Robot &robot, const std::vector<std::string>& actuatedJointNames,
+                           const std::vector<std::string>& otherNodeNames = std::vector<std::string>());
+
         /*!
             Creates a clone with changed structure, so that the given robot node is the new root of the resulting kinematic tree.
         */
@@ -124,7 +147,6 @@ namespace VirtualRobot
 
         static bool detach(RobotPtr robot, RobotNodePtr rn);
 
-
     protected:
 
         // some internal stuff
diff --git a/VirtualRobot/SceneObject.cpp b/VirtualRobot/SceneObject.cpp
index 4a5abee89..607d8a532 100644
--- a/VirtualRobot/SceneObject.cpp
+++ b/VirtualRobot/SceneObject.cpp
@@ -1618,4 +1618,44 @@ namespace VirtualRobot
         return cloned;
     }
 
+    SceneObject::PrimitiveApproximation &SceneObject::PrimitiveApproximation::localTransformation(const Eigen::Matrix4f &localTransformation)
+    {
+        for (auto& primitive : this->defaultPrimitives)
+        {
+            primitive->transform = localTransformation * primitive->transform;
+        }
+
+        for (auto& [id, primitives] : this->primitives)
+        {
+            for (auto& primitive : primitives)
+            {
+                primitive->transform = localTransformation * primitive->transform;
+            }
+        }
+        return *this;
+    }
+
+    void SceneObject::PrimitiveApproximation::join(const PrimitiveApproximation &primitiveApproximation, const Eigen::Matrix4f &localTransformation)
+    {
+        auto cloned = primitiveApproximation.clone().localTransformation(localTransformation);
+        this->defaultPrimitives.insert(this->defaultPrimitives.end(), cloned.defaultPrimitives.begin(), cloned.defaultPrimitives.end());
+
+        for (auto& [id, primitives] : cloned.primitives)
+        {
+            if (this->primitives.count(id) > 0)
+            {
+                this->primitives.at(id).insert(this->primitives.at(id).end(), primitives.begin(), primitives.end());
+            }
+            else
+            {
+                this->primitives[id] = primitives;
+            }
+        }
+    }
+
+    bool SceneObject::PrimitiveApproximation::empty() const
+    {
+        return defaultPrimitives.empty() && primitives.empty();
+    }
+
 } // namespace
diff --git a/VirtualRobot/SceneObject.h b/VirtualRobot/SceneObject.h
index 1832ffe6f..aefd37fc1 100644
--- a/VirtualRobot/SceneObject.h
+++ b/VirtualRobot/SceneObject.h
@@ -99,6 +99,12 @@ namespace VirtualRobot
 
             PrimitiveApproximation clone() const;
 
+            PrimitiveApproximation& localTransformation(const Eigen::Matrix4f &localTransformation);
+
+            void join(const PrimitiveApproximation& primitiveApproximation, const Eigen::Matrix4f& localTransformation = Eigen::Matrix4f::Identity());
+
+            bool empty() const;
+
         private:
             std::vector<Primitive::PrimitivePtr> defaultPrimitives;
             std::map<std::string, std::vector<Primitive::PrimitivePtr>> primitives;
diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp
index 466541151..bdd691762 100644
--- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp
+++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp
@@ -146,14 +146,11 @@ namespace VirtualRobot
         SoSeparator* coinVisualization = new SoSeparator();
         coinVisualization->ref();
 
-        Eigen::Matrix4f currentTransform = Eigen::Matrix4f::Identity();
-
         for (auto p : primitives)
         {
-            currentTransform *= p->transform;
             SoSeparator* soSep = new SoSeparator();
             SoNode* pNode = GetNodeFromPrimitive(p, boundingBox, color);
-            soSep->addChild(getMatrixTransformScaleMM2M(currentTransform));
+            soSep->addChild(getMatrixTransformScaleMM2M(p->transform));
             soSep->addChild(pNode);
             coinVisualization->addChild(soSep);
         }
@@ -4376,7 +4373,7 @@ namespace VirtualRobot
         return root;
     }
 
-    void CoinVisualizationFactory::applyDisplacement(VisualizationNodePtr o, Eigen::Matrix4f& m)
+    void CoinVisualizationFactory::applyDisplacement(VisualizationNodePtr o, const Eigen::Matrix4f& m)
     {
         if (!o)
         {
diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h
index 0afb2907d..3d99261e9 100644
--- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h
+++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h
@@ -110,7 +110,7 @@ namespace VirtualRobot
         /*!
             Move local visualization by homogeneous matrix m. MM is used.
         */
-        void applyDisplacement(VisualizationNodePtr o, Eigen::Matrix4f& m) override;
+        void applyDisplacement(VisualizationNodePtr o, const Eigen::Matrix4f& m) override;
 
         /*!
             Create an empty VisualizationNode.
diff --git a/VirtualRobot/Visualization/VisualizationFactory.h b/VirtualRobot/Visualization/VisualizationFactory.h
index ef9da305c..cd39d9cb9 100644
--- a/VirtualRobot/Visualization/VisualizationFactory.h
+++ b/VirtualRobot/Visualization/VisualizationFactory.h
@@ -206,7 +206,7 @@ namespace VirtualRobot
         /*!
             Move local visualization by homogeneous matrix m. (MM)
         */
-        virtual void applyDisplacement(VisualizationNodePtr /*o*/, Eigen::Matrix4f& /*m*/) {}
+        virtual void applyDisplacement(VisualizationNodePtr /*o*/, const Eigen::Matrix4f& /*m*/) {}
 
         /*!
             Create an empty VisualizationNode.
diff --git a/VirtualRobot/XML/RobotIO.cpp b/VirtualRobot/XML/RobotIO.cpp
index 01b3ec6bb..6b5808efc 100644
--- a/VirtualRobot/XML/RobotIO.cpp
+++ b/VirtualRobot/XML/RobotIO.cpp
@@ -641,8 +641,8 @@ namespace VirtualRobot
         // collision information
         bool colProcessed = false;
 
-        VisualizationNodePtr visualizationNode;
-        CollisionModelPtr collisionModel;
+        VisualizationNodePtr visualizationNode = nullptr;
+        CollisionModelPtr collisionModel = nullptr;
         RobotNodePtr robotNode;
         std::string visualizationModelXML;
         std::string collisionModelXML;
@@ -650,7 +650,6 @@ namespace VirtualRobot
         bool physicsDefined = false;
         Eigen::Matrix4f transformMatrix = Eigen::Matrix4f::Identity();
         SceneObject::PrimitiveApproximation primitiveApproximation;
-        //primitiveApproximation.addModel({ std::make_shared<Primitive::Cylinder>(10, 10) }, "test");
 
         rapidxml::xml_node<>* node = robotNodeXMLNode->first_node();
         rapidxml::xml_node<>* jointNodeXML = nullptr;
diff --git a/VirtualRobot/examples/RobotViewer/RobotViewer.ui b/VirtualRobot/examples/RobotViewer/RobotViewer.ui
index 4686e5df3..bae7f3692 100644
--- a/VirtualRobot/examples/RobotViewer/RobotViewer.ui
+++ b/VirtualRobot/examples/RobotViewer/RobotViewer.ui
@@ -301,9 +301,6 @@
               <layout class="QGridLayout" name="gridLayout_5">
                <item row="2" column="1">
                 <widget class="QComboBox" name="comboBoxPrimitiveModel">
-                 <property name="placeholderText">
-                  <string/>
-                 </property>
                 </widget>
                </item>
                <item row="5" column="0">
diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
index fceff5df8..2326f0b53 100644
--- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
+++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
@@ -6,6 +6,7 @@
 #include <VirtualRobot/RuntimeEnvironment.h>
 #include <VirtualRobot/Import/RobotImporterFactory.h>
 #include <VirtualRobot/CollisionDetection/CDManager.h>
+#include <VirtualRobot/RobotFactory.h>
 
 #include <SimoxUtility/algorithm/string/string_tools.h>
 
@@ -106,7 +107,6 @@ void showRobotWindow::setupUI()
     // setup
     viewer->setBackgroundColor(SbColor(1.0f, 1.0f, 1.0f));
 
-
     viewer->setGLRenderAction(new SoLineHighlightRenderAction);
     viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND);
     viewer->setFeedbackVisibility(true);
@@ -257,10 +257,7 @@ void showRobotWindow::rebuildVisualization()
 
     robotSep->removeAllChildren();
 
-    bool useIVModel = UI.checkBoxFullModel->checkState() == Qt::Checked;
-    useColModel = UI.checkBoxColModel->checkState() == Qt::Checked;
-
-    if (useColModel)
+    if (UI.checkBoxColModel->checkState() == Qt::Checked)
     {
         visualization = robot->getVisualization<CoinVisualization>(SceneObject::Collision);
         SoNode* visualisationNode = nullptr;
@@ -276,7 +273,10 @@ void showRobotWindow::rebuildVisualization()
         }
     }
 
-    if (useIVModel)
+    if (UI.checkBoxFullModel->checkState() == Qt::Checked
+        || UI.checkBoxStructure->checkState() == Qt::Checked
+        || UI.checkBoxRobotSensors->checkState() == Qt::Checked
+        || UI.checkBoxRobotCoordSystems->checkState() == Qt::Checked)
     {
         visualization = robot->getVisualization<CoinVisualization>(SceneObject::Full);
         SoNode* visualisationNode = nullptr;
@@ -788,8 +788,6 @@ void showRobotWindow::loadRobot()
         }
 
         robot = importer->loadFromFile(m_sRobotFilename, RobotIO::eFull);
-
-
     }
     catch (VirtualRobotException& e)
     {
-- 
GitLab