pcd_grabber_viewer.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *  
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  *
00038  */
00039 #include <pcl/io/pcd_grabber.h>
00040 #include <pcl/console/parse.h>
00041 #include <boost/filesystem.hpp>
00042 #include <boost/algorithm/string.hpp>
00043 #include <boost/thread/thread.hpp>
00044 #include <boost/date_time/posix_time/posix_time.hpp>
00045 #include <pcl/console/print.h>
00046 #include <pcl/visualization/cloud_viewer.h>
00047 #include <pcl/visualization/image_viewer.h>
00048 
00049 
00050 using pcl::console::print_error;
00051 using pcl::console::print_info;
00052 using pcl::console::print_value;
00053 
00054 boost::mutex mutex_;
00055 boost::shared_ptr<pcl::PCDGrabber<pcl::PointXYZRGBA> > grabber;
00056 pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr cloud_;
00057 
00058 void
00059 printHelp (int, char **argv)
00060 {
00061   //print_error ("Syntax is: %s <file_name 1..N>.pcd <options>\n", argv[0]);
00062   print_error ("Syntax is: %s <options>\n", argv[0]);
00063   print_info ("  where options are:\n");
00064   print_info ("                     -file file_name          = PCD file to be read from\n");
00065   print_info ("                     -dir directory_path      = directory path to PCD file(s) to be read from\n");
00066   print_info ("                     -fps frequency           = frames per second\n");
00067   print_info ("                     -repeat                  = optional parameter that tells wheter the PCD file(s) should be \"grabbed\" in a endless loop.\n");
00068   print_info ("\n");
00069   print_info ("                     -cam (*)                 = use given camera settings as initial view\n");
00070   print_info (stderr, " (*) [Clipping Range / Focal Point / Position / ViewUp / Distance / Window Size / Window Pos] or use a <filename.cam> that contains the same information.\n");
00071 }
00072 
00073 // Create the PCLVisualizer object
00074 boost::shared_ptr<pcl::visualization::PCLVisualizer> cloud_viewer;
00075 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00076 boost::shared_ptr<pcl::visualization::ImageViewer> img_viewer;
00077 #endif
00078 
00079 std::vector<double> fcolor_r, fcolor_b, fcolor_g;
00080 bool fcolorparam = false;
00081 
00082 struct EventHelper
00083 {
00084   void 
00085   cloud_cb (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr & cloud)
00086   {
00087     if (mutex_.try_lock ())
00088     {
00089       cloud_ = cloud;
00090       mutex_.unlock ();
00091     }
00092   }
00093 };
00094 
00095 void 
00096 keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00097 {
00099   if (event.getKeyCode() == ' ' && grabber)
00100     grabber->trigger ();
00101 }
00102 
00103 void 
00104 mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
00105 {
00106   std::string* message = static_cast<std::string*> (cookie);
00107   if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00108   {
00109     cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
00110   }
00111 }
00112 
00113 /* ---[ */
00114 int
00115 main (int argc, char** argv)
00116 {
00117   srand (unsigned (time (0)));
00118 
00119   if (argc > 1)
00120   {
00121     for (int i = 1; i < argc; i++)
00122     {
00123       if (std::string (argv[i]) == "-h")
00124       {
00125         printHelp (argc, argv);
00126         return (-1);
00127       }
00128     }
00129   }
00130 
00131   // Command line parsing
00132   double bcolor[3] = {0, 0, 0};
00133   pcl::console::parse_3x_arguments (argc, argv, "-bc", bcolor[0], bcolor[1], bcolor[2]);
00134 
00135   fcolorparam = pcl::console::parse_multiple_3x_arguments (argc, argv, "-fc", fcolor_r, fcolor_g, fcolor_b);
00136 
00137   int psize = 0;
00138   pcl::console::parse_argument (argc, argv, "-ps", psize);
00139 
00140   double opaque;
00141   pcl::console::parse_argument (argc, argv, "-opaque", opaque);
00142 
00143   cloud_viewer.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCD viewer"));
00144 
00145 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00146   img_viewer.reset (new pcl::visualization::ImageViewer ("OpenNI Viewer"));
00147 #endif
00148 
00149   //  // Change the cloud rendered point size
00150   //  if (psize > 0)
00151   //    p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, psize, "OpenNICloud");
00152   //
00153   //  // Change the cloud rendered opacity
00154   //  if (opaque >= 0)
00155   //    p->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, opaque, "OpenNICloud");
00156 
00157   cloud_viewer->setBackgroundColor (bcolor[0], bcolor[1], bcolor[2]);
00158 
00159   // Read axes settings
00160   double axes = 0.0;
00161   pcl::console::parse_argument (argc, argv, "-ax", axes);
00162   if (axes != 0.0 && cloud_viewer)
00163   {
00164     float ax_x = 0.0, ax_y = 0.0, ax_z = 0.0;
00165     pcl::console::parse_3x_arguments (argc, argv, "-ax_pos", ax_x, ax_y, ax_z, false);
00166     // Draw XYZ axes if command-line enabled
00167     cloud_viewer->addCoordinateSystem (axes, ax_x, ax_y, ax_z);
00168   }
00169 
00170   float frames_per_second = 0; // 0 means only if triggered!
00171   pcl::console::parse (argc, argv, "-fps", frames_per_second);
00172   if (frames_per_second < 0)
00173     frames_per_second = 0.0;
00174 
00175   bool repeat = (pcl::console::find_argument (argc, argv, "-repeat") != -1);
00176 
00177   std::cout << "fps: " << frames_per_second << " , repeat: " << repeat << std::endl;
00178   std::string path = "";
00179   pcl::console::parse_argument (argc, argv, "-file", path);
00180   std::cout << "path: " << path << std::endl;
00181   if (path != "" && boost::filesystem::exists (path))
00182   {
00183     grabber.reset (new pcl::PCDGrabber<pcl::PointXYZRGBA> (path, frames_per_second, repeat));
00184   }
00185   else
00186   {
00187     std::vector<std::string> pcd_files;
00188     pcl::console::parse_argument (argc, argv, "-dir", path);
00189     std::cout << "path: " << path << std::endl;
00190     if (path != "" && boost::filesystem::exists (path))
00191     {
00192       boost::filesystem::directory_iterator end_itr;
00193       for (boost::filesystem::directory_iterator itr (path); itr != end_itr; ++itr)
00194       {
00195 #if BOOST_FILESYSTEM_VERSION == 3
00196         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
00197 #else
00198         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->leaf ())) == ".PCD" )
00199 #endif
00200         {
00201 #if BOOST_FILESYSTEM_VERSION == 3
00202           pcd_files.push_back (itr->path ().string ());
00203           std::cout << "added: " << itr->path ().string () << std::endl;
00204 #else
00205           pcd_files.push_back (itr->path ().string ());
00206           std::cout << "added: " << itr->path () << std::endl;
00207 #endif
00208         }
00209       }
00210     }
00211     else
00212     {
00213       std::cout << "Neither a pcd file given using the \"-file\" option, nor given a directory containing pcd files using the \"-dir\" option." << std::endl;
00214     }
00215 
00216     // Sort the read files by name
00217     sort (pcd_files.begin (), pcd_files.end ());
00218     grabber.reset (new pcl::PCDGrabber<pcl::PointXYZRGBA> (pcd_files, frames_per_second, repeat));
00219   }
00220 
00221   EventHelper h;
00222   boost::function<void(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&) > f = boost::bind (&EventHelper::cloud_cb, &h, _1);
00223   boost::signals2::connection c1 = grabber->registerCallback (f);
00224 
00225   std::string mouse_msg_3D ("Mouse coordinates in PCL Visualizer");
00226   std::string key_msg_3D ("Key event for PCL Visualizer");
00227 
00228   cloud_viewer->registerMouseCallback (&mouse_callback, static_cast<void*> (&mouse_msg_3D));
00229   cloud_viewer->registerKeyboardCallback(&keyboard_callback, static_cast<void*> (&key_msg_3D));
00230 
00231   std::string mouse_msg_2D ("Mouse coordinates in image viewer");
00232   std::string key_msg_2D ("Key event for image viewer");
00233 
00234 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00235   img_viewer->registerMouseCallback (&mouse_callback, static_cast<void*> (&mouse_msg_2D));
00236   img_viewer->registerKeyboardCallback(&keyboard_callback, static_cast<void*> (&key_msg_2D));
00237 #endif
00238 
00239   grabber->start ();
00240   while (!cloud_viewer->wasStopped ())
00241   {
00242     cloud_viewer->spinOnce ();
00243 
00244 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00245     img_viewer->spinOnce ();
00246 #endif
00247 
00248     if (!cloud_)
00249     {
00250       boost::this_thread::sleep(boost::posix_time::microseconds(10000));
00251       continue;
00252     }
00253 
00254     if (mutex_.try_lock ())
00255     {
00256       pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr temp_cloud;
00257       temp_cloud.swap (cloud_);
00258       mutex_.unlock ();
00259 
00260 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00261       img_viewer->showRGBImage (*temp_cloud);
00262 #endif
00263 
00264       if (!cloud_viewer->updatePointCloud (temp_cloud, "PCDCloud"))
00265       {
00266         cloud_viewer->addPointCloud (temp_cloud, "PCDCloud");
00267         cloud_viewer->resetCameraViewpoint ("PCDCloud");
00268       }
00269     }
00270   }
00271 
00272   grabber->stop ();
00273 }
00274 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:24