openni_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/io/openni_grabber.h>
00044 #include <pcl/visualization/cloud_viewer.h>
00045 #include <pcl/visualization/image_viewer.h>
00046 #include <pcl/io/openni_camera/openni_driver.h>
00047 #include <pcl/console/parse.h>
00048 #include <pcl/visualization/boost.h>
00049 #include <pcl/visualization/mouse_event.h>
00050 #include <vtkImageViewer.h>
00051 #include <vtkImageImport.h>
00052 #include <vector>
00053 #include <string>
00054 
00055 using namespace std;
00056 
00057 #define SHOW_FPS 1
00058 #if SHOW_FPS
00059 #define FPS_CALC(_WHAT_) \
00060 do \
00061 { \
00062     static unsigned count = 0;\
00063     static double last = pcl::getTime ();\
00064     double now = pcl::getTime (); \
00065     ++count; \
00066     if (now - last >= 1.0) \
00067     { \
00068       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00069       count = 0; \
00070       last = now; \
00071     } \
00072 }while(false)
00073 #else
00074 #define FPS_CALC(_WHAT_) \
00075 do \
00076 { \
00077 }while(false)
00078 #endif
00079 
00081 template <typename PointType>
00082 class SimpleOpenNIViewer
00083 {
00084   public:
00085     typedef pcl::PointCloud<PointType> Cloud;
00086     typedef typename Cloud::ConstPtr CloudConstPtr;
00087 
00088     SimpleOpenNIViewer (pcl::OpenNIGrabber& grabber)
00089       : cloud_viewer_ ("PCL OpenNI Viewer")
00090       , grabber_ (grabber)
00091 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00092       , image_viewer_ ("PCL image viewer")
00093 #endif
00094     {
00095     }
00096 
00097     void
00098     cloud_callback (const CloudConstPtr& cloud)
00099     {
00100       FPS_CALC ("cloud callback");
00101       boost::mutex::scoped_lock lock (cloud_mutex_);
00102       cloud_ = cloud;
00103     }
00104 
00105 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00106     void
00107     image_callback (const boost::shared_ptr<openni_wrapper::Image>& image)
00108     {
00109       FPS_CALC ("image callback");
00110       boost::mutex::scoped_lock lock (image_mutex_);
00111       image_ = image;
00112     }
00113     
00114     boost::shared_ptr<openni_wrapper::Image>
00115     getLatestImage ()
00116     {
00117       boost::mutex::scoped_lock lock(image_mutex_);
00118       boost::shared_ptr<openni_wrapper::Image> temp_image;
00119       temp_image.swap (image_);
00120       return (temp_image);
00121     }    
00122 #endif
00123     
00124     void 
00125     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
00126     {
00127       string* message = (string*)cookie;
00128       cout << (*message) << " :: ";
00129       if (event.getKeyCode())
00130         cout << "the key \'" << event.getKeyCode() << "\' (" << (int)event.getKeyCode() << ") was";
00131       else
00132         cout << "the special key \'" << event.getKeySym() << "\' was";
00133       if (event.keyDown())
00134         cout << " pressed" << endl;
00135       else
00136         cout << " released" << endl;
00137     }
00138     
00139     void mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
00140     {
00141       string* message = (string*) cookie;
00142       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00143       {
00144         cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
00145       }
00146     }
00151     CloudConstPtr
00152     getLatestCloud ()
00153     {
00154       //lock while we swap our cloud and reset it.
00155       boost::mutex::scoped_lock lock(cloud_mutex_);
00156       CloudConstPtr temp_cloud;
00157       temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00158       //it is safe to set it again from our
00159       //callback
00160       return (temp_cloud);
00161     }
00162 
00166     void
00167     run ()
00168     {
00169       //pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id_, pcl::OpenNIGrabber::OpenNI_QQVGA_30Hz, pcl::OpenNIGrabber::OpenNI_VGA_30Hz);
00170 
00171       string mouseMsg3D("Mouse coordinates in PCL Visualizer");
00172       string keyMsg3D("Key event for PCL Visualizer");
00173       cloud_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg3D));    
00174       cloud_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg3D));
00175       boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&SimpleOpenNIViewer::cloud_callback, this, _1);
00176       boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb);
00177       
00178 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00179       boost::signals2::connection image_connection;
00180       if (grabber_.providesCallback<void (const boost::shared_ptr<openni_wrapper::Image>&)>())
00181       {
00182           string mouseMsg2D("Mouse coordinates in image viewer");
00183           string keyMsg2D("Key event for image viewer");
00184           image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg2D));
00185           image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg2D));
00186           boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&) > image_cb = boost::bind (&SimpleOpenNIViewer::image_callback, this, _1);
00187           image_connection = grabber_.registerCallback (image_cb);
00188       }
00189       unsigned char* rgb_data = 0;
00190       unsigned rgb_data_size = 0;
00191 #endif        
00192       
00193       grabber_.start ();
00194       
00195       while (!cloud_viewer_.wasStopped(1))
00196       {
00197         if (cloud_)
00198         {
00199           FPS_CALC ("drawing cloud");
00200           //the call to get() sets the cloud_ to null;
00201           cloud_viewer_.showCloud (getLatestCloud ());
00202         }
00203 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))        
00204         if (image_)
00205         {
00206           boost::shared_ptr<openni_wrapper::Image> image = getLatestImage ();
00207           
00208           if (image->getEncoding() == openni_wrapper::Image::RGB)
00209           {
00210             image_viewer_.showRGBImage(image->getMetaData().Data(), image->getWidth(), image->getHeight());
00211           }
00212           else
00213           {
00214             if (rgb_data_size < image->getWidth() * image->getHeight())
00215             {
00216               rgb_data_size = image->getWidth() * image->getHeight();
00217               rgb_data = new unsigned char [rgb_data_size * 3];
00218             }
00219             image->fillRGB (image->getWidth(), image->getHeight(), rgb_data);
00220             image_viewer_.showRGBImage(rgb_data, image->getWidth(), image->getHeight());
00221           }
00222           // This will crash: image_viewer_.spinOnce (10);
00223         }
00224 #endif        
00225       }
00226 
00227       grabber_.stop();
00228       
00229       cloud_connection.disconnect();
00230 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))      
00231       image_connection.disconnect();
00232       if (rgb_data)
00233         delete[] rgb_data;
00234 #endif      
00235     }
00236 
00237     pcl::visualization::CloudViewer cloud_viewer_;
00238     pcl::OpenNIGrabber& grabber_;
00239     boost::mutex cloud_mutex_;
00240     CloudConstPtr cloud_;
00241     
00242 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))    
00243     boost::mutex image_mutex_;
00244     boost::shared_ptr<openni_wrapper::Image> image_;
00245     pcl::visualization::ImageViewer image_viewer_;
00246 #endif    
00247 };
00248 
00249 void
00250 usage(char ** argv)
00251 {
00252   cout << "usage: " << argv[0] << " [((<device_id> | <path-to-oni-file>) [-depthmode <mode>] [-imagemode <mode>] [-xyz] | -l [<device_id>]| -h | --help)]" << endl;
00253   cout << argv[0] << " -h | --help : shows this help" << endl;
00254   cout << argv[0] << " -l : list all available devices" << endl;
00255   cout << argv[0] << " -l <device-id> : list all available modes for specified device" << endl;
00256 
00257   cout << "                 device_id may be #1, #2, ... for the first, second etc device in the list"
00258 #ifndef _WIN32
00259        << " or" << endl
00260        << "                 bus@address for the device connected to a specific usb-bus / address combination or" << endl
00261        << "                 <serial-number>"
00262 #endif
00263        << endl;
00264   cout << endl;
00265   cout << "examples:" << endl;
00266   cout << argv[0] << " \"#1\"" << endl;
00267   cout << "    uses the first device." << endl;
00268   cout << argv[0] << " \"./temp/test.oni\"" << endl;
00269   cout << "    uses the oni-player device to play back oni file given by path." << endl;
00270   cout << argv[0] << " -l" << endl;
00271   cout << "    lists all available devices." << endl;
00272   cout << argv[0] << " -l \"#2\"" << endl;
00273   cout << "    lists all available modes for the second device" << endl;
00274   #ifndef _WIN32
00275   cout << argv[0] << " A00361800903049A" << endl;
00276   cout << "    uses the device with the serial number \'A00361800903049A\'." << endl;
00277   cout << argv[0] << " 1@16" << endl;
00278   cout << "    uses the device on address 16 at USB bus 1." << endl;
00279   #endif
00280   return;
00281 }
00282 
00283 int
00284 main(int argc, char ** argv)
00285 {
00286   std::string device_id("");
00287   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00288   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00289   bool xyz = false;
00290   
00291   if (argc >= 2)
00292   {
00293     device_id = argv[1];
00294     if (device_id == "--help" || device_id == "-h")
00295     {
00296       usage(argv);
00297       return 0;
00298     }
00299     else if (device_id == "-l")
00300     {
00301       if (argc >= 3)
00302       {
00303         pcl::OpenNIGrabber grabber(argv[2]);
00304         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice();
00305         cout << "Supported depth modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00306         std::vector<std::pair<int, XnMapOutputMode > > modes = grabber.getAvailableDepthModes();
00307         for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00308         {
00309           cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00310         }
00311 
00312         if (device->hasImageStream ())
00313         {
00314           cout << endl << "Supported image modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00315           modes = grabber.getAvailableImageModes();
00316           for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00317           {
00318             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00319           }
00320         }
00321       }
00322       else
00323       {
00324         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00325         if (driver.getNumberDevices() > 0)
00326         {
00327           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx)
00328           {
00329             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName(deviceIdx) << ", product: " << driver.getProductName(deviceIdx)
00330               << ", connected: " << (int) driver.getBus(deviceIdx) << " @ " << (int) driver.getAddress(deviceIdx) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << endl;
00331           }
00332 
00333         }
00334         else
00335           cout << "No devices connected." << endl;
00336         
00337         cout <<"Virtual Devices available: ONI player" << endl;
00338       }
00339       return 0;
00340     }
00341   }
00342   else
00343   {
00344     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00345     if (driver.getNumberDevices() > 0)
00346       cout << "Device Id not set, using first device." << endl;
00347   }
00348   
00349   unsigned mode;
00350   if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
00351     depth_mode = (pcl::OpenNIGrabber::Mode) mode;
00352 
00353   if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
00354     image_mode = (pcl::OpenNIGrabber::Mode) mode;
00355   
00356   if (pcl::console::find_argument(argc, argv, "-xyz") != -1)
00357     xyz = true;
00358   
00359   pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode);
00360   
00361   if (xyz) // only if xyz flag is set, since grabber provides at least XYZ and XYZI pointclouds
00362   {
00363     SimpleOpenNIViewer<pcl::PointXYZ> v (grabber);
00364     v.run ();
00365   }
00366   else if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb> ())
00367   {
00368     SimpleOpenNIViewer<pcl::PointXYZRGBA> v (grabber);
00369     v.run ();
00370   }
00371   else
00372   {
00373     SimpleOpenNIViewer<pcl::PointXYZI> v (grabber);
00374     v.run ();
00375   }
00376 
00377   return (0);
00378 }


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