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 Willow Garage, Inc. 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: virtual_scanner.cpp 5066 2012-03-14 06:42:21Z rusu $
00035  *
00036  */
00037 
00046 #include <string>
00047 #include <pcl/ros/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/random.hpp>
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 
00071 
00075 vtkPolyData*
00076 loadPLYAsDataSet (const char* file_name)
00077 {
00078   vtkPLYReader* reader = vtkPLYReader::New ();
00079   reader->SetFileName (file_name);
00080   reader->Update ();
00081   return (reader->GetOutput ());
00082 }
00083 
00084 int
00085 main (int argc, char** argv)
00086 {
00087   if (argc < 3)
00088   {
00089     PCL_INFO ("Usage %s [options] <model.ply | model.vtk>\n", argv[0]);
00090     PCL_INFO (" * where options are:\n"
00091               "         -object_coordinates <0|1> : save the dataset in object coordinates (1) or camera coordinates (0)\n"
00092               "         -single_view <0|1>        : take a single snapshot (1) or record a lot of camera poses on a view sphere (0)\n"
00093               "         -view_point <x,y,z>       : set the camera viewpoint from where the acquisition will take place\n"
00094               "         -target_point <x,y,z>     : the target point that the camera should look at (default: 0, 0, 0)\n"
00095               "         -organized <0|1>          : create an organized, grid-like point cloud of width x height (1), or keep it unorganized with height = 1 (0)\n"
00096               "         -noise <0|1>              : add gausian noise (1) or keep the model noiseless (0)\n"
00097               "         -noise_std <x>            : use X times the standard deviation\n"
00098               "");
00099     return (-1);
00100   }
00101   std::string filename;
00102   // Parse the command line arguments for .vtk or .ply files
00103   std::vector<int> p_file_indices_vtk = console::parse_file_extension_argument (argc, argv, ".vtk");
00104   std::vector<int> p_file_indices_ply = console::parse_file_extension_argument (argc, argv, ".ply");
00105   bool object_coordinates = true;
00106   console::parse_argument (argc, argv, "-object_coordinates", object_coordinates);
00107   bool single_view = false;
00108   console::parse_argument (argc, argv, "-single_view", single_view);
00109   double vx = 0, vy = 0, vz = 0;
00110   console::parse_3x_arguments (argc, argv, "-view_point", vx, vy, vz);
00111   double tx = 0, ty = 0, tz = 0;
00112   console::parse_3x_arguments (argc, argv, "-target_point", tx, ty, tz);
00113   int organized = 0;
00114   console::parse_argument (argc, argv, "-organized", organized);
00115   if (organized)
00116     PCL_INFO ("Saving an organized dataset.\n");
00117   else
00118     PCL_INFO ("Saving an unorganized dataset.\n");
00119 
00120   vtkSmartPointer<vtkPolyData> data;
00121   // Loading PLY file
00122   if (p_file_indices_ply.size () == 0)
00123   {
00124     PCL_ERROR ("Error: .ply file not given.\n");
00125     return -1;
00126   }
00127   std::stringstream filename_stream;
00128   filename_stream << argv[p_file_indices_ply.at (0)];
00129   filename = filename_stream.str();
00130   data = loadPLYAsDataSet (filename.c_str());
00131   PCL_INFO ("Loaded ply model with %d vertices/points.\n", data->GetNumberOfPoints ());
00132 
00133   // Default scan parameters
00134   ScanParameters sp;
00135   sp.nr_scans           = 900;
00136   console::parse_argument (argc, argv, "-nr_scans", sp.nr_scans);
00137   sp.nr_points_in_scans = 900;
00138   console::parse_argument (argc, argv, "-pts_in_scan", sp.nr_points_in_scans);
00139   sp.max_dist           = 30000;   // maximum distance (in mm)
00140   sp.vert_res           = 0.25;
00141   console::parse_argument (argc, argv, "-vert_res", sp.vert_res);
00142   sp.hor_res            = 0.25;
00143   console::parse_argument (argc, argv, "-hor_res", sp.hor_res);
00144 
00145   int noise_model = 0;               // set the default noise level to none
00146   console::parse_argument (argc, argv, "-noise", noise_model);
00147   float noise_std = 0.05f;           // 0.5 standard deviations by default
00148   console::parse_argument (argc, argv, "-noise_std", noise_std);
00149   if (noise_model)
00150     PCL_INFO ("Adding Gaussian noise to the final model with %f x std_dev.\n", noise_std);
00151   else
00152     PCL_INFO ("Not adding any noise to the final model.\n");
00153 
00154   int subdiv_level = 1;
00155   double scan_dist = 3;
00156   std::string fname, base;
00157   char seq[256];
00158 
00159   // Compute start/stop for vertical and horizontal
00160   double vert_start = - (static_cast<double> (sp.nr_scans - 1) / 2.0) * sp.vert_res;
00161   double vert_end   = + ((sp.nr_scans-1) * sp.vert_res) + vert_start;
00162   double hor_start  = - (static_cast<double> (sp.nr_points_in_scans - 1) / 2.0) * sp.hor_res;
00163   double hor_end    = + ((sp.nr_points_in_scans-1) * sp.hor_res) + hor_start;
00164 
00165   // Prepare the point cloud data
00166   pcl::PointCloud<pcl::PointWithViewpoint> cloud;
00167 
00168   // Prepare the leaves for downsampling
00169   pcl::VoxelGrid<pcl::PointWithViewpoint> grid;
00170   grid.setLeafSize (2.5, 2.5, 2.5);    // @note: this value should be given in mm!
00171 
00172   // Reset and set a random seed for the Global Random Number Generator
00173   boost::mt19937 rng (static_cast<unsigned int> (std::time (0)));
00174   boost::normal_distribution<float> normal_distrib (0.0f, noise_std * noise_std);
00175   boost::variate_generator<boost::mt19937&, boost::normal_distribution<float> > gaussian_rng (rng, normal_distrib);
00176 
00177   std::vector<std::string> st;
00178   // Virtual camera parameters
00179   double eye[3]     = {0.0, 0.0, 0.0};
00180   double viewray[3] = {0.0, 0.0, 0.0};
00181   double up[3]      = {0.0, 0.0, 0.0};
00182   double right[3]  = {0.0, 0.0, 0.0};
00183   double x_axis[3] = {1.0, 0.0, 0.0};
00184   double z_axis[3] = {0.0, 0.0, 1.0};
00185   double bounds[6];
00186   double temp_beam[3], beam[3], p[3];
00187   double p_coords[3], x[3], t;
00188   int subId;
00189  
00190   // Create a Icosahedron at center in origin and radius of 1
00191   vtkSmartPointer<vtkPlatonicSolidSource> icosa = vtkSmartPointer<vtkPlatonicSolidSource>::New ();
00192   icosa->SetSolidTypeToIcosahedron ();
00193 
00194   // Tesselize the source icosahedron (subdivide each triangular face
00195   // of the icosahedron into smaller triangles)
00196   vtkSmartPointer<vtkLoopSubdivisionFilter> subdivide = vtkSmartPointer<vtkLoopSubdivisionFilter>::New ();
00197   subdivide->SetNumberOfSubdivisions (subdiv_level);
00198   subdivide->SetInputConnection (icosa->GetOutputPort ());
00199 
00200   // Get camera positions
00201   vtkPolyData *sphere = subdivide->GetOutput ();
00202   sphere->Update ();
00203   if (!single_view)
00204     PCL_INFO ("Created %ld camera position points.\n", sphere->GetNumberOfPoints ());
00205 
00206   // Build a spatial locator for our dataset
00207   vtkSmartPointer<vtkCellLocator> tree = vtkSmartPointer<vtkCellLocator>::New ();
00208   tree->SetDataSet (data);
00209   tree->CacheCellBoundsOn ();
00210   tree->SetTolerance (0.0);
00211   tree->SetNumberOfCellsPerBucket (1);
00212   tree->AutomaticOn ();
00213   tree->BuildLocator ();
00214   tree->Update ();
00215 
00216   // Get the min-max bounds of data
00217   data->GetBounds (bounds);
00218 
00219   // if single view is required iterate over loop only once
00220   int number_of_points = static_cast<int> (sphere->GetNumberOfPoints ());
00221   if (single_view)
00222     number_of_points = 1;
00223 
00224   int sid = -1;
00225   for (int i = 0; i < number_of_points; i++)
00226   {
00227     sphere->GetPoint (i, eye);
00228     if (fabs(eye[0]) < EPS) eye[0] = 0;
00229     if (fabs(eye[1]) < EPS) eye[1] = 0;
00230     if (fabs(eye[2]) < EPS) eye[2] = 0;
00231 
00232     viewray[0] = -eye[0];
00233     viewray[1] = -eye[1];
00234     viewray[2] = -eye[2];
00235     eye[0] *= scan_dist;
00236     eye[1] *= scan_dist;
00237     eye[2] *= scan_dist;
00238     //Change here if only single view point is required
00239     if (single_view)
00240     {
00241       eye[0] = vx;//0.0;
00242       eye[1] = vy;//-0.26;
00243       eye[2] = vz;//-0.86;
00244       viewray[0] = tx - vx;
00245       viewray[1] = ty - vy;
00246       viewray[2] = tz - vz;
00247       double len = sqrt (viewray[0]*viewray[0] + viewray[1]*viewray[1] + viewray[2]*viewray[2]);
00248       if (len == 0)
00249       {
00250         PCL_ERROR ("The single_view option is enabled but the view_point and the target_point are the same!\n");
00251         break;
00252       }
00253       viewray[0] /= len;
00254       viewray[1] /= len;
00255       viewray[2] /= len;
00256     }
00257 
00258     if ((viewray[0] == 0) && (viewray[1] == 0))
00259       vtkMath::Cross (viewray, x_axis, right);
00260     else
00261       vtkMath::Cross (viewray, z_axis, right);
00262     if (fabs(right[0]) < EPS) right[0] = 0;
00263     if (fabs(right[1]) < EPS) right[1] = 0;
00264     if (fabs(right[2]) < EPS) right[2] = 0;
00265 
00266     vtkMath::Cross (viewray, right, up);
00267     if (fabs(up[0]) < EPS) up[0] = 0;
00268     if (fabs(up[1]) < EPS) up[1] = 0;
00269     if (fabs(up[2]) < EPS) up[2] = 0;
00270 
00271     if (!object_coordinates)
00272     {
00273       // Normalization
00274       double right_len = sqrt (right[0]*right[0] + right[1]*right[1] + right[2]*right[2]);
00275       right[0] /= right_len;
00276       right[1] /= right_len;
00277       right[2] /= right_len;
00278       double up_len = sqrt (up[0]*up[0] + up[1]*up[1] + up[2]*up[2]);
00279       up[0] /= up_len;
00280       up[1] /= up_len;
00281       up[2] /= up_len;
00282     
00283       // Output resulting vectors
00284       cerr << "Viewray Right Up:" << endl;
00285       cerr << viewray[0] << " " << viewray[1] << " " << viewray[2] << " " << endl;
00286       cerr << right[0] << " " << right[1] << " " << right[2] << " " << endl;
00287       cerr << up[0] << " " << up[1] << " " << up[2] << " " << endl;
00288     }
00289 
00290     // Create a transformation
00291     vtkGeneralTransform* tr1 = vtkGeneralTransform::New ();
00292     vtkGeneralTransform* tr2 = vtkGeneralTransform::New ();
00293 
00294     // right = viewray x up
00295     vtkMath::Cross (viewray, up, right);
00296 
00297     // Sweep vertically
00298     for (double vert = vert_start; vert <= vert_end; vert += sp.vert_res)
00299     {
00300       sid++;
00301 
00302       tr1->Identity ();
00303       tr1->RotateWXYZ (vert, right);
00304       tr1->InternalTransformPoint (viewray, temp_beam);
00305 
00306       // Sweep horizontally
00307       int pid = -1;
00308       for (double hor = hor_start; hor <= hor_end; hor += sp.hor_res)
00309       {
00310         pid ++;
00311       
00312         // Create a beam vector with (lat,long) angles (vert, hor) with the viewray
00313         tr2->Identity ();
00314         tr2->RotateWXYZ (hor, up);
00315         tr2->InternalTransformPoint (temp_beam, beam);
00316         vtkMath::Normalize (beam);
00317 
00318         // Find point at max range: p = eye + beam * max_dist
00319         for (int d = 0; d < 3; d++)
00320           p[d] = eye[d] + beam[d] * sp.max_dist;
00321 
00322         // Put p_coords into laser scan at packetid = vert, scan id = hor
00323         vtkIdType cellId;
00324         if (tree->IntersectWithLine (eye, p, 0, t, x, p_coords, subId, cellId))
00325         {
00326           pcl::PointWithViewpoint pt;
00327           if (object_coordinates)
00328           {
00329             pt.x = static_cast<float> (x[0]); 
00330             pt.y = static_cast<float> (x[1]); 
00331             pt.z = static_cast<float> (x[2]);
00332             pt.vp_x = static_cast<float> (eye[0]); 
00333             pt.vp_y = static_cast<float> (eye[1]); 
00334             pt.vp_z = static_cast<float> (eye[2]);
00335           }
00336           else
00337           {
00338             // z axis is the viewray
00339             // y axis is up
00340             // x axis is -right (negative because z*y=-x but viewray*up=right)
00341             pt.x = static_cast<float> (-right[0]*x[1] + up[0]*x[2] + viewray[0]*x[0] + eye[0]);
00342             pt.y = static_cast<float> (-right[1]*x[1] + up[1]*x[2] + viewray[1]*x[0] + eye[1]);
00343             pt.z = static_cast<float> (-right[2]*x[1] + up[2]*x[2] + viewray[2]*x[0] + eye[2]);
00344             pt.vp_x = pt.vp_y = pt.vp_z = 0.0f;
00345           }
00346           cloud.points.push_back (pt);
00347         }
00348         else
00349           if (organized)
00350           {
00351             pcl::PointWithViewpoint pt;
00352             pt.x = pt.y = pt.z = std::numeric_limits<float>::quiet_NaN ();
00353             pt.vp_x = static_cast<float> (eye[0]);
00354             pt.vp_y = static_cast<float> (eye[1]);
00355             pt.vp_z = static_cast<float> (eye[2]);
00356             cloud.points.push_back (pt);
00357           }
00358       } // Horizontal
00359     } // Vertical
00360 
00361     // Noisify each point in the dataset
00362     // \note: we might decide to noisify along the ray later
00363     for (size_t cp = 0; cp < cloud.points.size (); ++cp)
00364     {
00365       // Add noise ?
00366       switch (noise_model)
00367       {
00368         // Gaussian
00369         case 1: { cloud.points[cp].x += gaussian_rng (); cloud.points[cp].y += gaussian_rng (); cloud.points[cp].z += gaussian_rng (); break; }
00370       }
00371     }
00372 
00373     // Downsample and remove silly point duplicates
00374     pcl::PointCloud<pcl::PointWithViewpoint> cloud_downsampled;
00375     grid.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointWithViewpoint> > (cloud));
00376     //grid.filter (cloud_downsampled);
00377 
00378     // Saves the point cloud data to disk
00379     sprintf (seq, "%d", i);
00380     boost::trim (filename);
00381     boost::split (st, filename, boost::is_any_of ("/"), boost::token_compress_on);
00382 
00383     std::stringstream ss;
00384     std::string output_dir = st.at (st.size () - 1);
00385     boost::filesystem::path outpath (output_dir);
00386     if (!boost::filesystem::exists (outpath))
00387     {
00388       if (!boost::filesystem::create_directories (outpath))
00389       {
00390         PCL_ERROR ("Error creating directory %s.\n", output_dir.c_str ());
00391         return (-1);
00392       }
00393       PCL_INFO ("Creating directory %s\n", output_dir.c_str ());
00394     }
00395 
00396     fname = st.at (st.size () - 1) + "/" + seq + ".pcd";
00397 
00398     if (organized)
00399     {
00400       cloud.height = 1 + static_cast<uint32_t> ((vert_end - vert_start) / sp.vert_res);
00401       cloud.width = 1 + static_cast<uint32_t> ((hor_end - hor_start) / sp.hor_res);
00402     }
00403     else
00404     {
00405       cloud.width = static_cast<uint32_t> (cloud.points.size ());
00406       cloud.height = 1;
00407     }
00408 
00409     pcl::PCDWriter writer;
00410     writer.writeBinaryCompressed (fname.c_str (), cloud);
00411     PCL_INFO ("Wrote %zu points (%d x %d) to %s\n", cloud.points.size (), cloud.width, cloud.height, fname.c_str ());
00412   } // sphere
00413   return (0);
00414 }
00415 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:01