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