@@ -70,7 +70,7 @@ void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
70
70
{
71
71
m.lock ();
72
72
printf (" \r PointCloud 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 (),
74
74
cloud->header .stamp .toSec (), cloud->header .frame_id .c_str ());
75
75
cloud_ = cloud;
76
76
m.unlock ();
@@ -96,8 +96,10 @@ PointCloudRGB::Ptr filter(PointCloudRGB::Ptr cloud, double voxel_size)
96
96
97
97
void keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event, void * nothing)
98
98
{
99
- if (event.getKeySym () == " space" && event.keyDown ())
99
+ if (event.getKeySym () == " space" && event.keyDown ()) {
100
+ ROS_INFO (" SAVING POINTCLOUD, PLEASE WAIT..." );
100
101
save_cloud_ = true ;
102
+ }
101
103
}
102
104
103
105
void updateVisualization ()
@@ -111,7 +113,7 @@ void updateVisualization()
111
113
bool rgb = false ;
112
114
// std::vector<sensor_msgs::PointField> fields;
113
115
std::vector<pcl::PCLPointField> fields;
114
-
116
+
115
117
// Create the visualizer
116
118
pcl::visualization::PCLVisualizer viewer (" Point Cloud Viewer" );
117
119
@@ -132,7 +134,7 @@ void updateVisualization()
132
134
if (cloud_old_ == cloud_)
133
135
continue ;
134
136
m.lock ();
135
-
137
+
136
138
// Convert to PointCloud<T>
137
139
if (pcl::getFieldIndex (*cloud_, " rgb" ) != -1 )
138
140
{
@@ -150,9 +152,9 @@ void updateVisualization()
150
152
151
153
// Delete the previous point cloud
152
154
viewer.removePointCloud (" cloud" );
153
-
155
+
154
156
// 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 &&
156
158
cloud_xyz_rgb.points [0 ].rgb != 0 )
157
159
{
158
160
// Initialize the camera view
@@ -161,7 +163,7 @@ void updateVisualization()
161
163
pcl::computeMeanAndCovarianceMatrix (cloud_xyz_rgb, covariance_matrix, xyz_centroid);
162
164
viewer.initCameraParameters ();
163
165
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: [" <<
165
167
xyz_centroid (0 ) << " , " << xyz_centroid (1 ) << " , " << xyz_centroid (2 )+3.0 << " ]" );
166
168
viewer_initialized_ = true ;
167
169
}
@@ -175,7 +177,7 @@ void updateVisualization()
175
177
{
176
178
if (pcl::io::savePCDFile (pcd_filename_, cloud_xyz_rgb) == 0 )
177
179
ROS_INFO_STREAM (" [PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
178
- else
180
+ else
179
181
ROS_ERROR_STREAM (" [PointCloudViewer:] Problem saving " << pcd_filename_.c_str ());
180
182
save_cloud_ = false ;
181
183
}
@@ -189,7 +191,7 @@ void updateVisualization()
189
191
pcl::computeMeanAndCovarianceMatrix (cloud_xyz_rgb, covariance_matrix, xyz_centroid);
190
192
viewer.initCameraParameters ();
191
193
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: [" <<
193
195
xyz_centroid (0 ) << " , " << xyz_centroid (1 ) << " , " << xyz_centroid (2 )+3.0 << " ]" );
194
196
viewer_initialized_ = true ;
195
197
}
@@ -202,7 +204,7 @@ void updateVisualization()
202
204
pcl::copyPointCloud (cloud_xyz_rgb, cloud_xyz);
203
205
}
204
206
}
205
-
207
+
206
208
// Show the xyz point cloud
207
209
PointCloudColorHandlerGenericField<Point> color_handler (cloud_xyz.makeShared (), " z" );
208
210
if (!color_handler.isCapable ())
@@ -218,7 +220,7 @@ void updateVisualization()
218
220
{
219
221
if (pcl::io::savePCDFile (pcd_filename_, cloud_xyz) == 0 )
220
222
ROS_INFO_STREAM (" [PointCloudViewer:] Pointcloud saved into: " << pcd_filename_);
221
- else
223
+ else
222
224
ROS_ERROR_STREAM (" [PointCloudViewer:] Problem saving " << pcd_filename_.c_str ());
223
225
save_cloud_ = false ;
224
226
}
0 commit comments