00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 import roslib; roslib.load_manifest('tf2_ros')
00031 import rospy
00032 import tf2
00033 import tf2_ros
00034 from tf2_msgs.srv import FrameGraph, FrameGraphResponse
00035 import rosgraph.masterapi
00036
00037 class Buffer(tf2.BufferCore, tf2_ros.BufferInterface):
00038 def __init__(self, cache_time = None, debug = True):
00039 if cache_time != None:
00040 tf2.BufferCore.__init__(self, cache_time)
00041 else:
00042 tf2.BufferCore.__init__(self)
00043 tf2_ros.BufferInterface.__init__(self)
00044
00045 if debug:
00046
00047 try:
00048 m = rosgraph.masterapi.Master(rospy.get_name())
00049 m.lookupService('~tf2_frames')
00050 except (rosgraph.masterapi.Error, rosgraph.masterapi.Failure):
00051 self.frame_server = rospy.Service('~tf2_frames', FrameGraph, self.__get_frames)
00052
00053 def __get_frames(self, req):
00054 return FrameGraphResponse(self.all_frames_as_yaml())
00055
00056
00057 def lookup_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)):
00058 self.can_transform(target_frame, source_frame, time, timeout)
00059 return self.lookup_transform_core(target_frame, source_frame, time)
00060
00061
00062 def lookup_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)):
00063 self.can_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout)
00064 return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)
00065
00066
00067
00068 def can_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)):
00069 if timeout != rospy.Duration(0.0):
00070 start_time = rospy.Time.now()
00071 while (rospy.Time.now() < start_time + timeout and
00072 not self.can_transform_core(target_frame, source_frame, time)):
00073 rospy.Duration(0.05).sleep()
00074 return self.can_transform_core(target_frame, source_frame, time)
00075
00076
00077 def can_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)):
00078 if timeout != rospy.Duration(0.0):
00079 start_time = rospy.Time.now()
00080 while (rospy.Time.now() < start_time + timeout and
00081 not self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)):
00082 rospy.Duration(0.05).sleep()
00083 return self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)
00084