00001 #include <pcl/common/time.h>
00002 #include <pcl/console/parse.h>
00003 #include <pcl/point_cloud.h>
00004 #include <pcl/point_types.h>
00005 #include <pcl/io/png_io.h>
00006 #include <pcl/io/pcd_io.h>
00007 #include <pcl/visualization/pcl_visualizer.h>
00008 #include <pcl/segmentation/supervoxel_clustering.h>
00009
00010 #include <vtkImageReader2Factory.h>
00011 #include <vtkImageReader2.h>
00012 #include <vtkImageData.h>
00013 #include <vtkImageFlip.h>
00014
00015
00016 typedef pcl::PointXYZRGBA PointT;
00017 typedef pcl::PointCloud<PointT> PointCloudT;
00018 typedef pcl::PointNormal PointNT;
00019 typedef pcl::PointCloud<PointNT> PointNCloudT;
00020 typedef pcl::PointXYZL PointLT;
00021 typedef pcl::PointCloud<PointLT> PointLCloudT;
00022
00023 bool show_voxel_centroids = true;
00024 bool show_supervoxels = true;
00025 bool show_supervoxel_normals = false;
00026 bool show_graph = true;
00027 bool show_normals = false;
00028 bool show_refined = false;
00029 bool show_help = true;
00030
00031 void
00032 keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00033 {
00034 int key = event.getKeyCode ();
00035
00036 if (event.keyUp ())
00037 switch (key)
00038 {
00039 case (int)'1': show_voxel_centroids = !show_voxel_centroids; break;
00040 case (int)'2': show_supervoxels = !show_supervoxels; break;
00041 case (int)'3': show_graph = !show_graph; break;
00042 case (int)'4': show_normals = !show_normals; break;
00043 case (int)'5': show_supervoxel_normals = !show_supervoxel_normals; break;
00044 case (int)'0': show_refined = !show_refined; break;
00045 case (int)'h': case (int)'H': show_help = !show_help; break;
00046 default: break;
00047 }
00048
00049 }
00050
00051 void addSupervoxelConnectionsToViewer (PointT &supervoxel_center,
00052 PointCloudT &adjacent_supervoxel_centers,
00053 std::string supervoxel_name,
00054 boost::shared_ptr<pcl::visualization::PCLVisualizer> & viewer);
00055
00056 void printText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer);
00057 void removeText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer);
00058
00059 using namespace pcl;
00060
00061 int
00062 main (int argc, char ** argv)
00063 {
00064 if (argc < 2)
00065 {
00066 pcl::console::print_info ("Syntax is: %s {-p <pcd-file> OR -r <rgb-file> -d <depth-file>} \n --NT (disables use of single camera transform) \n -o <output-file> \n -O <refined-output-file> \n-l <output-label-file> \n -L <refined-output-label-file> \n-v <voxel resolution> \n-s <seed resolution> \n-c <color weight> \n-z <spatial weight> \n-n <normal_weight>] \n", argv[0]);
00067 return (1);
00068 }
00069
00075 std::string rgb_path;
00076 bool rgb_file_specified = pcl::console::find_switch (argc, argv, "-r");
00077 if (rgb_file_specified)
00078 pcl::console::parse (argc, argv, "-r", rgb_path);
00079
00080 std::string depth_path;
00081 bool depth_file_specified = pcl::console::find_switch (argc, argv, "-d");
00082 if (depth_file_specified)
00083 pcl::console::parse (argc, argv, "-d", depth_path);
00084
00085 PointCloudT::Ptr cloud = boost::make_shared < PointCloudT >();
00086 bool pcd_file_specified = pcl::console::find_switch (argc, argv, "-p");
00087 std::string pcd_path;
00088 if (!depth_file_specified || !rgb_file_specified)
00089 {
00090 std::cout << "Using point cloud\n";
00091 if (!pcd_file_specified)
00092 {
00093 std::cout << "No cloud specified!";
00094 return (1);
00095 }else
00096 {
00097 pcl::console::parse (argc,argv,"-p",pcd_path);
00098 }
00099 }
00100
00101
00102 bool disable_transform = pcl::console::find_switch (argc, argv, "--NT");
00103
00104 std::string out_path;
00105 bool output_file_specified = pcl::console::find_switch (argc, argv, "-o");
00106 if (output_file_specified)
00107 pcl::console::parse (argc, argv, "-o", out_path);
00108 else
00109 out_path = "test_output.png";
00110
00111 std::string out_label_path;
00112 bool output_label_file_specified = pcl::console::find_switch (argc, argv, "-l");
00113 if (output_label_file_specified)
00114 pcl::console::parse (argc, argv, "-l", out_label_path);
00115 else
00116 out_label_path = "test_output_labels.png";
00117
00118 std::string refined_out_path;
00119 bool refined_output_file_specified = pcl::console::find_switch (argc, argv, "-O");
00120 if (refined_output_file_specified)
00121 pcl::console::parse (argc, argv, "-O", refined_out_path);
00122 else
00123 refined_out_path = "refined_test_output.png";
00124
00125 std::string refined_out_label_path;
00126 bool refined_output_label_file_specified = pcl::console::find_switch (argc, argv, "-L");
00127 if (refined_output_label_file_specified)
00128 pcl::console::parse (argc, argv, "-L", refined_out_label_path);
00129 else
00130 refined_out_label_path = "refined_test_output_labels.png";
00131
00132 float voxel_resolution = 0.008f;
00133 bool voxel_res_specified = pcl::console::find_switch (argc, argv, "-v");
00134 if (voxel_res_specified)
00135 pcl::console::parse (argc, argv, "-v", voxel_resolution);
00136
00137 float seed_resolution = 0.08f;
00138 bool seed_res_specified = pcl::console::find_switch (argc, argv, "-s");
00139 if (seed_res_specified)
00140 pcl::console::parse (argc, argv, "-s", seed_resolution);
00141
00142 float color_importance = 0.2f;
00143 if (pcl::console::find_switch (argc, argv, "-c"))
00144 pcl::console::parse (argc, argv, "-c", color_importance);
00145
00146 float spatial_importance = 0.4f;
00147 if (pcl::console::find_switch (argc, argv, "-z"))
00148 pcl::console::parse (argc, argv, "-z", spatial_importance);
00149
00150 float normal_importance = 1.0f;
00151 if (pcl::console::find_switch (argc, argv, "-n"))
00152 pcl::console::parse (argc, argv, "-n", normal_importance);
00153
00154 if (!pcd_file_specified)
00155 {
00156
00157 vtkSmartPointer<vtkImageReader2Factory> reader_factory = vtkSmartPointer<vtkImageReader2Factory>::New ();
00158 vtkImageReader2* rgb_reader = reader_factory->CreateImageReader2 (rgb_path.c_str ());
00159
00160 if ( ! rgb_reader->CanReadFile (rgb_path.c_str ()))
00161 {
00162 std::cout << "Cannot read rgb image file!";
00163 return (1);
00164 }
00165 rgb_reader->SetFileName (rgb_path.c_str ());
00166 rgb_reader->Update ();
00167
00168 vtkImageReader2* depth_reader = reader_factory->CreateImageReader2 (depth_path.c_str ());
00169 if ( ! depth_reader->CanReadFile (depth_path.c_str ()))
00170 {
00171 std::cout << "Cannot read depth image file!";
00172 return (1);
00173 }
00174 depth_reader->SetFileName (depth_path.c_str ());
00175 depth_reader->Update ();
00176
00177 vtkSmartPointer<vtkImageFlip> flipXFilter = vtkSmartPointer<vtkImageFlip>::New();
00178 flipXFilter->SetFilteredAxis(0);
00179 flipXFilter->SetInputConnection(rgb_reader->GetOutputPort());
00180 flipXFilter->Update();
00181
00182 vtkSmartPointer<vtkImageFlip> flipXFilter2 = vtkSmartPointer<vtkImageFlip>::New();
00183 flipXFilter2->SetFilteredAxis(0);
00184 flipXFilter2->SetInputConnection(depth_reader->GetOutputPort());
00185 flipXFilter2->Update();
00186
00187 vtkSmartPointer<vtkImageData> rgb_image = flipXFilter->GetOutput ();
00188 int *rgb_dims = rgb_image->GetDimensions ();
00189 vtkSmartPointer<vtkImageData> depth_image = flipXFilter2->GetOutput ();
00190 int *depth_dims = depth_image->GetDimensions ();
00191
00192 if (rgb_dims[0] != depth_dims[0] || rgb_dims[1] != depth_dims[1])
00193 {
00194 std::cout << "Depth and RGB dimensions to not match!";
00195 std::cout << "RGB Image is of size "<<rgb_dims[0] << " by "<<rgb_dims[1];
00196 std::cout << "Depth Image is of size "<<depth_dims[0] << " by "<<depth_dims[1];
00197 return (1);
00198 }
00199
00200 cloud->points.reserve (depth_dims[0] * depth_dims[1]);
00201 cloud->width = depth_dims[0];
00202 cloud->height = depth_dims[1];
00203 cloud->is_dense = false;
00204
00205
00206
00207 int centerX = static_cast<int>(cloud->width / 2.0);
00208 int centerY = static_cast<int>(cloud->height / 2.0);
00209 unsigned short* depth_pixel;
00210 unsigned char* color_pixel;
00211 float scale = 1.0f/1000.0f;
00212 float focal_length = 525.0f;
00213 float fl_const = 1.0f / focal_length;
00214 depth_pixel = static_cast<unsigned short*>(depth_image->GetScalarPointer (depth_dims[0]-1,depth_dims[1]-1,0));
00215 color_pixel = static_cast<unsigned char*> (rgb_image->GetScalarPointer (depth_dims[0]-1,depth_dims[1]-1,0));
00216
00217 for (int y=0; y<cloud->height; ++y)
00218 {
00219 for (int x=0; x<cloud->width; ++x, --depth_pixel, color_pixel-=3)
00220 {
00221 PointT new_point;
00222
00223 float depth = static_cast<float>(*depth_pixel) * scale;
00224 if (depth == 0.0f)
00225 {
00226 new_point.x = new_point.y = new_point.z = std::numeric_limits<float>::quiet_NaN ();
00227 }
00228 else
00229 {
00230 new_point.x = (static_cast<float>(x - centerX)) * depth * fl_const;
00231 new_point.y = (static_cast<float>(centerY - y)) * depth * fl_const;
00232 new_point.z = depth;
00233 }
00234
00235 uint32_t rgb = static_cast<uint32_t>(color_pixel[0]) << 16 | static_cast<uint32_t>(color_pixel[1]) << 8 | static_cast<uint32_t>(color_pixel[2]);
00236 new_point.rgb = *reinterpret_cast<float*> (&rgb);
00237 cloud->points.push_back (new_point);
00238
00239 }
00240 }
00241 }
00242 else
00243 {
00244 std::cout << "Loading pointcloud...\n";
00245 pcl::io::loadPCDFile (pcd_path, *cloud);
00246 for (PointCloudT::iterator cloud_itr = cloud->begin (); cloud_itr != cloud->end (); ++cloud_itr)
00247 if (cloud_itr->z < 0)
00248 cloud_itr->z = std::abs (cloud_itr->z);
00249 }
00250
00251 std::cout << "Done making cloud!\n";
00252
00258
00259 pcl::SupervoxelClustering<PointT> super (voxel_resolution, seed_resolution,!disable_transform);
00260 super.setInputCloud (cloud);
00261 super.setColorImportance (color_importance);
00262 super.setSpatialImportance (spatial_importance);
00263 super.setNormalImportance (normal_importance);
00264 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
00265
00266 std::cout << "Extracting supervoxels!\n";
00267 super.extract (supervoxel_clusters);
00268 std::cout << "Found " << supervoxel_clusters.size () << " Supervoxels!\n";
00269 PointCloudT::Ptr colored_voxel_cloud = super.getColoredVoxelCloud ();
00270 PointCloudT::Ptr voxel_centroid_cloud = super.getVoxelCentroidCloud ();
00271 PointCloudT::Ptr full_colored_cloud = super.getColoredCloud ();
00272 PointNCloudT::Ptr sv_normal_cloud = super.makeSupervoxelNormalCloud (supervoxel_clusters);
00273 PointLCloudT::Ptr full_labeled_cloud = super.getLabeledCloud ();
00274
00275 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr > refined_supervoxel_clusters;
00276 std::cout << "Refining supervoxels \n";
00277 super.refineSupervoxels (3, refined_supervoxel_clusters);
00278
00279 PointCloudT::Ptr refined_colored_voxel_cloud = super.getColoredVoxelCloud ();
00280 PointNCloudT::Ptr refined_sv_normal_cloud = super.makeSupervoxelNormalCloud (refined_supervoxel_clusters);
00281 PointLCloudT::Ptr refined_full_labeled_cloud = super.getLabeledCloud ();
00282 PointCloudT::Ptr refined_full_colored_cloud = super.getColoredCloud ();
00283
00284 std::cout << "Getting supervoxel adjacency\n";
00285 std::multimap<uint32_t, uint32_t> label_adjacency;
00286 super.getSupervoxelAdjacency (label_adjacency);
00287
00288
00289 pcl::io::savePNGFile (out_path, *full_colored_cloud);
00290 pcl::io::savePNGFile (refined_out_path, *refined_full_colored_cloud);
00291 pcl::io::savePNGFile (out_label_path, *full_labeled_cloud);
00292 pcl::io::savePNGFile (refined_out_label_path, *refined_full_labeled_cloud);
00293
00294 std::cout << "Constructing Boost Graph Library Adjacency List...\n";
00295 typedef boost::adjacency_list<boost::setS, boost::setS, boost::undirectedS, uint32_t, float> VoxelAdjacencyList;
00296 typedef VoxelAdjacencyList::vertex_descriptor VoxelID;
00297 typedef VoxelAdjacencyList::edge_descriptor EdgeID;
00298 VoxelAdjacencyList supervoxel_adjacency_list;
00299 super.getSupervoxelAdjacencyList (supervoxel_adjacency_list);
00300
00301
00302 std::cout << "Loading visualization...\n";
00303 boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00304 viewer->setBackgroundColor (0, 0, 0);
00305 viewer->registerKeyboardCallback(keyboard_callback, 0);
00306
00307
00308 bool refined_normal_shown = show_refined;
00309 bool refined_sv_normal_shown = show_refined;
00310 bool sv_added = false;
00311 bool normals_added = false;
00312 bool graph_added = false;
00313 std::vector<std::string> poly_names;
00314 std::cout << "Loading viewer...\n";
00315 while (!viewer->wasStopped ())
00316 {
00317 if (show_voxel_centroids)
00318 {
00319 if (!viewer->updatePointCloud (voxel_centroid_cloud, "voxel centroids"))
00320 viewer->addPointCloud (voxel_centroid_cloud, "voxel centroids");
00321 viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE,2.0, "voxel centroids");
00322 if (show_supervoxels)
00323 viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY,0.5, "voxel centroids");
00324 else
00325 viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY,1.0, "voxel centroids");
00326 }
00327 else
00328 {
00329 viewer->removePointCloud ("voxel centroids");
00330 }
00331
00332 if (show_supervoxels)
00333 {
00334 if (!viewer->updatePointCloud ((show_refined)?refined_colored_voxel_cloud:colored_voxel_cloud, "colored voxels"))
00335 viewer->addPointCloud ((show_refined)?refined_colored_voxel_cloud:colored_voxel_cloud, "colored voxels");
00336 viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY,0.9, "colored voxels");
00337 }
00338 else
00339 {
00340 viewer->removePointCloud ("colored voxels");
00341 }
00342
00343
00344 if (show_supervoxel_normals)
00345 {
00346 if (refined_sv_normal_shown != show_refined || !sv_added)
00347 {
00348 viewer->removePointCloud ("supervoxel_normals");
00349 viewer->addPointCloudNormals<PointNormal> ((show_refined)?refined_sv_normal_cloud:sv_normal_cloud,1,0.05f, "supervoxel_normals");
00350 sv_added = true;
00351 }
00352 refined_sv_normal_shown = show_refined;
00353 }
00354 else if (!show_supervoxel_normals)
00355 {
00356 viewer->removePointCloud ("supervoxel_normals");
00357 }
00358
00359 if (show_normals)
00360 {
00361 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr>::iterator sv_itr,sv_itr_end;
00362 sv_itr = ((show_refined)?refined_supervoxel_clusters.begin ():supervoxel_clusters.begin ());
00363 sv_itr_end = ((show_refined)?refined_supervoxel_clusters.end ():supervoxel_clusters.end ());
00364 for (; sv_itr != sv_itr_end; ++sv_itr)
00365 {
00366 std::stringstream ss;
00367 ss << sv_itr->first <<"_normal";
00368 if (refined_normal_shown != show_refined || !normals_added)
00369 {
00370 viewer->removePointCloud (ss.str ());
00371 viewer->addPointCloudNormals<PointT,Normal> ((sv_itr->second)->voxels_,(sv_itr->second)->normals_,10,0.02f,ss.str ());
00372
00373
00374 }
00375
00376 }
00377 normals_added = true;
00378 refined_normal_shown = show_refined;
00379 }
00380 else if (!show_normals)
00381 {
00382 std::map <uint32_t, pcl::Supervoxel<PointT>::Ptr>::iterator sv_itr,sv_itr_end;
00383 sv_itr = ((show_refined)?refined_supervoxel_clusters.begin ():supervoxel_clusters.begin ());
00384 sv_itr_end = ((show_refined)?refined_supervoxel_clusters.end ():supervoxel_clusters.end ());
00385 for (; sv_itr != sv_itr_end; ++sv_itr)
00386 {
00387 std::stringstream ss;
00388 ss << sv_itr->first << "_normal";
00389 viewer->removePointCloud (ss.str ());
00390 }
00391 }
00392
00393 if (show_graph && !graph_added)
00394 {
00395 poly_names.clear ();
00396 std::multimap<uint32_t,uint32_t>::iterator label_itr = label_adjacency.begin ();
00397 for ( ; label_itr != label_adjacency.end (); )
00398 {
00399
00400 uint32_t supervoxel_label = label_itr->first;
00401
00402 pcl::Supervoxel<PointT>::Ptr supervoxel = supervoxel_clusters.at (supervoxel_label);
00403
00404 PointCloudT adjacent_supervoxel_centers;
00405 std::multimap<uint32_t,uint32_t>::iterator adjacent_itr = label_adjacency.equal_range (supervoxel_label).first;
00406 for ( ; adjacent_itr!=label_adjacency.equal_range (supervoxel_label).second; ++adjacent_itr)
00407 {
00408 pcl::Supervoxel<PointT>::Ptr neighbor_supervoxel = supervoxel_clusters.at (adjacent_itr->second);
00409 adjacent_supervoxel_centers.push_back (neighbor_supervoxel->centroid_);
00410 }
00411
00412 std::stringstream ss;
00413 ss << "supervoxel_" << supervoxel_label;
00414 poly_names.push_back (ss.str ());
00415 addSupervoxelConnectionsToViewer (supervoxel->centroid_, adjacent_supervoxel_centers, ss.str (), viewer);
00416
00417 label_itr = label_adjacency.upper_bound (supervoxel_label);
00418 }
00419
00420 graph_added = true;
00421 }
00422 else if (!show_graph && graph_added)
00423 {
00424 for (std::vector<std::string>::iterator name_itr = poly_names.begin (); name_itr != poly_names.end (); ++name_itr)
00425 {
00426 viewer->removeShape (*name_itr);
00427 }
00428 graph_added = false;
00429 }
00430
00431 if (show_help)
00432 {
00433 viewer->removeShape ("help_text");
00434 printText (viewer);
00435 }
00436 else
00437 {
00438 removeText (viewer);
00439 if (!viewer->updateText("Press h to show help", 5, 10, 12, 1.0, 1.0, 1.0,"help_text") )
00440 viewer->addText("Press h to show help", 5, 10, 12, 1.0, 1.0, 1.0,"help_text");
00441 }
00442
00443
00444 viewer->spinOnce (100);
00445 boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00446
00447 }
00448 return (0);
00449 }
00450
00451 void
00452 addSupervoxelConnectionsToViewer (PointT &supervoxel_center,
00453 PointCloudT &adjacent_supervoxel_centers,
00454 std::string supervoxel_name,
00455 boost::shared_ptr<pcl::visualization::PCLVisualizer> & viewer)
00456 {
00457 vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New ();
00458 vtkSmartPointer<vtkCellArray> cells = vtkSmartPointer<vtkCellArray>::New ();
00459 vtkSmartPointer<vtkPolyLine> polyLine = vtkSmartPointer<vtkPolyLine>::New ();
00460
00461
00462 PointCloudT::iterator adjacent_itr = adjacent_supervoxel_centers.begin ();
00463 for ( ; adjacent_itr != adjacent_supervoxel_centers.end (); ++adjacent_itr)
00464 {
00465 points->InsertNextPoint (supervoxel_center.data);
00466 points->InsertNextPoint (adjacent_itr->data);
00467 }
00468
00469 vtkSmartPointer<vtkPolyData> polyData = vtkSmartPointer<vtkPolyData>::New ();
00470
00471 polyData->SetPoints (points);
00472 polyLine->GetPointIds ()->SetNumberOfIds(points->GetNumberOfPoints ());
00473 for(unsigned int i = 0; i < points->GetNumberOfPoints (); i++)
00474 polyLine->GetPointIds ()->SetId (i,i);
00475 cells->InsertNextCell (polyLine);
00476
00477 polyData->SetLines (cells);
00478 viewer->addModelFromPolyData (polyData,supervoxel_name);
00479 }
00480
00481
00482 void printText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer)
00483 {
00484 std::string on_str = "on";
00485 std::string off_str = "off";
00486 if (!viewer->updateText ("Press (1-n) to show different elements (h) to disable this", 5, 72, 12, 1.0, 1.0, 1.0,"hud_text"))
00487 viewer->addText ("Press 1-n to show different elements", 5, 72, 12, 1.0, 1.0, 1.0,"hud_text");
00488
00489 std::string temp = "(1) Voxels currently " + ((show_voxel_centroids)?on_str:off_str);
00490 if (!viewer->updateText (temp, 5, 60, 10, 1.0, 1.0, 1.0, "voxel_text"))
00491 viewer->addText (temp, 5, 60, 10, 1.0, 1.0, 1.0, "voxel_text");
00492
00493 temp = "(2) Supervoxels currently "+ ((show_supervoxels)?on_str:off_str);
00494 if (!viewer->updateText (temp, 5, 50, 10, 1.0, 1.0, 1.0, "supervoxel_text") )
00495 viewer->addText (temp, 5, 50, 10, 1.0, 1.0, 1.0, "supervoxel_text");
00496
00497 temp = "(3) Graph currently "+ ((show_graph)?on_str:off_str);
00498 if (!viewer->updateText (temp, 5, 40, 10, 1.0, 1.0, 1.0, "graph_text") )
00499 viewer->addText (temp, 5, 40, 10, 1.0, 1.0, 1.0, "graph_text");
00500
00501 temp = "(4) Voxel Normals currently "+ ((show_normals)?on_str:off_str);
00502 if (!viewer->updateText (temp, 5, 30, 10, 1.0, 1.0, 1.0, "voxel_normals_text") )
00503 viewer->addText (temp, 5, 30, 10, 1.0, 1.0, 1.0, "voxel_normals_text");
00504
00505 temp = "(5) Supervoxel Normals currently "+ ((show_supervoxel_normals)?on_str:off_str);
00506 if (!viewer->updateText (temp, 5, 20, 10, 1.0, 1.0, 1.0, "supervoxel_normals_text") )
00507 viewer->addText (temp, 5, 20, 10, 1.0, 1.0, 1.0, "supervoxel_normals_text");
00508
00509 temp = "(0) Showing "+ std::string((show_refined)?"":"UN-") + "refined supervoxels and normals";
00510 if (!viewer->updateText (temp, 5, 10, 10, 1.0, 1.0, 1.0, "refined_text") )
00511 viewer->addText (temp, 5, 10, 10, 1.0, 1.0, 1.0, "refined_text");
00512 }
00513
00514 void removeText (boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer)
00515 {
00516 viewer->removeShape ("hud_text");
00517 viewer->removeShape ("voxel_text");
00518 viewer->removeShape ("supervoxel_text");
00519 viewer->removeShape ("graph_text");
00520 viewer->removeShape ("voxel_normals_text");
00521 viewer->removeShape ("supervoxel_normals_text");
00522 viewer->removeShape ("refined_text");
00523 }
00524
00525