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

error when subscribing to /camera/depth/points

asked 2011-10-13 06:49:24 -0500

rune gravatar image

Hello, I am currently running ros electric on Ubuntu 10.04, using a Kinect sensor and trying to subscribe to the /camera/depth/points topic published by openni_launch. Doing it the following way works:

cloudsub = n.subscribe <sensor_msgs::PointCloud2> ("/camera/depth/points", 1, cloudcb);

However, when trying to subscribe to it as follows:

cloudsub = n.subscribe <pcl::PointCloud<pcl::PointXYZ> > ("/camera/depth/points", 1, cloudcb);

I get the error message below:

In file included from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:37,
             from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/publisher.h:34,
             from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:32,
             from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/ros.h:45,
             from /home/rune/ros_workspace/hand_tracker/src/segment.cpp:1:
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::MD5Sum<M>::value() [with M = pcl::PointCloud<pcl::PointXYZ>]’:
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h:228:   instantiated from ‘const char* ros::message_traits::md5sum() [with M = pcl::PointCloud<pcl::PointXYZ>]’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/subscribe_options.h:110:   instantiated from ‘void ros::SubscribeOptions::init(const std::string&, uint32_t, const boost::function<void(const boost::shared_ptr<const M>&)>&, const boost::function<boost::shared_ptr<X>()>&) [with M = pcl::PointCloud<pcl::PointXYZ>]’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:665:   instantiated from ‘ros::Subscriber ros::NodeHandle::subscribe(const std::string&, uint32_t, void (*)(const boost::shared_ptr<const M>&), const ros::TransportHints&) [with M = pcl::PointCloud<pcl::PointXYZ>]’
/home/rune/ros_workspace/hand_tracker/src/segment.cpp:216:   instantiated from here
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h:121: error: ‘__s_getMD5Sum’ is not a member of ‘pcl::PointCloud<pcl::PointXYZ>’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::DataType<M>::value() [with M = pcl::PointCloud<pcl::PointXYZ>]’:
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h:237:   instantiated from ‘const char* ros::message_traits::datatype() [with M = pcl::PointCloud<pcl::PointXYZ>]’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/subscribe_options.h:111:   instantiated from ‘void ros::SubscribeOptions::init(const std::string&, uint32_t, const boost::function<void(const boost::shared_ptr<const M>&)>&, const boost::function<boost::shared_ptr<X>()>&) [with M = pcl::PointCloud<pcl::PointXYZ>]’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:665:   instantiated from ‘ros::Subscriber ros::NodeHandle::subscribe(const std::string&, uint32_t, void (*)(const boost::shared_ptr<const M>&), const ros::TransportHints&) [with M = pcl::PointCloud<pcl::PointXYZ>]’
/home/rune/ros_workspace/hand_tracker/src/segment.cpp:216:   instantiated from here
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp_traits/include/ros/message_traits.h:138: error: ‘__s_getDataType’ is not a member of ‘pcl::PointCloud<pcl::PointXYZ>’
In file included from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include ...
(more)
edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
3

answered 2011-10-13 15:42:22 -0500

Patrick Mihelich gravatar image

To clarify fergs' answer, it looks like you've done

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

but not

#include <pcl_ros/point_cloud.h>

The pcl/XXX headers define pcl::PointCloud and pcl::PointXYZ types used by PCL. However, PCL is a stand-alone library that knows nothing about ROS. If you include only those headers, ROS doesn't know what to do with pcl::PointCloud, because it's not a native ROS message type. Thus the ROS serialization code barfs.

pcl_ros/point_cloud.h contains the glue code that tells ROS how to serialize/deserialize pcl::PointCloud. This code serializes pcl::PointCloud into exactly the same over-the-wire format as the ROS-native sensor_msgs/PointCloud2 message type, which is why you can use them interchangeably in your subscriber code.

If you exactly cut-and-paste the subscribing example, does it work?

edit flag offensive delete link more

Comments

Ah, how silly. I have indeed forgot to include pcl_ros/point_cloud.h. I am not able to test this at the moment, but I'm sure this will help. Thanks! I'll post an update when I have actually made sure it works
rune gravatar image rune  ( 2011-10-14 01:35:15 -0500 )edit
It worked. Thanks!
rune gravatar image rune  ( 2011-10-15 21:52:16 -0500 )edit

hi. I have a bagfile containing Velodyne pointcloud data. i rosbag play it to publish msgs on type sensor_msgs/PointCloud2. I want a range image. is it mandatory to convert it to PointCloud<T> ?Any ideas how to use PointCloud2 type and obtain range image?any links?

KARTHIK MURUGAN gravatar image KARTHIK MURUGAN  ( 2012-12-08 02:33:15 -0500 )edit
0

answered 2011-10-13 07:56:03 -0500

fergs gravatar image

Have you included <pcl_ros point_cloud.h=""> (make sure it is the pcl_ros version, not just the pcl version, as only the pcl_ros version will include the subscriber aspects).

edit flag offensive delete link more
0

answered 2011-10-13 07:08:02 -0500

David Lu gravatar image

It looks like you need to convert the PointCloud2 to a PointCloud with a function like this one

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-10-13 06:49:24 -0500

Seen: 2,179 times

Last updated: Oct 13 '11