openni_grabber_example.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: Suat Gedikli (gedikli@willowgarage.com)
00035  */
00036 
00037 #include <pcl/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/common/time.h>
00042 #include <pcl/console/parse.h>
00043 
00044 class SimpleOpenNIProcessor
00045 {
00046   public:
00047     bool save;
00048     openni_wrapper::OpenNIDevice::DepthMode mode;
00049 
00050     SimpleOpenNIProcessor (openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth) : mode (depth_mode) {}
00051 
00052     void 
00053     cloud_cb_ (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud)
00054     {
00055       static unsigned count = 0;
00056       static double last = pcl::getTime ();
00057       if (++count == 30)
00058       {
00059         double now = pcl::getTime ();
00060         std::cout << "distance of center pixel :" << cloud->points [(cloud->width >> 1) * (cloud->height + 1)].z << " mm. Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
00061         count = 0;
00062         last = now;
00063       }
00064 
00065       if (save)
00066       {
00067         std::stringstream ss;
00068         ss << std::setprecision (12) << pcl::getTime () * 100 << ".pcd";
00069         pcl::PCDWriter w;
00070         w.writeBinaryCompressed (ss.str (), *cloud);
00071         std::cout << "wrote point clouds to file " << ss.str () << std::endl;
00072       }
00073     }
00074 
00075     void 
00076     imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>& d_img, float constant)
00077     {
00078       static unsigned count = 0;
00079       static double last = pcl::getTime ();
00080       if (++count == 30)
00081       {
00082         double now = pcl::getTime ();
00083         std::cout << "got synchronized image x depth-image with constant factor: " << constant << ". Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
00084         std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl;
00085         count = 0;
00086         last = now;
00087       }
00088     }
00089 
00090     void 
00091     run ()
00092     {
00093       save = false;
00094 
00095       // create a new grabber for OpenNI devices
00096       pcl::OpenNIGrabber interface;
00097 
00098       // Set the depth output format
00099       interface.getDevice ()->setDepthOutputFormat (mode);
00100 
00101       // make callback function from member function
00102       boost::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
00103         boost::bind (&SimpleOpenNIProcessor::cloud_cb_, this, _1);
00104 
00105       // connect callback function for desired signal. In this case its a point cloud with color values
00106       boost::signals2::connection c = interface.registerCallback (f);
00107 
00108       // make callback function from member function
00109       boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant)> f2 =
00110         boost::bind (&SimpleOpenNIProcessor::imageDepthImageCallback, this, _1, _2, _3);
00111 
00112       // connect callback function for desired signal. In this case its a point cloud with color values
00113       boost::signals2::connection c2 = interface.registerCallback (f2);
00114 
00115       // start receiving point clouds
00116       interface.start ();
00117 
00118       std::cout << "<Esc>, \'q\', \'Q\': quit the program" << std::endl;
00119       std::cout << "\' \': pause" << std::endl;
00120       std::cout << "\'s\': save" << std::endl;
00121       char key;
00122       do
00123       {
00124         key = static_cast<char> (getchar ());
00125         switch (key)
00126         {
00127           case ' ':
00128             if (interface.isRunning ())
00129               interface.stop ();
00130             else
00131               interface.start ();
00132           case 's':
00133             save = !save;
00134         }
00135       } while (key != 27 && key != 'q' && key != 'Q');
00136 
00137       // stop the grabber
00138       interface.stop ();
00139     }
00140 };
00141 
00142 int
00143 main (int argc, char **argv)
00144 {
00145   int mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
00146   pcl::console::parse_argument (argc, argv, "-mode", mode);
00147 
00148   SimpleOpenNIProcessor v (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (mode));
00149   v.run ();
00150   return (0);
00151 }


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