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 
00039 
00040 
00041 #include <pcl/common/common.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <cfloat>
00044 #include <pcl/visualization/eigen.h>
00045 
00046 #include <pcl/visualization/point_cloud_handlers.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 #include <pcl/visualization/image_viewer.h>
00049 #include <pcl/visualization/histogram_visualizer.h>
00050 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00051 #include <pcl/visualization/pcl_plotter.h>
00052 #endif
00053 #include <pcl/visualization/point_picking_event.h>
00054 #include <pcl/console/print.h>
00055 #include <pcl/console/parse.h>
00056 #include <pcl/console/time.h>
00057 #include <pcl/search/kdtree.h>
00058 #include <vtkPolyDataReader.h>
00059 
00060 using namespace pcl::console;
00061 
00062 typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;
00063 typedef ColorHandler::Ptr ColorHandlerPtr;
00064 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00065 
00066 typedef pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2> GeometryHandler;
00067 typedef GeometryHandler::Ptr GeometryHandlerPtr;
00068 typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00069 
00070 #define NORMALS_SCALE 0.01f
00071 #define PC_SCALE 0.001f
00072 
00073 bool
00074 isValidFieldName (const std::string &field)
00075 {
00076   if (field == "_")
00077     return (false);
00078 
00079   if ((field == "vp_x") || (field == "vx") || (field == "vp_y") || (field == "vy") || (field == "vp_z") || (field == "vz"))
00080     return (false);
00081   return (true);
00082 }
00083 
00084 bool
00085 isMultiDimensionalFeatureField (const pcl::PCLPointField &field)
00086 {
00087   if (field.count > 1)
00088     return (true);
00089   return (false);
00090 }
00091 
00092 bool
00093 isOnly2DImage (const pcl::PCLPointField &field)
00094 {
00095   if (field.name == "rgba" || field.name == "rgb")
00096     return (true);
00097   return (false);
00098 }
00099   
00100 void
00101 printHelp (int, char **argv)
00102 {
00103   print_error ("Syntax is: %s <file_name 1..N>.<pcd or vtk> <options>\n", argv[0]);
00104   print_info ("  where options are:\n");
00105   print_info ("                     -bc r,g,b                = background color\n");
00106   print_info ("                     -fc r,g,b                = foreground color\n");
00107   print_info ("                     -ps X                    = point size ("); print_value ("1..64"); print_info (") \n");
00108   print_info ("                     -opaque X                = rendered point cloud opacity ("); print_value ("0..1"); print_info (")\n");
00109   print_info ("                     -shading X               = rendered surface shading ("); print_value ("'flat' (default), 'gouraud', 'phong'"); print_info (")\n");
00110 
00111   print_info ("                     -ax "); print_value ("n"); print_info ("                    = enable on-screen display of ");
00112   print_color (stdout, TT_BRIGHT, TT_RED, "X"); print_color (stdout, TT_BRIGHT, TT_GREEN, "Y"); print_color (stdout, TT_BRIGHT, TT_BLUE, "Z");
00113   print_info (" axes and scale them to "); print_value ("n\n");
00114   print_info ("                     -ax_pos X,Y,Z            = if axes are enabled, set their X,Y,Z position in space (default "); print_value ("0,0,0"); print_info (")\n");
00115 
00116   print_info ("\n");
00117   print_info ("                     -cam (*)                 = use given camera settings as initial view\n");
00118   print_info (stderr, " (*) [Clipping Range / Focal Point / Position / ViewUp / Distance / Field of View Y / Window Size / Window Pos] or use a <filename.cam> that contains the same information.\n");
00119 
00120   print_info ("\n");
00121   print_info ("                     -multiview 0/1           = enable/disable auto-multi viewport rendering (default "); print_value ("disabled"); print_info (")\n");
00122   print_info ("\n");
00123 
00124   print_info ("\n");
00125   print_info ("                     -normals 0/X             = disable/enable the display of every Xth point's surface normal as lines (default "); print_value ("disabled"); print_info (")\n");
00126   print_info ("                     -normals_scale X         = resize the normal unit vector size to X (default "); print_value ("0.02"); print_info (")\n");
00127   print_info ("\n");
00128   print_info ("                     -pc 0/X                  = disable/enable the display of every Xth point's principal curvatures as lines (default "); print_value ("disabled"); print_info (")\n");
00129   print_info ("                     -pc_scale X              = resize the principal curvatures vectors size to X (default "); print_value ("0.02"); print_info (")\n");
00130   print_info ("\n");
00131   print_info ("                     -immediate_rendering 0/1 = use immediate mode rendering to draw the data (default: "); print_value ("disabled"); print_info (")\n");
00132   print_info ("                                                Note: the use of immediate rendering will enable the visualization of larger datasets at the expense of extra RAM.\n");
00133   print_info ("                                                See http://en.wikipedia.org/wiki/Immediate_mode for more information.\n");
00134   print_info ("                     -vbo_rendering 0/1       = use OpenGL 1.4+ Vertex Buffer Objects for rendering (default: "); print_value ("disabled"); print_info (")\n");
00135   print_info ("                                                Note: the use of VBOs will enable the visualization of larger datasets at the expense of extra RAM.\n");
00136   print_info ("                                                See http://en.wikipedia.org/wiki/Vertex_Buffer_Object for more information.\n");
00137   print_info ("\n");
00138   print_info ("                     -use_point_picking       = enable the usage of picking points on screen (default "); print_value ("disabled"); print_info (")\n");
00139   print_info ("\n");
00140 
00141   print_info ("\n(Note: for multiple .pcd files, provide multiple -{fc,ps,opaque} parameters; they will be automatically assigned to the right file)\n");
00142 }
00143 
00144 
00145 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00146 pcl::visualization::PCLPlotter ph_global;
00147 #endif
00148 boost::shared_ptr<pcl::visualization::PCLVisualizer> p;
00149 std::vector<boost::shared_ptr<pcl::visualization::ImageViewer> > imgs;
00150 pcl::search::KdTree<pcl::PointXYZ> search;
00151 pcl::PCLPointCloud2::Ptr cloud;
00152 pcl::PointCloud<pcl::PointXYZ>::Ptr xyzcloud;
00153 
00154 void
00155 pp_callback (const pcl::visualization::PointPickingEvent& event, void* cookie)
00156 {
00157   int idx = event.getPointIndex ();
00158   if (idx == -1)
00159     return;
00160 
00161   if (!cloud)
00162   {
00163     cloud = *reinterpret_cast<pcl::PCLPointCloud2::Ptr*> (cookie);
00164     xyzcloud.reset (new pcl::PointCloud<pcl::PointXYZ>);
00165     pcl::fromPCLPointCloud2 (*cloud, *xyzcloud);
00166     search.setInputCloud (xyzcloud);
00167   }
00168   
00169   std::vector<int> indices (1);
00170   std::vector<float> distances (1);
00171 
00172   
00173   pcl::PointXYZ picked_pt;
00174   event.getPoint (picked_pt.x, picked_pt.y, picked_pt.z);
00175   search.nearestKSearch (picked_pt, 1, indices, distances);
00176 
00177   PCL_INFO ("Point index picked: %d (real: %d) - [%f, %f, %f]\n", idx, indices[0], picked_pt.x, picked_pt.y, picked_pt.z);
00178 
00179   idx = indices[0];
00180   
00181   pcl::PointXYZ p1, p2;
00182   if (event.getPoints (p1.x, p1.y, p1.z, p2.x, p2.y, p2.z) && p)
00183   {
00184     std::stringstream ss;
00185     ss << p1 << p2;
00186     p->addArrow<pcl::PointXYZ, pcl::PointXYZ> (p1, p2, 1.0, 1.0, 1.0, ss.str ());
00187     return;
00188   }
00189 
00190   
00191   std::stringstream ss;
00192   ss << idx;
00193   
00194   for (size_t i = 0; i < cloud->fields.size (); ++i)
00195   {
00196     if (!isMultiDimensionalFeatureField (cloud->fields[i]))
00197       continue;
00198     PCL_INFO ("Multidimensional field found: %s\n", cloud->fields[i].name.c_str ());
00199 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00200     ph_global.addFeatureHistogram (*cloud, cloud->fields[i].name, idx, ss.str ());
00201     ph_global.renderOnce ();
00202 #endif
00203   }
00204   if (p)
00205   {
00206     pcl::PointXYZ pos;
00207     event.getPoint (pos.x, pos.y, pos.z);
00208     p->addText3D<pcl::PointXYZ> (ss.str (), pos, 0.0005, 1.0, 1.0, 1.0, ss.str ());
00209   }
00210   
00211 }
00212 
00213 
00214 int
00215 main (int argc, char** argv)
00216 {
00217   srand (static_cast<unsigned int> (time (0)));
00218 
00219   print_info ("The viewer window provides interactive commands; for help, press 'h' or 'H' from within the window.\n");
00220 
00221   if (argc < 2)
00222   {
00223     printHelp (argc, argv);
00224     return (-1);
00225   }
00226 
00227   bool debug = false;
00228   pcl::console::parse_argument (argc, argv, "-debug", debug);
00229   if (debug)
00230     pcl::console::setVerbosityLevel (pcl::console::L_DEBUG);
00231 
00232   bool cam = pcl::console::find_switch (argc, argv, "-cam");
00233 
00234   
00235   std::vector<int> p_file_indices   = pcl::console::parse_file_extension_argument (argc, argv, ".pcd");
00236   std::vector<int> vtk_file_indices = pcl::console::parse_file_extension_argument (argc, argv, ".vtk");
00237 
00238   if (p_file_indices.size () == 0 && vtk_file_indices.size () == 0)
00239   {
00240     print_error ("No .PCD or .VTK file given. Nothing to visualize.\n");
00241     return (-1);
00242   }
00243 
00244   
00245   double bcolor[3] = {0, 0, 0};
00246   pcl::console::parse_3x_arguments (argc, argv, "-bc", bcolor[0], bcolor[1], bcolor[2]);
00247 
00248   std::vector<double> fcolor_r, fcolor_b, fcolor_g;
00249   bool fcolorparam = pcl::console::parse_multiple_3x_arguments (argc, argv, "-fc", fcolor_r, fcolor_g, fcolor_b);
00250 
00251   std::vector<int> psize;
00252   pcl::console::parse_multiple_arguments (argc, argv, "-ps", psize);
00253 
00254   std::vector<double> opaque;
00255   pcl::console::parse_multiple_arguments (argc, argv, "-opaque", opaque);
00256 
00257   std::vector<std::string> shadings;
00258   pcl::console::parse_multiple_arguments (argc, argv, "-shading", shadings);
00259 
00260   int mview = 0;
00261   pcl::console::parse_argument (argc, argv, "-multiview", mview);
00262 
00263   int normals = 0;
00264   pcl::console::parse_argument (argc, argv, "-normals", normals);
00265   float normals_scale = NORMALS_SCALE;
00266   pcl::console::parse_argument (argc, argv, "-normals_scale", normals_scale);
00267 
00268   int pc = 0;
00269   pcl::console::parse_argument (argc, argv, "-pc", pc);
00270   float pc_scale = PC_SCALE;
00271   pcl::console::parse_argument (argc, argv, "-pc_scale", pc_scale);
00272 
00273   bool use_vbos = false;
00274   pcl::console::parse_argument (argc, argv, "-vbo_rendering", use_vbos);
00275   if (use_vbos) 
00276     print_highlight ("Vertex Buffer Object (VBO) visualization enabled.\n");
00277 
00278   bool use_pp   = pcl::console::find_switch (argc, argv, "-use_point_picking");
00279   if (use_pp) 
00280     print_highlight ("Point picking enabled.\n");
00281 
00282   
00283   bool use_immediate_rendering = false;
00284   if (!use_vbos)
00285   {
00286     pcl::console::parse_argument (argc, argv, "-immediate_rendering", use_immediate_rendering);
00287     if (use_immediate_rendering) 
00288       print_highlight ("Using immediate mode rendering.\n");
00289   }
00290 
00291   
00292   int y_s = 0, x_s = 0;
00293   double x_step = 0, y_step = 0;
00294   if (mview)
00295   {
00296     print_highlight ("Multi-viewport rendering enabled.\n");
00297 
00298     y_s = static_cast<int>(floor (sqrt (static_cast<float>(p_file_indices.size () + vtk_file_indices.size ()))));
00299     x_s = y_s + static_cast<int>(ceil (double (p_file_indices.size () + vtk_file_indices.size ()) / double (y_s) - y_s));
00300 
00301     if (p_file_indices.size () != 0)
00302     {
00303       print_highlight ("Preparing to load "); print_value ("%d", p_file_indices.size ()); print_info (" pcd files.\n");
00304     }
00305 
00306     if (vtk_file_indices.size () != 0)
00307     {
00308       print_highlight ("Preparing to load "); print_value ("%d", vtk_file_indices.size ()); print_info (" vtk files.\n");
00309     }
00310 
00311     x_step = static_cast<double>(1.0 / static_cast<double>(x_s));
00312     y_step = static_cast<double>(1.0 / static_cast<double>(y_s));
00313     print_value ("%d", x_s);    print_info ("x"); print_value ("%d", y_s);
00314     print_info (" / ");      print_value ("%f", x_step); print_info ("x"); print_value ("%f", y_step);
00315     print_info (")\n");
00316   }
00317 
00318   
00319   if (psize.size () != p_file_indices.size () && psize.size () > 0)
00320     for (size_t i = psize.size (); i < p_file_indices.size (); ++i)
00321       psize.push_back (1);
00322   if (opaque.size () != p_file_indices.size () && opaque.size () > 0)
00323     for (size_t i = opaque.size (); i < p_file_indices.size (); ++i)
00324       opaque.push_back (1.0);
00325 
00326   if (shadings.size () != p_file_indices.size () && shadings.size () > 0)
00327     for (size_t i = shadings.size (); i < p_file_indices.size (); ++i)
00328       shadings.push_back ("flat");
00329 
00330   
00331 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00332   boost::shared_ptr<pcl::visualization::PCLPlotter> ph;
00333 #endif  
00334   
00335   float min_p = FLT_MAX; float max_p = -FLT_MAX;
00336 
00337   int k = 0, l = 0, viewport = 0;
00338   
00339   pcl::PCDReader pcd;
00340   pcl::console::TicToc tt;
00341   ColorHandlerPtr color_handler;
00342   GeometryHandlerPtr geometry_handler;
00343 
00344   
00345   for (size_t i = 0; i < vtk_file_indices.size (); ++i)
00346   {
00347     
00348     tt.tic ();
00349     print_highlight (stderr, "Loading "); print_value (stderr, "%s ", argv[vtk_file_indices.at (i)]);
00350     vtkPolyDataReader* reader = vtkPolyDataReader::New ();
00351     reader->SetFileName (argv[vtk_file_indices.at (i)]);
00352     reader->Update ();
00353     vtkSmartPointer<vtkPolyData> polydata = reader->GetOutput ();
00354     if (!polydata)
00355       return (-1);
00356     print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", polydata->GetNumberOfPoints ()); print_info (" points]\n");
00357 
00358     
00359     if (!p)
00360       p.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00361 
00362     
00363     if (mview)
00364     {
00365       p->createViewPort (k * x_step, l * y_step, (k + 1) * x_step, (l + 1) * y_step, viewport);
00366       k++;
00367       if (k >= x_s)
00368       {
00369         k = 0;
00370         l++;
00371       }
00372     }
00373 
00374     
00375     std::stringstream cloud_name ("vtk-");
00376     cloud_name << argv[vtk_file_indices.at (i)] << "-" << i;
00377     p->addModelFromPolyData (polydata, cloud_name.str (), viewport);
00378 
00379     
00380     if (fcolorparam && fcolor_r.size () > i && fcolor_g.size () > i && fcolor_b.size () > i)
00381       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, fcolor_r[i], fcolor_g[i], fcolor_b[i], cloud_name.str ());
00382 
00383     
00384     if (psize.size () > 0)
00385       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize.at (i), cloud_name.str ());
00386 
00387     
00388     if (opaque.size () > 0)
00389       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opaque.at (i), cloud_name.str ());
00390 
00391     
00392     if (shadings.size () > 0)
00393     {
00394       if (shadings[i] == "flat")
00395       {
00396         print_highlight (stderr, "Setting shading property for %s to FLAT.\n", argv[vtk_file_indices.at (i)]);
00397         p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_SHADING, pcl::visualization::PCL_VISUALIZER_SHADING_FLAT, cloud_name.str ());
00398       }
00399       else if (shadings[i] == "gouraud")
00400       {
00401         print_highlight (stderr, "Setting shading property for %s to GOURAUD.\n", argv[vtk_file_indices.at (i)]);
00402         p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_SHADING, pcl::visualization::PCL_VISUALIZER_SHADING_GOURAUD, cloud_name.str ());
00403       }
00404       else if (shadings[i] == "phong")
00405       {
00406         print_highlight (stderr, "Setting shading property for %s to PHONG.\n", argv[vtk_file_indices.at (i)]);
00407         p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_SHADING, pcl::visualization::PCL_VISUALIZER_SHADING_PHONG, cloud_name.str ());
00408       }
00409     }
00410   }
00411 
00412   pcl::PCLPointCloud2::Ptr cloud;
00413   
00414   for (size_t i = 0; i < p_file_indices.size (); ++i)
00415   {
00416     tt.tic ();
00417     cloud.reset (new pcl::PCLPointCloud2);
00418     Eigen::Vector4f origin;
00419     Eigen::Quaternionf orientation;
00420     int version;
00421 
00422     print_highlight (stderr, "Loading "); print_value (stderr, "%s ", argv[p_file_indices.at (i)]);
00423 
00424     if (pcd.read (argv[p_file_indices.at (i)], *cloud, origin, orientation, version) < 0)
00425       return (-1);
00426 
00427     std::stringstream cloud_name;
00428 
00429     
00430     if (cloud->fields.size () == 1 && isMultiDimensionalFeatureField (cloud->fields[0]))
00431     {
00432       cloud_name << argv[p_file_indices.at (i)];
00433 
00434 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00435       if (!ph)
00436         ph.reset (new pcl::visualization::PCLPlotter);
00437 #endif
00438 
00439       pcl::getMinMax (*cloud, 0, cloud->fields[0].name, min_p, max_p);
00440 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00441       ph->addFeatureHistogram (*cloud, cloud->fields[0].name, cloud_name.str ());
00442 #endif
00443       print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud->fields[0].count); print_info (" points]\n");
00444       continue;
00445     }
00446 
00447     
00448     if (cloud->fields.size () == 1 && isOnly2DImage (cloud->fields[0]))
00449     {
00450       print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%u", cloud->width * cloud->height); print_info (" points]\n");
00451       print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (*cloud).c_str ());
00452       
00453       std::stringstream name;
00454       name << "PCD Viewer :: " << argv[p_file_indices.at (i)];
00455       pcl::visualization::ImageViewer::Ptr img (new pcl::visualization::ImageViewer (name.str ()));
00456       pcl::PointCloud<pcl::RGB> rgb_cloud;
00457       pcl::fromPCLPointCloud2 (*cloud, rgb_cloud);
00458 
00459       img->addRGBImage (rgb_cloud);
00460       imgs.push_back (img);
00461 
00462       continue;
00463     }
00464 
00465     cloud_name << argv[p_file_indices.at (i)] << "-" << i;
00466 
00467     
00468     if (!p)
00469     {
00470       p.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00471       if (use_pp)   
00472         p->registerPointPickingCallback (&pp_callback, static_cast<void*> (&cloud));
00473 
00474       
00475       p->setUseVbos (use_vbos);
00476 
00477       if (!cam)
00478       {
00479         Eigen::Matrix3f rotation;
00480         rotation = orientation;
00481         p->setCameraPosition (origin [0]                  , origin [1]                  , origin [2],
00482                               origin [0] + rotation (0, 2), origin [1] + rotation (1, 2), origin [2] + rotation (2, 2),
00483                                            rotation (0, 1),              rotation (1, 1),              rotation (2, 1));
00484       }
00485     }
00486 
00487     
00488     if (mview)
00489     {
00490       p->createViewPort (k * x_step, l * y_step, (k + 1) * x_step, (l + 1) * y_step, viewport);
00491       k++;
00492       if (k >= x_s)
00493       {
00494         k = 0;
00495         l++;
00496       }
00497     }
00498 
00499     if (cloud->width * cloud->height == 0)
00500     {
00501       print_error ("[error: no points found!]\n");
00502       return (-1);
00503     }
00504 
00505     
00506     if (fcolorparam)
00507     {
00508       if (fcolor_r.size () > i && fcolor_g.size () > i && fcolor_b.size () > i)
00509         color_handler.reset (new pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2> (cloud, fcolor_r[i], fcolor_g[i], fcolor_b[i]));
00510       else
00511         color_handler.reset (new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (cloud));
00512     }
00513     else
00514       color_handler.reset (new pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2> (cloud));
00515 
00516     
00517     geometry_handler.reset (new pcl::visualization::PointCloudGeometryHandlerXYZ<pcl::PCLPointCloud2> (cloud));
00518     
00519     
00520     p->addPointCloud (cloud, geometry_handler, color_handler, origin, orientation, cloud_name.str (), viewport);
00521 
00522 
00523     if (mview)
00524       
00525       p->addText (argv[p_file_indices.at (i)], 5, 5, 10, 1.0, 1.0, 1.0, "text_" + std::string (argv[p_file_indices.at (i)]), viewport);
00526 
00527     
00528     if (normals != 0)
00529     {
00530       int normal_idx = pcl::getFieldIndex (*cloud, "normal_x");
00531       if (normal_idx == -1)
00532       {
00533         print_error ("Normal information requested but not available.\n");
00534         continue;
00535         
00536       }
00537       
00538       
00539       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00540       pcl::fromPCLPointCloud2 (*cloud, *cloud_xyz);
00541       cloud_xyz->sensor_origin_ = origin;
00542       cloud_xyz->sensor_orientation_ = orientation;
00543 
00544       pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00545       pcl::fromPCLPointCloud2 (*cloud, *cloud_normals);
00546       std::stringstream cloud_name_normals;
00547       cloud_name_normals << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00548       p->addPointCloudNormals<pcl::PointXYZ, pcl::Normal> (cloud_xyz, cloud_normals, normals, normals_scale, cloud_name_normals.str (), viewport);
00549     }
00550 
00551     
00552     if (pc != 0)
00553     {
00554       if (normals == 0)
00555         normals = pc;
00556 
00557       int normal_idx = pcl::getFieldIndex (*cloud, "normal_x");
00558       if (normal_idx == -1)
00559       {
00560         print_error ("Normal information requested but not available.\n");
00561         continue;
00562         
00563       }
00564       int pc_idx = pcl::getFieldIndex (*cloud, "principal_curvature_x");
00565       if (pc_idx == -1)
00566       {
00567         print_error ("Principal Curvature information requested but not available.\n");
00568         continue;
00569         
00570       }
00571       
00572       
00573       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00574       pcl::fromPCLPointCloud2 (*cloud, *cloud_xyz);
00575       cloud_xyz->sensor_origin_ = origin;
00576       cloud_xyz->sensor_orientation_ = orientation;
00577       pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00578       pcl::fromPCLPointCloud2 (*cloud, *cloud_normals);
00579       pcl::PointCloud<pcl::PrincipalCurvatures>::Ptr cloud_pc (new pcl::PointCloud<pcl::PrincipalCurvatures>);
00580       pcl::fromPCLPointCloud2 (*cloud, *cloud_pc);
00581       std::stringstream cloud_name_normals_pc;
00582       cloud_name_normals_pc << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00583       int factor = (std::min)(normals, pc);
00584       p->addPointCloudNormals<pcl::PointXYZ, pcl::Normal> (cloud_xyz, cloud_normals, factor, normals_scale, cloud_name_normals_pc.str (), viewport);
00585       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, cloud_name_normals_pc.str ());
00586       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00587       cloud_name_normals_pc << "-pc";
00588       p->addPointCloudPrincipalCurvatures (cloud_xyz, cloud_normals, cloud_pc, factor, pc_scale, cloud_name_normals_pc.str (), viewport);
00589       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00590     }
00591 
00592     
00593     if (!fcolorparam)
00594     {
00595       for (size_t f = 0; f < cloud->fields.size (); ++f)
00596       {
00597         if (cloud->fields[f].name == "rgb" || cloud->fields[f].name == "rgba")
00598           color_handler.reset (new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2> (cloud));
00599         else
00600         {
00601           if (!isValidFieldName (cloud->fields[f].name))
00602             continue;
00603           color_handler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (cloud, cloud->fields[f].name));
00604         }
00605         
00606         
00607         p->addPointCloud (cloud, color_handler, origin, orientation, cloud_name.str (), viewport);
00608       }
00609     }
00610 
00611     
00612     geometry_handler.reset (new pcl::visualization::PointCloudGeometryHandlerSurfaceNormal<pcl::PCLPointCloud2> (cloud));
00613     if (geometry_handler->isCapable ())
00614       
00615       p->addPointCloud (cloud, geometry_handler, origin, orientation, cloud_name.str (), viewport);
00616 
00617     if (use_immediate_rendering)
00618       
00619       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_IMMEDIATE_RENDERING, 1.0, cloud_name.str ());
00620 
00621     
00622     if (psize.size () > 0)
00623       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize.at (i), cloud_name.str ());
00624 
00625     
00626     if (opaque.size () > 0)
00627       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opaque.at (i), cloud_name.str ());
00628 
00629     
00630     if (i == 0 && !p->cameraParamsSet ())
00631       p->resetCameraViewpoint (cloud_name.str ());
00632 
00633     print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%u", cloud->width * cloud->height); print_info (" points]\n");
00634     print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (*cloud).c_str ());
00635   }
00636 
00637   if (!mview && p)
00638   {
00639     std::string str;
00640     if (!p_file_indices.empty ())
00641       str = std::string (argv[p_file_indices.at (0)]);
00642     else if (!vtk_file_indices.empty ())
00643       str = std::string (argv[vtk_file_indices.at (0)]);
00644 
00645     for (size_t i = 1; i < p_file_indices.size (); ++i)
00646       str += ", " + std::string (argv[p_file_indices.at (i)]);
00647 
00648     for (size_t i = 1; i < vtk_file_indices.size (); ++i)
00649       str += ", " + std::string (argv[vtk_file_indices.at (i)]);
00650 
00651     p->addText (str, 5, 5, 10, 1.0, 1.0, 1.0, "text_allnames");
00652   }
00653 
00654   if (p)
00655     p->setBackgroundColor (bcolor[0], bcolor[1], bcolor[2]);
00656   
00657   double axes  = 0.0;
00658   pcl::console::parse_argument (argc, argv, "-ax", axes);
00659   if (axes != 0.0 && p)
00660   {
00661     float ax_x = 0.0, ax_y = 0.0, ax_z = 0.0;
00662     pcl::console::parse_3x_arguments (argc, argv, "-ax_pos", ax_x, ax_y, ax_z, false);
00663     
00664     p->addCoordinateSystem (axes, ax_x, ax_y, ax_z);
00665   }
00666 
00667   
00668   
00669   if (!use_pp)   
00670   {
00671     cloud.reset ();
00672     xyzcloud.reset ();
00673   }
00674 
00675   
00676   if (!imgs.empty ())
00677   {
00678     bool stopped = false;
00679     do
00680     {
00681 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00682       if (ph) ph->spinOnce ();
00683 #endif
00684 
00685       for (int i = 0; i < int (imgs.size ()); ++i)
00686       {
00687         if (imgs[i]->wasStopped ())
00688         {
00689           stopped = true;
00690           break;
00691         }
00692         imgs[i]->spinOnce ();
00693       }
00694         
00695       if (p)
00696       {
00697         if (p->wasStopped ())
00698         {
00699           stopped = true;
00700           break;
00701         }
00702         p->spinOnce ();
00703       }
00704       boost::this_thread::sleep (boost::posix_time::microseconds (100));
00705     }
00706     while (!stopped);
00707   }
00708   else
00709   {
00710     
00711 #if VTK_MAJOR_VERSION==6 || (VTK_MAJOR_VERSION==5 && VTK_MINOR_VERSION>6)
00712     if (ph)
00713     {
00714       
00715       
00716       
00717       if (p)
00718         p->spin ();
00719       else
00720         ph->spin ();
00721     }
00722     else
00723 #endif
00724       if (p)
00725         p->spin ();
00726   }
00727 }
00728