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

Publishing a vector of point clouds

asked 2020-01-06 08:37:15 -0500

rosNewbie gravatar image

updated 2022-01-22 16:10:14 -0500

Evgeny gravatar image

I successfully published pointclouds by converting them to ROSMsg. But is it somehow possible to publish a vector containing multiple pointclouds?

I tried this:

pcl::PointCloud<ClassPoint> out;
 ....
sensor_msgs::PointCloud2 out_msg;
pcl::toROSMsg(out, out_msg);

std::vector<sensor_msgs::PointCloud2> clouds(2); 
clouds[0] = out_msg;
out_msg.header.frame_id = corner_frame_name;

pub_merged_clouds.publish(clouds);

while I got

pub_merged_clouds = nh.advertise<std::vector<sensor_msgs::PointCloud2>>(merged_clouds_topic, 1);

This unfortunately doesn't work. I get the following error when compiling

error: ‘const class std::vector<sensor_msgs::PointCloud2_<std::allocator<void> > >’ has no member named ‘__getMD5Sum’
     return m.__getMD5Sum().c_str();

Is there a way to do this? Thanks alot!

edit retag flag offensive close merge delete

Comments

1

You need to define a new message type containing an array of pointclouds.

stevemacenski gravatar image stevemacenski  ( 2020-01-06 09:58:09 -0500 )edit

@stevemacenski Thank you for you reply. Could you elaborate? How exactly can I create an own sensor_msgs type?

rosNewbie gravatar image rosNewbie  ( 2020-01-06 16:52:48 -0500 )edit

To add on to @stevemacenski's comment, have a look at ROS tutorial . The custom msg will have an array of sensor_msgs::PointCloud2, e.g. in a filename.msg, sensor_msgs/PointCloud2[ ] clouds. Then, in your code declare packagename::filename clouds and clouds.push_back(cloud) each cloud. Include the new header file for the custom msg in your code. It would be better to build the new msg package first then your other package.

ap gravatar image ap  ( 2020-01-08 02:31:38 -0500 )edit

1 Answer

Sort by » oldest newest most voted
3

answered 2020-01-08 02:52:15 -0500

pavel92 gravatar image

updated 2020-01-08 02:58:16 -0500

sensor_msgs::PointCloud2 is already defined sensor message but an array of sensor_msgs::PointCloud2 is not. Therefore you will need to define your own custom message. Check the tutorials on how to create and use a custom message.
Your .msg file (for example you can name it PointClouds.msg) should look something like this:

sensor_msgs::PointCloud2[] pointclouds

Once you have created and included your msg, the following should work:

#include "your_pkg_name/PointClouds.h"
...
pcl::PointCloud<ClassPoint> out;
 ....
sensor_msgs::PointCloud2 out_msg;
pcl::toROSMsg(out, out_msg);

your_pkg_name::PointClouds clouds_msg(2); 
clouds_msg.pointclouds[0] = out_msg; // or just clouds_msg.pointclouds.push_back(out_msg);
out_msg.header.frame_id = corner_frame_name;

pub_merged_clouds.publish(clouds_msg);

and your publisher:

pub_merged_clouds = nh.advertise<your_pkg_name::PointClouds>(merged_clouds_topic, 1);
edit flag offensive delete link more

Comments

1

I would also add to think about whether you (ie: @rosNewbie ) actually really need to (or should) publish a set of PointClouds together. If you're doing this because they were "captured at the same time" and you want to publish them together as it would maintain that temporal relationship, then I would suggest using message_filters with a time-based synchroniser instead.

No custom message needed, all visualisation tools will remain compatible with what you already have and you still get the same behaviour.

gvdhoorn gravatar image gvdhoorn  ( 2020-01-08 03:13:07 -0500 )edit

I agree with @gvdhoorn. Publishing multiple pointclouds at once is also bad performance-wise. Unfortunately the OP did not provide any additional info on why he needs multiple pointclouds and what does he plan to do with them. All we can infer is that he is publishing them via a pub_merged_clouds publisher, which means he wants to merge/process these clouds somewhere else. There are definitely better ways to handle poitcloud data, but looking at the question, it comes down to a beginner lesson of learning how to write custom messages in ROS.

pavel92 gravatar image pavel92  ( 2020-01-08 03:42:57 -0500 )edit
1

Please don't take my comment as criticism @pavel92. I just wanted to provide some additional information.

As-is, this could be an xy-problem. Let's see whether @rosNewbie can clear things up for us with some more information on why he wants to do this.

Your answer is a perfectly fine one (if the question really is: "how do I create a custom message that carries an array/list of other messages").

gvdhoorn gravatar image gvdhoorn  ( 2020-01-08 03:46:17 -0500 )edit

None taken, it is more for the OP to clarify his intent so we can provide a better solution if it is possible :)

pavel92 gravatar image pavel92  ( 2020-01-08 03:52:51 -0500 )edit

@gvdhoorn@pavel92 Thank you both for your help! This really helped. Now I now how to create my own msg type. But as gvdhoorn mentioned it is performance-wise not the best solution. I didn't know about message_filters and will try this. Because this is exactly what I need. I have some pointclouds that have a temporal relationship.

rosNewbie gravatar image rosNewbie  ( 2020-01-08 08:31:03 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-01-06 08:37:15 -0500

Seen: 1,384 times

Last updated: Jan 08 '20