Exemplo n.º 1
0
void getKDLChainInfo(kinematics_msgs::KinematicSolverInfo &chain_info)
{
	unsigned int nj = chain.getNrOfJoints();
	unsigned int nl = chain.getNrOfSegments();
	
	ROS_DEBUG("nj: %d", nj);
	ROS_DEBUG("nl: %d", nl);

	//---setting up response

	//joint_names
	for(unsigned int i=0; i<nj; i++)
	{
		ROS_DEBUG("joint_name[%d]: %s", i, chain.getSegment(i).getJoint().getName().c_str());
		chain_info.joint_names.push_back(chain.getSegment(i).getJoint().getName());
	}
	//limits
		//joint limits are only saved in KDL::ChainIkSolverPos_NR_JL iksolverpos -> ik_solve().....but this is not visible here!
/*for(unsigned int i=0; i<nj; i++)
  {
		chain_info.limits[i].joint_name=chain.getSegment(i).getJoint().getName();
		chain_info.limits[i].has_position_limits=
		chain_info.limits[i].min_position=
		chain_info.limits[i].max_position=	
		chain_info.limits[i].has_velocity_limits=
		chain_info.limits[i].max_velocity=
		chain_info.limits[i].has_acceleration_limits=
		chain_info.limits[i].max_acceleration=
	}*/
	//link_names	
	for(unsigned int i=0; i<nl; i++)
	{
		chain_info.link_names.push_back(chain.getSegment(i).getName());
	}
}
Exemplo n.º 2
0
    // Get Joint Limits from an URDF model
    void getJointLimitsFromModel(const urdf::Model& model,
                                 std::vector<double> &q_min,
                                 std::vector<double> &q_max,                                 
                                 KDL::Chain &kdlArmChain
                                ) 
    {
        boost::shared_ptr<const urdf::Joint> joint;

        for(unsigned int i=0; i< kdlArmChain.getNrOfJoints(); ++i)
        {
            if (kdlArmChain.getSegment(i).getJoint().getType() != KDL::Joint::None)
            {
                joint = model.getJoint(kdlArmChain.getSegment(i).getJoint().getName());
                if ( joint->type != urdf::Joint::CONTINUOUS )
                {
                    q_min.at(i) = joint->limits->lower;
                    q_max.at(i) = joint->limits->upper;
                }
                else
                {
                    q_min.at(i) = -3.14/2.0;
                    q_max.at(i) = 3.14/2.0;
                }
            }
        }
    }
Exemplo n.º 3
0
void leatherman::printKDLChain(const KDL::Chain &c, std::string text)
{
  ROS_INFO("[%s] # segments: %d  # joints: %d", text.c_str(), c.getNrOfSegments(), c.getNrOfJoints());
  double r,p,y,jnt_pos = 0;
  for(size_t j = 0; j < c.getNrOfSegments(); ++j)
  {
    c.getSegment(j).pose(jnt_pos).M.GetRPY(r,p,y);
    ROS_INFO("[%s] [%2d] segment: %21s  xyz: %0.3f %0.3f %0.3f  rpy: %0.3f %0.3f %0.3f", 
        text.c_str(), int(j),
        c.getSegment(j).getName().c_str(),
        c.getSegment(j).pose(jnt_pos).p.x(),
        c.getSegment(j).pose(jnt_pos).p.y(),
        c.getSegment(j).pose(jnt_pos).p.z(),
        r,p,y);

    c.getSegment(j).getJoint().pose(jnt_pos).M.GetRPY(r,p,y);
    ROS_INFO("[%s]        joint: %21s  xyz: %0.3f %0.3f %0.3f  rpy: %0.3f %0.3f %0.3f  type: %s", 
        text.c_str(),
        c.getSegment(j).getJoint().getName().c_str(),
        c.getSegment(j).getJoint().pose(jnt_pos).p.x(),
        c.getSegment(j).getJoint().pose(jnt_pos).p.y(),
        c.getSegment(j).getJoint().pose(jnt_pos).p.z(),
        r,p,y,
        c.getSegment(j).getJoint().getTypeName().c_str());

  }
}
Exemplo n.º 4
0
IkSolver::IkSolver(const KDL::Chain& chain)
{
  const std::string root_name = chain.getSegment(0).getName();
  const std::string tip_name  = chain.getSegment(chain.getNrOfSegments() - 1).getName();

  KDL::Tree tree("root");
  tree.addChain(chain, "root");

  std::vector<std::string> endpoint_names(1, tip_name);
  std::vector<EndpointCoupling> endpoint_couplings(1, Pose);

  init(tree, endpoint_names, endpoint_couplings);
}
 void getKDLChainInfo(const KDL::Chain &chain,
                      kinematics_msgs::KinematicSolverInfo &chain_info)
 {
   int i=0; // segment number
   while(i < (int)chain.getNrOfSegments())
   {
     chain_info.link_names.push_back(chain.getSegment(i).getName());
     i++;
   }
 }
