voxel_grid_occlusion_estimation.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011-2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the copyright holder(s) nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author : Christian Potthast
00036  * Email  : potthast@usc.edu
00037  *
00038  */
00039 
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 #include <pcl/common/transforms.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 #include <pcl/filters/voxel_grid_occlusion_estimation.h>
00049 #include <vtkCubeSource.h>
00050 #include <vtkRenderer.h>
00051 #include <vtkRenderWindow.h>
00052 #include <vtkRenderWindowInteractor.h>
00053 #include <vtkLine.h>
00054 
00055 using namespace pcl;
00056 using namespace pcl::io;
00057 using namespace pcl::console;
00058 
00059 typedef PointXYZ PointT;
00060 typedef PointCloud<PointT> CloudT;
00061 
00062 float default_leaf_size = 0.01f;
00063 
00064 vtkDataSet*
00065 createDataSetFromVTKPoints (vtkPoints *points)
00066 {
00067   vtkCellArray *verts = vtkCellArray::New ();
00068   vtkPolyData *data   = vtkPolyData::New  ();
00069   // Iterate through the points                                                          
00070                              
00071   for (vtkIdType i = 0; i < points->GetNumberOfPoints (); i++)
00072     verts->InsertNextCell ((vtkIdType)1, &i);
00073   data->SetPoints (points);
00074   data->SetVerts (verts);
00075   return data;
00076 }
00077 
00078 vtkSmartPointer<vtkPolyData>
00079 getCuboid (double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
00080 {
00081   vtkSmartPointer < vtkCubeSource > cube = vtkSmartPointer<vtkCubeSource>::New ();
00082   cube->SetBounds (minX, maxX, minY, maxY, minZ, maxZ);
00083   return cube->GetOutput ();
00084 }
00085 
00086 void
00087 getVoxelActors (pcl::PointCloud<pcl::PointXYZ>& voxelCenters,
00088                  double voxelSideLen, Eigen::Vector3f color,
00089                  vtkSmartPointer<vtkActorCollection> coll)
00090 {
00091   vtkSmartPointer < vtkAppendPolyData > treeWireframe = vtkSmartPointer<vtkAppendPolyData>::New ();
00092   
00093   size_t i;
00094   double s = voxelSideLen/2.0;
00095   
00096   for (i = 0; i < voxelCenters.points.size (); i++)
00097   {
00098     double x = voxelCenters.points[i].x;
00099     double y = voxelCenters.points[i].y;
00100     double z = voxelCenters.points[i].z;
00101     
00102     treeWireframe->AddInput (getCuboid (x - s, x + s, y - s, y + s, z - s, z + s));
00103   }
00104 
00105   vtkSmartPointer < vtkLODActor > treeActor = vtkSmartPointer<vtkLODActor>::New ();
00106   
00107   vtkSmartPointer < vtkDataSetMapper > mapper = vtkSmartPointer<vtkDataSetMapper>::New ();
00108   mapper->SetInput (treeWireframe->GetOutput ());
00109   treeActor->SetMapper (mapper);
00110   
00111   treeActor->GetProperty ()->SetRepresentationToWireframe ();
00112   treeActor->GetProperty ()->SetColor (color[0], color[1], color[2]);
00113   treeActor->GetProperty ()->SetLineWidth (4);
00114   coll->AddItem (treeActor);
00115 }
00116 
00117 void
00118 displayBoundingBox (Eigen::Vector3f& min_b, Eigen::Vector3f& max_b,
00119                     vtkSmartPointer<vtkActorCollection> coll)
00120 {
00121   vtkSmartPointer < vtkAppendPolyData > treeWireframe = vtkSmartPointer<vtkAppendPolyData>::New ();
00122   treeWireframe->AddInput (getCuboid (min_b[0], max_b[0], min_b[1], max_b[1], min_b[2], max_b[2]));
00123 
00124   vtkSmartPointer < vtkActor > treeActor = vtkSmartPointer<vtkActor>::New ();
00125 
00126   vtkSmartPointer < vtkDataSetMapper > mapper = vtkSmartPointer<vtkDataSetMapper>::New ();
00127   mapper->SetInput (treeWireframe->GetOutput ());
00128   treeActor->SetMapper (mapper);
00129 
00130   treeActor->GetProperty ()->SetRepresentationToWireframe ();
00131   treeActor->GetProperty ()->SetColor (0.0, 0.0, 1.0);
00132   treeActor->GetProperty ()->SetLineWidth (2);
00133   coll->AddItem (treeActor);
00134 }
00135 
00136 void
00137 printHelp (int, char **argv)
00138 {
00139   print_error ("Syntax is: %s input.pcd <options>\n", argv[0]);
00140   print_info ("  where options are:\n");
00141   print_info ("                     -leaf x,y,z   = the VoxelGrid leaf size (default: "); 
00142   print_value ("%f, %f, %f", default_leaf_size, default_leaf_size, default_leaf_size); print_info (")\n");
00143 }
00144 
00145 int main (int argc, char** argv)
00146 {
00147   print_info ("Estimate occlusion using pcl::VoxelGridOcclusionEstimation. For more information, use: %s -h\n", argv[0]);
00148 
00149   if (argc < 2)
00150   {
00151     printHelp (argc, argv);
00152     return (-1);
00153   }
00154 
00155   // Command line parsing
00156   float leaf_x = default_leaf_size,
00157         leaf_y = default_leaf_size,
00158         leaf_z = default_leaf_size;
00159 
00160   std::vector<double> values;
00161   parse_x_arguments (argc, argv, "-leaf", values);
00162   if (values.size () == 1)
00163   {
00164     leaf_x = static_cast<float> (values[0]);
00165     leaf_y = static_cast<float> (values[0]);
00166     leaf_z = static_cast<float> (values[0]);
00167   }
00168   else if (values.size () == 3)
00169   {
00170     leaf_x = static_cast<float> (values[0]);
00171     leaf_y = static_cast<float> (values[1]);
00172     leaf_z = static_cast<float> (values[2]);
00173   }
00174   else
00175   {
00176     print_error ("Leaf size must be specified with either 1 or 3 numbers (%zu given).\n", values.size ());
00177   }
00178   print_info ("Using a leaf size of: "); print_value ("%f, %f, %f\n", leaf_x, leaf_y, leaf_z);
00179 
00180   // input cloud
00181   CloudT::Ptr input_cloud (new CloudT);
00182   loadPCDFile (argv[1], *input_cloud);
00183 
00184   // VTK actors
00185   vtkSmartPointer<vtkActorCollection> coll = vtkActorCollection::New ();
00186 
00187   // voxel grid
00188   VoxelGridOcclusionEstimation<PointT> vg;
00189   vg.setInputCloud (input_cloud);
00190   vg.setLeafSize (leaf_x, leaf_y, leaf_z);
00191   vg.initializeVoxelGrid ();
00192 
00193   Eigen::Vector3f b_min, b_max;
00194   b_min = vg.getMinBoundCoordinates ();
00195   b_max = vg.getMaxBoundCoordinates ();
00196 
00197   TicToc tt;
00198   print_highlight ("Ray-Traversal ");
00199   tt.tic ();
00200 
00201   // estimate the occluded space
00202   std::vector <Eigen::Vector3i> occluded_voxels;
00203   vg.occlusionEstimationAll (occluded_voxels);
00204 
00205   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", (int)occluded_voxels.size ()); print_info (" occluded voxels]\n");
00206   
00207   CloudT::Ptr occ_centroids (new CloudT);
00208   occ_centroids->width = static_cast<int> (occluded_voxels.size ());
00209   occ_centroids->height = 1;
00210   occ_centroids->is_dense = false;
00211   occ_centroids->points.resize (occluded_voxels.size ());
00212   for (size_t i = 0; i < occluded_voxels.size (); ++i)
00213   {
00214     Eigen::Vector4f xyz = vg.getCentroidCoordinate (occluded_voxels[i]);
00215     PointT point;
00216     point.x = xyz[0];
00217     point.y = xyz[1];
00218     point.z = xyz[2];
00219     occ_centroids->points[i] = point;
00220   }
00221 
00222   CloudT::Ptr cloud_centroids (new CloudT);
00223   cloud_centroids->width = static_cast<int> (input_cloud->points.size ());
00224   cloud_centroids->height = 1;
00225   cloud_centroids->is_dense = false;
00226   cloud_centroids->points.resize (input_cloud->points.size ());
00227 
00228   for (size_t i = 0; i < input_cloud->points.size (); ++i)
00229   {
00230     float x = input_cloud->points[i].x;
00231     float y = input_cloud->points[i].y;
00232     float z = input_cloud->points[i].z;
00233     Eigen::Vector3i c = vg.getGridCoordinates (x, y, z);
00234     Eigen::Vector4f xyz = vg.getCentroidCoordinate (c);
00235     PointT point;
00236     point.x = xyz[0];
00237     point.y = xyz[1];
00238     point.z = xyz[2];
00239     cloud_centroids->points[i] = point;
00240   }
00241 
00242   // visualization
00243   Eigen::Vector3f red (1.0, 0.0, 0.0);  
00244   Eigen::Vector3f blue (0.0, 0.0, 1.0);
00245   // draw point cloud voxels
00246   getVoxelActors (*cloud_centroids, leaf_x, red, coll);
00247   // draw the bounding box of the voxel grid
00248   displayBoundingBox (b_min, b_max, coll);
00249   // draw the occluded voxels
00250   getVoxelActors (*occ_centroids, leaf_x, blue, coll);
00251 
00252   // Create the RenderWindow, Renderer and RenderWindowInteractor
00253   vtkSmartPointer<vtkRenderer> renderer = vtkSmartPointer<vtkRenderer>::New();
00254   vtkSmartPointer<vtkRenderWindow> renderWindow = 
00255     vtkSmartPointer<vtkRenderWindow>::New();
00256   renderWindow->AddRenderer (renderer);  
00257   vtkSmartPointer<vtkRenderWindowInteractor> renderWindowInteractor = 
00258     vtkSmartPointer<vtkRenderWindowInteractor>::New();
00259   renderWindowInteractor->SetRenderWindow (renderWindow);
00260 
00261   // Add the actors to the renderer, set the background and size
00262   renderer->SetBackground (1.0, 1.0, 1.0);
00263   renderWindow->SetSize (640, 480);
00264 
00265   vtkActor* a;
00266   coll->InitTraversal ();
00267   a = coll->GetNextActor ();
00268   while(a!=0)
00269     {
00270       renderer->AddActor (a);
00271       a = coll->GetNextActor ();
00272     }
00273 
00274   renderWindow->Render ();
00275   renderWindowInteractor->Start ();
00276 
00277   return 0;
00278 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:38:25