transform pointcloud with tf2
Hello,
I have two tf2 frames in ROS "World" and "Robot" the world is on position 0, 0, 0 and the Robot is on different position, it is a moving robot, but for now let say he is on position 8, 4, 6.
I have a kinect v2 hooked up on ROS with the iai_bridge, so i get the pointclouds on a topic. The problem is when i lookup the transformation between the world and transform the given camera on frame "World" pointcloud to the "Robot" pointcloud the compiler gives me an error.
The code:
#include <ros/ros.h>
#include <tf2_ros/transform_listener.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf2/convert.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "my_tf2_listener");
ros::NodeHandle node;
tf2_ros::Buffer tfBuffer;
tf2_ros::TransformListener tfListener(tfBuffer);
sensor_msgs::PointCloud2 cloud_in, cloud_out;
ros::Rate rate(10.0);
while (node.ok()) {
geometry_msgs::TransformStamped transformStamped;
try {
transformStamped = tfBuffer.lookupTransform("world", "robotarm",
ros::Time(0));
std::cout << transformStamped << std::endl;
tf2::doTransform(cloud_in, cloud_out, transformStamped);
// pcl_ros::transformPointCloud("robotarm", cloud_in, cloud_out, tfListener);
} catch (tf2::TransformException &ex) {
ROS_WARN("%s", ex.what());
ros::Duration(1.0).sleep();
continue;
}
rate.sleep();
}
return 0;
}
;
My CMakeLists:
cmake_minimum_required(VERSION 2.8.3)
project(learning_tf2)
add_definitions(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
roscpp
tf2
tf2_ros
tf2_msgs
tf2_sensor_msgs
geometry_msgs
sensor_msgs
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(turtle_tf2_listener src/turtle_tf2_listener.cpp)
target_link_libraries(turtle_tf2_listener
${catkin_LIBRARIES}
)
add_executable(frame_tf2_broadcaster src/frame_tf2_broadcaster.cpp)
target_link_libraries(frame_tf2_broadcaster
${catkin_LIBRARIES}
)
And the error:
CMakeFiles/turtle_tf2_listener.dir/src/turtle_tf2_listener.cpp.o: In function `main':
turtle_tf2_listener.cpp:(.text+0x316): undefined reference to `void tf2::doTransform<sensor_msgs::PointCloud2_<std::allocator<void> > >(sensor_msgs::PointCloud2_<std::allocator<void> > const&, sensor_msgs::PointCloud2_<std::allocator<void> >&, geometry_msgs::TransformStamped_<std::allocator<void> > const&)'
collect2: error: ld returned 1 exit status
learning_tf2/CMakeFiles/turtle_tf2_listener.dir/build.make:117: recipe for target 'learning_tf2/turtle_tf2_listener' failed
And finally, all the installed ros TF packages, all from the ubuntu repo's:
ros-kinetic-tf2
ros-kinetic-tf2-eigen
ros-kinetic-tf2-geometry-msgs
ros-kinetic-tf2-kdl
ros-kinetic-tf2-msgs
ros-kinetic-tf2-py
ros-kinetic-tf2-ros
ros-kinetic-tf2-sensor-msgs
ros-kinetic-tf2-tools
My question: How can I transform the pointcloud so that the pointcloud is transformed from the "World" frame to the "Robot" frame?
Best Regards, Maurice
It looks like doTransform isn't defined for PointCloud2 http://docs.ros.org/jade/api/tf2_geom... . I was going to suggest using
pcl_ros::transformPointCloud
, but I think you'd have to use a regular tf listener rathertf2_ros::TransformListener
.Hello, I don't get your comment. Could you please explain it a little bit better? How can I transform it in this little project?
Oh I see it here http://docs.ros.org/jade/api/tf2/html... , PointCloud2 must be a compatible type for the template