openni_3d_concave_hull.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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  */
00035 
00036 #include <boost/thread/thread.hpp>
00037 #include <boost/date_time/posix_time/posix_time.hpp>
00038 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/io/openni_camera/openni_driver.h>
00043 #include <pcl/filters/voxel_grid.h>
00044 #include <pcl/surface/concave_hull.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/common/time.h>
00047 #include <pcl/visualization/cloud_viewer.h>
00048 
00049 using namespace pcl;
00050 using namespace pcl::visualization;
00051 using namespace std;
00052 
00053 #define FPS_CALC(_WHAT_) \
00054 do \
00055 { \
00056     static unsigned count = 0;\
00057     static double last = pcl::getTime ();\
00058     if (++count == 100) \
00059     { \
00060       double now = pcl::getTime (); \
00061       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00062       count = 0; \
00063       last = now; \
00064     } \
00065 }while(false)
00066 
00067 template <typename PointType>
00068 class OpenNI3DConcaveHull
00069 {
00070   public:
00071     typedef pcl::PointCloud<PointType> Cloud;
00072     typedef typename Cloud::Ptr CloudPtr;
00073     typedef typename Cloud::ConstPtr CloudConstPtr;
00074 
00075     OpenNI3DConcaveHull (const std::string& device_id = "")
00076       : viewer ("PCL OpenNI 3D Concave Hull Viewer") 
00077     , device_id_(device_id)
00078     {
00079       grid.setFilterFieldName ("z");
00080       grid.setFilterLimits (0.0, 1.0);
00081       grid.setLeafSize (0.01f, 0.01f, 0.01f);
00082     }
00083     
00084     void 
00085     cloud_cb (const CloudConstPtr& cloud)
00086     {
00087       boost::mutex::scoped_lock lock (mtx_);
00088       FPS_CALC ("computation");
00089 
00090       cloud_pass_.reset (new Cloud);
00091       // Computation goes here
00092       grid.setInputCloud (cloud);
00093       grid.filter (*cloud_pass_);
00094 
00095       // Estimate 3D convex hull
00096       pcl::ConcaveHull<PointType> hr;
00097       hr.setAlpha (0.1);
00098       hr.setInputCloud (cloud_pass_);
00099       cloud_hull_.reset (new Cloud);
00100       hr.reconstruct (*cloud_hull_, vertices_);
00101 
00102       cloud_ = cloud;
00103       new_cloud_ = true;
00104     }
00105 
00106     void
00107     viz_cb (pcl::visualization::PCLVisualizer& viz)
00108     {
00109       if (!cloud_ || !new_cloud_)
00110       {
00111         boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00112         return;
00113       }
00114 
00115       {
00116         boost::mutex::scoped_lock lock (mtx_);
00117         FPS_CALC ("visualization");
00118         CloudPtr temp_cloud;
00119         temp_cloud.swap (cloud_pass_);
00120 
00121         if (!viz.updatePointCloud (temp_cloud, "OpenNICloud"))
00122         {
00123           viz.addPointCloud (temp_cloud, "OpenNICloud");
00124           viz.resetCameraViewpoint ("OpenNICloud");
00125         }
00126         // Render the data 
00127         if (new_cloud_ && cloud_hull_)
00128         {
00129           viz.removePointCloud ("hull");
00130           viz.addPolygonMesh<PointType> (cloud_hull_, vertices_, "hull");
00131         }
00132         new_cloud_ = false;
00133       }
00134     }
00135 
00136     void
00137     run ()
00138     {
00139       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00140 
00141       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNI3DConcaveHull::cloud_cb, this, _1);
00142       boost::signals2::connection c = interface->registerCallback (f);
00143      
00144       viewer.runOnVisualizationThread (boost::bind(&OpenNI3DConcaveHull::viz_cb, this, _1), "viz_cb");
00145 
00146       interface->start ();
00147       
00148       while (!viewer.wasStopped ())
00149       {
00150         boost::this_thread::sleep(boost::posix_time::milliseconds(1));
00151       }
00152 
00153       interface->stop ();
00154     }
00155 
00156     pcl::VoxelGrid<PointType> grid;
00157     pcl::visualization::CloudViewer viewer;
00158 
00159     std::string device_id_;
00160     boost::mutex mtx_;
00161     // Data
00162     CloudConstPtr cloud_;
00163     CloudPtr cloud_pass_, cloud_hull_;
00164     std::vector<pcl::Vertices> vertices_;
00165     bool new_cloud_;
00166 };
00167 
00168 void
00169 usage (char ** argv)
00170 {
00171   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00172 
00173   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00174   if (driver.getNumberDevices () > 0)
00175   {
00176     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00177     {
00178       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00179               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00180       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00181            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00182            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00183     }
00184   }
00185   else
00186     cout << "No devices connected." << endl;
00187 }
00188 
00189 int
00190 main (int argc, char ** argv)
00191 {
00192   std::string arg;
00193   if (argc > 1)
00194     arg = std::string (argv[1]);
00195   
00196   if (arg == "--help" || arg == "-h")
00197   {
00198     usage (argv);
00199     return 1;
00200   }
00201 
00202   pcl::OpenNIGrabber grabber ("");
00203   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00204   {
00205     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00206     OpenNI3DConcaveHull<pcl::PointXYZRGBA> v ("");
00207     v.run ();
00208   }
00209   else
00210   {
00211     PCL_INFO ("PointXYZ mode enabled.\n");
00212     OpenNI3DConcaveHull<pcl::PointXYZ> v ("");
00213     v.run ();
00214   }
00215   return (0);
00216 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:58