ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Setting up your robot using tf, migration to tf2

asked 2018-08-23 06:02:35 -0500

gavindvs gravatar image

updated 2018-08-28 06:02:39 -0500

Hi all,

I am following the tutorial from this link here: http://wiki.ros.org/navigation/Tutori... Noticed that it is using tf, however I would like to code it in tf2 seeing I have gone through the tf2 tutorials.

For the broadcaster file I had converted the original tf version which is this:

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>

int main(int argc, char** argv){
  ros::init(argc, argv, "robot_tf_publisher");
  ros::NodeHandle n;

  ros::Rate r(100);

  tf::TransformBroadcaster broadcaster;

  while(n.ok()){
    broadcaster.sendTransform(
      tf::StampedTransform(
        tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)),
        ros::Time::now(),"base_link", "base_laser"));
    r.sleep();
  }
}

To the tf2 version which I did up here (not sure if I did it correctly):

#include <ros/ros.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
#include <geometry_msgs/TransformStamped.h>

int main(int argc, char** argv){
  ros::init(argc, argv, "robot_tf2_ros_publisher");
  ros::NodeHandle n;

  ros::Rate r(100);

  tf2_ros::TransformBroadcaster broadcaster;
  geometry_msgs::TransformStamped transformStamped;

  while(n.ok()){
    transformStamped.header.stamp = ros::Time::now();
    transformStamped.header.frame_id = "base_link";
    transformStamped.child_frame_id = "base_laser";
    transformStamped.transform.translation.x = 0.1;
    transformStamped.transform.translation.y = 0.0;
    transformStamped.transform.translation.z = 0.2;
    transformStamped.transform.rotation.x = 0;
    transformStamped.transform.rotation.y = 0;
    transformStamped.transform.rotation.z = 0;
    transformStamped.transform.rotation.w = 1;
    broadcaster.sendTransform(transformStamped);
    r.sleep();
  }
}

As for the listener file, I'm not sure how to convert it into the tf2 version :(

The original tf version of the listener file is as follows:

#include <ros/ros.h>
#include <geometry_msgs/PointStamped.h>
#include <tf/transform_listener.h>

void transformPoint(const tf::TransformListener& listener){
  //we'll create a point in the base_laser frame that we'd like to transform to the base_link frame
  geometry_msgs::PointStamped laser_point;
  laser_point.header.frame_id = "base_laser";

  //we'll just use the most recent transform available for our simple example
  laser_point.header.stamp = ros::Time();

  //just an arbitrary point in space
  laser_point.point.x = 1.0;
  laser_point.point.y = 0.2;
  laser_point.point.z = 0.0;

  try{
    geometry_msgs::PointStamped base_point;
    listener.transformPoint("base_link", laser_point, base_point);

    ROS_INFO("base_laser: (%.2f, %.2f. %.2f) -----> base_link: (%.2f, %.2f, %.2f) at time %.2f",
        laser_point.point.x, laser_point.point.y, laser_point.point.z,
        base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec());
  }
  catch(tf::TransformException& ex){
    ROS_ERROR("Received an exception trying to transform a point from \"base_laser\" to \"base_link\": %s", ex.what());
  }
}

int main(int argc, char** argv){
  ros::init(argc, argv, "robot_tf_listener");
  ros::NodeHandle n;

  tf::TransformListener listener(ros::Duration(10));

  //we'll transform a point once every second
  ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));

  ros::spin();

}

If anyone would be able to help it would be very much appreciated.


Edit: Followed ur suggestions and changed the code. However I am getting errors :(

Listed the errors below -

/home/gavin/catkin_ws/src/robot_setup_tf/src/tf_listener.cpp: In function ‘void transformPoint(const tf2_ros::TransformListener&)’:
/home/gavin/catkin_ws/src/robot_setup_tf/src/tf_listener ...
(more)
edit retag flag offensive close merge delete

Comments

@gavindvs: could I ask you to not post answers unless you are answering your own question? To interact with other posters, please use comments. To update us on things that require more characters (ie: code, console logs, etc), please edit your original question. Use the edit button/link.

gvdhoorn gravatar image gvdhoorn  ( 2018-08-24 02:17:35 -0500 )edit

See my update, there are three errors in your code you need to fix.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-08-24 03:25:55 -0500 )edit

@gvdhoorn: ah ok sorry about that

gavindvs gravatar image gavindvs  ( 2018-08-24 22:11:57 -0500 )edit

@PeteBlackerThe3rd: did the updates you suggested tho am still getting an error :\ Not sure what I'm doing wrong. Edited my original post.

gavindvs gravatar image gavindvs  ( 2018-08-24 22:13:21 -0500 )edit

Almost there, the type of the parameter passed to the transform function should be tf2_ros::Buffer as below.

void transform(const tf2_ros::Buffer& tfBuffer)

Then I think you'll be there.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-08-25 05:48:58 -0500 )edit

@PeteBlackerThe3rd: made the edit you suggested though got a set of errors, as listed in my latest edit :(

gavindvs gravatar image gavindvs  ( 2018-08-25 22:05:15 -0500 )edit

That's my mistake this time. The order of the parameters is different to the old transformPoint method. The transform line should be: tfBuffer.transform(laser_point, base_point, "base_link");

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-08-26 12:27:46 -0500 )edit

@PeteBlackerThe3rd changed the parameters tho got a whole string of errors :\ listed them in my latest edit.

gavindvs gravatar image gavindvs  ( 2018-08-28 05:14:29 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2018-08-23 06:50:53 -0500

updated 2018-08-24 03:25:31 -0500

There are four things you'll need to change. The creation of the listener will need to be this:

tf2_ros::Buffer tfBuffer(ros::Duration(10));
tf2_ros::TransformListener tfListener(tfBuffer);

You'll have to pass the tfBuffer object to the transformPoint function instead of the listener object.

The transform point operation can be done using the transform method of the buffer object:

tfBuffer.transform("base_link", laser_point, base_point);

Finally the type of the exception object will need to be changed to:

catch (tf2::TransformException &ex)
...

Hope this helps.

UPDATE :

3 things, if you look carefully there are a few differences between your new code and what I suggested.

  1. The namespace of TransformException should be tf2 not tf2_ros
  2. You're still passing the listener object to transform point you need to change this to the Buffer object.
  3. The method used to transform the point is now called transform not transformPoint.
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-08-23 06:02:35 -0500

Seen: 324 times

Last updated: Aug 28 '18