openni_viewer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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  * $Id$
00035  *
00036  */
00037 
00038 #define MEASURE_FUNCTION_TIME
00039 #include <pcl/common/time.h> //fps calculations
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/visualization/pcl_visualizer.h>
00042 #include <pcl/visualization/boost.h>
00043 #include <pcl/visualization/image_viewer.h>
00044 #include <pcl/console/print.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/console/time.h>
00047 
00048 #define SHOW_FPS 1
00049 #if SHOW_FPS
00050 #define FPS_CALC(_WHAT_) \
00051 do \
00052 { \
00053     static unsigned count = 0;\
00054     static double last = pcl::getTime ();\
00055     double now = pcl::getTime (); \
00056     ++count; \
00057     if (now - last >= 1.0) \
00058     { \
00059       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00060       count = 0; \
00061       last = now; \
00062     } \
00063 }while(false)
00064 #else
00065 #define FPS_CALC(_WHAT_) \
00066 do \
00067 { \
00068 }while(false)
00069 #endif
00070 
00071 void
00072 printHelp (int, char **argv)
00073 {
00074   using pcl::console::print_error;
00075   using pcl::console::print_info;
00076 
00077   print_error ("Syntax is: %s [((<device_id> | <path-to-oni-file>) [-depthmode <mode>] [-imagemode <mode>] [-xyz] | -l [<device_id>]| -h | --help)]\n", argv [0]);
00078   print_info ("%s -h | --help : shows this help\n", argv [0]);
00079   print_info ("%s -xyz : use only XYZ values and ignore RGB components (this flag is required for use with ASUS Xtion Pro) \n", argv [0]);
00080   print_info ("%s -l : list all available devices\n", argv [0]);
00081   print_info ("%s -l <device-id> :list all available modes for specified device\n", argv [0]);
00082   print_info ("\t\t<device_id> may be \"#1\", \"#2\", ... for the first, second etc device in the list\n");
00083 #ifndef _WIN32
00084   print_info ("\t\t                   bus@address for the device connected to a specific usb-bus / address combination\n");
00085   print_info ("\t\t                   <serial-number>\n");
00086 #endif
00087   print_info ("\n\nexamples:\n");
00088   print_info ("%s \"#1\"\n", argv [0]);
00089   print_info ("\t\t uses the first device.\n");
00090   print_info ("%s  \"./temp/test.oni\"\n", argv [0]);
00091   print_info ("\t\t uses the oni-player device to play back oni file given by path.\n");
00092   print_info ("%s -l\n", argv [0]);
00093   print_info ("\t\t list all available devices.\n");
00094   print_info ("%s -l \"#2\"\n", argv [0]);
00095   print_info ("\t\t list all available modes for the second device.\n");
00096   #ifndef _WIN32
00097   print_info ("%s A00361800903049A\n", argv [0]);
00098   print_info ("\t\t uses the device with the serial number \'A00361800903049A\'.\n");
00099   print_info ("%s 1@16\n", argv [0]);
00100   print_info ("\t\t uses the device on address 16 at USB bus 1.\n");
00101   #endif
00102 }
00103 
00105 template <typename PointType>
00106 class OpenNIViewer
00107 {
00108   public:
00109     typedef pcl::PointCloud<PointType> Cloud;
00110     typedef typename Cloud::ConstPtr CloudConstPtr;
00111 
00112     OpenNIViewer (pcl::Grabber& grabber)
00113       : cloud_viewer_ (new pcl::visualization::PCLVisualizer ("PCL OpenNI cloud"))
00114       , image_viewer_ ()
00115       , grabber_ (grabber)
00116       , rgb_data_ (0), rgb_data_size_ (0)
00117     {
00118     }
00119 
00120     void
00121     cloud_callback (const CloudConstPtr& cloud)
00122     {
00123       FPS_CALC ("cloud callback");
00124       boost::mutex::scoped_lock lock (cloud_mutex_);
00125       cloud_ = cloud;
00126     }
00127 
00128     void
00129     image_callback (const boost::shared_ptr<openni_wrapper::Image>& image)
00130     {
00131       FPS_CALC ("image callback");
00132       boost::mutex::scoped_lock lock (image_mutex_);
00133       image_ = image;
00134       
00135       if (image->getEncoding () != openni_wrapper::Image::RGB)
00136       {
00137         if (rgb_data_size_ < image->getWidth () * image->getHeight ())
00138         {
00139           if (rgb_data_)
00140             delete [] rgb_data_;
00141           rgb_data_size_ = image->getWidth () * image->getHeight ();
00142           rgb_data_ = new unsigned char [rgb_data_size_ * 3];
00143         }
00144         image_->fillRGB (image_->getWidth (), image_->getHeight (), rgb_data_);
00145       }
00146     }
00147     
00148     void 
00149     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00150     {
00151       if (event.getKeyCode ())
00152         cout << "the key \'" << event.getKeyCode() << "\' (" << event.getKeyCode() << ") was";
00153       else
00154         cout << "the special key \'" << event.getKeySym() << "\' was";
00155       if (event.keyDown())
00156         cout << " pressed" << endl;
00157       else
00158         cout << " released" << endl;
00159     }
00160     
00161     void 
00162     mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void*)
00163     {
00164       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00165       {
00166         cout << "left button pressed @ " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
00167       }
00168     }
00169 
00173     void
00174     run ()
00175     {
00176       cloud_viewer_->registerMouseCallback (&OpenNIViewer::mouse_callback, *this);
00177       cloud_viewer_->registerKeyboardCallback(&OpenNIViewer::keyboard_callback, *this);
00178       boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&OpenNIViewer::cloud_callback, this, _1);
00179       boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb);
00180       
00181       boost::signals2::connection image_connection;
00182       if (grabber_.providesCallback<void (const boost::shared_ptr<openni_wrapper::Image>&)>())
00183       {
00184         image_viewer_.reset (new pcl::visualization::ImageViewer ("PCL OpenNI image"));
00185         image_viewer_->registerMouseCallback (&OpenNIViewer::mouse_callback, *this);
00186         image_viewer_->registerKeyboardCallback(&OpenNIViewer::keyboard_callback, *this);
00187         boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&) > image_cb = boost::bind (&OpenNIViewer::image_callback, this, _1);
00188         image_connection = grabber_.registerCallback (image_cb);
00189       }
00190       
00191       bool image_init = false, cloud_init = false;
00192       
00193       grabber_.start ();
00194 
00195       while (!cloud_viewer_->wasStopped () && (image_viewer_ && !image_viewer_->wasStopped ()))
00196       {
00197         boost::shared_ptr<openni_wrapper::Image> image;
00198         CloudConstPtr cloud;
00199 
00200         cloud_viewer_->spinOnce ();
00201 
00202         // See if we can get a cloud
00203         if (cloud_mutex_.try_lock ())
00204         {
00205           cloud_.swap (cloud);
00206           cloud_mutex_.unlock ();
00207         }
00208 
00209         if (cloud)
00210         {
00211           FPS_CALC ("drawing cloud");
00212           
00213           if (!cloud_init)
00214           {
00215             cloud_viewer_->setPosition (0, 0);
00216             cloud_viewer_->setSize (cloud->width, cloud->height);
00217             cloud_init = !cloud_init;
00218           }
00219 
00220           if (!cloud_viewer_->updatePointCloud (cloud, "OpenNICloud"))
00221           {
00222             cloud_viewer_->addPointCloud (cloud, "OpenNICloud");
00223             cloud_viewer_->resetCameraViewpoint ("OpenNICloud");
00224           }          
00225         }
00226 
00227         // See if we can get an image
00228         if (image_mutex_.try_lock ())
00229         {
00230           image_.swap (image);
00231           image_mutex_.unlock ();
00232         }
00233 
00234         if (image)
00235         {
00236           if (!image_init && cloud && cloud->width != 0)
00237           {
00238             image_viewer_->setPosition (cloud->width, 0);
00239             image_viewer_->setSize (cloud->width, cloud->height);
00240             image_init = !image_init;
00241           }
00242 
00243           if (image->getEncoding() == openni_wrapper::Image::RGB)
00244             image_viewer_->addRGBImage (image->getMetaData ().Data (), image->getWidth (), image->getHeight ());
00245           else
00246             image_viewer_->addRGBImage (rgb_data_, image->getWidth (), image->getHeight ());
00247           image_viewer_->spinOnce ();
00248         }
00249         
00250       }
00251 
00252       grabber_.stop ();
00253       
00254       cloud_connection.disconnect ();
00255       image_connection.disconnect ();
00256       if (rgb_data_)
00257         delete[] rgb_data_;
00258     }
00259     
00260     boost::shared_ptr<pcl::visualization::PCLVisualizer> cloud_viewer_;
00261     boost::shared_ptr<pcl::visualization::ImageViewer> image_viewer_;
00262     
00263     pcl::Grabber& grabber_;
00264     boost::mutex cloud_mutex_;
00265     boost::mutex image_mutex_;
00266     
00267     CloudConstPtr cloud_;
00268     boost::shared_ptr<openni_wrapper::Image> image_;
00269     unsigned char* rgb_data_;
00270     unsigned rgb_data_size_;
00271 };
00272 
00273 // Create the PCLVisualizer object
00274 boost::shared_ptr<pcl::visualization::PCLVisualizer> cld;
00275 boost::shared_ptr<pcl::visualization::ImageViewer> img;
00276 
00277 /* ---[ */
00278 int
00279 main (int argc, char** argv)
00280 {
00281   std::string device_id("");
00282   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00283   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00284   bool xyz = false;
00285   
00286   if (argc >= 2)
00287   {
00288     device_id = argv[1];
00289     if (device_id == "--help" || device_id == "-h")
00290     {
00291       printHelp(argc, argv);
00292       return 0;
00293     }
00294     else if (device_id == "-l")
00295     {
00296       if (argc >= 3)
00297       {
00298         pcl::OpenNIGrabber grabber(argv[2]);
00299         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice();
00300         cout << "Supported depth modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00301         std::vector<std::pair<int, XnMapOutputMode > > modes = grabber.getAvailableDepthModes();
00302         for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00303         {
00304           cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00305         }
00306 
00307         if (device->hasImageStream ())
00308         {
00309           cout << endl << "Supported image modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00310           modes = grabber.getAvailableImageModes();
00311           for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00312           {
00313             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00314           }
00315         }
00316       }
00317       else
00318       {
00319         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00320         if (driver.getNumberDevices() > 0)
00321         {
00322           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx)
00323           {
00324             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName(deviceIdx) << ", product: " << driver.getProductName(deviceIdx)
00325               << ", connected: " << driver.getBus(deviceIdx) << " @ " << driver.getAddress(deviceIdx) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << endl;
00326           }
00327 
00328         }
00329         else
00330           cout << "No devices connected." << endl;
00331         
00332         cout <<"Virtual Devices available: ONI player" << endl;
00333       }
00334       return 0;
00335     }
00336   }
00337   else
00338   {
00339     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00340     if (driver.getNumberDevices() > 0)
00341       cout << "Device Id not set, using first device." << endl;
00342   }
00343   
00344   unsigned mode;
00345   if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
00346     depth_mode = pcl::OpenNIGrabber::Mode (mode);
00347 
00348   if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
00349     image_mode = pcl::OpenNIGrabber::Mode (mode);
00350   
00351   if (pcl::console::find_argument (argc, argv, "-xyz") != -1)
00352     xyz = true;
00353   
00354   pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode);
00355   
00356   if (xyz || !grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb> ())
00357   {
00358     OpenNIViewer<pcl::PointXYZ> openni_viewer (grabber);
00359     openni_viewer.run ();
00360   }
00361   else
00362   {
00363     OpenNIViewer<pcl::PointXYZRGBA> openni_viewer (grabber);
00364     openni_viewer.run ();
00365   }
00366   
00367   return (0);
00368 }
00369 /* ]--- */


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