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

Subscribe to sensor_msgs/PointCloud

asked 2014-09-15 06:51:58 -0500

Missing gravatar image

Hey,

i have a node that publishes sensor_msgs/PointCloud data and i want to subscribe to this. My Subscriber looks like this:

distance_sub = nh.subscribe<pcl::PointCloud<pcl::PointXYZ>>("/distance_sensors", 1, &SafetyBelt::distanceCallback, this);

I included the point_cloud.h and the point_types.h headers. But i am not able to compile this Code and i have no idea what the error means:

/opt/ros/indigo/include/ros/subscribe_options.h:111:54:   required from ‘void ros::SubscribeOptions::init(const 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>; std::string = std::basic_string<char>; uint32_t = unsigned int]’
  /opt/ros/indigo/include/ros/node_handle.h:443:5:   required from ‘ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(const boost::shared_ptr<const M>&), T*, const ros::TransportHints&) [with M = pcl::PointCloud<pcl::PointXYZ>; T = SafetyBelt; std::string = std::basic_string<char>; uint32_t = unsigned int]’
  /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/src/SafetyBelt.cpp:16:121:   required from here
  /opt/ros/indigo/include/ros/message_traits.h:138:31: error: ‘__s_getDataType’ is not a member of ‘pcl::PointCloud<pcl::PointXYZ>’
       return M::__s_getDataType().c_str();
                                 ^
  In file included from /opt/ros/indigo/include/ros/publisher.h:34:0,
                   from /opt/ros/indigo/include/ros/node_handle.h:32,
                   from /opt/ros/indigo/include/ros/ros.h:45,
                   from /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/include/SafetyBelt.h:1,
                   from /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/src/SafetyBelt.cpp:1:
  /opt/ros/indigo/include/ros/serialization.h: In instantiation of ‘static void ros::serialization::Serializer<T>::read(Stream&, typename boost::call_traits<T>::reference) [with Stream = ros::serialization::IStream; T = pcl::PointCloud<pcl::PointXYZ>; typename boost::call_traits<T>::reference = pcl::PointCloud<pcl::PointXYZ>&]’:
  /opt/ros/indigo/include/ros/serialization.h:163:32:   required from ‘void ros::serialization::deserialize(Stream&, T&) [with T = pcl::PointCloud<pcl::PointXYZ>; Stream = ros::serialization::IStream]’
  /opt/ros/indigo/include/ros/subscription_callback_helper.h:136:34:   required from ‘ros::VoidConstPtr ros::SubscriptionCallbackHelperT<P, Enabled>::deserialize(const ros::SubscriptionCallbackHelperDeserializeParams&) [with P = const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&; Enabled = void; ros::VoidConstPtr = boost::shared_ptr<const void>]’
  /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/src/SafetyBelt.cpp:81:1:   required from here
  /opt/ros/indigo/include/ros/serialization.h:136:5: error: ‘class pcl::PointCloud<pcl::PointXYZ>’ has no member named ‘deserialize’
       t.deserialize(stream.getData());
       ^
  In file included from /opt/ros/indigo/include/ros/serialization.h:37:0,
                   from /opt/ros/indigo/include/ros/publisher.h:34,
                   from /opt/ros/indigo/include/ros/node_handle.h:32,
                   from /opt/ros/indigo/include/ros/ros.h:45,
                   from /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/include/SafetyBelt.h:1,
                   from /home/daniel/Desktop/robotino/trunk2/trunk/robotino/robotino_teleop/src/SafetyBelt.cpp:1:
  /opt/ros/indigo/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/indigo/include/ros/message_traits.h:122:3 ...
(more)
edit retag flag offensive close merge delete

4 Answers

Sort by » oldest newest most voted
7

answered 2014-09-15 09:40:06 -0500

paulbovbel gravatar image

updated 2014-09-15 09:42:48 -0500

From http://wiki.ros.org/pcl/Overview , for a subscriber that receives pcl::PointCloud objects directly:

// Need to include the pcl ros utilities
#include "pcl_ros/point_cloud.h"

// callback signature, assuming your points are pcl::PointXYZRGB type:
void callback(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr&);

// create a templated subscriber
ros::Subscriber sub = nh.subscribe<pcl::PointCloud<pcl::PointXYZRGB> > (topic, queue_size, callback);

Are you sure you included <pcl_ros/point_cloud.h>, not just <pcl/point_cloud.h>?

If you can post a gist of your full node, I can take a look.

edit flag offensive delete link more

Comments

Thank you very much paulbovbel, that solved my problem :)

Missing gravatar image Missing  ( 2014-09-16 03:21:41 -0500 )edit
0

answered 2016-06-20 08:16:52 -0500

rasoo gravatar image

