Skip to content

Commit 74315f5

Browse files
author
svn
committed
Use debug stream instead of info stream logging in cloud cb function
1 parent 6dffbec commit 74315f5

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

src/ipa_pointcloud_to_laserscan_nodelet.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ namespace pointcloud_to_laserscan
173173
void IpaPointCloudToLaserScanNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
174174
{
175175
ros::Time start_time = ros::Time::now();
176-
NODELET_INFO_STREAM("PC with timestamp from init " << cloud_msg->header.stamp.toSec() << " recevied with a delay of " << (start_time - cloud_msg->header.stamp).toSec() << " ");
176+
NODELET_DEBUG_STREAM("PC with timestamp from init " << cloud_msg->header.stamp.toSec() << " recevied with a delay of " << (start_time - cloud_msg->header.stamp).toSec() << " ");
177177

178178
// convert const ptr to ptr to support downsampling
179179
sensor_msgs::PointCloud2Ptr cloud(boost::const_pointer_cast<sensor_msgs::PointCloud2>(cloud_msg));
@@ -335,7 +335,7 @@ namespace pointcloud_to_laserscan
335335

336336
ros::Time end_time = ros::Time::now();
337337
ros::Duration dur = end_time-start_time;
338-
NODELET_INFO_STREAM("Transform for PC took " << dur.toSec());
338+
NODELET_DEBUG_STREAM("Transform for PC took " << dur.toSec());
339339

340340
pub_.publish(output);
341341
}

0 commit comments

Comments
 (0)