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

transform pointcloud with tf2

asked 2017-05-20 05:28:02 -0500

MrC11 gravatar image

updated 2017-05-22 07:23:45 -0500

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

edit retag flag offensive close merge delete

Comments

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 rather tf2_ros::TransformListener.

lucasw gravatar image lucasw  ( 2017-05-21 13:38:10 -0500 )edit

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?

MrC11 gravatar image MrC11  ( 2017-05-22 05:51:12 -0500 )edit

Oh I see it here http://docs.ros.org/jade/api/tf2/html... , PointCloud2 must be a compatible type for the template

lucasw gravatar image lucasw  ( 2017-05-22 11:20:23 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
9

answered 2017-05-22 06:56:16 -0500

updated 2017-05-22 07:29:30 -0500

Looks good what you are doing and works for me!

What you actually have is a linking error. Do you link against the tf2 libraries?

So specially:

find_package(catkin REQUIRED COMPONENTS
  roscpp
  tf2
  tf2_ros
  tf2_msgs
  tf2_sensor_msgs
  geometry_msgs
  sensor_msgs
)

 target_link_libraries(your_node_name
    ${catkin_LIBRARIES}
)

Update:

Can you also update your Headers so everthing is includes correctly:

#include <tf2_ros/buffer.h>
#include <tf2/transform_datatypes.h>
#include <tf2_sensor_msgs/tf2_sensor_msgs.h>

I hope I dont forget one.

edit flag offensive delete link more

Comments

Hello,

it still isn't working (Edited main question). I really don't know why it isn't working..

Best regards, Maurice

MrC11 gravatar image MrC11  ( 2017-05-22 07:10:40 -0500 )edit

Its still a linking error. Can you also add sensor_msgs to the the catkon packages and try again?

chwimmer gravatar image chwimmer  ( 2017-05-22 07:15:27 -0500 )edit

Ah and please always update your Question and dont post answers!

chwimmer gravatar image chwimmer  ( 2017-05-22 07:16:04 -0500 )edit

I added the sensor_msgs to catkin_packages, but still the same error.

I updated the main question, you can look over there for the up-to-date CMakelists

MrC11 gravatar image MrC11  ( 2017-05-22 07:21:03 -0500 )edit
5

Thank you! I didn't include the right messages.

This was the one i needed:

#include <tf2_sensor_msgs/tf2_sensor_msgs.h>

Thank you very much!

MrC11 gravatar image MrC11  ( 2017-05-22 07:38:53 -0500 )edit

perfect! You are welcome

chwimmer gravatar image chwimmer  ( 2017-05-22 07:41:32 -0500 )edit
2

answered 2018-09-27 10:52:32 -0500

lucasw gravatar image

updated 2018-09-27 10:53:45 -0500

I've made a node (maybe later I will make it a nodelet) that uses tf2 to transform PointCloud2 messages https://github.com/lucasw/transform_p... in both C++ and python, and it uses dynamic reconfigure to control what frames are used in the transform. It can serve as an example and is useful as a standalone node to transform point clouds.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-05-20 05:28:02 -0500

Seen: 8,863 times

Last updated: Sep 27 '18