Link in rviz teleports between original and transformed position with tf2
Here's a video of what I'm referring to. I'm using rviz to display a transformation using a tf2 broadcaster, but link1 keeps popping back and forth between its specified location from the URDF, and the location that the tf2 message sent. How can I get it to stay where it transformed to?
Additionally, since link2 is the child of link1, why doesn't link2 move along with link1?
Here's the python code:
import rospy
import tf2_ros
import geometry_msgs.msg
import math
if __name__ == '__main__':
rospy.init_node('dynamic_tf2_broadcaster')
br = tf2_ros.TransformBroadcaster()
t = geometry_msgs.msg.TransformStamped()
t.header.frame_id = "body"
t.child_frame_id = "link1"
rate = rospy.Rate(100.0)
while not rospy.is_shutdown():
x = rospy.Time.now().to_sec() * math.pi
t.header.stamp = rospy.Time.now()
t.transform.translation.x = 10 * math.sin(x)
t.transform.translation.y = 10 * math.cos(x)
t.transform.translation.z = 0.0
t.transform.rotation.x = 0.0
t.transform.rotation.y = 0.0
t.transform.rotation.z = 0.0
t.transform.rotation.w = 1.0
br.sendTransform(t)
rate.sleep()
And here's the rviz launch file:
<launch>
<arg name="gui" default="True" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find basic_bot)/description/urdf/robot.xacro'"/>
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find basic_bot)/rviz/robot.rviz" required="true" />
</launch>