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

How to transform PointCloud2 with TF?

asked 2011-02-16 19:37:06 -0600

Captain gravatar image

updated 2011-02-17 06:46:10 -0600

Eric Perko gravatar image

Hi,

I'm writing a small node aggregating data from a Kinect sensor (PointCloud2) taken from different angle of view. I therefore use the tf library to transform all images in the /world frame before aggregating them with the pcl lib.

After looking through tf API doc, I found the TransformListener::transformPointCloud function to tranform PointCloud messages but nothing to transform PointCloud2 messages. I am therefore using a code like this:

sensor_msgs::convertPointCloud2ToPointCloud(pc2SensorFrame,pcSensorFrame) TfListener.transformPointCloud("/world", pcSensorFrame, pcWorldFrame); sensor_msgs::convertPointCloudToPointCloud2(pcWorldFrame,pc2WorldFrame) pcl::fromROSMsg(pc2WorldFrame,pclCloud);

It seems to work but I was wondering if there was a more direct way to transform PointCloud2 with tf avoiding the conversion in PointCloud.

Thanks

edit retag flag offensive close merge delete

4 Answers

Sort by » oldest newest most voted
11

answered 2011-02-16 20:25:09 -0600

Lorenz gravatar image

updated 2017-11-09 18:25:00 -0600

peci1 gravatar image

I guess you are looking for the pcl_ros package. It contains functions to do exactly what you want. Have a look here:

http://docs.ros.org/api/pcl_ros/html/...

edit flag offensive delete link more

Comments

Why is the page not available now? PCL ROS has been taken out or what?

lahiruherath gravatar image lahiruherath  ( 2017-11-09 14:51:48 -0600 )edit
1

This is a very old link. We've moved the documentation years ago to docs.ros.org It's now at: http://docs.ros.org/api/pcl_ros/html/... In the future if you're looking for docs visit the wiki page for a package eg http://wiki.ros.org/pcl_ros and click on the Code API link.

tfoote gravatar image tfoote  ( 2017-11-09 15:21:10 -0600 )edit

Thanks :). Managed to get this done using tf2. Had to do some blind manipulations since i was using python

lahiruherath gravatar image lahiruherath  ( 2017-11-09 18:05:19 -0600 )edit
1

answered 2015-08-13 18:19:59 -0600

peci1 gravatar image

updated 2020-07-16 23:16:39 -0600

You can transform using the tf2_sensor_msgs (both C++ and Python interface, since at least Indigo):

#include <tf2_sensor_msgs/tf2_sensor_msgs.h>
#include <sensor_msgs/PointCloud2.h>
#include <geometry_msgs/TransformStamped.h>

const sensor_msgs::PointCloud2 cloud_in, cloud_out;
const geometry_msgs::TransformStamped transform;
// TODO load everything
tf2::doTransform (cloud_in, cloud_out, transform);

Or in Python:

from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
cloud_out = do_transform_cloud(cloud_in, transform)

Please note that all of these transform functions only transform the x,y,z channel. If your pointcloud contains viewpoints or normals, you'd have to transform them yourself.

edit flag offensive delete link more

Comments

I get a tf2_sensor_msgs.pycannot import name read_cloud error in Indigo. Is the transform the return value of a lookupTransform?

lucasw gravatar image lucasw  ( 2015-08-14 17:16:14 -0600 )edit
1

You're right, @lucasw, there seems to be a bug in do_transform_cloud . I've reported it here: https://github.com/ros/geometry_exper... .

peci1 gravatar image peci1  ( 2015-08-17 04:17:59 -0600 )edit
1

Until the bug gets fixed, you can manually copy&paste the code of the method's body and change read_cloud to read_points . The method body is here: https://github.com/ros/geometry_exper...

peci1 gravatar image peci1  ( 2015-08-17 04:18:47 -0600 )edit

Have anyone got this to work? Seems to be deprecated.

Azergoo gravatar image Azergoo  ( 2018-07-10 11:48:07 -0600 )edit

I tried using this method (in python) but it somehow doesn't work as expected. That's why I used a transformation with 0 translation and 0 rotation to test, but it nevertheless changes my pointcloud. Anyone expericened something like this?

rosNewbie gravatar image rosNewbie  ( 2020-01-02 16:29:21 -0600 )edit

I keep getting compilation errors when trying to include tf2_sensor_msgs.h Is is this code depreciated?

M@t gravatar image M@t  ( 2020-07-15 22:01:45 -0600 )edit

No, the code still works great. You have to add a build dependency on tf2_sensor_msgs to your CMakeLists.txt and package.xml (and you have to actually install the package, e.g. ros-melodic-tf2-sensor-msgs).

peci1 gravatar image peci1  ( 2020-07-16 03:22:58 -0600 )edit

