Skip to content

Commit f878fd5

Browse files
author
plnegre
committed
Add info message when save pointcloud
1 parent 398107c commit f878fd5

File tree

1 file changed

+13
-11
lines changed

1 file changed

+13
-11
lines changed

pointcloud_tools/src/pointcloud_viewer.cpp

Lines changed: 13 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
7070
{
7171
m.lock ();
7272
printf("\rPointCloud with %d data points (%s), stamp %f, and frame %s.",
73-
cloud->width * cloud->height, pcl::getFieldsList(*cloud).c_str(),
73+
cloud->width * cloud->height, pcl::getFieldsList(*cloud).c_str(),
7474
cloud->header.stamp.toSec(), cloud->header.frame_id.c_str());
7575
cloud_ = cloud;
7676
m.unlock();
@@ -96,8 +96,10 @@ PointCloudRGB::Ptr filter(PointCloudRGB::Ptr cloud, double voxel_size)
9696

9797
void keyboardEventOccurred(const pcl::visualization::KeyboardEvent& event, void* nothing)
9898
{
99-
if (event.getKeySym() == "space" && event.keyDown())
99+
if (event.getKeySym() == "space" && event.keyDown()) {
100+
ROS_INFO("SAVING POINTCLOUD, PLEASE WAIT...");
100101
save_cloud_ = true;
102+
}
101103
}
102104

103105
void updateVisualization()
@@ -111,7 +113,7 @@ void updateVisualization()
111113
bool rgb = false;
112114
//std::vector<sensor_msgs::PointField> fields;
113115
std::vector<pcl::PCLPointField> fields;
114-
116+
115117
// Create the visualizer
116118
pcl::visualization::PCLVisualizer viewer("Point Cloud Viewer");
117119

@@ -132,7 +134,7 @@ void updateVisualization()
132134
if(cloud_old_ == cloud_)
133135
continue;
134136
m.lock ();
135-
137+
136138
// Convert to PointCloud<T>
137139
if(pcl::getFieldIndex(*cloud_, "rgb") != -1)
138140
{
@@ -150,9 +152,9 @@ void updateVisualization()
150152

151153
// Delete the previous point cloud
152154
viewer.removePointCloud("cloud");
153-
155+
154156
// If no RGB data present, use a simpler white handler
155-
if(rgb && pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1 &&
157+
if(rgb && pcl::getFieldIndex(cloud_xyz_rgb, "rgb", fields) != -1 &&
156158
cloud_xyz_rgb.points[0].rgb != 0)
157159
{
158160
// Initialize the camera view
@@ -161,7 +163,7 @@ void updateVisualization()
161163
pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
162164
viewer.initCameraParameters();
163165
viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
164-
ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
166+
ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
165167
xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
166168
viewer_initialized_ = true;
167169
}
@@ -175,7 +177,7 @@ void updateVisualization()
175177
{
176178
if (pcl::io::savePCDFile(pcd_filename_, cloud_xyz_rgb) == 0)
177179
ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
178-
else
180+
else
179181
ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
180182
save_cloud_ = false;
181183
}
@@ -189,7 +191,7 @@ void updateVisualization()
189191
pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb, covariance_matrix, xyz_centroid);
190192
viewer.initCameraParameters();
191193
viewer.setCameraPosition(xyz_centroid(0), xyz_centroid(1), xyz_centroid(2)+3.0, 0, -1, 0);
192-
ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
194+
ROS_INFO_STREAM("[PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
193195
xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
194196
viewer_initialized_ = true;
195197
}
@@ -202,7 +204,7 @@ void updateVisualization()
202204
pcl::copyPointCloud(cloud_xyz_rgb, cloud_xyz);
203205
}
204206
}
205-
207+
206208
// Show the xyz point cloud
207209
PointCloudColorHandlerGenericField<Point> color_handler (cloud_xyz.makeShared(), "z");
208210
if (!color_handler.isCapable ())
@@ -218,7 +220,7 @@ void updateVisualization()
218220
{
219221
if (pcl::io::savePCDFile(pcd_filename_, cloud_xyz) == 0)
220222
ROS_INFO_STREAM("[PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
221-
else
223+
else
222224
ROS_ERROR_STREAM("[PointCloudViewer:] Problem saving " << pcd_filename_.c_str());
223225
save_cloud_ = false;
224226
}

0 commit comments

Comments
 (0)