virtual_scanner.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id$
00035  *
00036  */
00037 
00046 #include <string>
00047 #include <pcl/register_point_struct.h>
00048 #include <pcl/io/pcd_io.h>
00049 #include <pcl/io/vtk_lib_io.h>
00050 #include <pcl/filters/voxel_grid.h>
00051 #include <pcl/point_types.h>
00052 #include <pcl/console/parse.h>
00053 #include <pcl/visualization/vtk.h>
00054 #include "boost.h"
00055 
00056 using namespace pcl;
00057 
00058 #define EPS 0.00001
00059 
00060 struct ScanParameters
00061 {
00062   int nr_scans;             // number of steps for sweep movement
00063   int nr_points_in_scans;   // number of laser beam measurements per scan
00064   double vert_res;          // vertical resolution (res. of sweep) in degrees
00065   double hor_res;           // horizontal  resolution (of laser beam) in degrees
00066   double max_dist;          // maximum distance in units.
00067 };
00068 
00069 
00074 vtkPolyData*
00075 loadDataSet (const char* file_name)
00076 {
00077   std::string extension = boost::filesystem::extension (file_name);
00078   if (extension == ".ply")
00079   {
00080     vtkPLYReader* reader = vtkPLYReader::New ();
00081     reader->SetFileName (file_name);
00082     reader->Update ();
00083     return (reader->GetOutput ());
00084   }
00085   else if (extension == ".vtk")
00086   {
00087     vtkPolyDataReader* reader = vtkPolyDataReader::New ();
00088     reader->SetFileName (file_name);
00089     reader->Update ();
00090     return (reader->GetOutput ());
00091   }
00092   else
00093   {
00094     PCL_ERROR ("Needs a VTK/PLY file to continue.\n");
00095     return (NULL);
00096   }
00097 }
00098 
00099 int
00100 main (int argc, char** argv)
00101 {
00102   if (argc < 2)
00103   {
00104     PCL_INFO ("Usage %s [options] <model.ply | model.vtk>\n", argv[0]);
00105     PCL_INFO (" * where options are:\n"
00106               "         -object_coordinates <0|1> : save the dataset in object coordinates (1) or camera coordinates (0)\n"
00107               "         -single_view <0|1>        : take a single snapshot (1) or record a lot of camera poses on a view sphere (0)\n"
00108               "         -view_point <x,y,z>       : set the camera viewpoint from where the acquisition will take place\n"
00109               "         -target_point <x,y,z>     : the target point that the camera should look at (default: 0, 0, 0)\n"
00110               "         -organized <0|1>          : create an organized, grid-like point cloud of width x height (1), or keep it unorganized with height = 1 (0)\n"
00111               "         -noise <0|1>              : add gausian noise (1) or keep the model noiseless (0)\n"
00112               "         -noise_std <x>            : use X times the standard deviation\n"
00113               "");
00114     return (-1);
00115   }
00116   std::string filename;
00117   // Parse the command line arguments for .vtk or .ply files
00118   std::vector<int> p_file_indices_vtk = console::parse_file_extension_argument (argc, argv, ".vtk");
00119   std::vector<int> p_file_indices_ply = console::parse_file_extension_argument (argc, argv, ".ply");
00120   bool object_coordinates = true;
00121   console::parse_argument (argc, argv, "-object_coordinates", object_coordinates);
00122   bool single_view = false;
00123   console::parse_argument (argc, argv, "-single_view", single_view);
00124   double vx = 0, vy = 0, vz = 0;
00125   console::parse_3x_arguments (argc, argv, "-view_point", vx, vy, vz);
00126   double tx = 0, ty = 0, tz = 0;
00127   console::parse_3x_arguments (argc, argv, "-target_point", tx, ty, tz);
00128   int organized = 0;
00129   console::parse_argument (argc, argv, "-organized", organized);
00130   if (organized)
00131     PCL_INFO ("Saving an organized dataset.\n");
00132   else
00133     PCL_INFO ("Saving an unorganized dataset.\n");
00134 
00135   vtkSmartPointer<vtkPolyData> data;
00136   // Loading PLY/VTK file
00137   if (p_file_indices_ply.empty () && p_file_indices_vtk.empty ())
00138   {
00139     PCL_ERROR ("Error: no .PLY or .VTK files given!\n");
00140     return (-1);
00141   }
00142   
00143   std::stringstream filename_stream;
00144   if (!p_file_indices_ply.empty ())
00145     filename_stream << argv[p_file_indices_ply.at (0)];
00146   else
00147     filename_stream << argv[p_file_indices_vtk.at (0)];
00148 
00149   filename = filename_stream.str ();
00150   
00151   data = loadDataSet (filename.c_str ());
00152   
00153   PCL_INFO ("Loaded model with %d vertices/points.\n", data->GetNumberOfPoints ());
00154 
00155   // Default scan parameters
00156   ScanParameters sp;
00157   sp.nr_scans           = 900;
00158   console::parse_argument (argc, argv, "-nr_scans", sp.nr_scans);
00159   sp.nr_points_in_scans = 900;
00160   console::parse_argument (argc, argv, "-pts_in_scan", sp.nr_points_in_scans);
00161   sp.max_dist           = 30000;   // maximum distance (in mm)
00162   sp.vert_res           = 0.25;
00163   console::parse_argument (argc, argv, "-vert_res", sp.vert_res);
00164   sp.hor_res            = 0.25;
00165   console::parse_argument (argc, argv, "-hor_res", sp.hor_res);
00166 
00167   int noise_model = 0;               // set the default noise level to none
00168   console::parse_argument (argc, argv, "-noise", noise_model);
00169   float noise_std = 0.05f;           // 0.5 standard deviations by default
00170   console::parse_argument (argc, argv, "-noise_std", noise_std);
00171   if (noise_model)
00172     PCL_INFO ("Adding Gaussian noise to the final model with %f x std_dev.\n", noise_std);
00173   else
00174     PCL_INFO ("Not adding any noise to the final model.\n");
00175 
00176   int subdiv_level = 1;
00177   double scan_dist = 3;
00178   std::string fname, base;
00179   char seq[256];
00180 
00181   // Compute start/stop for vertical and horizontal
00182   double vert_start = - (static_cast<double> (sp.nr_scans - 1) / 2.0) * sp.vert_res;
00183   double vert_end   = + ((sp.nr_scans-1) * sp.vert_res) + vert_start;
00184   double hor_start  = - (static_cast<double> (sp.nr_points_in_scans - 1) / 2.0) * sp.hor_res;
00185   double hor_end    = + ((sp.nr_points_in_scans-1) * sp.hor_res) + hor_start;
00186 
00187   // Prepare the point cloud data
00188   pcl::PointCloud<pcl::PointWithViewpoint> cloud;
00189 
00190   // Prepare the leaves for downsampling
00191   pcl::VoxelGrid<pcl::PointWithViewpoint> grid;
00192   grid.setLeafSize (2.5, 2.5, 2.5);    // @note: this value should be given in mm!
00193 
00194   // Reset and set a random seed for the Global Random Number Generator
00195   boost::mt19937 rng (static_cast<unsigned int> (std::time (0)));
00196   boost::normal_distribution<float> normal_distrib (0.0f, noise_std * noise_std);
00197   boost::variate_generator<boost::mt19937&, boost::normal_distribution<float> > gaussian_rng (rng, normal_distrib);
00198 
00199   std::vector<std::string> st;
00200   // Virtual camera parameters
00201   double eye[3]     = {0.0, 0.0, 0.0};
00202   double viewray[3] = {0.0, 0.0, 0.0};
00203   double up[3]      = {0.0, 0.0, 0.0};
00204   double right[3]  = {0.0, 0.0, 0.0};
00205   double x_axis[3] = {1.0, 0.0, 0.0};
00206   double z_axis[3] = {0.0, 0.0, 1.0};
00207   double bounds[6];
00208   double temp_beam[3], beam[3], p[3];
00209   double p_coords[3], x[3], t;
00210   int subId;
00211  
00212   // Create a Icosahedron at center in origin and radius of 1
00213   vtkSmartPointer<vtkPlatonicSolidSource> icosa = vtkSmartPointer<vtkPlatonicSolidSource>::New ();
00214   icosa->SetSolidTypeToIcosahedron ();
00215 
00216   // Tesselize the source icosahedron (subdivide each triangular face
00217   // of the icosahedron into smaller triangles)
00218   vtkSmartPointer<vtkLoopSubdivisionFilter> subdivide = vtkSmartPointer<vtkLoopSubdivisionFilter>::New ();
00219   subdivide->SetNumberOfSubdivisions (subdiv_level);
00220   subdivide->SetInputConnection (icosa->GetOutputPort ());
00221 
00222   // Get camera positions
00223   vtkPolyData *sphere = subdivide->GetOutput ();
00224   sphere->Update ();
00225   if (!single_view)
00226     PCL_INFO ("Created %ld camera position points.\n", sphere->GetNumberOfPoints ());
00227 
00228   // Build a spatial locator for our dataset
00229   vtkSmartPointer<vtkCellLocator> tree = vtkSmartPointer<vtkCellLocator>::New ();
00230   tree->SetDataSet (data);
00231   tree->CacheCellBoundsOn ();
00232   tree->SetTolerance (0.0);
00233   tree->SetNumberOfCellsPerBucket (1);
00234   tree->AutomaticOn ();
00235   tree->BuildLocator ();
00236   tree->Update ();
00237 
00238   // Get the min-max bounds of data
00239   data->GetBounds (bounds);
00240 
00241   // if single view is required iterate over loop only once
00242   int number_of_points = static_cast<int> (sphere->GetNumberOfPoints ());
00243   if (single_view)
00244     number_of_points = 1;
00245 
00246   int sid = -1;
00247   for (int i = 0; i < number_of_points; i++)
00248   {
00249     sphere->GetPoint (i, eye);
00250     if (fabs(eye[0]) < EPS) eye[0] = 0;
00251     if (fabs(eye[1]) < EPS) eye[1] = 0;
00252     if (fabs(eye[2]) < EPS) eye[2] = 0;
00253 
00254     viewray[0] = -eye[0];
00255     viewray[1] = -eye[1];
00256     viewray[2] = -eye[2];
00257     eye[0] *= scan_dist;
00258     eye[1] *= scan_dist;
00259     eye[2] *= scan_dist;
00260     //Change here if only single view point is required
00261     if (single_view)
00262     {
00263       eye[0] = vx;//0.0;
00264       eye[1] = vy;//-0.26;
00265       eye[2] = vz;//-0.86;
00266       viewray[0] = tx - vx;
00267       viewray[1] = ty - vy;
00268       viewray[2] = tz - vz;
00269       double len = sqrt (viewray[0]*viewray[0] + viewray[1]*viewray[1] + viewray[2]*viewray[2]);
00270       if (len == 0)
00271       {
00272         PCL_ERROR ("The single_view option is enabled but the view_point and the target_point are the same!\n");
00273         break;
00274       }
00275       viewray[0] /= len;
00276       viewray[1] /= len;
00277       viewray[2] /= len;
00278     }
00279 
00280     if ((viewray[0] == 0) && (viewray[1] == 0))
00281       vtkMath::Cross (viewray, x_axis, right);
00282     else
00283       vtkMath::Cross (viewray, z_axis, right);
00284     if (fabs(right[0]) < EPS) right[0] = 0;
00285     if (fabs(right[1]) < EPS) right[1] = 0;
00286     if (fabs(right[2]) < EPS) right[2] = 0;
00287 
00288     vtkMath::Cross (viewray, right, up);
00289     if (fabs(up[0]) < EPS) up[0] = 0;
00290     if (fabs(up[1]) < EPS) up[1] = 0;
00291     if (fabs(up[2]) < EPS) up[2] = 0;
00292 
00293     if (!object_coordinates)
00294     {
00295       // Normalization
00296       double right_len = sqrt (right[0]*right[0] + right[1]*right[1] + right[2]*right[2]);
00297       right[0] /= right_len;
00298       right[1] /= right_len;
00299       right[2] /= right_len;
00300       double up_len = sqrt (up[0]*up[0] + up[1]*up[1] + up[2]*up[2]);
00301       up[0] /= up_len;
00302       up[1] /= up_len;
00303       up[2] /= up_len;
00304     
00305       // Output resulting vectors
00306       cerr << "Viewray Right Up:" << endl;
00307       cerr << viewray[0] << " " << viewray[1] << " " << viewray[2] << " " << endl;
00308       cerr << right[0] << " " << right[1] << " " << right[2] << " " << endl;
00309       cerr << up[0] << " " << up[1] << " " << up[2] << " " << endl;
00310     }
00311 
00312     // Create a transformation
00313     vtkGeneralTransform* tr1 = vtkGeneralTransform::New ();
00314     vtkGeneralTransform* tr2 = vtkGeneralTransform::New ();
00315 
00316     // right = viewray x up
00317     vtkMath::Cross (viewray, up, right);
00318 
00319     // Sweep vertically
00320     for (double vert = vert_start; vert <= vert_end; vert += sp.vert_res)
00321     {
00322       sid++;
00323 
00324       tr1->Identity ();
00325       tr1->RotateWXYZ (vert, right);
00326       tr1->InternalTransformPoint (viewray, temp_beam);
00327 
00328       // Sweep horizontally
00329       int pid = -1;
00330       for (double hor = hor_start; hor <= hor_end; hor += sp.hor_res)
00331       {
00332         pid ++;
00333       
00334         // Create a beam vector with (lat,long) angles (vert, hor) with the viewray
00335         tr2->Identity ();
00336         tr2->RotateWXYZ (hor, up);
00337         tr2->InternalTransformPoint (temp_beam, beam);
00338         vtkMath::Normalize (beam);
00339 
00340         // Find point at max range: p = eye + beam * max_dist
00341         for (int d = 0; d < 3; d++)
00342           p[d] = eye[d] + beam[d] * sp.max_dist;
00343 
00344         // Put p_coords into laser scan at packetid = vert, scan id = hor
00345         vtkIdType cellId;
00346         if (tree->IntersectWithLine (eye, p, 0, t, x, p_coords, subId, cellId))
00347         {
00348           pcl::PointWithViewpoint pt;
00349           if (object_coordinates)
00350           {
00351             pt.x = static_cast<float> (x[0]); 
00352             pt.y = static_cast<float> (x[1]); 
00353             pt.z = static_cast<float> (x[2]);
00354             pt.vp_x = static_cast<float> (eye[0]); 
00355             pt.vp_y = static_cast<float> (eye[1]); 
00356             pt.vp_z = static_cast<float> (eye[2]);
00357           }
00358           else
00359           {
00360             // z axis is the viewray
00361             // y axis is up
00362             // x axis is -right (negative because z*y=-x but viewray*up=right)
00363             pt.x = static_cast<float> (-right[0]*x[1] + up[0]*x[2] + viewray[0]*x[0] + eye[0]);
00364             pt.y = static_cast<float> (-right[1]*x[1] + up[1]*x[2] + viewray[1]*x[0] + eye[1]);
00365             pt.z = static_cast<float> (-right[2]*x[1] + up[2]*x[2] + viewray[2]*x[0] + eye[2]);
00366             pt.vp_x = pt.vp_y = pt.vp_z = 0.0f;
00367           }
00368           cloud.points.push_back (pt);
00369         }
00370         else
00371           if (organized)
00372           {
00373             pcl::PointWithViewpoint pt;
00374             pt.x = pt.y = pt.z = std::numeric_limits<float>::quiet_NaN ();
00375             pt.vp_x = static_cast<float> (eye[0]);
00376             pt.vp_y = static_cast<float> (eye[1]);
00377             pt.vp_z = static_cast<float> (eye[2]);
00378             cloud.points.push_back (pt);
00379           }
00380       } // Horizontal
00381     } // Vertical
00382 
00383     // Noisify each point in the dataset
00384     // \note: we might decide to noisify along the ray later
00385     for (size_t cp = 0; cp < cloud.points.size (); ++cp)
00386     {
00387       // Add noise ?
00388       switch (noise_model)
00389       {
00390         // Gaussian
00391         case 1: { cloud.points[cp].x += gaussian_rng (); cloud.points[cp].y += gaussian_rng (); cloud.points[cp].z += gaussian_rng (); break; }
00392       }
00393     }
00394 
00395     // Downsample and remove silly point duplicates
00396     pcl::PointCloud<pcl::PointWithViewpoint> cloud_downsampled;
00397     grid.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointWithViewpoint> > (cloud));
00398     //grid.filter (cloud_downsampled);
00399 
00400     // Saves the point cloud data to disk
00401     sprintf (seq, "%d", i);
00402     boost::trim (filename);
00403     boost::split (st, filename, boost::is_any_of ("/\\"), boost::token_compress_on);
00404 
00405     std::stringstream ss;
00406     std::string output_dir = st.at (st.size () - 1);
00407     ss << output_dir << "_output";
00408 
00409     boost::filesystem::path outpath (ss.str ());
00410     if (!boost::filesystem::exists (outpath))
00411     {
00412       if (!boost::filesystem::create_directories (outpath))
00413       {
00414         PCL_ERROR ("Error creating directory %s.\n", ss.str ().c_str ());
00415         return (-1);
00416       }
00417       PCL_INFO ("Creating directory %s\n", ss.str ().c_str ());
00418     }
00419 
00420     fname = ss.str () + "/" + seq + ".pcd";
00421 
00422     if (organized)
00423     {
00424       cloud.height = 1 + static_cast<uint32_t> ((vert_end - vert_start) / sp.vert_res);
00425       cloud.width = 1 + static_cast<uint32_t> ((hor_end - hor_start) / sp.hor_res);
00426     }
00427     else
00428     {
00429       cloud.width = static_cast<uint32_t> (cloud.points.size ());
00430       cloud.height = 1;
00431     }
00432 
00433     pcl::PCDWriter writer;
00434     PCL_INFO ("Wrote %zu points (%d x %d) to %s\n", cloud.points.size (), cloud.width, cloud.height, fname.c_str ());
00435     writer.writeBinaryCompressed (fname.c_str (), cloud);
00436   } // sphere
00437   return (0);
00438 }
00439 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:37:28