pcd_video_player.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) 2010-2012, Willow Garage, Inc.
00006  * 
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 //PCL
00039 #include <pcl/apps/pcd_video_player.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/point_types.h>
00042 
00043 //STD
00044 #include <iostream>
00045 #include <fstream>
00046 
00047 //BOOST
00048 #include <boost/filesystem.hpp>
00049 #include <boost/foreach.hpp>
00050 #include <boost/property_tree/xml_parser.hpp>
00051 #include <boost/property_tree/ptree.hpp>
00052 
00053 //QT4
00054 #include <QApplication>
00055 #include <QMutexLocker>
00056 #include <QEvent>
00057 #include <QObject>
00058 #include <QFileDialog>
00059 #include <QGroupBox>
00060 #include <QRadioButton>
00061 #include <QButtonGroup>
00062 
00063 // VTK
00064 #include <vtkRenderWindow.h>
00065 #include <vtkRendererCollection.h>
00066 #include <vtkCamera.h>
00067 
00068 using namespace pcl;
00069 using namespace std;
00070 
00072 PCDVideoPlayer::PCDVideoPlayer ()
00073 {
00074   cloud_present_ = false;
00075   cloud_modified_ = false;
00076   play_mode_ = false;
00077   speed_counter_ = 0;
00078   speed_value_ = 5;
00079 
00080   //Create a timer
00081   vis_timer_ = new QTimer (this);
00082   vis_timer_->start (5);//5ms
00083 
00084   connect (vis_timer_, SIGNAL (timeout ()), this, SLOT (timeoutSlot ()));
00085 
00086   ui_ = new Ui::MainWindow;
00087   ui_->setupUi (this);
00088   
00089   this->setWindowTitle ("PCL PCD Video Player");
00090 
00091   // Setup the cloud pointer
00092   cloud_.reset (new pcl::PointCloud<pcl::PointXYZRGBA>);
00093 
00094   // Set up the qvtk window
00095   vis_.reset (new pcl::visualization::PCLVisualizer ("", false));
00096   ui_->qvtkWidget->SetRenderWindow (vis_->getRenderWindow ());
00097   vis_->setupInteractor (ui_->qvtkWidget->GetInteractor (), ui_->qvtkWidget->GetRenderWindow ());
00098   vis_->getInteractorStyle ()->setKeyboardModifier (pcl::visualization::INTERACTOR_KB_MOD_SHIFT);
00099   ui_->qvtkWidget->update ();
00100 
00101   // Connect all buttons
00102   connect (ui_->playButton, SIGNAL (clicked ()), this, SLOT (playButtonPressed ()));
00103   connect (ui_->stopButton, SIGNAL (clicked ()), this, SLOT (stopButtonPressed ()));
00104   connect (ui_->backButton, SIGNAL (clicked ()), this, SLOT (backButtonPressed ()));
00105   connect (ui_->nextButton, SIGNAL (clicked ()), this, SLOT (nextButtonPressed ()));
00106 
00107   connect (ui_->selectFolderButton, SIGNAL (clicked ()), this, SLOT (selectFolderButtonPressed ()));
00108   connect (ui_->selectFilesButton, SIGNAL (clicked ()), this, SLOT (selectFilesButtonPressed ()));
00109   
00110   connect (ui_->indexSlider, SIGNAL (valueChanged (int)), this, SLOT (indexSliderValueChanged (int)));
00111 }
00112 
00113 void 
00114 PCDVideoPlayer::backButtonPressed ()
00115 {
00116   if(current_frame_ == 0) // Allready in the beginning
00117   {
00118     PCL_DEBUG ("[PCDVideoPlayer::nextButtonPressed] : reached the end\n");
00119     current_frame_ = nr_of_frames_ - 1; // reset to end
00120   }
00121   else
00122   {
00123     current_frame_--;
00124     cloud_modified_ = true;
00125     ui_->indexSlider->setSliderPosition (current_frame_);        // Update the slider position
00126   }
00127 }
00128 
00129 void 
00130 PCDVideoPlayer::nextButtonPressed ()
00131 {
00132   if (current_frame_ == (nr_of_frames_ - 1)) // Reached the end
00133   {
00134     PCL_DEBUG ("[PCDVideoPlayer::nextButtonPressed] : reached the end\n");
00135     current_frame_ = 0; // reset to beginning
00136   }
00137   else
00138   {
00139     current_frame_++;
00140     cloud_modified_ = true;
00141     ui_->indexSlider->setSliderPosition (current_frame_);        // Update the slider position
00142   }
00143 }
00144 
00145 void
00146 PCDVideoPlayer::selectFolderButtonPressed ()
00147 {
00148   pcd_files_.clear ();     // Clear the std::vector
00149   pcd_paths_.clear ();     // Clear the boost filesystem paths
00150 
00151   dir_ = QFileDialog::getExistingDirectory (this,
00152                                             tr("Open Directory"),
00153                                             "/home",
00154                                             QFileDialog::ShowDirsOnly | QFileDialog::DontResolveSymlinks);
00155 
00156   boost::filesystem::directory_iterator end_itr;
00157 
00158   if (boost::filesystem::is_directory (dir_.toStdString ()))
00159   {
00160     for (boost::filesystem::directory_iterator itr (dir_.toStdString ()); itr != end_itr; ++itr)
00161     {
00162       std::string ext = itr->path ().extension ().string ();
00163       if (ext.compare (".pcd") == 0)
00164       {
00165         pcd_files_.push_back (itr->path ().string ());
00166         pcd_paths_.push_back (itr->path ());
00167       }
00168       else
00169       {
00170         // Found non pcd file
00171         PCL_DEBUG ("[PCDVideoPlayer::selectFolderButtonPressed] : found a different file\n");
00172       }
00173     }
00174   }
00175   else
00176   {
00177     PCL_ERROR("Path is not a directory\n");
00178     exit(-1);
00179   }
00180   nr_of_frames_ = pcd_files_.size ();
00181   PCL_DEBUG ("[PCDVideoPlayer::selectFolderButtonPressed] : found %d files\n", nr_of_frames_ );
00182 
00183   if (nr_of_frames_ == 0)
00184   {
00185     PCL_ERROR ("Please select valid pcd folder\n");
00186     cloud_present_ = false;
00187     return;
00188   }
00189   else
00190   {
00191     // Reset the Slider
00192     ui_->indexSlider->setValue (0);                // set cursor back in the beginning
00193     ui_->indexSlider->setRange (0, nr_of_frames_ - 1);  // rescale the slider
00194 
00195     current_frame_ = 0;
00196 
00197     cloud_present_ = true;
00198     cloud_modified_ = true;
00199   }
00200 }
00201 
00202 void 
00203 PCDVideoPlayer::selectFilesButtonPressed ()
00204 {
00205   pcd_files_.clear ();  // Clear the std::vector
00206   pcd_paths_.clear ();     // Clear the boost filesystem paths
00207 
00208   QStringList qt_pcd_files = QFileDialog::getOpenFileNames (this,
00209                                                             "Select one or more PCD files to open",
00210                                                             "/home",
00211                                                             "PointClouds (*.pcd)");
00212   nr_of_frames_ = qt_pcd_files.size ();
00213   PCL_INFO ("[PCDVideoPlayer::selectFilesButtonPressed] : selected %ld files\n", nr_of_frames_);
00214 
00215   if (nr_of_frames_ == 0)
00216   {
00217     PCL_ERROR ("Please select valid pcd files\n");
00218     cloud_present_ = false;
00219     return;
00220   }
00221   else
00222   {
00223     for(int i = 0; i < qt_pcd_files.size (); i++)
00224     {
00225       pcd_files_.push_back (qt_pcd_files.at (i).toStdString ());
00226     }
00227 
00228     current_frame_ = 0;
00229 
00230     // Reset the Slider
00231     ui_->indexSlider->setValue (0);                // set cursor back in the beginning
00232     ui_->indexSlider->setRange (0, nr_of_frames_ - 1);  // rescale the slider
00233 
00234     cloud_present_ = true;
00235     cloud_modified_ = true;
00236   }
00237 }
00238 
00239 void 
00240 PCDVideoPlayer::timeoutSlot ()
00241 {
00242   if (play_mode_)
00243   {
00244     if (speed_counter_ == speed_value_)
00245     {
00246       if (current_frame_ == (nr_of_frames_-1)) // Reached the end
00247       {
00248         current_frame_ = 0; // reset to beginning
00249       }
00250       else
00251       {
00252         current_frame_++;
00253         cloud_modified_ = true;
00254         ui_->indexSlider->setSliderPosition (current_frame_);        // Update the slider position
00255       }
00256     }
00257     else
00258     {
00259       speed_counter_++;
00260     }
00261   }
00262 
00263   if (cloud_present_ && cloud_modified_)
00264   {
00265     if (pcl::io::loadPCDFile<pcl::PointXYZRGBA> (pcd_files_[current_frame_], *cloud_) == -1) //* load the file
00266     {
00267       PCL_ERROR ("[PCDVideoPlayer::timeoutSlot] : Couldn't read file %s\n");
00268     }
00269 
00270     if (!vis_->updatePointCloud(cloud_, "cloud_"))
00271     {
00272       vis_->addPointCloud (cloud_, "cloud_");
00273       vis_->resetCameraViewpoint("cloud_");
00274     }
00275     cloud_modified_ = false;
00276   }
00277   ui_->qvtkWidget->update ();
00278 }
00279 
00280 void
00281 PCDVideoPlayer::indexSliderValueChanged (int value)
00282 {
00283   PCL_DEBUG ("[PCDVideoPlayer::indexSliderValueChanged] : (I) : value %d\n", value);
00284   current_frame_ = value;
00285   cloud_modified_ = true;
00286 }
00287 
00288 void
00289 print_usage ()
00290 {
00291   PCL_INFO ("PCDVideoPlayer V0.1\n");
00292   PCL_INFO ("-------------------\n");
00293   PCL_INFO ("\tThe slider accepts focus on Tab and provides both a mouse wheel and a keyboard interface. The keyboard interface is the following:\n");
00294   PCL_INFO ("\t  Left/Right move a horizontal slider by one single step.\n");
00295   PCL_INFO ("\t  Up/Down move a vertical slider by one single step.\n");
00296   PCL_INFO ("\t  PageUp moves up one page.\n");
00297   PCL_INFO ("\t  PageDown moves down one page.\n");
00298   PCL_INFO ("\t  Home moves to the start (mininum).\n");
00299   PCL_INFO ("\t  End moves to the end (maximum).\n");
00300 }
00301 
00302 int
00303 main (int argc, char** argv)
00304 {
00305   QApplication app (argc, argv);
00306 
00307   PCDVideoPlayer VideoPlayer;
00308 
00309   VideoPlayer.show ();
00310 
00311   return (app.exec ());
00312 }


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