@@ -67,7 +67,7 @@ namespace jsk_pcl_ros_utils
67
67
return ;
68
68
}
69
69
70
- ROS_INFO (" Received %d data points in frame %s with the following fields: %s" ,
70
+ NODELET_INFO (" Received %d data points in frame %s with the following fields: %s" ,
71
71
(int )cloud->width * cloud->height ,
72
72
cloud->header .frame_id .c_str (),
73
73
pcl::getFieldsList (*cloud).c_str ());
@@ -76,7 +76,7 @@ namespace jsk_pcl_ros_utils
76
76
Eigen::Quaternionf q = Eigen::Quaternionf::Identity ();
77
77
if (!fixed_frame_.empty ()) {
78
78
if (!tf_listener_->waitForTransform (fixed_frame_, cloud->header .frame_id , pcl_conversions::fromPCL (cloud->header ).stamp , ros::Duration (duration_))) {
79
- ROS_WARN (" Could not get transform!" );
79
+ NODELET_WARN (" Could not get transform!" );
80
80
return ;
81
81
}
82
82
tf::StampedTransform transform_stamped;
@@ -90,7 +90,7 @@ namespace jsk_pcl_ros_utils
90
90
91
91
std::stringstream ss;
92
92
ss << prefix_ << cloud->header .stamp << " .pcd" ;
93
- ROS_INFO (" Data saved to %s" , ss.str ().c_str ());
93
+ NODELET_INFO (" Data saved to %s" , ss.str ().c_str ());
94
94
95
95
pcl::PCDWriter writer;
96
96
if (binary_)
@@ -122,16 +122,16 @@ namespace jsk_pcl_ros_utils
122
122
{
123
123
if (compressed_)
124
124
{
125
- ROS_INFO_STREAM (" Saving as binary compressed PCD" );
125
+ NODELET_INFO (" Saving as binary compressed PCD" ) ;
126
126
}
127
127
else
128
128
{
129
- ROS_INFO_STREAM (" Saving as binary PCD" );
129
+ NODELET_INFO (" Saving as binary PCD" );
130
130
}
131
131
}
132
132
else
133
133
{
134
- ROS_INFO_STREAM (" Saving as binary PCD" );
134
+ NODELET_INFO (" Saving as ASCII PCD" );
135
135
}
136
136
}
137
137
0 commit comments