1 #ifndef JSK_PCL_ROS_SELF_MASK_URDF_ROBOT_ 
    2 #define JSK_PCL_ROS_SELF_MASK_URDF_ROBOT_ 
    5 #include <kdl/tree.hpp> 
    6 #include <kdl/chainjnttojacsolver.hpp> 
    7 #include <kdl/chainfksolverpos_recursive.hpp> 
   12 #include <sensor_msgs/JointState.h> 
   13 #include <geometry_msgs/PoseStamped.h> 
   22                     const std::vector<LinkInfo> &links,
 
   24                     std::string root_link_id = 
"BODY",
 
   25                     std::string world_frame_id = 
"map",
 
   26                     bool set_foot_pose = 
false)
 
   42         ROS_FATAL(
"Failed to load robot_description");
 
   46       for(
unsigned int i = 0 ; 
i < 
bodies_.size() ; 
i++) {
 
   62       KDL::JntArray jnt_pos(chain.getNrOfJoints());
 
   63       for (
int i = 0, j = 0; 
i < chain.getNrOfSegments(); 
i++) {
 
   64         std::string joint_name = chain.getSegment(
i).getJoint().getName();
 
   65         if (joint_angles.find(joint_name) != joint_angles.end()) {
 
   66           jnt_pos(j++) = joint_angles[joint_name];
 
   69       KDL::ChainFkSolverPos_recursive fk_solver(chain);
 
   71       if (fk_solver.JntToCart(jnt_pos, 
pose) < 0) {
 
   85       for(std::map<std::string, double>::iterator it = joint_angles.begin(); it != joint_angles.end(); ++it) {
 
   89       for(
unsigned int i = 0 ; 
i < 
bodies_.size() ; 
i++) {
 
   97         std::vector<tf::StampedTransform> link_transforms;
 
   98         for(
unsigned int i = 0 ; 
i < 
bodies_.size() ; 
i++) {
 
  113       std::map<std::string, double> joint_angles;
 
  114       for (
size_t i = 0; 
i < joint.name.size(); 
i++) {
 
  115         joint_angles[joint.name[
i]] = joint.position[
i];