ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Static Latch frames not shown in TF Frame graph?

asked 2013-10-17 07:55:01 -0500

rnunziata gravatar image

updated 2013-10-27 08:40:48 -0500

Update: any reason why I should not open a ticket on this item now.

I have re-tested this under both the compiled source and the lasted upgrade and still tf2 static latch transforms do not show in the tf_frame graph.

Update: a simplified example. I have replaced the body of the question with this example.

Update: I will open a ticket on this if no one has any additional input.

image description

Here is the code and the resulting rviz image. I also did a variation with the addition of a base_link to fixed_frame with the same results.

int main(int argc, char **argv)
{
  ros::init(argc, argv, "robot_odometry");
  tf2_ros::StaticTransformBroadcaster static_broadcaster;

  geometry_msgs::TransformStamped msg2;

  msg2.header.stamp = ros::Time::now();
  msg2.transform.translation.z = 0.1;
  msg2.transform.rotation.w =  1;
  msg2.transform.translation.z = 0.1;
  msg2.transform.translation.y = 0.13; 
  msg2.transform.translation.x = 0.13; 
  msg2.header.frame_id = "base_link";   
  msg2.child_frame_id  = "right";;
  static_broadcaster.sendTransform(msg2);


  ros::spin();
  return 0;
}



<?xml version="1.0"?>
<robot name="rrbot">
   <link name='base_link'>
      <visual name='visual'>
        <geometry>
          <box  size=".4 .2 .1"/>
        </geometry>
      </visual>
  </link>


  <link name="right">
    <visual name="visual">
      <origin xyz="0.13 0.13 0.1" />
      <geometry>
        <cylinder  length="0.5" radius="0.5"/>
      </geometry>
    </visual>
  </link>

  <joint type="fixed" name="joint2">
    <origin xyz="0.13 0.13 0.1" />
    <parent link="base_link"/>
    <child link="right"/>
  </joint>

</robot>

Also to note : no matter how many transforms I send weather independently or via vector only the last transform is published. The model was updated to new links in this case.

  std::vector<geometry_msgs::TransformStamped> v1;
  v1.push_back(msg1);
  v1.push_back(msg2);
      .
      .
      .
  static_broadcaster.sendTransform(v1);
edit retag flag offensive close merge delete

Comments

Did you check this function gets called?

BennyRe gravatar image BennyRe  ( 2013-10-17 21:09:31 -0500 )edit

yes..it is being called.

rnunziata gravatar image rnunziata  ( 2013-10-18 02:31:06 -0500 )edit

Hm can't find an error. Could you provide more code?

BennyRe gravatar image BennyRe  ( 2013-10-18 06:48:09 -0500 )edit

I updated the question with the full code for the node. The routine name is the same.

rnunziata gravatar image rnunziata  ( 2013-10-18 07:16:06 -0500 )edit

You should isolate it down to the minimum possible code path before filing a ticket to make sure you know exactly what the problem is.

tfoote gravatar image tfoote  ( 2013-10-20 14:38:09 -0500 )edit

I have tried to do as you said....please comment on new example.

rnunziata gravatar image rnunziata  ( 2013-10-21 04:46:43 -0500 )edit

Thanks for the update. I still don't see any error. The rviz plugin is reporting successfully transforming both base_link and right frame_ids.

tfoote gravatar image tfoote  ( 2013-10-21 06:27:42 -0500 )edit

yes, but that is not the question. The question is why do static transforms not show in the TF tree. If you use the static transform node they do show. So why should they not show if sent programmaticly. Also this is just a single tf. If you publish more then one form the same node as indicate only one is transformed.

rnunziata gravatar image rnunziata  ( 2013-10-21 06:50:58 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2013-10-21 07:15:11 -0500

tfoote gravatar image

Ahh, I think you're running into this issue: https://github.com/ros/geometry_experimental/pull/29 patched last week.

edit flag offensive delete link more

Comments

Not much info on what was fixed. Looking at my ubuntu software center I have this package installed and I am current. So this issue seems not to be fixed,yes?

rnunziata gravatar image rnunziata  ( 2013-10-21 07:41:27 -0500 )edit

It's patched in the source. If you want it immediately you can pull it from source. It will be released into binary packages in the near future.

tfoote gravatar image tfoote  ( 2013-10-21 10:36:06 -0500 )edit

Trying to install fix form source....see update question for error...not sure what this error means.

rnunziata gravatar image rnunziata  ( 2013-10-22 05:17:42 -0500 )edit

You seem to have a conflicting target name in your rrbot_gazebo. Please open a new question as this is a new issue and we don't want to dilute this question for future searchers with a similar problem.

tfoote gravatar image tfoote  ( 2013-10-22 10:45:59 -0500 )edit

I have updated question...have downloaded and test latest code. Problem still present.

rnunziata gravatar image rnunziata  ( 2013-10-24 05:56:56 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-10-17 07:55:01 -0500

Seen: 716 times

Last updated: Oct 27 '13