Skip to content

Commit d349f2b

Browse files
committed
Add visualization for clouds with normals
1 parent ccafc03 commit d349f2b

File tree

1 file changed

+38
-2
lines changed

1 file changed

+38
-2
lines changed

pointcloud_tools/src/pointcloud_viewer.cpp

Lines changed: 38 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,9 @@
5353
using pcl::visualization::PointCloudColorHandlerGenericField;
5454

5555
typedef pcl::PointXYZ Point;
56+
typedef pcl::PointNormal PointNormal;
5657
typedef pcl::PointCloud<Point> PointCloud;
58+
typedef pcl::PointCloud<PointNormal> PointCloudNormal;
5759
typedef pcl::PointXYZRGB PointRGB;
5860
typedef pcl::PointCloud<PointRGB> PointCloudRGB;
5961

@@ -67,6 +69,7 @@ int counter_;
6769
ros::WallTimer save_timer_;
6870

6971
PointCloud cloud_xyz_;
72+
PointCloudNormal cloud_xyzn_;
7073
PointCloudRGB cloud_xyz_rgb_;
7174

7275
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud)
@@ -92,6 +95,7 @@ void updateVisualization()
9295

9396
ros::WallDuration d(0.01);
9497
bool rgb = false;
98+
bool normal = false;
9599
std::vector<pcl::PCLPointField> fields;
96100

97101
// Create the visualizer
@@ -121,9 +125,15 @@ void updateVisualization()
121125
rgb = true;
122126
pcl::fromROSMsg(*cloud_, cloud_xyz_rgb_);
123127
}
128+
else if (pcl::getFieldIndex(*cloud_, "normal_x") != -1)
129+
{
130+
normal = true;
131+
pcl::fromROSMsg(*cloud_, cloud_xyzn_);
132+
}
124133
else
125134
{
126135
rgb = false;
136+
normal = false;
127137
pcl::fromROSMsg(*cloud_, cloud_xyz_);
128138
pcl::getFields(cloud_xyz_, fields);
129139
}
@@ -143,7 +153,7 @@ void updateVisualization()
143153
pcl::computeMeanAndCovarianceMatrix(cloud_xyz_rgb_, covariance_matrix, xyz_centroid);
144154
viewer.initCameraParameters();
145155
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: [" <<
147157
xyz_centroid(0) << ", " << xyz_centroid(1) << ", " << xyz_centroid(2)+3.0 << "]");
148158
viewer_initialized_ = true;
149159
}
@@ -152,6 +162,32 @@ void updateVisualization()
152162
cloud_xyz_rgb_.makeShared());
153163
viewer.addPointCloud(cloud_xyz_rgb_.makeShared(), color_handler, "cloud");
154164
}
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+
}
155191
else
156192
{
157193
// Initialize the camera view
@@ -238,7 +274,7 @@ int main(int argc, char** argv)
238274
nh_priv.param("pcd_filename", pcd_filename_, std::string("pointcloud_file.pcd"));
239275

240276
// Create a ROS subscriber
241-
ros::Subscriber sub = nh.subscribe("input", 30, cloud_cb);
277+
ros::Subscriber sub = nh.subscribe("input", 1, cloud_cb);
242278

243279
ROS_INFO("[PointCloudViewer:] Subscribing to %s for PointCloud2 messages...", nh.resolveName ("input").c_str ());
244280

0 commit comments

Comments
 (0)