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

Write PCD File from a Topic - Hydro + PCL (Migration)

asked 2014-01-23 22:53:10 -0500

lfelipesv gravatar image

updated 2014-01-28 17:07:21 -0500

ngrennan gravatar image

Hello, I'm doing a hand gesture recognition project and I am having some troubles with the migration of the PCL data types to ROS Hydro. I started with Hydro + PCL this week so, not all the concepts are really clear for me. I'm using Ubuntu 12.04.

My problem is to transform the data that come from my passthrough filter (sensor_msgs/PointCloud2) to a pcl::PointCloud pcl::PointXYZRGB, so I can write the data using the savePCDFileASCII function.

My code is:

#include <ros/ros.h>
#include <pcl_conversions/pcl_conversions.h> //hydro
#include <sensor_msgs/PointCloud2.h> //hydro
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>

ros::Publisher pub;

void
cloud_cb (const pcl::PCLPointCloud2ConstPtr& input)
{

  pcl::PointCloud<pcl::PointXYZRGB> cloud_filtered;
  pcl::fromROSMsg(*input, cloud_filtered);

  //cloud_filtered.header = pcl_conversions::toPCL(input.header); 

  //pcl_conversions::toPCL(input, cloud_filtered);

  pcl::io::savePCDFileASCII ("test_pcd.pcd", cloud_filtered);

  pub.publish(input);
}

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "pcl_node");
  ros::NodeHandle nh;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub = nh.subscribe ("/passthrough", 1, cloud_cb);

  // Create a ROS publisher for the output point cloud
  pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);

  // Spin
  ros::spin ();

  //End Program
  return (0);
}

As you guys can see in my code, I tried some transformations after reading the hydro/Migration page, but I couldn't figure it out what i need to do to make my code work.

The error while doing catkin_make is a no matching function because the type error:

/home/breil/catkin_ws/src/pcl_tutorial/src/example.cpp: In function ‘void cloud_cb(const PCLPointCloud2ConstPtr&)’:
/home/breil/catkin_ws/src/pcl_tutorial/src/example.cpp:21:41: error: no matching function for call to ‘fromROSMsg(const pcl::PCLPointCloud2&, pcl::PointCloud<pcl::PointXYZRGB>&)’
/home/breil/catkin_ws/src/pcl_tutorial/src/example.cpp:21:41: note: candidate is:
/opt/ros/hydro/include/pcl_conversions/pcl_conversions.h:486:8: note: template<class T> void pcl::fromROSMsg(const PointCloud2&, pcl::PointCloud<PointT>&)

Thank you very much for your attention.

edit retag flag offensive close merge delete

Comments

I think you do not need this to... and fromRosMSG() anymore in hydro. A least for publishing you just put the cloud into the publish method of a sensro_msgs::PointCloud2 publisher and unlike in prev versions it just works. But I dont know the opposite way..

Wolf gravatar image Wolf  ( 2014-01-24 00:39:04 -0500 )edit

Yes Wolf, the publisher is working fine with the type. The problem is to save the PCD File, because I can't use sensor_msgs/PointCloud2 type. The pcl::io::savePCDFileASCII function. So I need to do some transformation before. int pcl::io::savePCDFileASCII(const string&, const pcl::PointCloud<pointt>&)

lfelipesv gravatar image lfelipesv  ( 2014-01-24 01:01:49 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2014-01-26 20:07:11 -0500

Tirjen gravatar image

I think the problem is that you are trying to use fromROSmsg using as input a point cloud that is already with namespace pcl. Does pcl::io::savePCDFileASCII(*input) work? Another way to make it work could be using a sensor_msgs/PointCloud2 in your callback as input type (void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)) and then use the conversion with fromROSmsg. Let me know if it works!

edit flag offensive delete link more

Comments

Thank you Tirjen! It worked using sensor_msgs/PointCloud2 =)

lfelipesv gravatar image lfelipesv  ( 2014-01-26 20:51:42 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-01-23 22:53:10 -0500

Seen: 2,114 times

Last updated: Jan 26 '14