Ah, the bit I was missing is that the include needs to be #include <tf2_sensor_msgs/tf2_sensor_msgs.h> Now it works

M@t gravatar image M@t  ( 2020-07-16 23:13:03 -0600 )edit
1

answered 2017-07-13 13:18:28 -0600

Gayan Brahmanage gravatar image

updated 2017-12-06 13:45:09 -0600

This is a simple code to transform scan point cloud to base link. Use a separate script for class laser_to_points2d: for ease of use.

from math import sin, cos
import tf
import numpy as np
from sensor_msgs.msg import PointCloud
from geometry_msgs.msg import Point32

 class laser_to_points2d:
    def __init__(self,):
        self.base_link_point2d=PointCloud()
        self.base_link_point2d.header.frame_id = "base_link" 

    def update(self,scandata,angle_min,angle_max,angle_increment):
        self.base_link_point2d.points=[]
        self.base_link_point2d.channels=[]

        for i in xrange(len(scandata)):     
            angle=angle_min+i*angle_increment
            if not math.isnan(scandata[i]):
                r=scandata[i]
            else:r=0.0 

            px=float(r)*cos(angle)
            py=float(r)*sin(angle)
            self.base_link_point2d.points.append(Point32(px,py, 0.0))
            self.base_link_point2d.channels.append(0)# add some information if needed

You need to listen to the transformation for Odom to base_link and subscribe the scan topic

import rospy
import roslib
from sensor_msgs.msg import LaserScan
import tf
from file_name_your_ class _laser_to_points2d import laser_to_points2d

def scanCb(msg):
    py,px=[],[]
    scandata=msg.ranges
    angle_min=msg.angle_min
    angle_max=msg.angle_max
    angle_increment=msg.angle_increment
    range_min=msg.range_min
    range_max=msg.range_max
    points2d.update(scandata,angle_min,angle_max,angle_increment)

if __name__ == "__main__":

    rospy.init_node('main', anonymous=True) #make node  
    rospy.Subscriber("/scan", LaserScan, scanCb,queue_size = 1) 
    rate = rospy.Rate(5) # 5hz         
    points2d=laser_to_points2d()
    listener = tf.TransformListener()           
    while not rospy.is_shutdown():

        listener.waitForTransform("/base_link", "/odom", rospy.Time(0),rospy.Duration(1.0))     
        p=listener.transformPointCloud("odom",points2d.base_link_point2d)   
        rate.sleep()
edit flag offensive delete link more

Comments

As is, this won't run. You'll need to indent everything after the if __name__ == "__main__":

jayess gravatar image jayess  ( 2017-07-13 16:38:52 -0600 )edit

Hi Gayan, I first created named laserTF package. After that I created two python files named lasertf.py and laserTransform.py in the packaged src file I created. I pasted the code above into the lasertf file and the code below into the laserTransform file.

Mekateng gravatar image Mekateng  ( 2017-08-11 07:01:50 -0600 )edit

And file name your class at the time I wrote lasertf. But ı got an error like below Traceback (most recent call last): File "/home/ahmet/catkin_ws/src/laserTF/src/laserTransform.py", line 2, in <module> import rospy .... Can I learn the reason for this ?

Mekateng gravatar image Mekateng  ( 2017-08-11 07:04:35 -0600 )edit
1

@Mekateng, you should create a new question and reference this question.

jayess gravatar image jayess  ( 2017-08-11 10:06:53 -0600 )edit

I couldn't create new question . Mr foote is closing my questions.

Mekateng gravatar image Mekateng  ( 2017-08-11 11:17:06 -0600 )edit
1

Just follow the guidelines as @tfoote said and they won't get closed.

jayess gravatar image jayess  ( 2017-08-11 11:53:26 -0600 )edit

ı had asked my question to Gayan. but if you want to reply my question ,ı am looking forward to wait your answer bro

Mekateng gravatar image Mekateng  ( 2017-08-11 16:26:35 -0600 )edit

I will, just ask a new question. Comments aren't the place for asking and answering new questions.

jayess gravatar image jayess  ( 2017-08-11 16:28:47 -0600 )edit
0

answered 2017-11-09 18:34:09 -0600

lahiruherath gravatar image

You can use do_transform_cloud from tf2 to get this done just have to feed in the incoming cloud with the transform. This is using Python. And you'll have to convert the tuple from lookupTransform to a TransformStamped to be fed into the function. Follow this other thread for execution

link text

Cheers

edit flag offensive delete link more

Comments

I tried using this method (in python) but it somehow doesn't work as expected. That's why I used a transformation with 0 translation and 0 rotation to test, but it nevertheless changes my pointcloud. Anyone expericened something like this?

rosNewbie gravatar image rosNewbie  ( 2020-01-02 16:29:42 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-02-16 19:37:06 -0600

Seen: 27,741 times

Last updated: Jul 16 '20