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

PointCloud subscriber/publisher types

asked 2011-03-23 03:37:45 -0600

updated 2011-03-24 21:04:13 -0600

tfoote gravatar image

Hi,

When working with PointClouds, I usually subscribe to a sensor_msgs::PointCloud2 topic, and convert to a pcl::PointCloud inside my code. Then, once I'm done mainpulating the cloud, I convert it back to a sensor_msgs::PointCloud2 to publish it, using these functions:

pcl::fromROSMsg
pcl::toROSMsg

My first question is: what is the cost of using these functions? I am assuming there's a memcpy involved, which (when dealing with kinect data) is probably not negligible.

Second: is there a way to avoid this, by directly subscribing/publishing pcl::PointCloud types? I believe that there is a publisher/subscriber for pcl types, but I'm not sure whether it actually saves time, or does the same conversion/memcpy behind the scenes.

Thanks, Ivan

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2011-03-24 21:04:02 -0600

tfoote gravatar image

The conversion to and from PCL datatypes is quite computationally expensive. I have observed something like 100ms for a conversion of a Kinect frame on a 1Ghz Atom core.

To avoid this you can use direct publication of pcl datatypes and nodelets. A very simple example of a nodelet which does this is in the pointcloud_to_laserscan package is cloud_throttle.cpp

When publishing over the network the Kinect data was unusable.

Using nodelets I was able to take processing of the Kinect from 10Hz and 150% cpu to 30Hz and 87% cpu on an Atom by publishing using the exact same data type. Here's a launch file which brings up the kinect and processes the data inside the same process using nodelets.

edit flag offensive delete link more

Comments

what about the second part of the question? when publishing / subscribing directly with pcl PointCloud, does it first convert to sensors_msgs::PointCloud2 then serialize, then deserialize and convert to PCL? Or does it serialize deserialize directly from / to PCL? I am not using nodelets.

brice rebsamen gravatar image brice rebsamen  ( 2013-12-19 14:06:42 -0600 )edit

If ti does require conversion it will directly convert to the wire format to or from the pcl datatype.

tfoote gravatar image tfoote  ( 2013-12-19 14:11:36 -0600 )edit

Question Tools

Stats

Asked: 2011-03-23 03:37:45 -0600

Seen: 1,404 times

Last updated: Mar 24 '11