40 #include <kdl/frames_io.hpp> 
   41 #include <geometry_msgs/TransformStamped.h> 
   56   addChildren(tree.getRootSegment());
 
   62   const std::string& root = GetTreeElementSegment(segment->second).getName();
 
   64   const std::vector<KDL::SegmentMap::const_iterator>& children = GetTreeElementChildren(segment->second);
 
   65   for (
size_t i = 0; i < children.size(); ++i) {
 
   66     const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
 
   67     SegmentPair 
s(GetTreeElementSegment(children[i]->second), root, child.getName());
 
   68     if (child.getJoint().getType() == KDL::Joint::None) {
 
   69       if (
model_.getJoint(child.getJoint().getName()) && 
model_.getJoint(child.getJoint().getName())->type == urdf::Joint::FLOATING) {
 
   70         ROS_INFO(
"Floating joint. Not adding segment from %s to %s. This TF can not be published based on joint_states info", root.c_str(), child.getName().c_str());
 
   74         ROS_DEBUG(
"Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
 
   78       segments_.insert(make_pair(child.getJoint().getName(), s));
 
   79       ROS_DEBUG(
"Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
 
   87   if (in.size() && in[0] == 
'/')
 
   95 std::string 
prefix_frame(
const std::string & tf_prefix, 
const std::string & frame)
 
   98   if (frame.size() && frame[0] == 
'/') {
 
   99     return frame.substr(1);
 
  102   std::string prefixed_frame;
 
  105   if (tf_prefix.size() && tf_prefix[0] == 
'/') {
 
  106     prefixed_frame = tf_prefix.substr(1);
 
  108     prefixed_frame = tf_prefix;
 
  112   if (!tf_prefix.empty()) {
 
  113     prefixed_frame += 
'/';
 
  116   prefixed_frame += frame;
 
  118   return prefixed_frame;
 
  124   ROS_DEBUG(
"Publishing transforms for moving joints");
 
  125   std::vector<geometry_msgs::TransformStamped> tf_transforms;
 
  128   for (std::map<std::string, double>::const_iterator jnt = joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
 
  129     std::map<std::string, SegmentPair>::const_iterator seg = 
segments_.find(jnt->first);
 
  131       geometry_msgs::TransformStamped tf_transform = 
tf2::kdlToTransform(seg->second.segment.pose(jnt->second));
 
  132       tf_transform.header.stamp = time;
 
  133       tf_transform.header.frame_id = 
prefix_frame(tf_prefix, seg->second.root);
 
  134       tf_transform.child_frame_id = 
prefix_frame(tf_prefix, seg->second.tip);
 
  135       tf_transforms.push_back(tf_transform);
 
  138       ROS_WARN_THROTTLE(10, 
"Joint state with name: \"%s\" was received but not found in URDF", jnt->first.c_str());
 
  147   ROS_DEBUG(
"Publishing transforms for fixed joints");
 
  148   std::vector<geometry_msgs::TransformStamped> tf_transforms;
 
  149   geometry_msgs::TransformStamped tf_transform;
 
  153     geometry_msgs::TransformStamped tf_transform = 
tf2::kdlToTransform(seg->second.segment.pose(0));
 
  155     if (!use_tf_static) {
 
  158     tf_transform.header.frame_id = 
prefix_frame(tf_prefix, seg->second.root);
 
  159     tf_transform.child_frame_id = 
prefix_frame(tf_prefix, seg->second.tip);
 
  160     tf_transforms.push_back(tf_transform);