openni_grab_frame.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  *         Christian Potthast (potthast@usc.edu)
00036  */
00037 
00038 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/common/time.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <boost/filesystem.hpp>
00046 #include <pcl/visualization/pcl_visualizer.h>
00047 
00048 
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     double now = pcl::getTime (); \
00058     ++count; \
00059     if (now - last >= 1.0) \
00060     { \
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 using namespace pcl::console;
00074 using namespace boost::filesystem;
00075 
00076 template<typename PointType>
00077 class OpenNIGrabFrame
00078 {
00079   typedef pcl::PointCloud<PointType> Cloud;
00080   typedef typename Cloud::ConstPtr CloudConstPtr;  
00081   public:
00082     OpenNIGrabFrame (pcl::OpenNIGrabber &grabber)
00083     : visualizer_ (new pcl::visualization::PCLVisualizer ("OpenNI Viewer"))
00084     , writer_ ()
00085     , quit_ (false)
00086     , continuous_ (false)
00087     , trigger_ (false)
00088     , file_name_ ("")
00089     , dir_name_ ("")
00090     , format_ (4)
00091     , grabber_ (grabber)
00092     , visualizer_enable_ (true)
00093     {
00094     }
00095 
00096     void 
00097     cloud_cb_ (const CloudConstPtr& cloud)
00098     {
00099       if (quit_)
00100         return;
00101       
00102       boost::mutex::scoped_lock lock (cloud_mutex_);
00103         cloud_ = cloud;
00104         
00105       if (continuous_ || trigger_)
00106         saveCloud ();
00107       
00108       trigger_ = false;
00109     }
00110     
00111     void 
00112     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00113     {
00114       if (event.keyUp ())
00115       {
00116         switch (event.getKeyCode ())
00117         {
00118           case 27:
00119           case 'Q':
00120           case 'q': quit_ = true; visualizer_->close ();
00121             break;
00122           case 'V':
00123           case 'v': visualizer_enable_ = !visualizer_enable_;
00124             break;
00125           case ' ': continuous_ = !continuous_;
00126             break;
00127         }
00128       }
00129     }
00130     
00131     void 
00132     mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void*)
00133     {
00134       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00135       {
00136         trigger_ = true;
00137       }
00138     }
00139     
00140     CloudConstPtr
00141     getLatestCloud ()
00142     {
00143       //lock while we swap our cloud and reset it.
00144       boost::mutex::scoped_lock lock(cloud_mutex_);
00145       CloudConstPtr temp_cloud;
00146       temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00147       //it is safe to set it again from our
00148       //callback
00149       return (temp_cloud);
00150     }
00151     
00152     void saveCloud ()
00153     {
00154       FPS_CALC ("I/O");
00155       std::stringstream ss;
00156       ss << dir_name_ << "/" << file_name_ << "_" << boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ()) << ".pcd";
00157 
00158       if (format_ & 1)
00159       {
00160         writer_.writeBinary<PointType> (ss.str (), *cloud_);
00161         //std::cerr << "Data saved in BINARY format to " << ss.str () << std::endl;
00162       }
00163       
00164       if (format_ & 2)
00165       {
00166         writer_.writeBinaryCompressed<PointType> (ss.str (), *cloud_);
00167         //std::cerr << "Data saved in BINARY COMPRESSED format to " << ss.str () << std::endl;
00168       }
00169       
00170       if (format_ & 4)
00171       {
00172         writer_.writeBinaryCompressed<PointType> (ss.str (), *cloud_);
00173         //std::cerr << "Data saved in BINARY COMPRESSED format to " << ss.str () << std::endl;
00174       }
00175     }
00176     
00177     void 
00178     run ()
00179     {
00180       // register the keyboard and mouse callback for the visualizer
00181       visualizer_->registerMouseCallback (&OpenNIGrabFrame::mouse_callback, *this);
00182       visualizer_->registerKeyboardCallback(&OpenNIGrabFrame::keyboard_callback, *this);
00183       
00184 
00185       // make callback function from member function
00186       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIGrabFrame::cloud_cb_, this, _1);
00187 
00188       // connect callback function for desired signal. In this case its a point cloud with color values
00189       boost::signals2::connection c = grabber_.registerCallback (f);
00190 
00191       // start receiving point clouds
00192       grabber_.start ();
00193 
00194       // wait until user quits program with Ctrl-C, but no busy-waiting -> sleep (1);
00195       while (!visualizer_->wasStopped())
00196       {
00197         boost::this_thread::sleep (boost::posix_time::microseconds (100));
00198 
00199         visualizer_->spinOnce ();
00200         
00201         if (!visualizer_enable_)
00202           continue;
00203 
00204         if (cloud_)
00205         {
00206           CloudConstPtr cloud = getLatestCloud ();
00207           if (!visualizer_->updatePointCloud (cloud, "OpenNICloud"))
00208           {
00209             visualizer_->addPointCloud (cloud, "OpenNICloud");
00210             visualizer_->resetCameraViewpoint ("OpenNICloud");
00211           }          
00212         }
00213       }
00214       
00215       //while (!quit_)
00216         //boost::this_thread::sleep (boost::posix_time::seconds (1));
00217    
00218       // stop the grabber
00219       grabber_.stop ();
00220     }
00221 
00222     void
00223     setOptions (std::string filename, std::string pcd_format, bool paused, bool visualizer)
00224     {
00225       boost::filesystem::path path(filename);
00226 
00227       if (filename.empty ())
00228       {
00229         dir_name_ = ".";
00230         file_name_ = "frame";
00231       }
00232       else
00233       {
00234         dir_name_ = path.parent_path ().string ();
00235         
00236         if (!dir_name_.empty () && !boost::filesystem::exists (path.parent_path ()))
00237         {
00238           std::cerr << "directory \"" << path.parent_path () << "\" does not exist!\n";
00239           exit (1);
00240         }
00241 #if BOOST_FILESYSTEM_VERSION == 3
00242         file_name_ = path.stem ().string ();
00243 #else
00244         file_name_ = path.stem ();
00245 #endif
00246       }
00247       
00248       std::cout << "dir: " << dir_name_ << " :: " << path.parent_path () << std::endl;
00249 #if BOOST_FILESYSTEM_VERSION == 3
00250       std::cout << "file: " << file_name_ << " :: " << path.stem (). string () << std::endl;
00251 #else
00252       std::cout << "file: " << file_name_ << " :: " << path.stem () << std::endl;
00253 #endif
00254       
00255       if (pcd_format == "b" || pcd_format == "all")
00256         format_ |= 1;
00257       else if (pcd_format == "ascii" || pcd_format == "all")
00258         format_ |= 2;
00259       else if (pcd_format == "bc" || pcd_format == "all")
00260         format_ |= 4;
00261     
00262       continuous_ = !paused;
00263       visualizer_enable_ = visualizer;
00264     }
00265 
00266     boost::shared_ptr<pcl::visualization::PCLVisualizer> visualizer_;
00267     pcl::PCDWriter writer_;
00268     bool quit_;
00269     bool continuous_;
00270     bool trigger_;
00271     std::string file_name_;
00272     std::string dir_name_;
00273     unsigned format_;
00274     CloudConstPtr cloud_;
00275     mutable boost::mutex cloud_mutex_;
00276     pcl::OpenNIGrabber &grabber_;
00277     bool visualizer_enable_;
00278 };
00279 
00280 void
00281 usage (char ** argv)
00282 {
00283   std::cout << "usage: " << argv[0] << " <filename> <options>\n\n";
00284   
00285   print_info ("  filename: if no filename is provided a generic timestamp will be set as filename\n\n");
00286   print_info ("  where options are:\n");
00287   print_info ("                    -format = PCD file format (b=binary; bc=binary compressed; ascii=ascii; all=all) (default: bc)\n");
00288   print_info ("                    -XYZ  = store just a XYZ cloud\n");
00289   print_info ("                    -paused = start grabber in paused mode. Toggle pause by pressing the space bar\n");
00290   print_info ("                              or grab single frames by just pressing the left mouse button.\n");
00291   print_info ("                    -imagemode = select the image mode (resolution, fps) for the grabber, see pcl::OpenNIGrabber::Mode for details.\n");
00292   print_info ("                    -depthmode = select the depth mode (resolution, fps) for the grabber, see pcl::OpenNIGrabber::Mode for details.\n");
00293   print_info ("                    -visualizer 0/1 = turn OFF or ON the visualization of point clouds in the viewer (can also be changed using 'v'/'V' in the viewer).\n");
00294 }
00295 
00296 int 
00297 main (int argc, char** argv)
00298 {
00299   std::string arg;
00300   if (argc > 1)
00301     arg = std::string (argv[1]);
00302 
00303   if (arg == "--help" || arg == "-h")
00304   {
00305     usage (argv);
00306     return 1;
00307   }
00308 
00309   std::string format = "bc";
00310   std::string filename;
00311   bool paused = false;
00312   bool xyz = false;
00313   bool visualizer = true;
00314   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00315   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00316 
00317   if (argc > 1)
00318   {
00319     // Parse the command line arguments for .pcd file
00320     std::vector<int> p_file_indices;
00321     p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00322     if (p_file_indices.size () > 0)
00323       filename = argv[p_file_indices[0]];
00324     
00325     std::cout << "fname: " << filename << std::endl;
00326     // Command line parsing
00327     parse_argument (argc, argv, "-format", format);
00328     xyz = find_switch (argc, argv, "-XYZ");
00329     paused = find_switch (argc, argv, "-paused");
00330     visualizer = find_switch (argc, argv, "-visualizer");
00331 
00332     unsigned mode;
00333     if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
00334       depth_mode = pcl::OpenNIGrabber::Mode (mode);
00335 
00336     if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
00337       image_mode = pcl::OpenNIGrabber::Mode (mode);
00338   }
00339 
00340   pcl::OpenNIGrabber grabber ("#1", depth_mode, image_mode);
00341 
00342   if (xyz)
00343   {
00344     OpenNIGrabFrame<pcl::PointXYZ> grab_frame (grabber);
00345     grab_frame.setOptions (filename, format, paused, visualizer);
00346     grab_frame.run ();
00347   }
00348   else
00349   {
00350     OpenNIGrabFrame<pcl::PointXYZRGBA> grab_frame (grabber);
00351     grab_frame.setOptions (filename, format, paused, visualizer);
00352     grab_frame.run ();
00353   }
00354   return (0);
00355 }
00356 


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