00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 #include <pcl/apps/in_hand_scanner/offline_integration.h>
00042 
00043 #include <iomanip>
00044 #include <fstream>
00045 
00046 #include <boost/filesystem.hpp>
00047 #include <boost/algorithm/string/case_conv.hpp>
00048 
00049 #include <QApplication>
00050 #include <QFileDialog>
00051 #include <QtCore>
00052 #include <QKeyEvent>
00053 #if (QT_VERSION >= QT_VERSION_CHECK(5, 0, 0))
00054 #include <QtConcurrent/QtConcurrent>
00055 #endif
00056 
00057 #include <pcl/io/pcd_io.h>
00058 #include <pcl/common/transforms.h>
00059 #include <pcl/features/integral_image_normal.h>
00060 #include <pcl/apps/in_hand_scanner/integration.h>
00061 
00063 
00064 pcl::ihs::OfflineIntegration::OfflineIntegration (Base* parent)
00065   : Base               (parent),
00066     mutex_             (),
00067     mutex_quit_        (),
00068     computation_fps_   (),
00069     visualization_fps_ (),
00070     path_dir_          (),
00071     mesh_model_        (new Mesh ()),
00072     normal_estimation_ (new NormalEstimation ()),
00073     integration_       (new Integration ()),
00074     destructor_called_ (false)
00075 {
00076   normal_estimation_->setNormalEstimationMethod (NormalEstimation::AVERAGE_3D_GRADIENT);
00077   normal_estimation_->setMaxDepthChangeFactor (0.02f); 
00078   normal_estimation_->setNormalSmoothingSize (10.0f);
00079 
00080   integration_->setMaxSquaredDistance (1e-4); 
00081   integration_->setMinDirections (2);
00082 
00083 
00084   Base::setVisibilityConfidenceNormalization (static_cast <float> (integration_->getMinDirections ()));
00085 }
00086 
00088 
00089 pcl::ihs::OfflineIntegration::~OfflineIntegration ()
00090 {
00091   boost::mutex::scoped_lock lock (mutex_);
00092   boost::mutex::scoped_lock lock_quit (mutex_quit_);
00093   destructor_called_ = true;
00094 }
00095 
00097 
00098 void
00099 pcl::ihs::OfflineIntegration::start ()
00100 {
00101   QString dir = QFileDialog::getExistingDirectory (0, "Please select a directory containing .pcd and .transform files.");
00102 
00103   if (dir.isEmpty ())
00104   {
00105     return (QApplication::quit ());
00106   }
00107 
00108   path_dir_ = dir.toStdString ();
00109   QtConcurrent::run (boost::bind (&pcl::ihs::OfflineIntegration::computationThread, this));
00110 }
00111 
00113 
00114 void
00115 pcl::ihs::OfflineIntegration::computationThread ()
00116 {
00117   std::vector <std::string> filenames;
00118 
00119   if (!this->getFilesFromDirectory (path_dir_, ".pcd", filenames))
00120   {
00121     std::cerr << "ERROR in offline_integration.cpp: Could not get the files from the directory\n";
00122     return;
00123   }
00124 
00125   
00126   std::cerr << "Processing file " << std::setw (5) << 1 << " / " << filenames.size () << std::endl;
00127   CloudXYZRGBNormalPtr cloud_model (new CloudXYZRGBNormal ());
00128   Eigen::Matrix4f T = Eigen::Matrix4f::Identity ();
00129   if (!this->load (filenames [0], cloud_model, T))
00130   {
00131     std::cerr << "ERROR in offline_integration.cpp: Could not load the model cloud.\n";
00132     return;
00133   }
00134 
00135   pcl::transformPointCloudWithNormals (*cloud_model, *cloud_model, T);
00136 
00137   if (!integration_->reconstructMesh (cloud_model, mesh_model_))
00138   {
00139     std::cerr << "ERROR in offline_integration.cpp: Could not reconstruct the model mesh.\n";
00140     return;
00141   }
00142 
00143   Base::setPivot ("model");
00144   Base::addMesh (mesh_model_, "model");
00145 
00146   if (filenames.size () < 1)
00147   {
00148     return;
00149   }
00150 
00151   for (unsigned int i=1; i<filenames.size (); ++i)
00152   {
00153     std::cerr << "Processing file " << std::setw (5) << i+1 << " / " << filenames.size () << std::endl;
00154 
00155     {
00156       boost::mutex::scoped_lock lock (mutex_);
00157       if (destructor_called_) return;
00158     }
00159     boost::mutex::scoped_lock lock_quit (mutex_quit_);
00160 
00161     CloudXYZRGBNormalPtr cloud_data (new CloudXYZRGBNormal ());
00162     if (!this->load (filenames [i], cloud_data, T))
00163     {
00164       std::cerr << "ERROR in offline_integration.cpp: Could not load the data cloud.\n";
00165       return;
00166     }
00167 
00168     if (!integration_->merge (cloud_data, mesh_model_, T))
00169     {
00170       std::cerr << "ERROR in offline_integration.cpp: merge failed.\n";
00171       return;
00172     }
00173 
00174     integration_->age (mesh_model_);
00175 
00176     {
00177       lock_quit.unlock ();
00178       boost::mutex::scoped_lock lock (mutex_);
00179       if (destructor_called_) return;
00180 
00181       Base::addMesh (mesh_model_, "model", Eigen::Isometry3d (T.inverse ().cast <double> ()));
00182       Base::calcFPS (computation_fps_);
00183     }
00184   }
00185   Base::setPivot ("model");
00186 }
00187 
00189 
00190 bool
00191 pcl::ihs::OfflineIntegration::getFilesFromDirectory (const std::string          path_dir,
00192                                                      const std::string          extension,
00193                                                      std::vector <std::string>& files) const
00194 {
00195   if (path_dir == "" || !boost::filesystem::exists (path_dir))
00196   {
00197     std::cerr << "ERROR in offline_integration.cpp: Invalid path\n  '" << path_dir << "'\n";
00198     return (false);
00199   }
00200 
00201   boost::filesystem::directory_iterator it_end;
00202   for (boost::filesystem::directory_iterator it (path_dir); it != it_end; ++it)
00203   {
00204     if (!is_directory (it->status ()) &&
00205         boost::algorithm::to_upper_copy (boost::filesystem::extension (it->path ())) == boost::algorithm::to_upper_copy (extension))
00206     {
00207       files.push_back (it->path ().string ());
00208     }
00209   }
00210 
00211   if (files.empty ())
00212   {
00213     std::cerr << "ERROR in offline_integration.cpp: No '" << extension << "' files found\n";
00214     return (false);
00215   }
00216 
00217   sort (files.begin (), files.end ());
00218 
00219   return (true);
00220 }
00221 
00223 
00224 bool
00225 pcl::ihs::OfflineIntegration::loadTransform (const std::string& filename,
00226                                              Eigen::Matrix4f&   transform) const
00227 {
00228  Eigen::Matrix4d tr;
00229  std::ifstream file;
00230  file.open (filename.c_str (), std::ios::binary);
00231 
00232  if (!file.is_open ())
00233  {
00234    std::cerr << "Error in offline_integration.cpp: Could not open the file '" << filename << "'\n";
00235    return (false);
00236  }
00237 
00238  for (int i = 0; i < 4; ++i)
00239  {
00240    for (int j = 0; j < 4; ++j)
00241    {
00242      file.read (reinterpret_cast<char*>(&tr (i, j)), sizeof (double));
00243 
00244      if (!file.good ())
00245      {
00246        std::cerr << "Error in offline_integration.cpp: Could not read the transformation from the file.\n";
00247        return (false);
00248      }
00249    }
00250  }
00251 
00252  transform = tr.cast<float> ();
00253 
00254  return (true);
00255 }
00256 
00258 
00259 bool
00260 pcl::ihs::OfflineIntegration::load (const std::string&    filename,
00261                                     CloudXYZRGBNormalPtr& cloud,
00262                                     Eigen::Matrix4f&      T) const
00263 {
00264   if (!cloud)
00265   {
00266     cloud = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
00267   }
00268 
00269   
00270   CloudXYZRGBAPtr cloud_input (new CloudXYZRGBA ());
00271 
00272   pcl::PCDReader reader;
00273   if (reader.read (filename, *cloud_input) < 0)
00274   {
00275     std::cerr << "ERROR in offline_integration.cpp: Could not read the pcd file.\n";
00276     return (false);
00277   }
00278 
00279   
00280   normal_estimation_->setInputCloud (cloud_input);
00281   normal_estimation_->compute (*cloud);
00282 
00283   pcl::copyPointCloud (*cloud_input, *cloud);
00284 
00285   
00286   
00287   std::string fn_transform = filename;
00288 
00289   size_t pos = fn_transform.find_last_of (".");
00290   if (pos == std::string::npos || pos == (fn_transform.size () - 1))
00291   {
00292     std::cerr << "ERROR in offline_integration.cpp: No file extension\n";
00293     return (false);
00294   }
00295 
00296   fn_transform.replace (pos, std::string::npos, ".transform");
00297 
00298   if (!this->loadTransform (fn_transform, T))
00299   {
00300     std::cerr << "ERROR in offline_integration.cpp: Could not load the transformation.\n";
00301     return (false);
00302   }
00303 
00304   return (true);
00305 }
00306 
00308 
00309 void
00310 pcl::ihs::OfflineIntegration::paintEvent (QPaintEvent* event)
00311 {
00312   Base::paintEvent (event);
00313 
00314   QPainter painter (this);
00315   painter.setPen (Qt::white);
00316   QFont font;
00317   font.setPointSize (this->width () / 50);
00318   painter.setFont (font);
00319 
00320   std::string vis_fps ("Visualization: "), comp_fps ("Computation: ");
00321   {
00322     boost::mutex::scoped_lock lock (mutex_);
00323     this->calcFPS (visualization_fps_);
00324 
00325     vis_fps.append  (visualization_fps_.str ()).append (" fps");
00326     comp_fps.append (computation_fps_.str   ()).append (" fps");
00327   }
00328 
00329   const std::string str = std::string (comp_fps).append ("\n").append (vis_fps);
00330 
00331   painter.drawText (0, 0, this->width (), this->height (), Qt::AlignBottom | Qt::AlignLeft, str.c_str ());
00332 }
00333 
00335 
00336 void
00337 pcl::ihs::OfflineIntegration::keyPressEvent (QKeyEvent* event)
00338 {
00339   if (event->key () == Qt::Key_Escape)
00340   {
00341     boost::mutex::scoped_lock lock (mutex_);
00342     QApplication::quit ();
00343   }
00344 
00345   switch (event->key ())
00346   {
00347     case Qt::Key_H:
00348     {
00349       std::cerr << "======================================================================\n"
00350                 << "Help:\n"
00351                 << "----------------------------------------------------------------------\n"
00352                 << "ESC: Quit the application.\n"
00353                 << "c  : Reset the camera.\n"
00354                 << "k  : Toggle the coloring (rgb, one color, visibility-confidence).\n"
00355                 << "s  : Toggle the mesh representation between points and faces.\n"
00356                 << "======================================================================\n";
00357       break;
00358     }
00359     case Qt::Key_C: Base::resetCamera ();              break;
00360     case Qt::Key_K: Base::toggleColoring ();           break;
00361     case Qt::Key_S: Base::toggleMeshRepresentation (); break;
00362     default:                                           break;
00363   }
00364 }
00365