53
53
using pcl::visualization::PointCloudColorHandlerGenericField;
54
54
55
55
typedef pcl::PointXYZ Point;
56
+ typedef pcl::PointNormal PointNormal;
56
57
typedef pcl::PointCloud<Point> PointCloud;
58
+ typedef pcl::PointCloud<PointNormal> PointCloudNormal;
57
59
typedef pcl::PointXYZRGB PointRGB;
58
60
typedef pcl::PointCloud<PointRGB> PointCloudRGB;
59
61
@@ -67,6 +69,7 @@ int counter_;
67
69
ros::WallTimer save_timer_;
68
70
69
71
PointCloud cloud_xyz_;
72
+ PointCloudNormal cloud_xyzn_;
70
73
PointCloudRGB cloud_xyz_rgb_;
71
74
72
75
void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
@@ -92,6 +95,7 @@ void updateVisualization()
92
95
93
96
ros::WallDuration d (0.01 );
94
97
bool rgb = false ;
98
+ bool normal = false ;
95
99
std::vector<pcl::PCLPointField> fields;
96
100
97
101
// Create the visualizer
@@ -121,9 +125,15 @@ void updateVisualization()
121
125
rgb = true ;
122
126
pcl::fromROSMsg (*cloud_, cloud_xyz_rgb_);
123
127
}
128
+ else if (pcl::getFieldIndex (*cloud_, " normal_x" ) != -1 )
129
+ {
130
+ normal = true ;
131
+ pcl::fromROSMsg (*cloud_, cloud_xyzn_);
132
+ }
124
133
else
125
134
{
126
135
rgb = false ;
136
+ normal = false ;
127
137
pcl::fromROSMsg (*cloud_, cloud_xyz_);
128
138
pcl::getFields (cloud_xyz_, fields);
129
139
}
@@ -143,7 +153,7 @@ void updateVisualization()
143
153
pcl::computeMeanAndCovarianceMatrix (cloud_xyz_rgb_, covariance_matrix, xyz_centroid);
144
154
viewer.initCameraParameters ();
145
155
viewer.setCameraPosition (xyz_centroid (0 ), xyz_centroid (1 ), xyz_centroid (2 )+3.0 , 0 , -1 , 0 );
146
- ROS_INFO_STREAM (" [PointCloudViewer:] Point cloud viewer camera initialized in: [" <<
156
+ ROS_INFO_STREAM (" [PointCloudViewer:] Point cloud rgb viewer camera initialized in: [" <<
147
157
xyz_centroid (0 ) << " , " << xyz_centroid (1 ) << " , " << xyz_centroid (2 )+3.0 << " ]" );
148
158
viewer_initialized_ = true ;
149
159
}
@@ -152,6 +162,32 @@ void updateVisualization()
152
162
cloud_xyz_rgb_.makeShared ());
153
163
viewer.addPointCloud (cloud_xyz_rgb_.makeShared (), color_handler, " cloud" );
154
164
}
165
+ else if (normal && pcl::getFieldIndex (cloud_xyzn_, " normal_x" , fields) != -1 )
166
+ {
167
+ // Initialize the camera view
168
+ if (!viewer_initialized_)
169
+ {
170
+ pcl::computeMeanAndCovarianceMatrix (cloud_xyzn_, covariance_matrix, xyz_centroid);
171
+ viewer.initCameraParameters ();
172
+ viewer.setCameraPosition (xyz_centroid (0 ), xyz_centroid (1 ), xyz_centroid (2 )+3.0 , 0 , -1 , 0 );
173
+ ROS_INFO_STREAM (" [PointCloudViewer:] Point cloud normal viewer camera initialized in: [" <<
174
+ xyz_centroid (0 ) << " , " << xyz_centroid (1 ) << " , " << xyz_centroid (2 )+3.0 << " ]" );
175
+ viewer_initialized_ = true ;
176
+ }
177
+ // Show the point cloud
178
+ // Show the xyz point cloud
179
+ PointCloudColorHandlerGenericField<PointNormal> color_handler (cloud_xyzn_.makeShared (), " z" );
180
+ if (!color_handler.isCapable ())
181
+ {
182
+ ROS_WARN_STREAM (" [PointCloudViewer:] Cannot create curvature color handler!" );
183
+ pcl::visualization::PointCloudColorHandlerCustom<PointNormal> color_handler (
184
+ cloud_xyzn_.makeShared (), 255 , 0 , 255 );
185
+ }
186
+ viewer.addPointCloud <PointNormal>(cloud_xyzn_.makeShared (), color_handler, " cloud" );
187
+ // Delete the previous point cloud
188
+ viewer.removePointCloud (" normals" );
189
+ viewer.addPointCloudNormals <PointNormal>(cloud_xyzn_.makeShared (), 100 , 0.02 , " normals" );
190
+ }
155
191
else
156
192
{
157
193
// Initialize the camera view
@@ -238,7 +274,7 @@ int main(int argc, char** argv)
238
274
nh_priv.param (" pcd_filename" , pcd_filename_, std::string (" pointcloud_file.pcd" ));
239
275
240
276
// Create a ROS subscriber
241
- ros::Subscriber sub = nh.subscribe (" input" , 30 , cloud_cb);
277
+ ros::Subscriber sub = nh.subscribe (" input" , 1 , cloud_cb);
242
278
243
279
ROS_INFO (" [PointCloudViewer:] Subscribing to %s for PointCloud2 messages..." , nh.resolveName (" input" ).c_str ());
244
280
0 commit comments