Revert debug statements in kdl_parser.cpp

This commit is contained in:
Jackie Kay 2015-12-09 16:21:38 -08:00
parent b95dbf2295
commit 9869a67924
1 changed files with 2 additions and 6 deletions

View File

@ -168,19 +168,15 @@ bool treeFromXml(TiXmlDocument *xml_doc, Tree& tree)
bool treeFromUrdfModel(const urdf::ModelInterface& robot_model, Tree& tree) bool treeFromUrdfModel(const urdf::ModelInterface& robot_model, Tree& tree)
{ {
tree = Tree(robot_model.getRoot()->name); tree = Tree(robot_model.getRoot()->name);
ROS_INFO("constructed tree");
// warn if root link has inertia. KDL does not support this // warn if root link has inertia. KDL does not support this
if (robot_model.getRoot()->inertial) if (robot_model.getRoot()->inertial)
ROS_WARN("The root link %s has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF.", robot_model.getRoot()->name.c_str()); ROS_WARN("The root link %s has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF.", robot_model.getRoot()->name.c_str());
// add all children // add all children
for (size_t i=0; i<robot_model.getRoot()->child_links.size(); i++) { for (size_t i=0; i<robot_model.getRoot()->child_links.size(); i++)
ROS_INFO("Adding link to KDL tree"); if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree))
if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree)) {
return false; return false;
}
}
return true; return true;
} }