Skip to content

Commit

Permalink
Add node to use tf2
Browse files Browse the repository at this point in the history
  • Loading branch information
OTL committed Jan 5, 2017
1 parent c5e6615 commit 243744c
Showing 1 changed file with 22 additions and 0 deletions.
22 changes: 22 additions & 0 deletions nodes/transform_stamped_to_tf2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
#!/usr/bin/env python

import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped


class TransformBroadcaster(object):
'''This is hack to avoid tf2_ros on python3
'''
def __init__(self):
self._sub = rospy.Subscriber('transforms', TransformStamped,
self.broadcast_tf)
self._br = tf2_ros.TransformBroadcaster()

def broadcast_tf(self, transform_msg):
self._br.sendTransform(transform_msg)

if __name__ == '__main__':
rospy.init_node('transform_stamped_to_tf2')
br = TransformBroadcaster()
rospy.spin()

0 comments on commit 243744c

Please sign in to comment.