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