## page was renamed from tf/Tutorials/tf and Time #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = This tutorial assumes you have completed the adding a frame tutorial [[tf/Tutorials/Adding a frame (Python)|(Python)]] [[tf/Tutorials/Adding a frame (C++)|(C++)]] ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Learning about tf and time (Python) ## multi-line description to be displayed in search ## description = This tutorial teaches you to use the `waitForTransform` function to wait for a transform to be available on the `tf` tree. ## the next tutorial description (optional) ## next = Time travel with tf ## links to next tutorial (optional) ## next.0.link=[[tf/Tutorials/Time travel with tf (Python)|(Python)]] ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = #################################### <<IncludeCSTemplate(TutorialCSHeaderTemplate)>> {{{#!wiki caution tf is deprecated in favor of [[tf2]]. [[tf2]] provides a superset of the functionality of tf and is actually now the implementation under the hood. If you're just learning now it's strongly recommended to use the [[tf2/Tutorials]] instead. }}} <<TableOfContents(4)>> <<Include(tf/Tutorials/tf and Time (C++),,from="##introstart",to="##introend")>> Edit '''`nodes/turtle_tf_listener.py`''' and change the `lookupTransform()` call and `except` statement to: {{{#!python try: now = rospy.Time.now() (trans,rot) = listener.lookupTransform("/turtle2", "/carrot1", now) except (tf.LookupException, tf.ConnectivityException): }}} So, all of the sudden `lookupTransform()` is failing, telling you: {{{ Traceback (most recent call last): File "~/ros/pkgs/wg-ros-pkg-trunk/sandbox/learning_tf/nodes/turtle_tf_listener.py", line 25, in <module> (trans,rot) = listener.lookupTransform('/turtle2', '/carrot1', now) tf.ExtrapolationException: Extrapolation Too Far in the future: target_time is 1253830476.460, but the closest tf data is at 1253830476.435 which is 0.024 seconds away.Extrapolation Too Far in the future: target_time is 1253830476.460, but the closest tf data is at 1253830476.459 which is 0.001 seconds away.Extrapolation Too Far from single value: target_time is 1253830476.460, but the closest tf data is at 1253830476.459 which is 0.001 seconds away. See http://pr.willowgarage.com/pr-docs/ros-packages/tf/html/faq.html for more info. When trying to transform between /carrot1 and /turtle2. See http://www.ros.org/wiki/tf#Frequently_Asked_Questions }}} Or if you're using `electric`, message might look something like this: {{{ Traceback (most recent call last): File "/home/rosGreat/ROS_tutorial/learning_tf/nodes/turtle_tf_listener.py", line 28, in <module> (trans,rot) = listener.lookupTransform('/turtle2', '/carrot1', now) tf.ExtrapolationException: Lookup would require extrapolation into the future. Requested time 1319591145.491288900 but the latest data is at time 1319591145.490932941, when looking up transform from frame [/carrot1] to frame [/turtle2] }}} <<Include(tf/Tutorials/tf and Time (C++),,from="##lookupstart",to="##lookupend")>> {{{#!python listener.waitForTransform("/turtle2", "/carrot1", rospy.Time(), rospy.Duration(4.0)) while not rospy.is_shutdown(): try: now = rospy.Time.now() listener.waitForTransform("/turtle2", "/carrot1", now, rospy.Duration(4.0)) (trans,rot) = listener.lookupTransform("/turtle2", "/carrot1", now) }}} The `waitForTransform()` takes four arguments: 1. Wait for the transform from this frame... 2. ... to this frame, 3. at this time, and 4. timeout: don't wait for longer than this maximum duration So `waitForTransform()` will actually block until the transform between the two turtles becomes available (this will usually take a few milli-seconds), OR --if the transform does not become available-- until the timeout has been reached. So why the two `waitForTransform()` calls? At the beginning of code we spawned `turtle2` but tf may have not ever seen the `/turtle2` frame before waiting for the transform. The first `waitForTransform()` will wait until the `/turtle2` frame is broadcast on tf before trying to `waitForTransform()` at time `now`. <<Include(tf/Tutorials/tf and Time (C++),,from="##checkingstart",to="##checkingend")>> ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## TutorialTurtlesim ## PythonCategory ## LearningCategory