diff --git a/VirtualRobot/Dynamics/dynamics.cpp b/VirtualRobot/Dynamics/dynamics.cpp index 32f953f39748d81a92ed842534b24910b121cfb2..c9247e72991a4c2dacf7ee94e9b43463e4a2d553 100644 --- a/VirtualRobot/Dynamics/dynamics.cpp +++ b/VirtualRobot/Dynamics/dynamics.cpp @@ -18,6 +18,9 @@ #include <string> #include <iostream> +#include <rbdl/rbdl_utils.h> + + using std::cout; using std::cin; using namespace VirtualRobot; @@ -106,6 +109,19 @@ int Dynamics::getnDoF() return model->dof_count; } +void Dynamics::print() +{ + std::string result = RigidBodyDynamics::Utils::GetModelHierarchy (*model.get()); + cout << "RBDL hierarchy of RNS:" << rns->getName() << endl; + cout << result; + result = RigidBodyDynamics::Utils::GetNamedBodyOriginsOverview (*model.get()); + cout << "RBDL origins of RNS:" << rns->getName() << endl; + cout << result; + result = RigidBodyDynamics::Utils::GetModelDOFOverview (*model.get()); + cout << "RBDL DoF of RNS:" << rns->getName() << endl; + cout << result; +} + void Dynamics::toRBDL(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNodePtr node, RobotNodePtr parentNode, int parentID) { @@ -187,9 +203,17 @@ void Dynamics::toRBDL(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNo if (joint.mJointType != JointTypeFixed) { - nodeID = model->AddBody(parentID, spatial_transform, joint, body); + nodeID = model->AddBody(parentID, spatial_transform, joint, body, node->getName()); this->identifierMap[node->getName()] = nodeID; - cout << node->getName() << ", " << nodeID << endl; // Debugging Info + + cout << node->getName() << ", " << nodeID << " <<:" <<endl; // Debugging Info + cout << "** SPATIAL TRAFO: " << endl << spatial_transform.toMatrix() << endl; + cout << "** MASS: " << body.mMass << endl; + cout << "** COM: " << body.mCenterOfMass.transpose() << endl; + cout << "** INERTIA: " << endl << body.mInertia << endl; + cout << "** mIsVirtual: " << body.mIsVirtual << endl; + if (joint.mJointAxes) + cout << "** JOINT AXES " << endl << *(joint.mJointAxes) << endl; } std::vector<SceneObjectPtr> children; diff --git a/VirtualRobot/Dynamics/dynamics.h b/VirtualRobot/Dynamics/dynamics.h index efd7e1cb2bd946c895a0aa6d11d25618e5398cb3..23f03b770ab5afb392722d450166e47b33d32e0c 100644 --- a/VirtualRobot/Dynamics/dynamics.h +++ b/VirtualRobot/Dynamics/dynamics.h @@ -38,6 +38,8 @@ namespace VirtualRobot int getIdentifier(std::string name){return identifierMap.at(name);} + void print(); + protected: RobotNodeSetPtr rns; boost::shared_ptr<RigidBodyDynamics::Model> model; diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp index 3a4920672ff71a332ca864daf8c6685fe8e4de9b..13b29d4dc8ec19541e4a8c560bedce93856ee209 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationNode.cpp @@ -322,7 +322,7 @@ namespace VirtualRobot if (deepCopy) { - newModel->addChild(visualization->copy(FALSE)); + newModel->addChild(visualization->copy(TRUE)); } else {