mesh2pcd.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) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #include <pcl/visualization/pcl_visualizer.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/common/transforms.h>
00041 #include <vtkPLYReader.h>
00042 #include <vtkOBJReader.h>
00043 #include <vtkPolyDataMapper.h>
00044 #include <pcl/filters/voxel_grid.h>
00045 #include <pcl/console/print.h>
00046 #include <pcl/console/parse.h>
00047 
00048 using namespace pcl;
00049 using namespace pcl::io;
00050 using namespace pcl::console;
00051 
00052 int default_tesselated_sphere_level = 2;
00053 int default_resolution = 100;
00054 float default_leaf_size = 0.01f;
00055 
00056 void
00057 printHelp (int, char **argv)
00058 {
00059   print_error ("Syntax is: %s input.{ply,obj} output.pcd <options>\n", argv[0]);
00060   print_info ("  where options are:\n");
00061   print_info ("                     -level X      = tesselated sphere level (default: ");
00062   print_value ("%d", default_tesselated_sphere_level);
00063   print_info (")\n");
00064   print_info ("                     -resolution X = the sphere resolution in angle increments (default: ");
00065   print_value ("%d", default_resolution);
00066   print_info (" deg)\n");
00067   print_info (
00068               "                     -leaf_size X  = the XYZ leaf size for the VoxelGrid -- for data reduction (default: ");
00069   print_value ("%f", default_leaf_size);
00070   print_info (" m)\n");
00071 }
00072 
00073 /* ---[ */
00074 int
00075 main (int argc, char **argv)
00076 {
00077   print_info ("Convert a CAD model to a point cloud using ray tracing operations. For more information, use: %s -h\n",
00078               argv[0]);
00079 
00080   if (argc < 3)
00081   {
00082     printHelp (argc, argv);
00083     return (-1);
00084   }
00085 
00086   // Parse command line arguments
00087   int tesselated_sphere_level = default_tesselated_sphere_level;
00088   parse_argument (argc, argv, "-level", tesselated_sphere_level);
00089   int resolution = default_resolution;
00090   parse_argument (argc, argv, "-resolution", resolution);
00091   float leaf_size = default_leaf_size;
00092   parse_argument (argc, argv, "-leaf_size", leaf_size);
00093 
00094   // Parse the command line arguments for .ply and PCD files
00095   std::vector<int> pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00096   if (pcd_file_indices.size () != 1)
00097   {
00098     print_error ("Need a single output PCD file to continue.\n");
00099     return (-1);
00100   }
00101   std::vector<int> ply_file_indices = parse_file_extension_argument (argc, argv, ".ply");
00102   std::vector<int> obj_file_indices = parse_file_extension_argument (argc, argv, ".obj");
00103   if (ply_file_indices.size () != 1 && obj_file_indices.size () != 1)
00104   {
00105     print_error ("Need a single input PLY/OBJ file to continue.\n");
00106     return (-1);
00107   }
00108 
00109   vtkSmartPointer<vtkPolyData> polydata1;
00110   if (ply_file_indices.size () == 1)
00111   {
00112     vtkSmartPointer<vtkPLYReader> readerQuery = vtkSmartPointer<vtkPLYReader>::New ();
00113     readerQuery->SetFileName (argv[ply_file_indices[0]]);
00114     polydata1 = readerQuery->GetOutput ();
00115     polydata1->Update ();
00116   }
00117   else if (obj_file_indices.size () == 1)
00118   {
00119     vtkSmartPointer<vtkOBJReader> readerQuery = vtkSmartPointer<vtkOBJReader>::New ();
00120     readerQuery->SetFileName (argv[obj_file_indices[0]]);
00121     polydata1 = readerQuery->GetOutput ();
00122     polydata1->Update ();
00123   }
00124 
00125   bool INTER_VIS = false;
00126   bool VIS = true;
00127 
00128   visualization::PCLVisualizer vis;
00129   vis.addModelFromPolyData (polydata1, "mesh1", 0);
00130   vis.setRepresentationToSurfaceForAllActors ();
00131 
00132   PointCloud<PointXYZ>::CloudVectorType views_xyz;
00133   std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > poses;
00134   std::vector<float> enthropies;
00135   vis.renderViewTesselatedSphere (resolution, resolution, views_xyz, poses, enthropies, tesselated_sphere_level);
00136 
00137   //take views and fuse them together
00138   std::vector<PointCloud<PointXYZ>::Ptr> aligned_clouds;
00139 
00140   for (size_t i = 0; i < views_xyz.size (); i++)
00141   {
00142     PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ> ());
00143     Eigen::Matrix4f pose_inverse;
00144     pose_inverse = poses[i].inverse ();
00145     transformPointCloud (views_xyz[i], *cloud, pose_inverse);
00146     aligned_clouds.push_back (cloud);
00147   }
00148 
00149   if (INTER_VIS)
00150   {
00151     visualization::PCLVisualizer vis2 ("visualize");
00152 
00153     for (size_t i = 0; i < aligned_clouds.size (); i++)
00154     {
00155       std::stringstream name;
00156       name << "cloud_" << i;
00157       vis2.addPointCloud (aligned_clouds[i], name.str ());
00158       vis2.spin ();
00159     }
00160   }
00161 
00162   // Fuse clouds
00163   PointCloud<PointXYZ>::Ptr big_boy (new PointCloud<PointXYZ> ());
00164   for (size_t i = 0; i < aligned_clouds.size (); i++)
00165     *big_boy += *aligned_clouds[i];
00166 
00167   if (VIS)
00168   {
00169     visualization::PCLVisualizer vis2 ("visualize");
00170     vis2.addPointCloud (big_boy);
00171     vis2.spin ();
00172   }
00173 
00174   // Voxelgrid
00175   VoxelGrid<PointXYZ> grid_;
00176   grid_.setInputCloud (big_boy);
00177   grid_.setLeafSize (leaf_size, leaf_size, leaf_size);
00178   grid_.filter (*big_boy);
00179 
00180   if (VIS)
00181   {
00182     visualization::PCLVisualizer vis3 ("visualize");
00183     vis3.addPointCloud (big_boy);
00184     vis3.spin ();
00185   }
00186 
00187   savePCDFileASCII (argv[pcd_file_indices[0]], *big_boy);
00188 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:39