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

ros publish pcl::ModelCoefficients

asked 2013-10-22 12:29:52 -0600

HiroCollins gravatar image

updated 2013-11-18 18:58:56 -0600

tfoote gravatar image

I am following "How to use a pcl tutorial on ROS" under /pcl/Tutorials. I managed to build and run section 4.1 with no problems but when I build 4.2 I get the following error:

[ 50%] [100%] Built target example2 Building CXX object my_pcl_tutorial/CMakeFiles/example.dir/src/example.cpp.o In file included from /opt/ros/hydro/include/ros/serialization.h:37:0, from /opt/ros/hydro/include/ros/publisher.h:34, from /opt/ros/hydro/include/ros/node_handle.h:32, from /opt/ros/hydro/include/ros/ros.h:45, from /home/ndivhuwo/Documents/cloud/src/my_pcl_tutorial/src/example.cpp:1: /opt/ros/hydro/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::MD5Sum<m>::value(const M&) [with M = pcl::ModelCoefficients]’: /opt/ros/hydro/include/ros/message_traits.h:255:104: instantiated from ‘const char* ros::message_traits::md5sum(const M&) [with M = pcl::ModelCoefficients]’ /opt/ros/hydro/include/ros/publisher.h:112:7: instantiated from ‘void ros::Publisher::publish(const M&) const [with M = pcl::ModelCoefficients]’ /home/ndivhuwo/Documents/cloud/src/my_pcl_tutorial/src/example.cpp:49:28: instantiated from here /opt/ros/hydro/include/ros/message_traits.h:126:34: error: ‘const struct pcl::ModelCoefficients’ has no member named ‘__getMD5Sum’ /opt/ros/hydro/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::DataType<m>::value(const M&) [with M = pcl::ModelCoefficients]’: /opt/ros/hydro/include/ros/message_traits.h:264:106: instantiated from ‘const char* ros::message_traits::datatype(const M&) [with M = pcl::ModelCoefficients]’ /opt/ros/hydro/include/ros/publisher.h:112:7: instantiated from ‘void ros::Publisher::publish(const M&) const [with M = pcl::ModelCoefficients]’ /home/ndivhuwo/Documents/cloud/src/my_pcl_tutorial/src/example.cpp:49:28: instantiated from here /opt/ros/hydro/include/ros/message_traits.h:143:36: error: ‘const struct pcl::ModelCoefficients’ has no member named ‘__getDataType’ In file included from /opt/ros/hydro/include/ros/publisher.h:34:0, from /opt/ros/hydro/include/ros/node_handle.h:32, from /opt/ros/hydro/include/ros/ros.h:45, from /home/ndivhuwo/Documents/cloud/src/my_pcl_tutorial/src/example.cpp:1: /opt/ros/hydro/include/ros/serialization.h: In static member function ‘static uint32_t ros::serialization::Serializer<t>::serializedLength(typename boost::call_traits<t>::param_type) [with T = pcl::ModelCoefficients, uint32_t = unsigned int, typename boost::call_traits<t>::param_type = const pcl::ModelCoefficients&]’: /opt/ros/hydro/include/ros/serialization.h:170:43: instantiated from ‘uint32_t ros::serialization::serializationLength(const T&) [with T = pcl::ModelCoefficients, uint32_t = unsigned int]’ /opt/ros/hydro/include/ros/serialization.h:846:45: instantiated from ‘ros::SerializedMessage ros::serialization::serializeMessage(const M&) [with M = pcl::ModelCoefficients]’ /opt/ros/hydro/include/ros/publisher.h:118:7: instantiated from ‘void ros::Publisher::publish(const M&) const [with M = pcl::ModelCoefficients]’ /home/ndivhuwo/Documents/cloud/src/my_pcl_tutorial/src/example.cpp:49:28: instantiated from here /opt/ros/hydro/include/ros/serialization.h:142:34: error: ‘const struct pcl::ModelCoefficients’ has no member named ‘serializationLength’ /opt/ros/hydro/include/ros/serialization.h: In static member function ... (more)

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2013-11-18 03:58:06 -0600

sergifoix gravatar image

Hi, PCL is not integrated in ROS anymore. But there is package that allows you to perform conversions between ros and pcl messages. In order to publish pcl::ModelCoefficients you must do the following:

#include < pcl_conversions/pcl_conversions.h>

...

ros::Publisher pub;

// Create a ROS publisher for the output point cloud

pub = nh.advertise< pcl_msgs::ModelCoefficients> ("output", 1);

// ros message

pcl_msgs::ModelCoefficients ros_coefficients;

// pcl message

pcl::ModelCoefficients pcl_coefficients;

....

pcl_conversions::fromPCL(pcl_coefficients, ros_coefficients);

pub.publish(ros_coefficients);

edit flag offensive delete link more

Comments

1

Thanks for answering this question but not bothering to update the wiki, to ensure that people continue to have the most horrible experience trying to learn ROS.

Neil Traft gravatar image Neil Traft  ( 2014-07-23 23:56:49 -0600 )edit

Another tutorial follower here. Now that I've made the changes, how do I get rviz to display the result?

dinosaur gravatar image dinosaur  ( 2015-06-04 18:35:01 -0600 )edit

Try this example. If you only want to see the planes/non-planes there is a way to copy just those points into a new point cloud but I forget how. Some other PCL tutorial might show it.

Neil Traft gravatar image Neil Traft  ( 2015-06-04 19:16:16 -0600 )edit
0

answered 2013-10-22 21:07:26 -0600

Tirjen gravatar image

If I understand well, you are trying to publish a pcl::ModelCoefficients which is not a ros message. What you can do is create a ros msg that has a structure similar to ModelCoefficients and then publish that message.

edit flag offensive delete link more

Comments

Ok cool, that's what I thought. It's strange that the pcl ros tutorial I was following has this line in the code snippet. They should update it with the correct set of lines. Thanks for your response.

HiroCollins gravatar image HiroCollins  ( 2013-10-22 23:31:17 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2013-10-22 12:29:52 -0600

Seen: 1,405 times

Last updated: Nov 18 '13