oni_viewer_simple.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  * Author: Nico Blodow (blodow@cs.tum.edu)
00035  *         Radu Bogdan Rusu (rusu@willowgarage.com)
00036  *         Suat Gedikli (gedikli@willowgarage.com)
00037  *         Ethan Rublee (rublee@willowgarage.com)
00038  */
00039 
00040 #include <pcl/point_cloud.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/common/time.h> //fps calculations
00043 #include <pcl/console/parse.h>
00044 #include <pcl/io/oni_grabber.h>
00045 #include <pcl/visualization/boost.h>
00046 #include <pcl/visualization/cloud_viewer.h>
00047 #include <vector>
00048 #include <pcl/common/time_trigger.h>
00049 
00050 #define SHOW_FPS 1
00051 #if SHOW_FPS
00052 #define FPS_CALC(_WHAT_) \
00053 do \
00054 { \
00055     static unsigned count = 0;\
00056     static double last = pcl::getTime ();\
00057     ++count; \
00058     if (pcl::getTime() - last >= 1.0) \
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 #else
00067 #define FPS_CALC(_WHAT_) \
00068 do \
00069 { \
00070 }while(false)
00071 #endif
00072 
00073 template <typename PointType>
00074 class SimpleONIViewer
00075 {
00076 public:
00077   typedef pcl::PointCloud<PointType> Cloud;
00078   typedef typename Cloud::ConstPtr CloudConstPtr;
00079 
00080   SimpleONIViewer(pcl::ONIGrabber& grabber)
00081     : viewer("PCL OpenNI Viewer")
00082     , grabber_(grabber)
00083     , mtx_ ()
00084     , cloud_ ()
00085   {
00086   }
00087 
00092   void
00093   cloud_cb_ (const CloudConstPtr& cloud)
00094   {
00095     FPS_CALC ("callback");
00096     boost::mutex::scoped_lock lock (mtx_);
00097     cloud_ = cloud;
00098   }
00099 
00104   CloudConstPtr
00105   getLatestCloud ()
00106   {
00107     //lock while we swap our cloud and reset it.
00108     boost::mutex::scoped_lock lock(mtx_);
00109     CloudConstPtr temp_cloud;
00110     temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00111     //it is safe to set it again from our
00112     //callback
00113     return (temp_cloud);
00114   }
00115 
00119   void
00120   run()
00121   {
00122     //pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id_, pcl::OpenNIGrabber::OpenNI_QQVGA_30Hz, pcl::OpenNIGrabber::OpenNI_VGA_30Hz);
00123 
00124     boost::function<void (const CloudConstPtr&) > f = boost::bind (&SimpleONIViewer::cloud_cb_, this, _1);
00125 
00126     boost::signals2::connection c = grabber_.registerCallback (f);
00127 
00128     grabber_.start();
00129 
00130     while (!viewer.wasStopped ())
00131     {
00132       if (cloud_)
00133       {
00134         FPS_CALC ("drawing");
00135         //the call to get() sets the cloud_ to null;
00136         viewer.showCloud (getLatestCloud ());
00137       }
00138     }
00139 
00140     grabber_.stop();
00141   }
00142 
00143   pcl::visualization::CloudViewer viewer;
00144   pcl::ONIGrabber& grabber_;
00145   boost::mutex mtx_;
00146   CloudConstPtr cloud_;
00147 };
00148 
00149 void
00150 usage(char ** argv)
00151 {
00152   cout << "usage: " << argv[0] << " <path-to-oni-file> [framerate]\n";
00153   cout << argv[0] << " -h | --help : shows this help\n";
00154   cout << argv[0] << " -xyz        : enable just XYZ data display\n";
00155   return;
00156 }
00157 
00158 int
00159 main(int argc, char ** argv)
00160 {
00161   std::string arg("");
00162 
00163   unsigned frame_rate = 0;
00164   if (argc >= 2)
00165   {
00166     arg = argv[1];
00167 
00168     if (arg == "--help" || arg == "-h")
00169     {
00170       usage(argv);
00171       return 1;
00172     }
00173     
00174     if (argc >= 3)
00175     {
00176       frame_rate = atoi(argv[2]);
00177     }
00178   }
00179   else
00180   {
00181     usage (argv);
00182     return 1;
00183   }
00184 
00185   pcl::TimeTrigger trigger;
00186   
00187   pcl::ONIGrabber* grabber = 0;
00188   if (frame_rate == 0)
00189     grabber = new  pcl::ONIGrabber(arg, true, true);
00190   else
00191   {
00192     grabber = new  pcl::ONIGrabber(arg, true, false);
00193     trigger.setInterval (1.0 / static_cast<double> (frame_rate));
00194     trigger.registerCallback (boost::bind(&pcl::ONIGrabber::start, grabber));
00195     trigger.start();
00196   }
00197   if (grabber->providesCallback<pcl::ONIGrabber::sig_cb_openni_point_cloud_rgb > () && !pcl::console::find_switch (argc, argv, "-xyz"))
00198   {
00199     SimpleONIViewer<pcl::PointXYZRGBA> v(*grabber);
00200     v.run();
00201   }
00202   else
00203   {
00204     SimpleONIViewer<pcl::PointXYZ> v(*grabber);
00205     v.run();
00206   }
00207 
00208   return (0);
00209 }


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