Exemplo n.º 6
0
int Kinematics::getKDLSegmentIndex(const std::string &name) {
    int i=0; 
    while (i < (int)chain.getNrOfSegments()) {
        if (chain.getSegment(i).getName() == name) {
            return i+1;
        }
        i++;
    }
    return -1;
}
int ExcavaROBArmKinematics::getKDLSegmentIndex(const std::string &name) {
    int i=0; 
    while (i < (int) arm_chain_.getNrOfSegments()) {
        if (arm_chain_.getSegment(i).getName() == name) {
            return i + 1;
        }
        i++;
    }
    return -1;
}
Exemplo n.º 8
0
FkLookup::ChainFK::ChainFK(const KDL::Tree& tree, const std::string& root, const std::string& tip):root_name(root),tip_name(tip){
    KDL::Chain chain;
    tree.getChain(root_name, tip_name, chain);
    solver =  new KDL::ChainFkSolverPos_recursive(chain);
    unsigned int  num = chain.getNrOfSegments();
    for(unsigned int i = 0; i < num; ++i){
	const KDL::Joint &joint = chain.getSegment(i).getJoint();
	if (joint.getType() != KDL::Joint::None) joints.insert(std::make_pair(joint.getName(),joints.size()));
    }
    ROS_ASSERT(joints.size() == chain.getNrOfJoints());
}
Exemplo n.º 9
0
sensor_msgs::JointState init_message(const KDL::Chain &chain) {
	sensor_msgs::JointState msg;
	for (unsigned int i=0; i < chain.getNrOfSegments(); ++i) {
		KDL::Segment segment = chain.getSegment(i);
		KDL::Joint joint = segment.getJoint();
		if (joint.getType() == KDL::Joint::JointType::None) continue;
		msg.name.push_back(joint.getName());
		msg.position.push_back(0);
	}
	return msg;
}
Exemplo n.º 10
0
void printKDLchain(std::string s,const KDL::Chain & kdlChain)
{
    std::cout << s << std::endl;
    for(int p=0; p < (int)kdlChain.getNrOfSegments(); p++)
    {
        std::cout << "Segment " << p << ":" << std::endl;
        KDL::Segment seg = kdlChain.getSegment(p);
        KDL::Frame fra = seg.getFrameToTip();
        std::cout << seg << std::endl;
        std::cout << fra << std::endl;
    }
}
Exemplo n.º 11
0
bool leatherman::getSegmentIndex(const KDL::Chain &c, std::string name, int &index)
{
  for(size_t j = 0; j < c.getNrOfSegments(); ++j)
  {
    if(c.getSegment(j).getName().compare(name) == 0)
    {
      index = j;
      return true;
    }
  }
  return false;
}
    VirtualForcePublisher()
    {
        ros::NodeHandle n_tilde("~");
        ros::NodeHandle n;

        // subscribe to joint state
        joint_state_sub_ = n.subscribe("joint_states", 1, &VirtualForcePublisher::callbackJointState, this);
        wrench_stamped_pub_ = n.advertise<geometry_msgs::WrenchStamped>("wrench", 1);

        // set publish frequency
        double publish_freq;
        n_tilde.param("publish_frequency", publish_freq, 50.0);
        publish_interval_ = ros::Duration(1.0/std::max(publish_freq,1.0));

        //set time constant of low pass filter
        n_tilde.param("time_constant", t_const_, 0.3);
        // set root and tip
        n_tilde.param("root", root, std::string("torso_lift_link"));
        n_tilde.param("tip", tip, std::string("l_gripper_tool_frame"));

        // load robot model
        urdf::Model robot_model;
        robot_model.initParam("robot_description");

        KDL::Tree kdl_tree;
        kdl_parser::treeFromUrdfModel(robot_model, kdl_tree);
        kdl_tree.getChain(root, tip, chain_);
        jnt_to_jac_solver_.reset(new KDL::ChainJntToJacSolver(chain_));

        jnt_pos_.resize(chain_.getNrOfJoints());
        jacobian_.resize(chain_.getNrOfJoints());

        for (size_t i=0; i<chain_.getNrOfSegments(); i++) {
            if (chain_.getSegment(i).getJoint().getType() != KDL::Joint::None) {
                std::cerr << "kdl_chain(" << i << ") " << chain_.getSegment(i).getJoint().getName().c_str() << std::endl;
            }
        }
    }
 int getKDLSegmentIndex(const KDL::Chain &chain, 
                        const std::string &name)
 {
   int i=0; // segment number
   while(i < (int)chain.getNrOfSegments())
   {
     if(chain.getSegment(i).getName() == name)
     {
       return i+1;
     }
     i++;
   }
   return -1;   
 }
