$search
00001 00002 import roslib; roslib.load_manifest('pr2_plugs_actions') 00003 00004 import rospy 00005 import tf 00006 import tf2_ros 00007 import tf2_geometry_msgs 00008 from geometry_msgs.msg import PoseStamped 00009 from std_srvs.srv import * 00010 00011 import threading 00012 00013 __all__ = ['TFUtil'] 00014 00015 class TFUtil(): 00016 initialized = False 00017 00018 listener = None 00019 broadcaster = None 00020 00021 broadcast_lock = None 00022 broadcast_list = {} 00023 broadcast_threads = {} 00024 00025 def __init__(self): 00026 if not TFUtil.initialized: 00027 TFUtil.listener = tf2_ros.buffer_client.BufferClient('tf2_buffer_server_plugs') 00028 TFUtil.listener.wait_for_server() 00029 TFUtil.broadcaster = tf.TransformBroadcaster() 00030 TFUtil.initialized = True 00031 00032 TFUtil.broadcast_lock = threading.Lock() 00033 00034 @staticmethod 00035 def wait_and_transform(frame_id, pose): 00036 return TFUtil.listener.transform(pose, frame_id, rospy.Duration(5.0)) 00037 00038 00039 @staticmethod 00040 def wait_and_lookup(parent_frame_id, child_frame_id, time=None): 00041 if time == None: 00042 time = rospy.Time.now() 00043 00044 ps = PoseStamped() 00045 ps.header.stamp = time 00046 ps.header.frame_id = child_frame_id 00047 ps.pose.position.x = 0.0 00048 ps.pose.position.y = 0.0 00049 ps.pose.position.z = 0.0 00050 ps.pose.orientation.x = 0.0 00051 ps.pose.orientation.y = 0.0 00052 ps.pose.orientation.z = 0.0 00053 ps.pose.orientation.w = 1.0 00054 return TFUtil.listener.transform(ps, parent_frame_id, rospy.Duration(2.0)) 00055 00056 00057 @staticmethod 00058 def broadcast_transform(frame_id, pose,time = None, period = rospy.Duration(0.1)): 00059 if frame_id in TFUtil.broadcast_list: 00060 with TFUtil.broadcast_lock: 00061 TFUtil.broadcast_list[frame_id] = (pose, time, period) 00062 else: 00063 broadcast_thread = threading.Thread( 00064 target=TFUtil.broadcast_loop, 00065 name='TFUtil Broadcaster: \'%s\'' % frame_id, 00066 args=[frame_id]) 00067 TFUtil.broadcast_list[frame_id] = (pose,time,period) 00068 TFUtil.broadcast_threads[frame_id] = broadcast_thread 00069 broadcast_thread.start() 00070 00071 @staticmethod 00072 def stop_broadcasting_transform(frame_id): 00073 if frame_id in TFUtil.broadcast_list: 00074 with TFUtil.broadcast_lock: 00075 del TFUtil.broadcast_list[frame_id] 00076 00077 @staticmethod 00078 def broadcast_loop(frame_id): 00079 while not rospy.is_shutdown(): 00080 with TFUtil.broadcast_lock: 00081 if frame_id not in TFUtil.broadcast_list: 00082 break 00083 pose, time, period = TFUtil.broadcast_list[frame_id] 00084 if time is None: 00085 time = rospy.Time.now() 00086 TFUtil.broadcaster.sendTransform( 00087 [pose.pose.position.x, pose.pose.position.y, pose.pose.position.z], 00088 [pose.pose.orientation.x,pose.pose.orientation.y,pose.pose.orientation.z,pose.pose.orientation.w], 00089 time, 00090 frame_id, 00091 pose.header.frame_id) 00092 rospy.sleep(period) 00093