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


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