{{{#!wiki tip Using ROS 2? Check out the [[https://docs.ros.org/en/rolling/Tutorials/Intermediate/Tf2/Tf2-Main.html|ROS 2 tf2 tutorials]]. }}} #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = This tutorial assumes you have completed the writing a tf2 broadcaster tutorial [[tf2/Tutorials/Writing a tf2 broadcaster (Python)|(Python)]] [[tf2/Tutorials/Writing a tf2 broadcaster (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 =Writing a tf2 listener (C++) ## multi-line description to be displayed in search ## description = This tutorial teaches you how to use tf2 to get access to frame transformations. ## the next tutorial description (optional) ## next = Adding a frame ## links to next tutorial (optional) ## next.0.link=[[tf2/Tutorials/Adding a frame (C++)|(C++)]] ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = #################################### <> <> ##introstart In the previous tutorials we created a tf2 broadcaster to publish the pose of a turtle to tf2. In this tutorial we'll create a tf2 listener to start using tf2. == How to create a tf2 listener == Let's first create the source files. Go to the package we created in the previous tutorial: {{{ $ roscd learning_tf2 }}} ##introend === The Code === Fire up your favorite editor and paste the following code into a new file called `src/turtle_tf2_listener.cpp`. {{{#!cplusplus block=listener #include #include #include #include #include int main(int argc, char** argv){ ros::init(argc, argv, "my_tf2_listener"); ros::NodeHandle node; ros::service::waitForService("spawn"); ros::ServiceClient spawner = node.serviceClient("spawn"); turtlesim::Spawn turtle; turtle.request.x = 4; turtle.request.y = 2; turtle.request.theta = 0; turtle.request.name = "turtle2"; spawner.call(turtle); ros::Publisher turtle_vel = node.advertise("turtle2/cmd_vel", 10); tf2_ros::Buffer tfBuffer; tf2_ros::TransformListener tfListener(tfBuffer); ros::Rate rate(10.0); while (node.ok()){ geometry_msgs::TransformStamped transformStamped; try{ transformStamped = tfBuffer.lookupTransform("turtle2", "turtle1", ros::Time(0)); } catch (tf2::TransformException &ex) { ROS_WARN("%s",ex.what()); ros::Duration(1.0).sleep(); continue; } geometry_msgs::Twist vel_msg; vel_msg.angular.z = 4.0 * atan2(transformStamped.transform.translation.y, transformStamped.transform.translation.x); vel_msg.linear.x = 0.5 * sqrt(pow(transformStamped.transform.translation.x, 2) + pow(transformStamped.transform.translation.y, 2)); turtle_vel.publish(vel_msg); rate.sleep(); } return 0; }; }}} === The Code Explained === Now, let's take a look at the code that is relevant to publishing the turtle pose to tf2. {{{ #include }}} The tf2 package provides an implementation of a `TransformListener` to help make the task of receiving transforms easier. To use the `TransformListener`, we need to include the `tf2/transform_listener.h` header file. {{{ tf2_ros::Buffer tfBuffer; tf2_ros::TransformListener tfListener(tfBuffer); }}} Here, we create a `TransformListener` object. Once the listener is created, it starts receiving tf2 transformations over the wire, and buffers them for up to 10 seconds. The `TransformListener` object should be scoped to persist otherwise its cache will be unable to fill and almost every query will fail. A common method is to make the `TransformListener` object a member variable of a class. {{{ try{ transformStamped = tfBuffer.lookupTransform("turtle2", "turtle1", ros::Time(0)); } catch (tf2::TransformException &ex) { ROS_WARN("%s",ex.what()); ros::Duration(1.0).sleep(); continue; } }}} Here, the real work is done, we query the listener for a specific transformation. Let's take a look at the four arguments (full details of lookupTransform() found [[http://docs.ros.org/indigo/api/tf2_ros/html/c++/classtf2__ros_1_1BufferClient.html|here]].) 1. We want the transform to this frame (target frame) ... 1. ... from this frame (source frame). 1. The time at which we want to transform. Providing `ros::Time(0)` will just get us the latest available transform. 1. Duration before timeout. (optional, default=ros::Duration(0.0)) All this is wrapped in a `try-catch` block to catch possible exceptions. == Running the listener == Now that we created the code, lets compile it first. Open the `CMakeLists.txt` file and insert : {{{ add_executable(turtle_tf2_listener src/turtle_tf2_listener.cpp) target_link_libraries(turtle_tf2_listener ${catkin_LIBRARIES} ) }}} If everything went well, you should have a binary file called `turtle_tf2_listener` in your `bin` folder. If so, we're ready add it the launch file for this demo. With your text editor, open the launch file called `start_demo.launch`, and merge the node block below inside the `` block: {{{ ... }}} ##checkingstart First, make sure you stopped the launch file from the previous tutorial (use ctrl-c). Now you're ready to start your full turtle demo: {{{ $ roslaunch learning_tf2 start_demo.launch }}} You should see the turtle sim with '''two''' turtles. == Checking the results == To see if things work, simply drive around the first turtle using the arrow keys (make sure your terminal window is active, not your simulator window), and you'll see the second turtle following the first one! When the turtlesim starts up you may see: . {{{ [ERROR] [1418082761.220546623]: "turtle2" passed to lookupTransform argument target_frame does not exist. [ERROR] [1418082761.320422000]: "turtle2" passed to lookupTransform argument target_frame does not exist. }}} This happens because our listener is trying to compute the transform before turtle 2 is spawned in turtlesim and broadcasting a tf2 frame. == Transforming poses, points, etc. from frame to frame == Now that you know the transform from frame "turtle1" to frame "turtle2", you can transform vectors from one to the other. See [[tf2/Tutorials/Using stamped datatypes with tf2::MessageFilter|(Using Stamped datatypes with tf2_ros::MessageFilter)]] Now you're ready to move on to the next tutorial, where you'll learn how to add a frame [[tf2/Tutorials/Adding a frame (Python)|(Python)]] [[tf2/Tutorials/Adding a frame (C++)|(C++)]] ##checkingend ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## TutorialTurtlesim ## C++Category ## LearningCategory