00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #include <pcl/io/pcd_io.h>
00039 #include <pcl/common/time.h>
00040 #include <pcl/visualization/pcl_visualizer.h>
00041 #include <pcl/visualization/point_cloud_handlers.h>
00042 #include <pcl/visualization/common/common.h>
00043 
00044 #include <pcl/octree/octree.h>
00045 #include <pcl/octree/octree_impl.h>
00046 
00047 #include <pcl/filters/filter.h>
00048 #include "boost.h"
00049 
00050 #include <vtkRenderer.h>
00051 #include <vtkRenderWindow.h>
00052 #include <vtkCubeSource.h>
00053 
00054 
00055 
00056  const int MAX_DISPLAYED_CUBES(15000);
00057 
00058 
00059 class OctreeViewer
00060 {
00061 public:
00062   OctreeViewer (std::string &filename, double resolution) :
00063     viz ("Octree visualizator"), cloud (new pcl::PointCloud<pcl::PointXYZ>()),
00064         displayCloud (new pcl::PointCloud<pcl::PointXYZ>()), octree (resolution), displayCubes(false),
00065         showPointsWithCubes (false), wireframe (true)
00066   {
00067 
00068     
00069     if (!loadCloud(filename))
00070       return;
00071 
00072     
00073     viz.registerKeyboardCallback(&OctreeViewer::keyboardEventOccurred, *this, 0);
00074 
00075     
00076     viz.addText("Keys:", 0, 170, 0.0, 1.0, 0.0, "keys_t");
00077     viz.addText("a -> Increment displayed depth", 10, 155, 0.0, 1.0, 0.0, "key_a_t");
00078     viz.addText("z -> Decrement displayed depth", 10, 140, 0.0, 1.0, 0.0, "key_z_t");
00079     viz.addText("d -> Toggle Point/Cube representation", 10, 125, 0.0, 1.0, 0.0, "key_d_t");
00080     viz.addText("x -> Show/Hide original cloud", 10, 110, 0.0, 1.0, 0.0, "key_x_t");
00081     viz.addText("s/w -> Surface/Wireframe representation", 10, 95, 0.0, 1.0, 0.0, "key_sw_t");
00082 
00083     
00084     displayedDepth = static_cast<int> (floor (octree.getTreeDepth() / 2.0));
00085     if (displayedDepth == 0)
00086       displayedDepth = 1;
00087 
00088     
00089     extractPointsAtLevel(displayedDepth);
00090 
00091     
00092     viz.resetCameraViewpoint("cloud");
00093 
00094     
00095     run();
00096 
00097   }
00098 
00099 private:
00100   
00101   
00102   
00103   
00104   pcl::PointCloud<pcl::PointXYZ>::Ptr xyz;
00105   pcl::PointCloud<pcl::PointXYZRGB>::Ptr xyz_rgb;
00106 
00107   pcl::visualization::PCLVisualizer viz;
00108   
00109   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
00110   
00111   pcl::PointCloud<pcl::PointXYZ>::Ptr displayCloud;
00112   
00113   pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZ> octree;
00114   
00115   int displayedDepth;
00116   
00117   bool displayCubes, showPointsWithCubes, wireframe;
00118   
00119 
00120   
00121 
00122 
00123   void keyboardEventOccurred(const pcl::visualization::KeyboardEvent &event, void *)
00124   {
00125 
00126     if (event.getKeySym() == "a" && event.keyDown())
00127     {
00128       IncrementLevel();
00129     }
00130     else if (event.getKeySym() == "z" && event.keyDown())
00131     {
00132       DecrementLevel();
00133     }
00134     else if (event.getKeySym() == "d" && event.keyDown())
00135     {
00136       displayCubes = !displayCubes;
00137       update();
00138     }
00139     else if (event.getKeySym() == "x" && event.keyDown())
00140     {
00141       showPointsWithCubes = !showPointsWithCubes;
00142       update();
00143     }
00144     else if (event.getKeySym() == "w" && event.keyDown())
00145     {
00146       if(!wireframe)
00147         wireframe=true;
00148       update();
00149     }
00150     else if (event.getKeySym() == "s" && event.keyDown())
00151     {
00152       if(wireframe)
00153         wireframe=false;
00154       update();
00155     }
00156   }
00157 
00158   
00159 
00160 
00161   void run()
00162   {
00163     while (!viz.wasStopped())
00164     {
00165       
00166       viz.spinOnce(100);
00167       boost::this_thread::sleep(boost::posix_time::microseconds(100000));
00168     }
00169   }
00170 
00171   
00172 
00173 
00174 
00175   bool loadCloud(std::string &filename)
00176   {
00177     std::cout << "Loading file " << filename.c_str() << std::endl;
00178     
00179     if (pcl::io::loadPCDFile(filename, *cloud))
00180     {
00181       std::cerr << "ERROR: Cannot open file " << filename << "! Aborting..." << std::endl;
00182       return false;
00183     }
00184 
00185     
00186     std::vector<int> nanIndexes;
00187     pcl::removeNaNFromPointCloud(*cloud, *cloud, nanIndexes);
00188     std::cout << "Loaded " << cloud->points.size() << " points" << std::endl;
00189 
00190     
00191     octree.setInputCloud(cloud);
00192     
00193     octree.defineBoundingBox();
00194     
00195     octree.addPointsFromInputCloud();
00196     return true;
00197   }
00198 
00199   
00200 
00201 
00202   void showLegend(bool showCubes)
00203   {
00204     char dataDisplay[256];
00205     sprintf(dataDisplay, "Displaying data as %s", (showCubes) ? ("CUBES") : ("POINTS"));
00206     viz.removeShape("disp_t");
00207     viz.addText(dataDisplay, 0, 60, 1.0, 0.0, 0.0, "disp_t");
00208 
00209     char level[256];
00210     sprintf(level, "Displayed depth is %d on %d", displayedDepth, octree.getTreeDepth());
00211     viz.removeShape("level_t1");
00212     viz.addText(level, 0, 45, 1.0, 0.0, 0.0, "level_t1");
00213 
00214     viz.removeShape("level_t2");
00215     sprintf(level, "Voxel size: %.4fm [%zu voxels]", sqrt(octree.getVoxelSquaredSideLen(displayedDepth)),
00216             displayCloud->points.size());
00217     viz.addText(level, 0, 30, 1.0, 0.0, 0.0, "level_t2");
00218 
00219     viz.removeShape("org_t");
00220     if (showPointsWithCubes)
00221       viz.addText("Displaying original cloud", 0, 15, 1.0, 0.0, 0.0, "org_t");
00222   }
00223 
00224   
00225 
00226 
00227   void update()
00228   {
00229     
00230     clearView();
00231 
00232     
00233     bool displayCubeLegend = displayCubes && static_cast<int> (displayCloud->points.size ()) <= MAX_DISPLAYED_CUBES;
00234 
00235     showLegend(displayCubeLegend);
00236 
00237     if (displayCubeLegend)
00238     {
00239       
00240       showCubes(sqrt(octree.getVoxelSquaredSideLen(displayedDepth)));
00241       if (showPointsWithCubes)
00242       {
00243         
00244         pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointXYZ> color_handler(cloud, "z");
00245         viz.addPointCloud(cloud, color_handler, "cloud");
00246       }
00247     }
00248     else
00249     {
00250       
00251       pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointXYZ> color_handler(displayCloud,"z");
00252       viz.addPointCloud(displayCloud, color_handler, "cloud");
00253     }
00254   }
00255 
00256   
00257 
00258 
00259   void clearView()
00260   {
00261     
00262     vtkRenderer *renderer = viz.getRenderWindow()->GetRenderers()->GetFirstRenderer();
00263     while (renderer->GetActors()->GetNumberOfItems() > 0)
00264       renderer->RemoveActor(renderer->GetActors()->GetLastActor());
00265     
00266     viz.removePointCloud("cloud");
00267   }
00268 
00269   
00270 
00271 
00272   vtkSmartPointer<vtkPolyData> GetCuboid(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
00273   {
00274     vtkSmartPointer<vtkCubeSource> cube = vtkSmartPointer<vtkCubeSource>::New();
00275     cube->SetBounds(minX, maxX, minY, maxY, minZ, maxZ);
00276     return cube->GetOutput();
00277   }
00278 
00279   
00280 
00281 
00282   void showCubes(double voxelSideLen)
00283   {
00284     
00285     vtkRenderer *renderer = viz.getRenderWindow()->GetRenderers()->GetFirstRenderer();
00286 
00287     vtkSmartPointer<vtkAppendPolyData> treeWireframe = vtkSmartPointer<vtkAppendPolyData>::New();
00288     size_t i;
00289     double s = voxelSideLen / 2.0;
00290     for (i = 0; i < displayCloud->points.size(); i++)
00291     {
00292 
00293       double x = displayCloud->points[i].x;
00294       double y = displayCloud->points[i].y;
00295       double z = displayCloud->points[i].z;
00296 
00297       treeWireframe->AddInput(GetCuboid(x - s, x + s, y - s, y + s, z - s, z + s));
00298     }
00299 
00300     vtkSmartPointer<vtkActor> treeActor = vtkSmartPointer<vtkActor>::New();
00301 
00302     vtkSmartPointer<vtkDataSetMapper> mapper = vtkSmartPointer<vtkDataSetMapper>::New();
00303     mapper->SetInput(treeWireframe->GetOutput());
00304     treeActor->SetMapper(mapper);
00305 
00306     treeActor->GetProperty()->SetColor(1.0, 1.0, 1.0);
00307     treeActor->GetProperty()->SetLineWidth(2);
00308     if(wireframe)
00309     {
00310       treeActor->GetProperty()->SetRepresentationToWireframe();
00311       treeActor->GetProperty()->SetOpacity(0.35);
00312     }
00313     else
00314       treeActor->GetProperty()->SetRepresentationToSurface();
00315 
00316     renderer->AddActor(treeActor);
00317   }
00318 
00319   
00320 
00321 
00322   void extractPointsAtLevel(int depth)
00323   {
00324     displayCloud->points.clear();
00325 
00326     pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZ>::Iterator tree_it;
00327     pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZ>::Iterator tree_it_end = octree.end();
00328 
00329     pcl::PointXYZ pt;
00330     std::cout << "===== Extracting data at depth " << depth << "... " << std::flush;
00331     double start = pcl::getTime ();
00332 
00333     for (tree_it = octree.begin(depth); tree_it!=tree_it_end; ++tree_it)
00334     {
00335       Eigen::Vector3f voxel_min, voxel_max;
00336       octree.getVoxelBounds(tree_it, voxel_min, voxel_max);
00337 
00338       pt.x = (voxel_min.x() + voxel_max.x()) / 2.0f;
00339       pt.y = (voxel_min.y() + voxel_max.y()) / 2.0f;
00340       pt.z = (voxel_min.z() + voxel_max.z()) / 2.0f;
00341       displayCloud->points.push_back(pt);
00342     }
00343 
00344     double end = pcl::getTime ();
00345     printf("%zu pts, %.4gs. %.4gs./pt. =====\n", displayCloud->points.size (), end - start,
00346            (end - start) / static_cast<double> (displayCloud->points.size ()));
00347 
00348     update();
00349   }
00350 
00351   
00352 
00353 
00354   bool IncrementLevel()
00355   {
00356     if (displayedDepth < static_cast<int> (octree.getTreeDepth ()))
00357     {
00358       displayedDepth++;
00359       extractPointsAtLevel(displayedDepth);
00360       return true;
00361     }
00362     else
00363       return false;
00364   }
00365 
00366   
00367 
00368 
00369   bool DecrementLevel()
00370   {
00371     if (displayedDepth > 0)
00372     {
00373       displayedDepth--;
00374       extractPointsAtLevel(displayedDepth);
00375       return true;
00376     }
00377     return false;
00378   }
00379 
00380 };
00381 
00382 int main(int argc, char ** argv)
00383 {
00384   if (argc != 3)
00385   {
00386     std::cerr << "ERROR: Syntax is octreeVisu <pcd file> <resolution>" << std::endl;
00387     std::cerr << "EXAMPLE: ./octreeVisu bun0.pcd 0.001" << std::endl;
00388     return -1;
00389   }
00390 
00391   std::string cloud_path(argv[1]);
00392   OctreeViewer v(cloud_path, atof(argv[2]));
00393 }