// recursive function to walk through tree bool addChildrenToTree(urdf::LinkPtr root, Tree& tree) { urdf::LinkVector children = root->child_links; //std::cerr << "[INFO] Link " << root->name << " had " << children.size() << " children" << std::endl; // constructs the optional inertia RigidBodyInertia inert(0); if (root->inertial) inert = toKdl(root->inertial); // constructs the kdl joint Joint jnt = toKdl(root->parent_joint); // construct the kdl segment Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform), inert); // add segment to tree tree.addSegment(sgm, root->parent_joint->parent_link_name); // recurslively add all children for (size_t i=0; i<children.size(); i++){ if (!addChildrenToTree(children[i], tree)) return false; } return true; }
// recursive function to walk through tree bool addChildrenToTree(boost::shared_ptr<const urdf::Link> root, Tree& tree) { std::vector<boost::shared_ptr<urdf::Link> > children = root->child_links; std::cout<<"Link "<<root->name.c_str()<<" had "<<(int)children.size()<<" children."<<std::endl; // ROS_DEBUG("Link %s had %i children", root->name.c_str(), (int)children.size()); // constructs the optional inertia RigidBodyInertia inert(0); if (root->inertial) inert = toKdl(root->inertial); // constructs the kdl joint Joint jnt = toKdl(root->parent_joint); // construct the kdl segment Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform), inert); // add segment to tree tree.addSegment(sgm, root->parent_joint->parent_link_name); // recurslively add all children for (size_t i=0; i<children.size(); i++){ if (!addChildrenToTree(children[i], tree)) return false; } return true; }
bool treeFromUrdfModel(const urdf::ModelInterface& robot_model, Tree& tree) { tree = Tree(robot_model.getRoot()->name); // warn if root link has inertia. KDL does not support this if (robot_model.getRoot()->inertial) std::cout<<"The root link "<<robot_model.getRoot()->name.c_str()<<" 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."<<std::endl; // 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 for (size_t i=0; i<robot_model.getRoot()->child_links.size(); i++) if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree)) return false; return true; }
bool treeFromUrdfModel(const urdf::ModelInterface& robot_model, Tree& tree, const bool consider_root_link_inertia) { if (consider_root_link_inertia) { //For giving a name to the root of KDL using the robot name, //as it is not used elsewhere in the KDL tree std::string fake_root_name = "__kdl_import__" + robot_model.getName()+"__fake_root__"; std::string fake_root_fixed_joint_name = "__kdl_import__" + robot_model.getName()+"__fake_root_fixed_joint__"; tree = Tree(fake_root_name); const urdf::ConstLinkPtr root = robot_model.getRoot(); // constructs the optional inertia RigidBodyInertia inert(0); if (root->inertial) inert = toKdl(root->inertial); // constructs the kdl joint Joint jnt = Joint(fake_root_fixed_joint_name, Joint::None); // construct the kdl segment Segment sgm(root->name, jnt, Frame::Identity(), inert); // add segment to tree tree.addSegment(sgm, fake_root_name); } else { tree = Tree(robot_model.getRoot()->name); // warn if root link has inertia. KDL does not support this if (robot_model.getRoot()->inertial) std::cerr << "The root link " << robot_model.getRoot()->name << " 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." << std::endl; } // add all children for (size_t i=0; i<robot_model.getRoot()->child_links.size(); i++) if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree)) return false; return true; }