pcd_viewer.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) 2009-2012, 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  * $Id: pcd_viewer.cpp 5094 2012-03-15 01:03:51Z rusu $
00037  *
00038  */
00039 // PCL
00040 #include <Eigen/Geometry>
00041 #include <pcl/common/common.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <cfloat>
00044 #include <pcl/visualization/point_cloud_handlers.h>
00045 #include <pcl/visualization/pcl_visualizer.h>
00046 #include <pcl/visualization/histogram_visualizer.h>
00047 #include <pcl/visualization/point_picking_event.h>
00048 #include <pcl/console/print.h>
00049 #include <pcl/console/parse.h>
00050 #include <pcl/console/time.h>
00051 #include <vtkPolyDataReader.h>
00052 
00053 using namespace pcl::console;
00054 
00055 typedef pcl::visualization::PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler;
00056 typedef ColorHandler::Ptr ColorHandlerPtr;
00057 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
00058 
00059 typedef pcl::visualization::PointCloudGeometryHandler<sensor_msgs::PointCloud2> GeometryHandler;
00060 typedef GeometryHandler::Ptr GeometryHandlerPtr;
00061 typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
00062 
00063 #define NORMALS_SCALE 0.01
00064 #define PC_SCALE 0.001
00065 
00066 bool
00067 isValidFieldName (const std::string &field)
00068 {
00069   if (field == "_")
00070     return (false);
00071 
00072   if ((field == "vp_x") || (field == "vx") || (field == "vp_y") || (field == "vy") || (field == "vp_z") || (field == "vz"))
00073     return (false);
00074   return (true);
00075 }
00076 
00077 bool
00078 isMultiDimensionalFeatureField (const sensor_msgs::PointField &field)
00079 {
00080   if (field.count > 1)
00081     return (true);
00082   return (false);
00083 }
00084 
00085 void
00086 printHelp (int argc, char **argv)
00087 {
00088   print_error ("Syntax is: %s <file_name 1..N>.<pcd or vtk> <options>\n", argv[0]);
00089   print_info ("  where options are:\n");
00090   print_info ("                     -bc r,g,b                = background color\n");
00091   print_info ("                     -fc r,g,b                = foreground color\n");
00092   print_info ("                     -ps X                    = point size ("); print_value ("1..64"); print_info (") \n");
00093   print_info ("                     -opaque X                = rendered point cloud opacity ("); print_value ("0..1"); print_info (")\n");
00094 
00095   print_info ("                     -ax "); print_value ("n"); print_info ("                    = enable on-screen display of ");
00096   print_color (stdout, TT_BRIGHT, TT_RED, "X"); print_color (stdout, TT_BRIGHT, TT_GREEN, "Y"); print_color (stdout, TT_BRIGHT, TT_BLUE, "Z");
00097   print_info (" axes and scale them to "); print_value ("n\n");
00098   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");
00099 
00100   print_info ("\n");
00101   print_info ("                     -cam (*)                 = use given camera settings as initial view\n");
00102   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");
00103 
00104   print_info ("\n");
00105   print_info ("                     -multiview 0/1           = enable/disable auto-multi viewport rendering (default "); print_value ("disabled"); print_info (")\n");
00106   print_info ("\n");
00107 
00108   print_info ("\n");
00109   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");
00110   print_info ("                     -normals_scale X         = resize the normal unit vector size to X (default "); print_value ("0.02"); print_info (")\n");
00111   print_info ("\n");
00112   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");
00113   print_info ("                     -pc_scale X              = resize the principal curvatures vectors size to X (default "); print_value ("0.02"); print_info (")\n");
00114   print_info ("\n");
00115 
00116   print_info ("\n(Note: for multiple .pcd files, provide multiple -{fc,ps,opaque} parameters; they will be automatically assigned to the right file)\n");
00117 }
00118 
00119 // Global visualizer object
00120 pcl::visualization::PCLHistogramVisualizer ph_global;
00121 boost::shared_ptr<pcl::visualization::PCLVisualizer> p;
00122 
00123 void
00124 pp_callback (const pcl::visualization::PointPickingEvent& event, void* cookie)
00125 {
00126   if (event.getPointIndex () == -1)
00127     return;
00128   sensor_msgs::PointCloud2::Ptr cloud = *(sensor_msgs::PointCloud2::Ptr*)cookie;
00129   if (!cloud)
00130     return;
00131 
00132   // If two points were selected, draw an arrow between them
00133   pcl::PointXYZ p1, p2;
00134   if (event.getPoints (p1.x, p1.y, p1.z, p2.x, p2.y, p2.z) && p)
00135   {
00136     std::stringstream ss;
00137     ss << p1 << p2;
00138     p->addArrow<pcl::PointXYZ, pcl::PointXYZ> (p1, p2, 1.0, 1.0, 1.0, ss.str ());
00139     return;
00140   }
00141 
00142   // Else, if a single point has been selected
00143   std::stringstream ss;
00144   ss << event.getPointIndex ();
00145   // Get the cloud's fields
00146   for (size_t i = 0; i < cloud->fields.size (); ++i)
00147   {
00148     if (!isMultiDimensionalFeatureField (cloud->fields[i]))
00149       continue;
00150     ph_global.addFeatureHistogram (*cloud, cloud->fields[i].name, event.getPointIndex (), ss.str ());
00151   }
00152   if (p)
00153   {
00154     pcl::PointXYZ pos;
00155     event.getPoint (pos.x, pos.y, pos.z);
00156     p->addText3D<pcl::PointXYZ> (ss.str (), pos, 0.0005, 1.0, 1.0, 1.0, ss.str ());
00157   }
00158   ph_global.spinOnce ();
00159 }
00160 
00161 /* ---[ */
00162 int
00163 main (int argc, char** argv)
00164 {
00165   srand (time (0));
00166 
00167   print_info ("The viewer window provides interactive commands; for help, press 'h' or 'H' from within the window.\n");
00168 
00169   if (argc < 2)
00170   {
00171     printHelp (argc, argv);
00172     return (-1);
00173   }
00174 
00175   // Command line parsing
00176   double bcolor[3] = {0, 0, 0};
00177   pcl::console::parse_3x_arguments (argc, argv, "-bc", bcolor[0], bcolor[1], bcolor[2]);
00178 
00179   std::vector<double> fcolor_r, fcolor_b, fcolor_g;
00180   bool fcolorparam = pcl::console::parse_multiple_3x_arguments (argc, argv, "-fc", fcolor_r, fcolor_g, fcolor_b);
00181 
00182   std::vector<int> psize;
00183   pcl::console::parse_multiple_arguments (argc, argv, "-ps", psize);
00184 
00185   std::vector<double> opaque;
00186   pcl::console::parse_multiple_arguments (argc, argv, "-opaque", opaque);
00187 
00188   int mview = 0;
00189   pcl::console::parse_argument (argc, argv, "-multiview", mview);
00190 
00191   int normals = 0;
00192   pcl::console::parse_argument (argc, argv, "-normals", normals);
00193   double normals_scale = NORMALS_SCALE;
00194   pcl::console::parse_argument (argc, argv, "-normals_scale", normals_scale);
00195 
00196   int pc = 0;
00197   pcl::console::parse_argument (argc, argv, "-pc", pc);
00198   double pc_scale = PC_SCALE;
00199   pcl::console::parse_argument (argc, argv, "-pc_scale", pc_scale);
00200 
00201   // Parse the command line arguments for .pcd files
00202   std::vector<int> p_file_indices   = pcl::console::parse_file_extension_argument (argc, argv, ".pcd");
00203   std::vector<int> vtk_file_indices = pcl::console::parse_file_extension_argument (argc, argv, ".vtk");
00204 
00205   if (p_file_indices.size () == 0 && vtk_file_indices.size () == 0)
00206   {
00207     print_error ("No .PCD or .VTK file given. Nothing to visualize.\n");
00208     return (-1);
00209   }
00210 
00211   // Multiview enabled?
00212   int y_s = 0, x_s = 0;
00213   double x_step = 0, y_step = 0;
00214   if (mview)
00215   {
00216     print_highlight ("Multi-viewport rendering enabled.\n");
00217 
00218     if (p_file_indices.size () != 0)
00219     {
00220       y_s = static_cast<int>(floor (sqrt (static_cast<float>(p_file_indices.size ()))));
00221       x_s = y_s + static_cast<int>(ceil ((p_file_indices.size () / static_cast<double>(y_s)) - y_s));
00222       print_highlight ("Preparing to load "); print_value ("%d", p_file_indices.size ());
00223     }
00224     else if (vtk_file_indices.size () != 0)
00225     {
00226       y_s = static_cast<int>(floor (sqrt (static_cast<float>(vtk_file_indices.size ()))));
00227       x_s = y_s + static_cast<int>(ceil ((vtk_file_indices.size () / static_cast<double>(y_s)) - y_s));
00228       print_highlight ("Preparing to load "); print_value ("%d", vtk_file_indices.size ());
00229     }
00230 
00231     x_step = static_cast<double>(1.0 / static_cast<double>(x_s));
00232     y_step = static_cast<double>(1.0 / static_cast<double>(y_s));
00233     print_info (" files ("); print_value ("%d", x_s);    print_info ("x"); print_value ("%d", y_s);
00234     print_info (" / ");      print_value ("%f", x_step); print_info ("x"); print_value ("%f", y_step);
00235     print_info (")\n");
00236   }
00237 
00238   // Fix invalid multiple arguments
00239   if (psize.size () != p_file_indices.size () && psize.size () > 0)
00240     for (size_t i = psize.size (); i < p_file_indices.size (); ++i)
00241       psize.push_back (1);
00242   if (opaque.size () != p_file_indices.size () && opaque.size () > 0)
00243     for (size_t i = opaque.size (); i < p_file_indices.size (); ++i)
00244       opaque.push_back (1.0);
00245 
00246   // Create the PCLVisualizer object
00247   boost::shared_ptr<pcl::visualization::PCLHistogramVisualizer> ph;
00248 
00249   // Using min_p, max_p to set the global Y min/max range for the histogram
00250   float min_p = FLT_MAX; float max_p = -FLT_MAX;
00251 
00252   int k = 0, l = 0, viewport = 0;
00253   // Load the data files
00254   pcl::PCDReader pcd;
00255   pcl::console::TicToc tt;
00256   ColorHandlerPtr color_handler;
00257   GeometryHandlerPtr geometry_handler;
00258 
00259   // Go through VTK files
00260   for (size_t i = 0; i < vtk_file_indices.size (); ++i)
00261   {
00262     // Load file
00263     tt.tic ();
00264     print_highlight (stderr, "Loading "); print_value (stderr, "%s ", argv[vtk_file_indices.at (i)]);
00265     vtkPolyDataReader* reader = vtkPolyDataReader::New ();
00266     reader->SetFileName (argv[vtk_file_indices.at (i)]);
00267     reader->Update ();
00268     vtkSmartPointer<vtkPolyData> polydata = reader->GetOutput ();
00269     if (!polydata)
00270       return (-1);
00271     print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", polydata->GetNumberOfPoints ()); print_info (" points]\n");
00272 
00273     // Create the PCLVisualizer object here on the first encountered XYZ file
00274     if (!p)
00275       p.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00276 
00277     // Multiview enabled?
00278     if (mview)
00279     {
00280       p->createViewPort (k * x_step, l * y_step, (k + 1) * x_step, (l + 1) * y_step, viewport);
00281       k++;
00282       if (k >= x_s)
00283       {
00284         k = 0;
00285         l++;
00286       }
00287     }
00288 
00289     // Add as actor
00290     std::stringstream cloud_name ("vtk-");
00291     cloud_name << argv[vtk_file_indices.at (i)] << "-" << i;
00292     p->addModelFromPolyData (polydata, cloud_name.str (), viewport);
00293 
00294     // Change the shape rendered color
00295     if (fcolorparam && fcolor_r.size () > i && fcolor_g.size () > i && fcolor_b.size () > i)
00296       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, fcolor_r[i], fcolor_g[i], fcolor_b[i], cloud_name.str ());
00297 
00298     // Change the shape rendered point size
00299     if (psize.size () > 0)
00300       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize.at (i), cloud_name.str ());
00301 
00302     // Change the shape rendered opacity
00303     if (opaque.size () > 0)
00304       p->setShapeRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opaque.at (i), cloud_name.str ());
00305   }
00306 
00307   sensor_msgs::PointCloud2::Ptr cloud;
00308   // Go through PCD files
00309   for (size_t i = 0; i < p_file_indices.size (); ++i)
00310   {
00311     cloud.reset (new sensor_msgs::PointCloud2);
00312     Eigen::Vector4f origin;
00313     Eigen::Quaternionf orientation;
00314     int version;
00315 
00316     print_highlight (stderr, "Loading "); print_value (stderr, "%s ", argv[p_file_indices.at (i)]);
00317 
00318     tt.tic ();
00319     if (pcd.read (argv[p_file_indices.at (i)], *cloud, origin, orientation, version) < 0)
00320       return (-1);
00321 
00322     std::stringstream cloud_name;
00323 
00324     // ---[ Special check for 1-point multi-dimension histograms
00325     if (cloud->fields.size () == 1 && isMultiDimensionalFeatureField (cloud->fields[0]))
00326     {
00327       cloud_name << argv[p_file_indices.at (i)];
00328 
00329       if (!ph)
00330         ph.reset (new pcl::visualization::PCLHistogramVisualizer);
00331       print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud->fields[0].count); print_info (" points]\n");
00332 
00333       pcl::getMinMax (*cloud, 0, cloud->fields[0].name, min_p, max_p);
00334       ph->addFeatureHistogram (*cloud, cloud->fields[0].name, cloud_name.str ());
00335       continue;
00336     }
00337 
00338     cloud_name << argv[p_file_indices.at (i)] << "-" << i;
00339 
00340     // Create the PCLVisualizer object here on the first encountered XYZ file
00341     if (!p)
00342     {
00343       p.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00344       p->registerPointPickingCallback (&pp_callback, (void*)&cloud);
00345       Eigen::Matrix3f rotation;
00346       rotation = orientation;
00347       p->setCameraPose (origin [0]                  , origin [1]                  , origin [2],
00348                         origin [0] + rotation (0, 2), origin [1] + rotation (1, 2), origin [2] + rotation (2, 2),
00349                                      rotation (0, 1),              rotation (1, 1),              rotation (2, 1));
00350     }
00351 
00352     // Multiview enabled?
00353     if (mview)
00354     {
00355       p->createViewPort (k * x_step, l * y_step, (k + 1) * x_step, (l + 1) * y_step, viewport);
00356       k++;
00357       if (k >= x_s)
00358       {
00359         k = 0;
00360         l++;
00361       }
00362     }
00363 
00364     if (cloud->width * cloud->height == 0)
00365     {
00366       print_error ("[error: no points found!]\n");
00367       return (-1);
00368     }
00369     print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", (int)cloud->width * cloud->height); print_info (" points]\n");
00370     print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (*cloud).c_str ());
00371 
00372     // If no color was given, get random colors
00373     if (fcolorparam)
00374     {
00375       if (fcolor_r.size () > i && fcolor_g.size () > i && fcolor_b.size () > i)
00376         color_handler.reset (new pcl::visualization::PointCloudColorHandlerCustom<sensor_msgs::PointCloud2> (cloud, fcolor_r[i], fcolor_g[i], fcolor_b[i]));
00377       else
00378         color_handler.reset (new pcl::visualization::PointCloudColorHandlerRandom<sensor_msgs::PointCloud2> (cloud));
00379     }
00380     else
00381       color_handler.reset (new pcl::visualization::PointCloudColorHandlerRandom<sensor_msgs::PointCloud2> (cloud));
00382 
00383     // Add the dataset with a XYZ and a random handler
00384     geometry_handler.reset (new pcl::visualization::PointCloudGeometryHandlerXYZ<sensor_msgs::PointCloud2> (cloud));
00385     // Add the cloud to the renderer
00386     //p->addPointCloud<pcl::PointXYZ> (cloud_xyz, geometry_handler, color_handler, cloud_name.str (), viewport);
00387     p->addPointCloud (cloud, geometry_handler, color_handler, origin, orientation, cloud_name.str (), viewport);
00388 
00389     // If normal lines are enabled
00390     if (normals != 0)
00391     {
00392       int normal_idx = pcl::getFieldIndex (*cloud, "normal_x");
00393       if (normal_idx == -1)
00394       {
00395         print_error ("Normal information requested but not available.\n");
00396         continue;
00397         //return (-1);
00398       }
00399       //
00400       // Convert from blob to pcl::PointCloud
00401       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00402       pcl::fromROSMsg (*cloud, *cloud_xyz);
00403       cloud_xyz->sensor_origin_ = origin;
00404       cloud_xyz->sensor_orientation_ = orientation;
00405 
00406       pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00407       pcl::fromROSMsg (*cloud, *cloud_normals);
00408       std::stringstream cloud_name_normals;
00409       cloud_name_normals << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00410       p->addPointCloudNormals<pcl::PointXYZ, pcl::Normal> (cloud_xyz, cloud_normals, normals, normals_scale, cloud_name_normals.str (), viewport);
00411     }
00412 
00413     // If principal curvature lines are enabled
00414     if (pc != 0)
00415     {
00416       if (normals == 0)
00417         normals = pc;
00418 
00419       int normal_idx = pcl::getFieldIndex (*cloud, "normal_x");
00420       if (normal_idx == -1)
00421       {
00422         print_error ("Normal information requested but not available.\n");
00423         continue;
00424         //return (-1);
00425       }
00426       int pc_idx = pcl::getFieldIndex (*cloud, "principal_curvature_x");
00427       if (pc_idx == -1)
00428       {
00429         print_error ("Principal Curvature information requested but not available.\n");
00430         continue;
00431         //return (-1);
00432       }
00433       //
00434       // Convert from blob to pcl::PointCloud
00435       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00436       pcl::fromROSMsg (*cloud, *cloud_xyz);
00437       cloud_xyz->sensor_origin_ = origin;
00438       cloud_xyz->sensor_orientation_ = orientation;
00439       pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00440       pcl::fromROSMsg (*cloud, *cloud_normals);
00441       pcl::PointCloud<pcl::PrincipalCurvatures>::Ptr cloud_pc (new pcl::PointCloud<pcl::PrincipalCurvatures>);
00442       pcl::fromROSMsg (*cloud, *cloud_pc);
00443       std::stringstream cloud_name_normals_pc;
00444       cloud_name_normals_pc << argv[p_file_indices.at (i)] << "-" << i << "-normals";
00445       int factor = (std::min)(normals, pc);
00446       p->addPointCloudNormals<pcl::PointXYZ, pcl::Normal> (cloud_xyz, cloud_normals, factor, normals_scale, cloud_name_normals_pc.str (), viewport);
00447       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_COLOR, 1.0, 0.0, 0.0, cloud_name_normals_pc.str ());
00448       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00449       cloud_name_normals_pc << "-pc";
00450       p->addPointCloudPrincipalCurvatures (cloud_xyz, cloud_normals, cloud_pc, factor, pc_scale, cloud_name_normals_pc.str (), viewport);
00451       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_LINE_WIDTH, 3, cloud_name_normals_pc.str ());
00452     }
00453 
00454     // Add every dimension as a possible color
00455     if (!fcolorparam)
00456     {
00457       for (size_t f = 0; f < cloud->fields.size (); ++f)
00458       {
00459         if (cloud->fields[f].name == "rgb" || cloud->fields[f].name == "rgba")
00460           color_handler.reset (new pcl::visualization::PointCloudColorHandlerRGBField<sensor_msgs::PointCloud2> (cloud));
00461         else
00462         {
00463           if (!isValidFieldName (cloud->fields[f].name))
00464             continue;
00465           color_handler.reset (new pcl::visualization::PointCloudColorHandlerGenericField<sensor_msgs::PointCloud2> (cloud, cloud->fields[f].name));
00466         }
00467         // Add the cloud to the renderer
00468         //p->addPointCloud<pcl::PointXYZ> (cloud_xyz, color_handler, cloud_name.str (), viewport);
00469         p->addPointCloud (cloud, color_handler, origin, orientation, cloud_name.str (), viewport);
00470       }
00471     }
00472     // Additionally, add normals as a handler
00473     geometry_handler.reset (new pcl::visualization::PointCloudGeometryHandlerSurfaceNormal<sensor_msgs::PointCloud2> (cloud));
00474     if (geometry_handler->isCapable ())
00475       //p->addPointCloud<pcl::PointXYZ> (cloud_xyz, geometry_handler, cloud_name.str (), viewport);
00476       p->addPointCloud (cloud, geometry_handler, origin, orientation, cloud_name.str (), viewport);
00477 
00478     // Set immediate mode rendering ON
00479     p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_IMMEDIATE_RENDERING, 1.0, cloud_name.str ());
00480 
00481     // Change the cloud rendered point size
00482     if (psize.size () > 0)
00483       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize.at (i), cloud_name.str ());
00484 
00485     // Change the cloud rendered opacity
00486     if (opaque.size () > 0)
00487       p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opaque.at (i), cloud_name.str ());
00488 
00489     // Reset camera viewpoint to center of cloud if camera parameters were not passed manually and this is the first loaded cloud
00490     //if (i == 0 && !p->cameraParamsSet ())
00491      // p->resetCameraViewpoint (cloud_name.str ());
00492   }
00493 
00494   if (p)
00495     p->setBackgroundColor (bcolor[0], bcolor[1], bcolor[2]);
00496   // Read axes settings
00497   double axes  = 0.0;
00498   pcl::console::parse_argument (argc, argv, "-ax", axes);
00499   if (axes != 0.0 && p)
00500   {
00501     double ax_x = 0.0, ax_y = 0.0, ax_z = 0.0;
00502     pcl::console::parse_3x_arguments (argc, argv, "-ax_pos", ax_x, ax_y, ax_z, false);
00503     // Draw XYZ axes if command-line enabled
00504     p->addCoordinateSystem (axes, ax_x, ax_y, ax_z);
00505   }
00506 
00507   // Clean up the memory used by the binary blob
00508   // Note: avoid resetting the cloud, otherwise the PointPicking callback will fail
00509   //cloud.reset ();
00510 
00511   if (ph)
00512   {
00513     print_highlight ("Setting the global Y range for all histograms to: "); print_value ("%f -> %f\n", min_p, max_p);
00514     ph->setGlobalYRange (min_p, max_p);
00515     ph->updateWindowPositions ();
00516     if (p)
00517       p->spin ();
00518     else
00519       ph->spin ();
00520   }
00521   else if (p)
00522     p->spin ();
00523 }
00524 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:25