Setting up your robot using tf, migration to tf2
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 ...
@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.See my update, there are three errors in your code you need to fix.
@gvdhoorn: ah ok sorry about that
@PeteBlackerThe3rd: did the updates you suggested tho am still getting an error :\ Not sure what I'm doing wrong. Edited my original post.
Almost there, the type of the parameter passed to the transform function should be tf2_ros::Buffer as below.
Then I think you'll be there.
@PeteBlackerThe3rd: made the edit you suggested though got a set of errors, as listed in my latest 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 changed the parameters tho got a whole string of errors :\ listed them in my latest edit.