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

tf tree changes over time

asked 2016-08-16 13:43:05 -0500

patrchri gravatar image

updated 2016-08-16 15:21:23 -0500

Hello,

I have a 3 wheel robot with a hokuyo lidar on it and today I noticed that the tf tree changes over time. By the word change, I mean that it starts:

odom->base_footprint(--> l_wheel,r_wheel)->base_link-->caster_wheel, hokuyo

and it changes to:

odom->base_footprint->base_link---->l_wheel,r_wheel,caster_wheel,hokuyo

and goes back again at the first tree and then moves back to the other one as time goes by. There is also an intermediate state where the tree is like that;

odom->base_footprint(->l_wheel)->base-link--->r_wheel,caster_wheel,hokuyo.

Is this normal ? Or there is something wrong with my model ? And if yes, what could possibly cause that malfunction?

EDITED:

After using raultron's advice and using roswtf I got the following errors:

ERROR TF re-parenting contention:
 * reparenting of [r_wheel] to [base_footprint] by [/gazebo]
 * reparenting of [l_wheel] to [base_footprint] by [/gazebo]
 * reparenting of [l_wheel] to [base_link] by [/robot_state_publisher]
 * reparenting of [r_wheel] to [base_link] by [/robot_state_publisher]

ERROR TF multiple authority contention:
 * node [/gazebo] publishing transform [r_wheel] with parent [base_footprint] already published by node [/robot_state_publisher]
 * node [/gazebo] publishing transform [l_wheel] with parent [base_footprint] already published by node [/robot_state_publisher]
 * node [/robot_state_publisher] publishing transform [l_wheel] with parent [base_link] already published by node [/gazebo]
 * node [/robot_state_publisher] publishing transform [r_wheel] with parent [base_link] already published by node [/gazebo]

I use a robot_state_publisher node for the frames of my robot, and the gazebo node automatically broadcasts too, because I have a a differential_driver_controller plugin as a gazebo element at my urdf model as presented below:

  <gazebo>
   <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">

            <rosDebugLevel>Debug</rosDebugLevel>
            <publishWheelTF>True</publishWheelTF>
            <publishTF>1</publishTF>
            <publishWheelJointState>true</publishWheelJointState>
            <alwaysOn>true</alwaysOn>
            <updateRate>100.0</updateRate>
            <leftJoint>joint_l_wheel</leftJoint>
            <rightJoint>joint_r_wheel</rightJoint>
        <wheelSeparation>0.22</wheelSeparation>
            <wheelDiameter>0.16</wheelDiameter>
            <broadcastTF>1</broadcastTF>            
            <wheelTorque>30</wheelTorque>
        <commandTopic>/labrob/cmd_vel</commandTopic>
            <odometryFrame>odom</odometryFrame>
            <odometryTopic>/labrob/odom</odometryTopic>
            <robotBaseFrame>base_footprint</robotBaseFrame>
        <legacyMode>true</legacyMode>

   </plugin>
  </gazebo>

This plugin broacasts the connections to the wheels, which is something that the robot_state_publisher also does. I changed some parameters to that:

  <gazebo>
   <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">

            <rosDebugLevel>Debug</rosDebugLevel>
            <publishWheelTF>False</publishWheelTF>
            <publishWheelJointState>True</publishWheelJointState>
            <alwaysOn>True</alwaysOn>
            <updateRate>100.0</updateRate>
            <leftJoint>joint_l_wheel</leftJoint>
            <rightJoint>joint_r_wheel</rightJoint>
        <wheelSeparation>0.22</wheelSeparation>
            <wheelDiameter>0.16</wheelDiameter>           
            <wheelTorque>30</wheelTorque>
        <commandTopic>/labrob/cmd_vel</commandTopic>
            <robotBaseFrame>base_link</robotBaseFrame>
        <legacyMode>true</legacyMode>

   </plugin>
  </gazebo>

And now I have the following errors after roswtf:

Found 2 error(s).

ERROR TF re-parenting contention:
 * reparenting of [base_link] to [base_footprint] by [/robot_state_publisher]
 * reparenting of [base_link] to [odom] by [/gazebo]

ERROR TF multiple authority contention:
 * node [/robot_state_publisher] publishing transform [base_link] with parent [base_footprint] already published by node [/gazebo]
 * node [/gazebo] publishing transform [base_link] with parent [odom] already published by node [/robot_state_publisher]

Now I have two trees:

  1. odom

  2. base_footprint->base_link---->l_wheel,r_wheel,hokuyo_link,caster_wheel

Any idea on how to get rid of that gazebo broadcaster?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2016-08-16 14:22:18 -0500

raultron gravatar image

For me it looks like you have at least two different transform publishers publishing a TF to the same parent frame. Thats why you see different configurations of the three each time that you reload. Try to check which nodes are publishing transformations and try to disable them one by one until you don't see the changes on the tree anymore.

You can also use http://wiki.ros.org/roswtf to see if there is something weird.

Cheers

edit flag offensive delete link more

Comments

Hello and thank you for your answer. I re edited my question after using roswtf. Gazebo and state_publisher are broadcasting the same connections I guess. Any idea how to solve this and restrict the broadcasting to only one ?

patrchri gravatar image patrchri  ( 2016-08-16 15:02:10 -0500 )edit
1

answered 2016-08-16 15:25:08 -0500

patrchri gravatar image

updated 2016-08-16 15:42:07 -0500

I found the answer after raultron's help. I had to change the plugin to that:

  <gazebo>
   <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">

            <rosDebugLevel>Debug</rosDebugLevel>
            <publishWheelTF>False</publishWheelTF>
            <publishWheelJointState>True</publishWheelJointState>
            <alwaysOn>True</alwaysOn>
            <updateRate>100.0</updateRate>
            <leftJoint>joint_l_wheel</leftJoint>
            <rightJoint>joint_r_wheel</rightJoint>
        <wheelSeparation>0.22</wheelSeparation>
            <wheelDiameter>0.16</wheelDiameter>
            <broadcastTF>0</broadcastTF>            
            <wheelTorque>30</wheelTorque>
        <commandTopic>/labrob/cmd_vel</commandTopic>
            <robotBaseFrame>base_footprint</robotBaseFrame>
        <legacyMode>true</legacyMode>

   </plugin>
  </gazebo>

And roswtf shows the tree without errors.

edit flag offensive delete link more

Comments

I am glad you solved it :). Cheers.

raultron gravatar image raultron  ( 2016-08-17 02:21:34 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-08-16 13:43:05 -0500

Seen: 1,097 times

Last updated: Aug 16 '16