Heyii , I am trying to do almost the same thing. Trying to subcribe data from the topic "/distance_sensors" .... I had the same problem and I did the thing that were suggested here. But I am having another error..... [100%] Built target robotino_node In file included from /usr/include/boost/function/detail/maybe_include.hpp:18:0, from /usr/include/boost/function/detail/function_iterate.hpp:14, from /usr/include/boost/preprocessor/iteration/detail/iter/forward1.hpp:52, from /usr/include/boost/function.hpp:64, from /opt/ros/indigo/include/ros/forwards.h:40, from /opt/ros/indigo/include/ros/common.h:37, from /opt/ros/indigo/include/ros/ros.h:43, from /opt/ros/indigo/include/pcl_ros/point_cloud.h:4, from /home/ras/kinect_ws/src/beginner_tutorials/src/listener.cpp:30: /usr/include/boost/function/function_template.hpp: In instantiation of ‘static void boost::detail::function::void_function_invoker1<functionptr, r,="" t0="">::invoke(boost::detail::function::function_buffer&, T0) [with FunctionPtr = void ()(const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyzrgb=""> >&); R = void; T0 = const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyz=""> >&]’: /usr/include/boost/function/function_template.hpp:934:38: required from ‘void boost::function1<r, t1="">::assign_to(Functor) [with Functor = void ()(const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyzrgb=""> >&); R = void; T0 = const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyz=""> >&]’ /usr/include/boost/function/function_template.hpp:722:7: required from ‘boost::function1<r, t1="">::function1(Functor, typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<functor>::value>::value, int>::type) [with Functor = void ()(const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyzrgb=""> >&); R = void; T0 = const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyz=""> >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<functor>::value>::value, int>::type = int]’ /usr/include/boost/function/function_template.hpp:1069:16: required from ‘boost::function<r(t0)&gt;::function(functor, typename="" boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<functor="">::value>::value, int>::type) [with Functor = void ()(const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyzrgb=""> >&); R = void; T0 = const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyz=""> >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<functor>::value>::value, int>::type = int]’ /home/ras/kinect_ws/src/beginner_tutorials/src/listener.cpp:102:109: required from here /usr/include/boost/function/function_template.hpp:112:11: error: invalid initialization of reference of type ‘const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyzrgb=""> >&’ from expression of type ‘const boost::shared_ptr<const pcl::pointcloud<pcl::pointxyz=""> >’ BOOST_FUNCTION_RETURN(f(BOOST_FUNCTION_ARGS)); ^ make[2]: * [beginner_tutorials/CMakeFiles/listener.dir/src/listener.cpp.o] Error 1 make[1]: [beginner_tutorials/CMakeFiles/listener.dir/all] Error 2 make: ** [all] Error 2

Invoking "make -j4 -l4" failed

can you please help me regarding this issue? I am very new to ros and working with robotino. I am using ros indigo and ubuntu 14.04. Thank you in advance.

edit flag offensive delete link more

Comments

hello @rasoo, welcome to answers ros. please, bear in mind that this site does not work like a forum, so you should post you question as a new one, instead of as a response. cheers

Procópio gravatar image Procópio  ( 2016-06-21 03:53:57 -0500 )edit

ok. Thanks for your suggestion.

rasoo gravatar image rasoo  ( 2016-10-20 09:20:13 -0500 )edit
0

answered 2014-09-15 09:33:32 -0500

bajo gravatar image

updated 2014-09-15 09:36:18 -0500

Hi,

could it be that you are mixing up the PCL pointcloud data type with the one from sensor_msgs? See the definition of sensor_msgs/PointCloud [1] and you see that it is not pcl::PointCloud<pcl::pointxyz>.

[1] [http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud.html](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud.html)

edit flag offensive delete link more

Comments

1

You can subscribe to the pcl::Pointcloud and sensor_msgs::PointCloud interchangeably, pcl_ros does conversion magic in the background ( http://wiki.ros.org/pcl/Overview )

paulbovbel gravatar image paulbovbel  ( 2014-09-15 09:44:04 -0500 )edit

Thank you for this information. Good to know.

bajo gravatar image bajo  ( 2014-09-16 04:01:23 -0500 )edit
0

answered 2014-09-16 02:21:44 -0500

updated 2014-09-16 02:22:32 -0500

I think the answer of paulbovbel is the correct one. You just forgot to put a space in this line (between the >> ):

distance_sub = nh.subscribe<pcl::pointcloud<pcl::pointxyz>>("/distance_sensors", 1, &SafetyBelt::distanceCallback, this);

Change to this:

distance_sub = nh.subscribe<pcl::pointcloud<pcl::pointxyz> >("/distance_sensors", 1, &SafetyBelt::distanceCallback, this);
edit flag offensive delete link more

Comments

Yes that's right :) I forgot to include the pcl_ros/point_cloud.h and added the space. Now everything works fine, thank you :)

Missing gravatar image Missing  ( 2014-09-16 03:22:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-09-15 06:51:58 -0500

Seen: 5,419 times

Last updated: Sep 16 '14