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

Publishing PointCloud2

asked 2011-06-24 03:29:23 -0500

kang gravatar image

updated 2016-02-01 11:42:32 -0500

lucasw gravatar image

Hi,

I am currently using pcl under ros. i am trying to publish pointcloud2 which I have computed. I already read tutorial from here But somehow I still have not get this right yet.

Let's say I call my computed pointcloud as cloud: pcl::PointCloud<Point>::Ptr cloud_aligned (new pcl::PointCloud<Point>);

and here how I defined for publisher:

ros::NodeHandle nh3;
ros::Publisher pub = nh3.advertise<sensor_msgs::PointCloud2>("alignedcloud", 1);
ros::Rate loop_rate(10);

then here is how I try to call publish:

pub.publish(cloud_aligned);  
ros::spinOnce();
loop_rate.sleep();

Could someone give me some hints?

Best, kang

some errors:

/ros_diamondback/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h:121: error: 'const class pcl::PointCloud<pcl::PointXYZ>' has no member named '__getMD5Sum'
/ros_diamondback/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h: In static member function 'static const char* ros::message_traits::DataType<M>::value(const M&) [with M = pcl::PointCloud<pcl::PointXYZ>]':

/ros_diamondback/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:142: error: 'const class pcl::PointCloud<pcl::PointXYZ>' has no member named 'serializationLength'
/ros_diamondback/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h: In static member function 'static void ros::serialization::Serializer<T>::write(Stream&, typename boost::call_traits<T>::param_type) [with Stream = ros::serialization::OStream, T = pcl::PointCloud<pcl::PointXYZ>]':
/ros_diamondback/ros_comm/clients/cpp/roscpp/include/ros/publisher.h:87:   instantiated from 'void ros::Publisher::publish(const boost::shared_ptr<X>&) const [with M = pcl::PointCloud<pcl::PointXYZ>]'
/ros_diamondback/perception_pcl/pcl/src/tools/reg_icp_ros.cpp:88:   instantiated from here
/ros_diamondback/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:124: error: 'const class pcl::PointCloud<pcl::PointXYZ>' has no member named 'serialize'
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2011-06-24 04:22:39 -0500

dornhege gravatar image

You are mixing two things.

You have a PointCloud and declared the publisher for a sensor_msgs::PointCloud2.

The best way is to use a publisher from pcl_ros (3.1) to directly publish a PointCloud as a sensor_msgs::PointCloud2. Alternatively you would have to convert that manually. The pcl_ros publisher will do this for you.

edit flag offensive delete link more

Comments

Thanks, that was helpful.
kang gravatar image kang  ( 2011-06-27 02:09:38 -0500 )edit
Does this mean that pcl::PointCloud2 and sensor_msgs::PointCloud2 are not the same? Also, why so much namespace hell with either using pcl or pcl_ros?
ubuntuslave gravatar image ubuntuslave  ( 2011-07-20 13:37:15 -0500 )edit
There is no pcl::PointCloud2, only pcl::PointCloud. sensor_msgs::PointCloud2 is a generic structure that can hold any type of pcl::PointCloud (1 float, 30 doubles, whatever). pcl::PointClouds are specialized to whatever type you create them with (e.g. pcl::PointXYZ) and easier to work with in code.
Eric Perko gravatar image Eric Perko  ( 2011-07-20 13:46:32 -0500 )edit
1

answered 2011-06-24 04:09:54 -0500

fergs gravatar image

updated 2011-06-24 06:54:20 -0500

If you are using the diamondback pcl, you probably need to include pcl_ros/point_cloud.h

You should take a look at the tutorials for pcl under ros: http://www.ros.org/wiki/pcl/Tutorials

edit flag offensive delete link more

Comments

Thanks, that was helpful.
kang gravatar image kang  ( 2011-06-27 02:09:28 -0500 )edit
You're welcome. You should select an best answer by clicking the checkmark next to one of the answers.
fergs gravatar image fergs  ( 2011-06-27 06:44:28 -0500 )edit

Question Tools

Stats

Asked: 2011-06-24 03:29:23 -0500

Seen: 13,868 times

Last updated: Feb 01 '16