openni_uniform_sampling.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 <pcl/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 #include <pcl/io/openni_grabber.h>
00039 #include <pcl/visualization/cloud_viewer.h>
00040 #include <pcl/io/openni_camera/openni_driver.h>
00041 #include <pcl/keypoints/uniform_sampling.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/common/time.h>
00044 
00045 #define FPS_CALC(_WHAT_) \
00046 do \
00047 { \
00048     static unsigned count = 0;\
00049     static double last = pcl::getTime ();\
00050     double now = pcl::getTime (); \
00051     ++count; \
00052     if (now - last >= 1.0) \
00053     { \
00054       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00055       count = 0; \
00056       last = now; \
00057     } \
00058 }while(false)
00059 
00060 
00061 class OpenNIUniformSampling
00062 {
00063   public:
00064     typedef pcl::PointCloud<pcl::PointXYZRGBA> Cloud;
00065     typedef Cloud::Ptr CloudPtr;
00066     typedef Cloud::ConstPtr CloudConstPtr;
00067 
00068     OpenNIUniformSampling (const std::string& device_id = "", 
00069                        float leaf_size = 0.05)
00070     : viewer ("PCL OpenNI PassThrough Viewer")
00071     , device_id_(device_id)
00072     {
00073       pass_.setRadiusSearch (leaf_size);
00074     }
00075 
00076     void 
00077     cloud_cb_ (const CloudConstPtr& cloud)
00078     {
00079       boost::mutex::scoped_lock lock (mtx_);
00080       FPS_CALC ("computation");
00081 
00082       cloud_.reset (new Cloud);
00083       indices_.reset (new pcl::PointCloud<int>);
00084       keypoints_.reset (new pcl::PointCloud<pcl::PointXYZ>);
00085       // Computation goes here
00086       pass_.setInputCloud (cloud);
00087       pass_.compute (*indices_);
00088       *cloud_  = *cloud;
00089       
00090       pcl::copyPointCloud<pcl::PointXYZRGBA, pcl::PointXYZ> (*cloud, indices_->points, *keypoints_);
00091     }
00092 
00093     void
00094     viz_cb (pcl::visualization::PCLVisualizer& viz)
00095     {
00096       boost::mutex::scoped_lock lock (mtx_);
00097       if (!keypoints_ && !cloud_)
00098       {
00099         boost::this_thread::sleep(boost::posix_time::seconds(1));
00100         return;
00101       }
00102 
00103       FPS_CALC ("visualization");
00104       viz.removePointCloud ("raw");
00105       pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGBA> color_handler (cloud_);
00106       viz.addPointCloud<pcl::PointXYZRGBA> (cloud_, color_handler, "raw");
00107 
00108       if (!viz.updatePointCloud<pcl::PointXYZ> (keypoints_, "keypoints"))
00109       {
00110         viz.addPointCloud<pcl::PointXYZ> (keypoints_, "keypoints");
00111         viz.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 5.0, "keypoints");
00112         viz.resetCameraViewpoint ("keypoints");
00113       }
00114     }
00115 
00116     void
00117     run ()
00118     {
00119       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00120 
00121       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIUniformSampling::cloud_cb_, this, _1);
00122       boost::signals2::connection c = interface->registerCallback (f);
00123       viewer.runOnVisualizationThread (boost::bind(&OpenNIUniformSampling::viz_cb, this, _1), "viz_cb");
00124       
00125       interface->start ();
00126       
00127       while (!viewer.wasStopped ())
00128       {
00129         boost::this_thread::sleep(boost::posix_time::seconds(1));
00130       }
00131 
00132       interface->stop ();
00133     }
00134 
00135     pcl::UniformSampling<pcl::PointXYZRGBA> pass_;
00136     pcl::visualization::CloudViewer viewer;
00137     std::string device_id_;
00138     boost::mutex mtx_;
00139     CloudPtr cloud_;
00140     pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints_;
00141     pcl::PointCloud<int>::Ptr indices_;
00142 };
00143 
00144 void
00145 usage (char ** argv)
00146 {
00147   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00148             << "where options are:\n"
00149             << "                             -leaf X  :: set the UniformSampling leaf size (default: 0.01)\n";
00150 
00151   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00152   if (driver.getNumberDevices () > 0)
00153   {
00154     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00155     {
00156       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00157               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00158       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00159            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00160            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00161     }
00162   }
00163   else
00164     cout << "No devices connected." << endl;
00165 }
00166 
00167 int 
00168 main (int argc, char ** argv)
00169 {
00170   if (argc < 2)
00171   {
00172     usage (argv);
00173     return 1;
00174   }
00175 
00176   std::string arg (argv[1]);
00177   
00178   if (arg == "--help" || arg == "-h")
00179   {
00180     usage (argv);
00181     return 1;
00182   }
00183 
00184   float leaf_res = 0.05f;
00185   pcl::console::parse_argument (argc, argv, "-leaf", leaf_res);
00186   PCL_INFO ("Using %f as a leaf size for UniformSampling.\n", leaf_res);
00187 
00188   pcl::OpenNIGrabber grabber (arg);
00189   OpenNIUniformSampling v (arg, leaf_res);
00190   v.run ();
00191 
00192   return (0);
00193 }


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