Exemplo n.º 14
0
bool addBaseTransformation(const KDL::Chain & old_chain, KDL::Chain & new_chain, KDL::Frame H_new_old)
{
    new_chain = KDL::Chain();
    for(unsigned int i=0; i<old_chain.getNrOfSegments(); i++) {
        KDL::Segment segm;
        segm = old_chain.getSegment(i);
        //if is not the first segment add normally the segment
        if( i != 0 ) {
            new_chain.addSegment(segm);
        } else {
            //otherwise modify the segment before adding it
            KDL::Segment new_segm;
            KDL::Joint new_joint, old_joint;
            old_joint = segm.getJoint();
            KDL::Joint::JointType new_type;
            switch(old_joint.getType()) {
            case KDL::Joint::RotAxis:
            case KDL::Joint::RotX:
            case KDL::Joint::RotY:
            case KDL::Joint::RotZ:
                new_type = KDL::Joint::RotAxis;
                break;
            case KDL::Joint::TransAxis:
            case KDL::Joint::TransX:
            case KDL::Joint::TransY:
            case KDL::Joint::TransZ:
                new_type = KDL::Joint::TransAxis;
                break;
            case KDL::Joint::None:
            default:
                new_type = KDL::Joint::None;
            }

            //check !

            new_joint = KDL::Joint(old_joint.getName(),H_new_old*old_joint.JointOrigin(),H_new_old.M*old_joint.JointAxis(),new_type);
            new_segm = KDL::Segment(segm.getName(),new_joint,H_new_old*segm.getFrameToTip(),segm.getInertia());
            new_chain.addSegment(new_segm);
        }
    }
    return true;
}
Exemplo n.º 15
0
bool OrientationConstraint::initialize(const arm_navigation_msgs::OrientationConstraint& constraint,
                const KDL::Chain& chain)
{
  constraint_ = constraint;
  link_id_ = -1;
  for (unsigned int i=0; i<chain.getNrOfSegments(); ++i)
  {
    if (constraint_.link_name == chain.getSegment(i).getName())
    {
      link_id_ = i;
      break;
    }
  }
  if (link_id_ == -1)
  {
    ROS_ERROR("OrientationConstraint: couldn't find link %s in chain.", constraint_.link_name.c_str());
    return false;
  }
  return true;
}
Exemplo n.º 16
0
bool PositionConstraint::initialize(const arm_navigation_msgs::PositionConstraint& constraint,
                const KDL::Chain& chain)
{
  constraint_ = constraint;
  link_id_ = -1;
  for (unsigned int i=0; i<chain.getNrOfSegments(); ++i)
  {
    if (constraint_.link_name == chain.getSegment(i).getName())
    {
      link_id_ = i;
      break;
    }
  }
  if (link_id_ == -1)
  {
    ROS_ERROR("CIK PositionConstraint: couldn't find link %s in chain.", constraint_.link_name.c_str());
    return false;
  }

  rosPointToKdlVector(constraint_.target_point_offset, offset_);
  rosPointToKdlVector(constraint_.position, desired_location_);

  if (constraint_.constraint_region_shape.type != arm_navigation_msgs::Shape::BOX ||
      constraint_.constraint_region_shape.dimensions.size() != 3)
  {
    ROS_ERROR("CIK PositionConstraint: we only handle 3-d BOX constraints currently.");
    return false;
  }

  KDL::Rotation constraint_rotation;
  rosQuaternionToKdlRotation(constraint_.constraint_region_orientation, constraint_rotation);
  constraint_rotation_inverse_ = constraint_rotation.Inverse();
  kdlRotationToEigenMatrix3d(constraint_rotation_inverse_, constraint_rotation_inverse_eigen_);

  return true;
}
Exemplo n.º 17
0
bool idynSensorChain2kdlChain(iCub::iDyn::iDynChain & idynChain,
                              iCub::iDyn::iDynInvSensor & idynSensor,
                              KDL::Chain & kdlChain,
                              KDL::Frame & H_sensor_dh_child,
                              std::vector<std::string> link_names,std::vector<std::string> joint_names, std::string final_frame_name, std::string initial_frame_name, int max_links)
{
    bool use_names;
    int n_links, i, sensor_link;
    n_links = idynChain.getN();
    sensor_link = idynSensor.getSensorLink();

    int kdl_links = n_links + 1; //The sensor links transform a link in two different links
    int kdl_joints = kdl_links;

    if(n_links <= 0 ) return false;

    if( (int)link_names.size() < kdl_links || (int)joint_names.size() < kdl_joints ) {
        use_names = false;
    } else {
        use_names = true;
    }


    KDL::Frame kdlFrame = KDL::Frame();
    KDL::Frame kdl_H;
    kdlChain = KDL::Chain();
    KDL::Segment kdlSegment = KDL::Segment();
    KDL::RigidBodyInertia kdlRigidBodyInertia = KDL::RigidBodyInertia();

    int kdl_i = 0;

    if( initial_frame_name.length() != 0 ) {
        idynMatrix2kdlFrame(idynChain.getH0(),kdlFrame);
        kdlSegment = KDL::Segment(initial_frame_name,KDL::Joint(initial_frame_name+"_joint",KDL::Joint::None),kdlFrame);
        kdlChain.addSegment(kdlSegment);
    }


    KDL::Frame remainder_frame = KDL::Frame::Identity();
    for(i=0; i<n_links; i++)
    {
        if( i != sensor_link ) {
            //forgive him, as he does not know what is doing
            iCub::iKin::iKinLink & link_current = idynChain[i];
            //For the last link, take in account also HN
            if ( i == n_links - 1) {
                idynMatrix2kdlFrame(idynChain.getHN(),kdl_H);
                kdlFrame = kdlFrame.DH(link_current.getA(),link_current.getAlpha(),link_current.getD(),link_current.getOffset())*kdl_H;
            } else {
                kdlFrame = kdlFrame.DH(link_current.getA(),link_current.getAlpha(),link_current.getD(),link_current.getOffset());
            }

            bool ret = idynDynamicalParameters2kdlRigidBodyInertia(idynChain.getMass(i),idynChain.getCOM(i).subcol(0,3,3),idynChain.getInertia(i),kdlRigidBodyInertia);
            assert(ret);
            if(!ret) return false;

            //For the joint after the ft sensor, consider the offset between the ft sensor
            // and the joint

            if( idynChain.isLinkBlocked(i) ) {
                // if it is blocked, it is easy to add the remainder frame
                if( use_names ) {
                    kdlSegment = KDL::Segment(link_names[kdl_i],KDL::Joint(joint_names[kdl_i],KDL::Joint::None),remainder_frame*kdlFrame,kdlRigidBodyInertia);
                    kdl_i++;
                } else {
                    kdlSegment = KDL::Segment(KDL::Joint(KDL::Joint::None),remainder_frame*kdlFrame,kdlRigidBodyInertia);
                }
            } else {
                KDL::Vector new_joint_axis, new_joint_origin;
                new_joint_axis = remainder_frame.M*KDL::Vector(0.0,0.0,0.1);
                new_joint_origin = remainder_frame.p;
                if( use_names ) {
                    kdlSegment = KDL::Segment(link_names[kdl_i],KDL::Joint(joint_names[kdl_i],new_joint_origin,new_joint_axis,KDL::Joint::RotAxis),remainder_frame*kdlFrame,kdlRigidBodyInertia);
                    kdl_i++;
                } else {
                    kdlSegment = KDL::Segment(KDL::Joint(new_joint_origin,new_joint_axis,KDL::Joint::RotAxis),remainder_frame*kdlFrame,kdlRigidBodyInertia);
                }
            }
            kdlChain.addSegment(kdlSegment);
            remainder_frame = KDL::Frame::Identity();
        } else {
            //( i == segment_link )
            double m,m0,m1;
            yarp::sig::Vector r0(3),r1(3),r(3),rgg0(3),rgg1(3),r_i_s_wrt_i(3),r_i_C0_wrt_i;
            yarp::sig::Matrix I,I0,I1;
            yarp::sig::Matrix R_s_wrt_i;

            iCub::iKin::iKinLink & link_current = idynChain[sensor_link];
            KDL::Frame kdlFrame_0 = KDL::Frame();
            KDL::Frame kdlFrame_1 = KDL::Frame();

            //Imagine that we have i, s , i+1

            //yarp::sig::Matrix H_0;
            //The angle of the sensor link joint is put to 0 and then restored
            double angSensorLink = link_current.getAng();
            yarp::sig::Matrix  H_sensor_link = (link_current.getH(0.0)); //H_{i-1}_i
            link_current.setAng(angSensorLink);
            //idynSensor.getH() <--> H_i_s
            yarp::sig::Matrix H_0 = H_sensor_link  * (idynSensor.getH()); // H_{i-1}_s = H_{i-1}_i*H_i_s ?
            yarp::sig::Matrix H_1 = localSE3inv(idynSensor.getH()); //H_s_{i}
            //std::cout << "H_0" << std::endl << H_0.toString() << std::endl;
            //std::cout << "H_1" << std::endl << H_1.toString() << std::endl;
            idynMatrix2kdlFrame(H_0,kdlFrame_0);
            idynMatrix2kdlFrame(H_1,kdlFrame_1);

            remainder_frame = kdlFrame_1;

            H_sensor_dh_child = remainder_frame;

            kdlFrame_1 = KDL::Frame::Identity();

            //cout << "kdlFrame_0: " << endl;
            //cout << kdlFrame_0;
            //cout << "kdlFrame_1: " << endl;
            //cout << kdlFrame_1;


            KDL::RigidBodyInertia kdlRigidBodyInertia_0 = KDL::RigidBodyInertia();
            KDL::RigidBodyInertia kdlRigidBodyInertia_1 = KDL::RigidBodyInertia();

            m = idynChain.getMass(sensor_link);
            m1 = idynSensor.getMass();
            m0 = m-m1;
            //It is not possible that the semilink is more heavy than the link!!!
            assert(m0 > 0);

            //r_{i,C_i}^i
            r = idynChain.getCOM(i).subcol(0,3,3);

            //R_s^i
            R_s_wrt_i = idynSensor.getH().submatrix(0,2,0,2);

            r_i_s_wrt_i = idynSensor.getH().subcol(0,3,3);

            //r0 := r_{s,C_{{vl}_0}}^s
            //r1 := r_{i,C_{{vl}_1}}^i



            //
            r1 = r_i_s_wrt_i +  R_s_wrt_i*(idynSensor.getCOM().subcol(0,3,3));

            //cout << "m0: " << m0 << endl;
            r_i_C0_wrt_i = (1/m0)*(m*r-m1*r1);

            r0 = R_s_wrt_i.transposed()*(r_i_C0_wrt_i-r_i_s_wrt_i);

            I = idynChain.getInertia(i);

            I1 = R_s_wrt_i*idynSensor.getInertia()*R_s_wrt_i.transposed();
            rgg0 = -1*r+r_i_C0_wrt_i;
            rgg1 = -1*r+r1;

            I0 = R_s_wrt_i.transposed()*(I - I1 + m1*crossProductMatrix(rgg1)*crossProductMatrix(rgg1) +  m0*crossProductMatrix(rgg0)*crossProductMatrix(rgg0))*R_s_wrt_i;

            //DEBUG
            //printMatrix("I",I);
            //printMatrix("I1",I1);
            //printMatrix("I0",I0);
            //printMatrix("cross",crossProductMatrix(rgg1));

            //cout << "m0: " << m0 << endl;
            //printVector("r0",r0);
            //printMatrix("I0",I0);
            bool ret;
            ret = idynDynamicalParameters2kdlRigidBodyInertia(m0,r0,I0,kdlRigidBodyInertia_0);
            assert(ret);
            if(!ret) return false;
            ret = idynDynamicalParameters2kdlRigidBodyInertia(m1,r1,I1,kdlRigidBodyInertia_1);
            assert(ret);
            if(!ret) return false;

            KDL::RigidBodyInertia kdlRigidBodyInertia_1_buf;
            kdlRigidBodyInertia_1_buf = remainder_frame*kdlRigidBodyInertia_1;
            kdlRigidBodyInertia_1 = kdlRigidBodyInertia_1_buf;

            if( use_names ) {
                kdlSegment = KDL::Segment(link_names[kdl_i],KDL::Joint(joint_names[kdl_i],KDL::Joint::RotZ),kdlFrame_0,kdlRigidBodyInertia_0);
                kdl_i++;
            } else {
                kdlSegment = KDL::Segment(KDL::Joint(KDL::Joint::RotZ),kdlFrame_0,kdlRigidBodyInertia_0);
            }
            kdlChain.addSegment(kdlSegment);

            if( use_names ) {
                kdlSegment = KDL::Segment(link_names[kdl_i],KDL::Joint(joint_names[kdl_i],KDL::Joint::None),kdlFrame_1,kdlRigidBodyInertia_1);
                kdl_i++;
            } else {
                kdlSegment = KDL::Segment(KDL::Joint(KDL::Joint::None),kdlFrame_1,kdlRigidBodyInertia_1);
            }
            kdlChain.addSegment(kdlSegment);
        }

    }
    //Final link can be segment
    if( final_frame_name.length() != 0 ) {
        idynMatrix2kdlFrame(idynChain.getHN(),kdlFrame);
        kdlSegment = KDL::Segment(final_frame_name,KDL::Joint(final_frame_name+"_joint",KDL::Joint::None),kdlFrame);
        kdlChain.addSegment(kdlSegment);
    }

    if( max_links < (int)kdlChain.getNrOfSegments() )
    {
        KDL::Chain new_kdlChain;
        for(int p=0; p < max_links; p++)
        {
            new_kdlChain.addSegment(kdlChain.getSegment(p));
        }
        kdlChain = new_kdlChain;
    }

    //Considering the H0 transformation
    if( initial_frame_name.length() == 0 ) {
        KDL::Chain new_chain;
        KDL::Frame kdl_H0;
        idynMatrix2kdlFrame(idynChain.getH0(),kdl_H0);
        addBaseTransformation(kdlChain,new_chain,kdl_H0);
        kdlChain = new_chain;
    }

    return true;
}
Exemplo n.º 18
0
bool fk_solve_all(kinematics_msgs::GetPositionFK::Request &req,
		  kinematics_msgs::GetPositionFK::Response &res )
{
	ROS_INFO("[TESTING]: get_fk_all_service has been called!");

	unsigned int nj = chain.getNrOfJoints();
	unsigned int nl = chain.getNrOfSegments();
	
	ChainFkSolverPos_recursive fksolver1(chain);//Forward position solver

	JntArray conf(nj);
    geometry_msgs::PoseStamped pose;
    tf::Stamped<tf::Pose> tf_pose;

	for(int i = 0; i < nj; i++)
		conf(i) = req.robot_state.joint_state.position[i];
	Frame F_ist;
		res.pose_stamped.resize(nl);
	res.fk_link_names.resize(nl);
	for(int j = 0; j < nl; j++)
	{
		if(fksolver1.JntToCart(conf, F_ist, j+1) >= 0)
		{
		std::cout << "Calculated Position out of Configuration for segment " << j+1 << ":\n";
			std::cout << F_ist <<"\n";
		
			std::cout << "Calculated Position out of Configuration:\n";
			std::cout << F_ist <<"\n";
	
			//TODO: fill out response!!!

		    tf_pose.frame_id_ = "base_link";//root_name_;
		    tf_pose.stamp_ = ros::Time();
		    tf::PoseKDLToTF(F_ist,tf_pose);
		    try
			{
		      //tf_.transformPose(req.header.frame_id,tf_pose,tf_pose);
		    }
		    catch(...)
		    {
		      ROS_ERROR("Could not transform FK pose to frame: %s",req.header.frame_id.c_str());
		      res.error_code.val = res.error_code.FRAME_TRANSFORM_FAILURE;
		      return false;
		    }
		    tf::poseStampedTFToMsg(tf_pose,pose);
		    res.pose_stamped[j] = pose;
		    res.fk_link_names[j] = chain.getSegment(j).getName();
		    res.error_code.val = res.error_code.SUCCESS;
		}
		else
		{
		    ROS_ERROR("Could not compute FK for segment %d", j);
		    res.error_code.val = res.error_code.NO_FK_SOLUTION;
		}


		//TODO: fill out response!!!
		//res.pose_stamped[j]
	}

	return true;
}
    void callbackJointState(const JointStateConstPtr& state)
    {
        std::map<std::string, double> joint_name_position;
        if (state->name.size() != state->position.size()) {
            ROS_ERROR("Robot state publisher received an invalid joint state vector");
            return;
        }

        // determine least recently published joint
        ros::Time last_published = ros::Time::now();
        for (unsigned int i=0; i<state->name.size(); i++) {
            ros::Time t = last_publish_time_[state->name[i]];
            last_published = (t < last_published) ? t : last_published;
        }

        if (state->header.stamp >= last_published + publish_interval_) {
            // get joint positions from state message
            std::map<std::string, double> joint_positions;
            std::map<std::string, double> joint_efforts;
            for (unsigned int i=0; i<state->name.size(); i++) {
                joint_positions.insert(make_pair(state->name[i], state->position[i]));
                joint_efforts.insert(make_pair(state->name[i], state->effort[i]));
            }

            KDL::JntArray  tau;
            KDL::Wrench    F;
            Eigen::Matrix<double,Eigen::Dynamic,6> jac_t;
            Eigen::Matrix<double,6,Eigen::Dynamic> jac_t_pseudo_inv;
            tf::StampedTransform transform;
            KDL::Wrench    F_pub;
            tf::Vector3 tf_force;
            tf::Vector3 tf_torque;

            tau.resize(chain_.getNrOfJoints());

            //getPositions;
            for (size_t i=0, j=0; i<chain_.getNrOfSegments(); i++) {
                if (chain_.getSegment(i).getJoint().getType() == KDL::Joint::None)
                    continue;

                // check
                std::string joint_name = chain_.getSegment(i).getJoint().getName();
                if ( joint_positions.find(joint_name) == joint_positions.end() ) {
                    ROS_ERROR("Joint '%s' is not found in joint state vector", joint_name.c_str());
                }

                // set position
                jnt_pos_(j) = joint_positions[joint_name];
                tau(j) = joint_efforts[joint_name];
                j++;
            }

            jnt_to_jac_solver_->JntToJac(jnt_pos_, jacobian_);
            jac_t = jacobian_.data.transpose();
            if ( jacobian_.columns() >= jacobian_.rows() ) {
                jac_t_pseudo_inv =(jac_t.transpose() * jac_t).inverse() *  jac_t.transpose();
            } else {
                jac_t_pseudo_inv =jac_t.transpose() * ( jac_t *  jac_t.transpose() ).inverse();
            }
#if 1
            {
                ROS_INFO("jac_t# jac_t : ");
                Eigen::Matrix<double,6,6> mat_i =  mat_i = jac_t_pseudo_inv * jac_t;
                for (unsigned int i = 0; i < 6; i++) {
                    std::stringstream ss;
                    for (unsigned int j=0; j<6; j++)
                        ss << std::fixed << std::setw(8) << std::setprecision(4) << mat_i(j,i) << " ";
                    ROS_INFO_STREAM(ss.str());
                }
            }
#endif
            // f = - inv(jt) * effort
            for (unsigned int j=0; j<6; j++)
            {
                F(j) = 0;
                for (unsigned int i = 0; i < jnt_pos_.rows(); i++)
                {
                    F(j) += -1 * jac_t_pseudo_inv(j, i) * tau(i);
                }
            }

            //low pass filter
            F += (F_pre_ - F) * exp(-1.0 / t_const_);
            for (unsigned int j=0; j<6; j++) {
                F_pre_(j) = 0;
            }
            F_pre_ += F;

            //tf transformation
            tf::vectorKDLToTF(F.force, tf_force);
            tf::vectorKDLToTF(F.torque, tf_torque);
            try {
                listener_.waitForTransform( tip, root, state->header.stamp, ros::Duration(1.0));
                listener_.lookupTransform( tip, root, state->header.stamp , transform);
            }
            catch (tf::TransformException ex) {
                ROS_ERROR("%s",ex.what());
                ros::Duration(1.0).sleep();
            }
            for (unsigned int j=0; j<3; j++) {
                F_pub.force[j] = transform.getBasis()[j].dot(tf_force);
                F_pub.torque[j] = transform.getBasis()[j].dot(tf_torque);
            }

            geometry_msgs::WrenchStamped msg;
            msg.header.stamp = state->header.stamp;
            msg.header.frame_id = tip;
            // http://code.ros.org/lurker/message/20110107.151127.7177af06.nl.html
            //tf::WrenchKDLToMsg(F,msg.wrench);
            msg.wrench.force.x = F_pub.force[0];
            msg.wrench.force.y = F_pub.force[1];
            msg.wrench.force.z = F_pub.force[2];
            msg.wrench.torque.x = F_pub.torque[0];
            msg.wrench.torque.y = F_pub.torque[1];
            msg.wrench.torque.z = F_pub.torque[2];
            wrench_stamped_pub_.publish(msg);

            {
                ROS_INFO("jacobian : ");
                for (unsigned int i = 0; i < jnt_pos_.rows(); i++) {
                    std::stringstream ss;
                    for (unsigned int j=0; j<6; j++)
                        ss << std::fixed << std::setw(8) << std::setprecision(4) << jacobian_(j,i) << " ";
                    ROS_INFO_STREAM(ss.str());
                }
                ROS_INFO("effort : ");
                std::stringstream sstau;
                for (unsigned int i = 0; i < tau.rows(); i++) {
                    sstau << std::fixed << std::setw(8) << std::setprecision(4) << tau(i) << " ";
                }
                ROS_INFO_STREAM(sstau.str());
                ROS_INFO("force : ");
                std::stringstream ssf;
                for (unsigned int j = 0; j < 6; j++) {
                    ssf << std::fixed << std::setw(8) << std::setprecision(4) << F(j) << " ";
                }
                ROS_INFO_STREAM(ssf.str());
            }

            // store publish time in joint map
            for (unsigned int i=0; i<state->name.size(); i++)
                last_publish_time_[state->name[i]] = state->header.stamp;
        }
    }