Go to the documentation of this file.00001
00002 import rospy
00003 import tf
00004 from geometry_msgs.msg import TransformStamped
00005
00006 def callback(transform):
00007 global br
00008 global frame_id
00009 global child_frame_id
00010 local_frame_id = transform.header.frame_id
00011 local_child_frame_id = transform.child_frame_id
00012 if not local_frame_id:
00013 local_frame_id = frame_id
00014 if not local_child_frame_id:
00015 local_child_frame_id = child_frame_id
00016 br.sendTransform(
00017 (transform.transform.translation.x, transform.transform.translation.y, transform.transform.translation.z),
00018 (transform.transform.rotation.x, transform.transform.rotation.y, transform.transform.rotation.z, transform.transform.rotation.w),
00019 transform.header.stamp,
00020 child_frame_id,
00021 frame_id)
00022
00023 if __name__ == "__main__":
00024
00025 rospy.init_node("transform_to_tf", anonymous=True)
00026
00027 frame_id = rospy.get_param('~frame_id', 'world')
00028 child_frame_id = rospy.get_param('~child_frame_id', 'transform')
00029
00030 br = tf.TransformBroadcaster()
00031 rospy.Subscriber("transform", TransformStamped, callback, queue_size=1)
00032 rospy.spin()