Skip to content

Commit

Permalink
added LOG info to test node duration
Browse files Browse the repository at this point in the history
  • Loading branch information
jupidity committed Jul 21, 2017
1 parent 0a19e29 commit 8077421
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion scripts/segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@ ros::Publisher pub;
void
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
{



// Container for original & filtered data
pcl::PCLPointCloud2* cloud = new pcl::PCLPointCloud2;
pcl::PCLPointCloud2ConstPtr cloudPtr(cloud);
Expand Down Expand Up @@ -163,6 +166,9 @@ cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
sensor_msgs::PointCloud2 output;
pcl_conversions::fromPCL(outputPCL, output);


ROS_INFO(" ");

// Publish the data
pub.publish (output);
}
Expand All @@ -177,7 +183,7 @@ main (int argc, char** argv)
// Create a ROS subscriber for the input point cloud
ros::Subscriber sub = nh.subscribe ("/sensor_stick/point_cloud", 1, cloud_cb);

// Create a ROS publisher for the output point cloud

pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_objects", 1);

// Spin
Expand Down

0 comments on commit 8077421

Please sign in to comment.