Skip to content
Snippets Groups Projects
Commit 24d7d1ec authored by Thomas Moulard's avatar Thomas Moulard
Browse files

Add tf_broadcaster.

parent 08e16a2d
No related branches found
No related tags found
No related merge requests found
#!/usr/bin/env python
# This node subscribes to topic transformation published by
# dynamic_graph_bridge and forward them into tf.
#
# This is required as there is no easy way to publish to tf in
# real-time.
import roslib
roslib.load_manifest('dynamic_graph_bridge')
import rospy
import tf
import geometry_msgs.msg
def handleTransform(msg, topic):
br = tf.TransformBroadcaster()
br.sendTransform((msg.transform.translation.x,
msg.transform.translation.y,
msg.transform.translation.z),
(msg.transform.rotation.x,
msg.transform.rotation.y,
msg.transform.rotation.z,
msg.transform.rotation.w),
msg.header.stamp,
topic,
#msg.child_frame_id,
'/world')
#msg.header.frame_id)
def handleVector(msg, topic):
br = tf.TransformBroadcaster()
br.sendTransform((msg.vector.x, msg.vector.y, msg.vector.z), (0, 0, 0, 1),
msg.header.stamp,
topic,
#msg.child_frame_id,
'/world')
#msg.header.frame_id)
if __name__ == '__main__':
rospy.init_node('dynamic_graph_broadcaster')
topicsTransform = ['base_link', 'base_footprint']
topicsVector = ['com', 'zmp']
for topic in topicsTransform:
rospy.Subscriber('/dynamic_graph/{0}'.format(topic),
geometry_msgs.msg.TransformStamped,
handleTransform, topic)
for topic in topicsVector:
rospy.Subscriber('/dynamic_graph/{0}'.format(topic),
geometry_msgs.msg.Vector3Stamped,
handleVector, topic)
rospy.spin()
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment