pcl_visualizer_demo.cpp
Go to the documentation of this file.
00001 /* \author Geoffrey Biggs */
00002 
00003 
00004 #include <iostream>
00005 
00006 #include <boost/thread/thread.hpp>
00007 #include <pcl/common/common_headers.h>
00008 #include <pcl/common/common_headers.h>
00009 #include <pcl/features/normal_3d.h>
00010 #include <pcl/io/pcd_io.h>
00011 #include <pcl/visualization/pcl_visualizer.h>
00012 #include <pcl/console/parse.h>
00013 
00014 // --------------
00015 // -----Help-----
00016 // --------------
00017 void
00018 printUsage (const char* progName)
00019 {
00020   std::cout << "\n\nUsage: "<<progName<<" [options]\n\n"
00021             << "Options:\n"
00022             << "-------------------------------------------\n"
00023             << "-h           this help\n"
00024             << "-s           Simple visualisation example\n"
00025             << "-r           RGB colour visualisation example\n"
00026             << "-c           Custom colour visualisation example\n"
00027             << "-n           Normals visualisation example\n"
00028             << "-a           Shapes visualisation example\n"
00029             << "-v           Viewports example\n"
00030             << "-i           Interaction Customization example\n"
00031             << "\n\n";
00032 }
00033 
00034 
00035 boost::shared_ptr<pcl::visualization::PCLVisualizer> simpleVis (pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud)
00036 {
00037   // --------------------------------------------
00038   // -----Open 3D viewer and add point cloud-----
00039   // --------------------------------------------
00040   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00041   viewer->setBackgroundColor (0, 0, 0);
00042   viewer->addPointCloud<pcl::PointXYZ> (cloud, "sample cloud");
00043   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
00044   viewer->addCoordinateSystem (1.0);
00045   viewer->initCameraParameters ();
00046   return (viewer);
00047 }
00048 
00049 
00050 boost::shared_ptr<pcl::visualization::PCLVisualizer> rgbVis (pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud)
00051 {
00052   // --------------------------------------------
00053   // -----Open 3D viewer and add point cloud-----
00054   // --------------------------------------------
00055   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00056   viewer->setBackgroundColor (0, 0, 0);
00057   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(cloud);
00058   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, rgb, "sample cloud");
00059   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud");
00060   viewer->addCoordinateSystem (1.0);
00061   viewer->initCameraParameters ();
00062   return (viewer);
00063 }
00064 
00065 
00066 boost::shared_ptr<pcl::visualization::PCLVisualizer> customColourVis (pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud)
00067 {
00068   // --------------------------------------------
00069   // -----Open 3D viewer and add point cloud-----
00070   // --------------------------------------------
00071   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00072   viewer->setBackgroundColor (0, 0, 0);
00073   pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color(cloud, 0, 255, 0);
00074   viewer->addPointCloud<pcl::PointXYZ> (cloud, single_color, "sample cloud");
00075   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud");
00076   viewer->addCoordinateSystem (1.0);
00077   viewer->initCameraParameters ();
00078   return (viewer);
00079 }
00080 
00081 
00082 boost::shared_ptr<pcl::visualization::PCLVisualizer> normalsVis (
00083     pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud, pcl::PointCloud<pcl::Normal>::ConstPtr normals)
00084 {
00085   // --------------------------------------------------------
00086   // -----Open 3D viewer and add point cloud and normals-----
00087   // --------------------------------------------------------
00088   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00089   viewer->setBackgroundColor (0, 0, 0);
00090   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(cloud);
00091   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, rgb, "sample cloud");
00092   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud");
00093   viewer->addPointCloudNormals<pcl::PointXYZRGB, pcl::Normal> (cloud, normals, 10, 0.05, "normals");
00094   viewer->addCoordinateSystem (1.0);
00095   viewer->initCameraParameters ();
00096   return (viewer);
00097 }
00098 
00099 
00100 boost::shared_ptr<pcl::visualization::PCLVisualizer> shapesVis (pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud)
00101 {
00102   // --------------------------------------------
00103   // -----Open 3D viewer and add point cloud-----
00104   // --------------------------------------------
00105   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00106   viewer->setBackgroundColor (0, 0, 0);
00107   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(cloud);
00108   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, rgb, "sample cloud");
00109   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud");
00110   viewer->addCoordinateSystem (1.0);
00111   viewer->initCameraParameters ();
00112 
00113   //------------------------------------
00114   //-----Add shapes at cloud points-----
00115   //------------------------------------
00116   viewer->addLine<pcl::PointXYZRGB> (cloud->points[0],
00117                                      cloud->points[cloud->size() - 1], "line");
00118   viewer->addSphere (cloud->points[0], 0.2, 0.5, 0.5, 0.0, "sphere");
00119 
00120   //---------------------------------------
00121   //-----Add shapes at other locations-----
00122   //---------------------------------------
00123   pcl::ModelCoefficients coeffs;
00124   coeffs.values.push_back (0.0);
00125   coeffs.values.push_back (0.0);
00126   coeffs.values.push_back (1.0);
00127   coeffs.values.push_back (0.0);
00128   viewer->addPlane (coeffs, "plane");
00129   coeffs.values.clear ();
00130   coeffs.values.push_back (0.3);
00131   coeffs.values.push_back (0.3);
00132   coeffs.values.push_back (0.0);
00133   coeffs.values.push_back (0.0);
00134   coeffs.values.push_back (1.0);
00135   coeffs.values.push_back (0.0);
00136   coeffs.values.push_back (5.0);
00137   viewer->addCone (coeffs, "cone");
00138 
00139   return (viewer);
00140 }
00141 
00142 
00143 boost::shared_ptr<pcl::visualization::PCLVisualizer> viewportsVis (
00144     pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr cloud, pcl::PointCloud<pcl::Normal>::ConstPtr normals1, pcl::PointCloud<pcl::Normal>::ConstPtr normals2)
00145 {
00146   // --------------------------------------------------------
00147   // -----Open 3D viewer and add point cloud and normals-----
00148   // --------------------------------------------------------
00149   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00150   viewer->initCameraParameters ();
00151 
00152   int v1(0);
00153   viewer->createViewPort(0.0, 0.0, 0.5, 1.0, v1);
00154   viewer->setBackgroundColor (0, 0, 0, v1);
00155   viewer->addText("Radius: 0.01", 10, 10, "v1 text", v1);
00156   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(cloud);
00157   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, rgb, "sample cloud1", v1);
00158 
00159   int v2(0);
00160   viewer->createViewPort(0.5, 0.0, 1.0, 1.0, v2);
00161   viewer->setBackgroundColor (0.3, 0.3, 0.3, v2);
00162   viewer->addText("Radius: 0.1", 10, 10, "v2 text", v2);
00163   pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZRGB> single_color(cloud, 0, 255, 0);
00164   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, single_color, "sample cloud2", v2);
00165 
00166   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud1");
00167   viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "sample cloud2");
00168   viewer->addCoordinateSystem (1.0);
00169 
00170   viewer->addPointCloudNormals<pcl::PointXYZRGB, pcl::Normal> (cloud, normals1, 10, 0.05, "normals1", v1);
00171   viewer->addPointCloudNormals<pcl::PointXYZRGB, pcl::Normal> (cloud, normals2, 10, 0.05, "normals2", v2);
00172 
00173   return (viewer);
00174 }
00175 
00176 
00177 unsigned int text_id = 0;
00178 void keyboardEventOccurred (const pcl::visualization::KeyboardEvent &event,
00179                             void* viewer_void)
00180 {
00181   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer = *static_cast<boost::shared_ptr<pcl::visualization::PCLVisualizer> *> (viewer_void);
00182   if (event.getKeySym () == "r" && event.keyDown ())
00183   {
00184     std::cout << "r was pressed => removing all text" << std::endl;
00185 
00186     char str[512];
00187     for (unsigned int i = 0; i < text_id; ++i)
00188     {
00189       sprintf (str, "text#%03d", i);
00190       viewer->removeShape (str);
00191     }
00192     text_id = 0;
00193   }
00194 }
00195 
00196 void mouseEventOccurred (const pcl::visualization::MouseEvent &event,
00197                          void* viewer_void)
00198 {
00199   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer = *static_cast<boost::shared_ptr<pcl::visualization::PCLVisualizer> *> (viewer_void);
00200   if (event.getButton () == pcl::visualization::MouseEvent::LeftButton &&
00201       event.getType () == pcl::visualization::MouseEvent::MouseButtonRelease)
00202   {
00203     std::cout << "Left mouse button released at position (" << event.getX () << ", " << event.getY () << ")" << std::endl;
00204 
00205     char str[512];
00206     sprintf (str, "text#%03d", text_id ++);
00207     viewer->addText ("clicked here", event.getX (), event.getY (), str);
00208   }
00209 }
00210 
00211 boost::shared_ptr<pcl::visualization::PCLVisualizer> interactionCustomizationVis ()
00212 {
00213   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
00214   viewer->setBackgroundColor (0, 0, 0);
00215   viewer->addCoordinateSystem (1.0);
00216 
00217   viewer->registerKeyboardCallback (keyboardEventOccurred, (void*)&viewer);
00218   viewer->registerMouseCallback (mouseEventOccurred, (void*)&viewer);
00219 
00220   return (viewer);
00221 }
00222 
00223 
00224 // --------------
00225 // -----Main-----
00226 // --------------
00227 int
00228 main (int argc, char** argv)
00229 {
00230   // --------------------------------------
00231   // -----Parse Command Line Arguments-----
00232   // --------------------------------------
00233   if (pcl::console::find_argument (argc, argv, "-h") >= 0)
00234   {
00235     printUsage (argv[0]);
00236     return 0;
00237   }
00238   bool simple(false), rgb(false), custom_c(false), normals(false),
00239     shapes(false), viewports(false), interaction_customization(false);
00240   if (pcl::console::find_argument (argc, argv, "-s") >= 0)
00241   {
00242     simple = true;
00243     std::cout << "Simple visualisation example\n";
00244   }
00245   else if (pcl::console::find_argument (argc, argv, "-c") >= 0)
00246   {
00247     custom_c = true;
00248     std::cout << "Custom colour visualisation example\n";
00249   }
00250   else if (pcl::console::find_argument (argc, argv, "-r") >= 0)
00251   {
00252     rgb = true;
00253     std::cout << "RGB colour visualisation example\n";
00254   }
00255   else if (pcl::console::find_argument (argc, argv, "-n") >= 0)
00256   {
00257     normals = true;
00258     std::cout << "Normals visualisation example\n";
00259   }
00260   else if (pcl::console::find_argument (argc, argv, "-a") >= 0)
00261   {
00262     shapes = true;
00263     std::cout << "Shapes visualisation example\n";
00264   }
00265   else if (pcl::console::find_argument (argc, argv, "-v") >= 0)
00266   {
00267     viewports = true;
00268     std::cout << "Viewports example\n";
00269   }
00270   else if (pcl::console::find_argument (argc, argv, "-i") >= 0)
00271   {
00272     interaction_customization = true;
00273     std::cout << "Interaction Customization example\n";
00274   }
00275   else
00276   {
00277     printUsage (argv[0]);
00278     return 0;
00279   }
00280 
00281   // ------------------------------------
00282   // -----Create example point cloud-----
00283   // ------------------------------------
00284   pcl::PointCloud<pcl::PointXYZ>::Ptr basic_cloud_ptr (new pcl::PointCloud<pcl::PointXYZ>);
00285   pcl::PointCloud<pcl::PointXYZRGB>::Ptr point_cloud_ptr (new pcl::PointCloud<pcl::PointXYZRGB>);
00286   std::cout << "Genarating example point clouds.\n\n";
00287   // We're going to make an ellipse extruded along the z-axis. The colour for
00288   // the XYZRGB cloud will gradually go from red to green to blue.
00289   uint8_t r(255), g(15), b(15);
00290   for (float z(-1.0); z <= 1.0; z += 0.05)
00291   {
00292     for (float angle(0.0); angle <= 360.0; angle += 5.0)
00293     {
00294       pcl::PointXYZ basic_point;
00295       basic_point.x = 0.5 * cosf (pcl::deg2rad(angle));
00296       basic_point.y = sinf (pcl::deg2rad(angle));
00297       basic_point.z = z;
00298       basic_cloud_ptr->points.push_back(basic_point);
00299 
00300       pcl::PointXYZRGB point;
00301       point.x = basic_point.x;
00302       point.y = basic_point.y;
00303       point.z = basic_point.z;
00304       uint32_t rgb = (static_cast<uint32_t>(r) << 16 |
00305               static_cast<uint32_t>(g) << 8 | static_cast<uint32_t>(b));
00306       point.rgb = *reinterpret_cast<float*>(&rgb);
00307       point_cloud_ptr->points.push_back (point);
00308     }
00309     if (z < 0.0)
00310     {
00311       r -= 12;
00312       g += 12;
00313     }
00314     else
00315     {
00316       g -= 12;
00317       b += 12;
00318     }
00319   }
00320   basic_cloud_ptr->width = (int) basic_cloud_ptr->points.size ();
00321   basic_cloud_ptr->height = 1;
00322   point_cloud_ptr->width = (int) point_cloud_ptr->points.size ();
00323   point_cloud_ptr->height = 1;
00324 
00325   // ----------------------------------------------------------------
00326   // -----Calculate surface normals with a search radius of 0.05-----
00327   // ----------------------------------------------------------------
00328   pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
00329   ne.setInputCloud (point_cloud_ptr);
00330   pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB> ());
00331   ne.setSearchMethod (tree);
00332   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals1 (new pcl::PointCloud<pcl::Normal>);
00333   ne.setRadiusSearch (0.05);
00334   ne.compute (*cloud_normals1);
00335 
00336   // ---------------------------------------------------------------
00337   // -----Calculate surface normals with a search radius of 0.1-----
00338   // ---------------------------------------------------------------
00339   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals2 (new pcl::PointCloud<pcl::Normal>);
00340   ne.setRadiusSearch (0.1);
00341   ne.compute (*cloud_normals2);
00342 
00343   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer;
00344   if (simple)
00345   {
00346     viewer = simpleVis(basic_cloud_ptr);
00347   }
00348   else if (rgb)
00349   {
00350     viewer = rgbVis(point_cloud_ptr);
00351   }
00352   else if (custom_c)
00353   {
00354     viewer = customColourVis(basic_cloud_ptr);
00355   }
00356   else if (normals)
00357   {
00358     viewer = normalsVis(point_cloud_ptr, cloud_normals2);
00359   }
00360   else if (shapes)
00361   {
00362     viewer = shapesVis(point_cloud_ptr);
00363   }
00364   else if (viewports)
00365   {
00366     viewer = viewportsVis(point_cloud_ptr, cloud_normals1, cloud_normals2);
00367   }
00368   else if (interaction_customization)
00369   {
00370     viewer = interactionCustomizationVis();
00371   }
00372 
00373   //--------------------
00374   // -----Main loop-----
00375   //--------------------
00376   while (!viewer->wasStopped ())
00377   {
00378     viewer->spinOnce (100);
00379     boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00380   }
00381 }


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