Go to the documentation of this file.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
00031
00032
00033
00034
00035
00036
00037 PKG = 'tf2_ros'
00038 import roslib; roslib.load_manifest(PKG)
00039 import rospy
00040 import actionlib
00041 import tf2
00042 import tf2_ros
00043
00044 from tf2_msgs.msg import LookupTransformAction, LookupTransformGoal
00045 from actionlib_msgs.msg import GoalStatus
00046
00047 class BufferClient(tf2_ros.BufferInterface):
00048 def __init__(self, ns, check_frequency = 10.0, timeout_padding = rospy.Duration.from_sec(2.0)):
00049 tf2_ros.BufferInterface.__init__(self)
00050 self.client = actionlib.SimpleActionClient(ns, LookupTransformAction)
00051 self.check_frequency = check_frequency
00052 self.timeout_padding = timeout_padding
00053
00054 def wait_for_server(self, timeout = rospy.Duration()):
00055 return self.client.wait_for_server(timeout)
00056
00057
00058 def lookup_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)):
00059 goal = LookupTransformGoal()
00060 goal.target_frame = target_frame;
00061 goal.source_frame = source_frame;
00062 goal.source_time = time;
00063 goal.timeout = timeout;
00064 goal.advanced = False;
00065
00066 return self.__process_goal(goal)
00067
00068
00069 def lookup_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)):
00070 goal = LookupTransformGoal()
00071 goal.target_frame = target_frame;
00072 goal.source_frame = source_frame;
00073 goal.source_time = source_time;
00074 goal.timeout = timeout;
00075 goal.target_time = target_time;
00076 goal.fixed_frame = fixed_frame;
00077 goal.advanced = True;
00078
00079 return self.__process_goal(goal)
00080
00081
00082 def can_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)):
00083 try:
00084 self.lookup_transform(target_frame, source_frame, time, timeout)
00085 return True
00086 except tf2.TransformException:
00087 return False
00088
00089
00090
00091 def can_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)):
00092 try:
00093 self.lookup_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout)
00094 return True
00095 except tf2.TransformException:
00096 return False
00097
00098 def __is_done(self, state):
00099 if state == GoalStatus.REJECTED or state == GoalStatus.ABORTED or \
00100 state == GoalStatus.RECALLED or state == GoalStatus.PREEMPTED or \
00101 state == GoalStatus.SUCCEEDED or state == GoalStatus.LOST:
00102 return True
00103 return False
00104
00105 def __process_goal(self, goal):
00106 self.client.send_goal(goal)
00107 r = rospy.Rate(self.check_frequency)
00108 timed_out = False
00109 start_time = rospy.Time.now()
00110 while not rospy.is_shutdown() and not self.__is_done(self.client.get_state()) and not timed_out:
00111 if rospy.Time.now() > start_time + goal.timeout + self.timeout_padding:
00112 timed_out = True
00113 r.sleep()
00114
00115
00116 if timed_out:
00117 self.client.cancel_goal()
00118 raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server")
00119
00120 if self.client.get_state() != GoalStatus.SUCCEEDED:
00121 raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back with SUCCEEDED status. Something is likely wrong with the server.")
00122
00123 return self.__process_result(self.client.get_result())
00124
00125 def __process_result(self, result):
00126 if result == None or result.error == None:
00127 raise tf2.TransformException("The BufferServer returned None for result or result.error! Something is likely wrong with the server.")
00128 if result.error.error != result.error.NO_ERROR:
00129 if result.error.error == result.error.LOOKUP_ERROR:
00130 raise tf2.LookupException(result.error.error_string)
00131 if result.error.error == result.error.CONNECTIVITY_ERROR:
00132 raise tf2.ConnectivityException(result.error.error_string)
00133 if result.error.error == result.error.EXTRAPOLATION_ERROR:
00134 raise tf2.ExtrapolationException(result.error.error_string)
00135 if result.error.error == result.error.INVALID_ARGUMENT_ERROR:
00136 raise tf2.InvalidArgumentException(result.error.error_string)
00137 if result.error.error == result.error.TIMEOUT_ERROR:
00138 raise tf2.TimeoutException(result.error.error_string)
00139
00140 raise tf2.TransformException(result.error.error_string)
00141
00142 return result.transform
00143