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

Revision history [back]

Hi Martin!

I see several issues in your approach. Fristly: inside the main function you declare

sensor_msgs::PointCloud2::Ptr cloud_blob (new sensor_msgs::PointCloud2);

and I guess that you are expecting that the callback writes the information on it, but be aware that this variable is out of the scope of the callback! So it will never get written!

Also: You expect a const PointCloud::ConstPtr& cloud_blob in your callback but the topic /camera/depth_registered/points is of type sensor_msgs::PointCloud2

One more: You use ros::spinOnce() which will run the ros control loop only once, this does not guarantee that a point cloud would be received during that time.

Your code should look something like this (I haven't tried to compile, it is just an example)

//Define the publisher and the output point cloud here 
//so it can be accessed from inside the callback 
//(if you are familiar with OOP you can do this much more elegantly)
ros::Publisher pub;
sensor_msgs::PointCloud2 output;


void callback(const sensor_msgs::PointCloud2ConstPtr& input)
{
  //Inside the callback should be all the process that you want to do with your point cloud and at the end publish the results.
  printf ("Before filtering Cloud: width = %d, height = %d\n", input->width, input->height);

  // Do some processing to the point cloud
  pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  sor.setInputCloud (input);
  sor.setLeafSize (0.01f, 0.01f, 0.01f);
  sor.filter (output);
  printf ("After filtering Cloud: width = %d, height = %d\n", output->width, output->height);

  //Publish the results
  pub.publish(output);
}


int
main (int argc, char** argv)
{
// INITIALIZE ROS
  ros::init (argc, argv, "SUB_IND_PUB");
  ros::NodeHandle nh;
  pub = nh.advertise<PointCloud> ("pubIndices", 1);

  ros::Subscriber sub = nh.subscribe<PointCloud>("/camera/depth_registered/points", 1, callback);

  //This will run until you shutdown the node
  ros::spin();



  return 0;
}

I hope you find it helpful.

click to hide/show revision 2
fixed flagrant error in source code

Hi Martin!

I see several issues in your approach. Fristly: inside the main function you declare

sensor_msgs::PointCloud2::Ptr cloud_blob (new sensor_msgs::PointCloud2);

and I guess that you are expecting that the callback writes the information on it, but be aware that this variable is out of the scope of the callback! So it will never get written!

Also: You expect a const PointCloud::ConstPtr& cloud_blob in your callback but the topic /camera/depth_registered/points is of type sensor_msgs::PointCloud2

One more: You use ros::spinOnce() which will run the ros control loop only once, this does not guarantee that a point cloud would be received during that time.

Your code should look something like this (I haven't tried to compile, it is just an example)

//Define the publisher and the output point cloud here 
//so it can be accessed from inside the callback 
//(if you are familiar with OOP you can do this much more elegantly)
ros::Publisher pub;
sensor_msgs::PointCloud2 output;


void callback(const sensor_msgs::PointCloud2ConstPtr& input)
{
  //Inside the callback should be all the process that you want to do with your point cloud and at the end publish the results.
  printf ("Before filtering Cloud: width = %d, height = %d\n", input->width, input->height);

  // Do some processing to the point cloud
  pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  sor.setInputCloud (input);
  sor.setLeafSize (0.01f, 0.01f, 0.01f);
  sor.filter (output);
  printf ("After filtering Cloud: width = %d, height = %d\n", output->width, output->height);
output.width, output.height);

  //Publish the results
  pub.publish(output);
}


int
main (int argc, char** argv)
{
// INITIALIZE ROS
  ros::init (argc, argv, "SUB_IND_PUB");
  ros::NodeHandle nh;
  pub = nh.advertise<PointCloud> ("pubIndices", 1);

  ros::Subscriber sub = nh.subscribe<PointCloud>("/camera/depth_registered/points", 1, callback);

  //This will run until you shutdown the node
  ros::spin();



  return 0;
}

I hope you find it helpful.