openni_voxel_grid.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/visualization/cloud_viewer.h>
00042 #include <pcl/io/openni_camera/openni_driver.h>
00043 #include <pcl/filters/approximate_voxel_grid.h>
00044 #include <pcl/filters/voxel_grid.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/common/time.h>
00047 
00048 #define FPS_CALC(_WHAT_) \
00049 do \
00050 { \
00051     static unsigned count = 0;\
00052     static double last = pcl::getTime ();\
00053     double now = pcl::getTime (); \
00054     ++count; \
00055     if (now - last >= 1.0) \
00056     { \
00057       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00058       count = 0; \
00059       last = now; \
00060     } \
00061 }while(false)
00062 
00063 
00064 template <typename PointType>
00065 class OpenNIVoxelGrid
00066 {
00067   public:
00068     typedef pcl::PointCloud<PointType> Cloud;
00069     typedef typename Cloud::Ptr CloudPtr;
00070     typedef typename Cloud::ConstPtr CloudConstPtr;
00071 
00072     OpenNIVoxelGrid (const std::string& device_id = "", 
00073                      const std::string& = "z", float = 0, float = 5.0,
00074                      float leaf_size_x = 0.01, float leaf_size_y = 0.01, float leaf_size_z = 0.01)
00075     : viewer ("PCL OpenNI VoxelGrid Viewer")
00076     , device_id_(device_id)
00077     {
00078       grid_.setLeafSize (leaf_size_x, leaf_size_y, leaf_size_z);
00079       //grid_.setFilterFieldName (field_name);
00080       //grid_.setFilterLimits (min_v, max_v);
00081     }
00082     
00083     void 
00084     cloud_cb_ (const CloudConstPtr& cloud)
00085     {
00086       set (cloud);
00087     }
00088 
00089     void
00090     set (const CloudConstPtr& cloud)
00091     {
00092       //lock while we set our cloud;
00093       boost::mutex::scoped_lock lock (mtx_);
00094       cloud_  = cloud;
00095     }
00096 
00097     CloudPtr
00098     get ()
00099     {
00100       //lock while we swap our cloud and reset it.
00101       boost::mutex::scoped_lock lock (mtx_);
00102       CloudPtr temp_cloud (new Cloud);
00103      
00104       grid_.setInputCloud (cloud_);
00105       grid_.filter (*temp_cloud);
00106 
00107       return (temp_cloud);
00108     }
00109 
00110     void
00111     run ()
00112     {
00113       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00114 
00115       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIVoxelGrid::cloud_cb_, this, _1);
00116       boost::signals2::connection c = interface->registerCallback (f);
00117       
00118       interface->start ();
00119       
00120       while (!viewer.wasStopped ())
00121       {
00122         if (cloud_)
00123         {
00124           FPS_CALC ("drawing");
00125           //the call to get() sets the cloud_ to null;
00126           viewer.showCloud (get ());
00127         }
00128       }
00129 
00130       interface->stop ();
00131     }
00132 
00133     pcl::VoxelGrid<PointType> grid_;
00134     pcl::visualization::CloudViewer viewer;
00135     std::string device_id_;
00136     boost::mutex mtx_;
00137     CloudConstPtr cloud_;
00138 };
00139 
00140 void
00141 usage (char ** argv)
00142 {
00143   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00144             << "where options are:\n         -minmax min-max  :: set the ApproximateVoxelGrid min-max cutting values (default: 0-5.0)\n"
00145             <<                     "         -field  X        :: use field/dimension 'X' to filter data on (default: 'z')\n"
00146 
00147             << "                             -leaf x, y, z  :: set the ApproximateVoxelGrid leaf size (default: 0.01)\n";
00148 
00149   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00150   if (driver.getNumberDevices () > 0)
00151   {
00152     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00153     {
00154       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00155               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00156       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00157            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00158            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00159     }
00160   }
00161   else
00162     cout << "No devices connected." << endl;
00163 }
00164 
00165 int 
00166 main (int argc, char ** argv)
00167 {
00168   if (pcl::console::find_argument (argc, argv, "-h") != -1)
00169     usage (argv);
00170 
00171   float min_v = 0.0f, max_v = 5.0f;
00172   pcl::console::parse_2x_arguments (argc, argv, "-minmax", min_v, max_v, false);
00173   std::string field_name ("z");
00174   pcl::console::parse_argument (argc, argv, "-field", field_name);
00175   PCL_INFO ("Filtering data on %s between %f -> %f.\n", field_name.c_str (), min_v, max_v);
00176   float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f;
00177   pcl::console::parse_3x_arguments (argc, argv, "-leaf", leaf_x, leaf_y, leaf_z, false);
00178   PCL_INFO ("Using %f, %f, %f as a leaf size for VoxelGrid.\n", leaf_x, leaf_y, leaf_z);
00179 
00180   pcl::OpenNIGrabber grabber ("");
00181   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00182   {
00183     OpenNIVoxelGrid<pcl::PointXYZRGBA> v ("", field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
00184     v.run ();
00185   }
00186   else
00187   {
00188     OpenNIVoxelGrid<pcl::PointXYZ> v ("", field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
00189     v.run ();
00190   }
00191 
00192   return (0);
00193 }


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