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/in_hand_scanner.h>
00042
00043 #include <QApplication>
00044 #include <QtCore>
00045 #include <QKeyEvent>
00046 #include <QPainter>
00047
00048 #include <pcl/exceptions.h>
00049 #include <pcl/common/time.h>
00050 #include <pcl/common/transforms.h>
00051 #include <pcl/io/openni_grabber.h>
00052 #include <pcl/io/ply_io.h>
00053 #include <pcl/io/vtk_io.h>
00054 #include <pcl/geometry/get_boundary.h>
00055 #include <pcl/geometry/mesh_conversion.h>
00056 #include <pcl/apps/in_hand_scanner/icp.h>
00057 #include <pcl/apps/in_hand_scanner/input_data_processing.h>
00058 #include <pcl/apps/in_hand_scanner/integration.h>
00059 #include <pcl/apps/in_hand_scanner/mesh_processing.h>
00060
00062
00063 pcl::ihs::InHandScanner::InHandScanner (Base* parent)
00064 : Base (parent),
00065 mutex_ (),
00066 computation_fps_ (),
00067 visualization_fps_ (),
00068 running_mode_ (RM_UNPROCESSED),
00069 iteration_ (0),
00070 grabber_ (),
00071 starting_grabber_ (false),
00072 new_data_connection_ (),
00073 input_data_processing_ (new InputDataProcessing ()),
00074 icp_ (new ICP ()),
00075 transformation_ (Eigen::Matrix4f::Identity ()),
00076 integration_ (new Integration ()),
00077 mesh_processing_ (new MeshProcessing ()),
00078 mesh_model_ (new Mesh ()),
00079 destructor_called_ (false)
00080 {
00081
00082 qRegisterMetaType <pcl::ihs::InHandScanner::RunningMode> ("RunningMode");
00083
00084 Base::setScalingFactor (0.01);
00085
00086
00087 const float x_min = input_data_processing_->getXMin ();
00088 const float x_max = input_data_processing_->getXMax ();
00089 const float y_min = input_data_processing_->getYMin ();
00090 const float y_max = input_data_processing_->getYMax ();
00091 const float z_min = input_data_processing_->getZMin ();
00092 const float z_max = input_data_processing_->getZMax ();
00093
00094 Base::setPivot (Eigen::Vector3d ((x_min + x_max) / 2., (y_min + y_max) / 2., (z_min + z_max) / 2.));
00095 }
00096
00098
00099 pcl::ihs::InHandScanner::~InHandScanner ()
00100 {
00101 boost::mutex::scoped_lock lock (mutex_);
00102 destructor_called_ = true;
00103
00104 if (grabber_ && grabber_->isRunning ()) grabber_->stop ();
00105 if (new_data_connection_.connected ()) new_data_connection_.disconnect ();
00106 }
00107
00109
00110 void
00111 pcl::ihs::InHandScanner::startGrabber ()
00112 {
00113 QtConcurrent::run (boost::bind (&pcl::ihs::InHandScanner::startGrabberImpl, this));
00114 }
00115
00117
00118 void
00119 pcl::ihs::InHandScanner::showUnprocessedData ()
00120 {
00121 boost::mutex::scoped_lock lock (mutex_);
00122 if (destructor_called_) return;
00123
00124 std::cerr << "Showing the unprocessed input data.\n";
00125 Base::setDrawBox (false);
00126 Base::setColoring (Base::COL_RGB);
00127
00128 running_mode_ = RM_UNPROCESSED;
00129 emit runningModeChanged (running_mode_);
00130 }
00131
00133
00134 void
00135 pcl::ihs::InHandScanner::showProcessedData ()
00136 {
00137 boost::mutex::scoped_lock lock (mutex_);
00138 if (destructor_called_) return;
00139
00140 std::cerr << "Showing the processed input data.\n";
00141 Base::setDrawBox (true);
00142 Base::setColoring (Base::COL_RGB);
00143
00144 running_mode_ = RM_PROCESSED;
00145 emit runningModeChanged (running_mode_);
00146 }
00147
00149
00150 void
00151 pcl::ihs::InHandScanner::registerContinuously ()
00152 {
00153 boost::mutex::scoped_lock lock (mutex_);
00154 if (destructor_called_) return;
00155
00156 std::cerr << "Continuous registration.\n";
00157 Base::setDrawBox (true);
00158 Base::setColoring (Base::COL_VISCONF);
00159
00160 running_mode_ = RM_REGISTRATION_CONT;
00161 emit runningModeChanged (running_mode_);
00162 }
00163
00165
00166 void
00167 pcl::ihs::InHandScanner::registerOnce ()
00168 {
00169 boost::mutex::scoped_lock lock (mutex_);
00170 if (destructor_called_) return;
00171
00172 std::cerr << "Single registration.\n";
00173 Base::setDrawBox (true);
00174
00175 running_mode_ = RM_REGISTRATION_SINGLE;
00176 emit runningModeChanged (running_mode_);
00177 }
00178
00180
00181 void
00182 pcl::ihs::InHandScanner::showModel ()
00183 {
00184 boost::mutex::scoped_lock lock (mutex_);
00185 if (destructor_called_) return;
00186
00187 std::cerr << "Show the model\n";
00188 Base::setDrawBox (false);
00189
00190 running_mode_ = RM_SHOW_MODEL;
00191 emit runningModeChanged (running_mode_);
00192 }
00193
00195
00196 void
00197 pcl::ihs::InHandScanner::removeUnfitVertices ()
00198 {
00199 boost::mutex::scoped_lock lock (mutex_);
00200 if (destructor_called_) return;
00201
00202 std::cerr << "Removing unfit vertices ...\n";
00203
00204 integration_->removeUnfitVertices (mesh_model_);
00205 if (mesh_model_->emptyVertices ())
00206 {
00207 std::cerr << "Mesh got empty -> Reset\n";
00208 lock.unlock ();
00209 this->reset ();
00210 }
00211 else
00212 {
00213 lock.unlock ();
00214 this->showModel ();
00215 }
00216 }
00217
00219
00220 void
00221 pcl::ihs::InHandScanner::reset ()
00222 {
00223 boost::mutex::scoped_lock lock (mutex_);
00224 if (destructor_called_) return;
00225
00226 std::cerr << "Reset the scanning pipeline.\n";
00227
00228 mesh_model_->clear ();
00229 Base::removeAllMeshes ();
00230
00231 iteration_ = 0;
00232 transformation_ = Eigen::Matrix4f::Identity ();
00233
00234 lock.unlock ();
00235 this->showUnprocessedData ();
00236 }
00237
00239
00240 void
00241 pcl::ihs::InHandScanner::saveAs (const std::string& filename, const FileType& filetype)
00242 {
00243 boost::mutex::scoped_lock lock (mutex_);
00244 if (destructor_called_) return;
00245
00246 pcl::PolygonMesh pm;
00247 pcl::geometry::toFaceVertexMesh (*mesh_model_, pm);
00248
00249 switch (filetype)
00250 {
00251 case FT_PLY: pcl::io::savePLYFile (filename, pm); break;
00252 case FT_VTK: pcl::io::saveVTKFile (filename, pm); break;
00253 default: break;
00254 }
00255 }
00256
00258
00259 void
00260 pcl::ihs::InHandScanner::keyPressEvent (QKeyEvent* event)
00261 {
00262
00263 if (starting_grabber_) return;
00264 if (destructor_called_) return;
00265
00266 switch (event->key ())
00267 {
00268 case Qt::Key_1: this->showUnprocessedData (); break;
00269 case Qt::Key_2: this->showProcessedData (); break;
00270 case Qt::Key_3: this->registerContinuously (); break;
00271 case Qt::Key_4: this->registerOnce (); break;
00272 case Qt::Key_5: this->showModel (); break;
00273 case Qt::Key_6: this->removeUnfitVertices (); break;
00274 case Qt::Key_0: this->reset (); break;
00275 case Qt::Key_C: Base::resetCamera (); break;
00276 case Qt::Key_K: Base::toggleColoring (); break;
00277 case Qt::Key_S: Base::toggleMeshRepresentation (); break;
00278 default: break;
00279 }
00280 }
00281
00283
00284 void
00285 pcl::ihs::InHandScanner::newDataCallback (const CloudXYZRGBAConstPtr& cloud_in)
00286 {
00287 Base::calcFPS (computation_fps_);
00288
00289 boost::mutex::scoped_lock lock (mutex_);
00290 if (destructor_called_) return;
00291
00292 pcl::StopWatch sw;
00293
00294
00295 CloudXYZRGBNormalPtr cloud_data;
00296 CloudXYZRGBNormalPtr cloud_discarded;
00297 if (running_mode_ == RM_SHOW_MODEL)
00298 {
00299 cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
00300 }
00301 else if (running_mode_ == RM_UNPROCESSED)
00302 {
00303 if (!input_data_processing_->calculateNormals (cloud_in, cloud_data))
00304 return;
00305 }
00306 else if (running_mode_ >= RM_PROCESSED)
00307 {
00308 if (!input_data_processing_->segment (cloud_in, cloud_data, cloud_discarded))
00309 return;
00310 }
00311
00312 double time_input_data_processing = sw.getTime ();
00313
00314
00315 if (running_mode_ >= RM_REGISTRATION_CONT)
00316 {
00317 std::cerr << "\nGlobal iteration " << iteration_ << "\n";
00318 std::cerr << "Input data processing:\n"
00319 << " - time : "
00320 << std::setw (8) << std::right << time_input_data_processing << " ms\n";
00321
00322 if (iteration_ == 0)
00323 {
00324 transformation_ = Eigen::Matrix4f::Identity ();
00325
00326 sw.reset ();
00327 integration_->reconstructMesh (cloud_data, mesh_model_);
00328 std::cerr << "Integration:\n"
00329 << " - time reconstruct mesh : "
00330 << std::setw (8) << std::right << sw.getTime () << " ms\n";
00331
00332 cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
00333 ++iteration_;
00334 }
00335 else
00336 {
00337 Eigen::Matrix4f T_final = Eigen::Matrix4f::Identity ();
00338 if (icp_->findTransformation (mesh_model_, cloud_data, transformation_, T_final))
00339 {
00340 transformation_ = T_final;
00341
00342 sw.reset ();
00343 integration_->merge (cloud_data, mesh_model_, transformation_);
00344 std::cerr << "Integration:\n"
00345 << " - time merge : "
00346 << std::setw (8) << std::right << sw.getTime () << " ms\n";
00347
00348 sw.reset ();
00349 integration_->age (mesh_model_);
00350 std::cerr << " - time age : "
00351 << std::setw (8) << std::right << sw.getTime () << " ms\n";
00352
00353 sw.reset ();
00354 std::vector <Mesh::HalfEdgeIndices> boundary_collection;
00355 pcl::geometry::getBoundBoundaryHalfEdges (*mesh_model_, boundary_collection, 1000);
00356 std::cerr << " - time compute boundary : "
00357 << std::setw (8) << std::right << sw.getTime () << " ms\n";
00358
00359 sw.reset ();
00360 mesh_processing_->processBoundary (*mesh_model_, boundary_collection);
00361 std::cerr << " - time mesh processing : "
00362 << std::setw (8) << std::right << sw.getTime () << " ms\n";
00363
00364 cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
00365 ++iteration_;
00366 }
00367 }
00368 }
00369
00370
00371 double time_model = 0;
00372 double time_data = 0;
00373
00374 if (mesh_model_->empty ()) Base::setPivot ("data");
00375 else Base::setPivot ("model");
00376
00377 sw.reset ();
00378 Base::addMesh (mesh_model_, "model", Eigen::Isometry3d (transformation_.inverse ().cast <double> ()));
00379 time_model = sw.getTime ();
00380
00381 sw.reset ();
00382 Base::addMesh (cloud_data , "data");
00383
00384 if (running_mode_ < RM_REGISTRATION_CONT && cloud_discarded)
00385 {
00386 Base::addMesh (cloud_discarded, "cloud_discarded");
00387 }
00388 else
00389 {
00390 Base::removeMesh ("cloud_discarded");
00391 }
00392 time_data = sw.getTime ();
00393
00394 if (running_mode_ >= RM_REGISTRATION_CONT)
00395 {
00396 std::cerr << "Copy to visualization thread:\n"
00397 << " - time model : "
00398 << std::setw (8) << std::right << time_model << " ms\n"
00399 << " - time data : "
00400 << std::setw (8) << std::right << time_data << " ms\n";
00401 }
00402
00403 if (running_mode_ == RM_REGISTRATION_SINGLE)
00404 {
00405 lock.unlock ();
00406 this->showProcessedData ();
00407 }
00408 }
00409
00411
00412 void
00413 pcl::ihs::InHandScanner::paintEvent (QPaintEvent* event)
00414 {
00415
00416 if (destructor_called_) return;
00417
00418 Base::calcFPS (visualization_fps_);
00419 Base::BoxCoefficients coeffs (input_data_processing_->getXMin (),
00420 input_data_processing_->getXMax (),
00421 input_data_processing_->getYMin (),
00422 input_data_processing_->getYMax (),
00423 input_data_processing_->getZMin (),
00424 input_data_processing_->getZMax (),
00425 Eigen::Isometry3d::Identity ());
00426 Base::setBoxCoefficients (coeffs);
00427
00428 Base::setVisibilityConfidenceNormalization (static_cast <float> (integration_->getMinDirections ()));
00429
00430
00431 Base::paintEvent (event);
00432 this->drawText ();
00433 }
00434
00436
00437 void
00438 pcl::ihs::InHandScanner::drawText ()
00439 {
00440 QPainter painter (this);
00441 painter.setPen (Qt::white);
00442 QFont font;
00443
00444 if (starting_grabber_)
00445 {
00446 font.setPointSize (this->width () / 20);
00447 painter.setFont (font);
00448 painter.drawText (0, 0, this->width (), this->height (), Qt::AlignHCenter | Qt::AlignVCenter, "Starting the grabber.\n Please wait.");
00449 }
00450 else
00451 {
00452 std::string vis_fps ("Visualization: "), comp_fps ("Computation: ");
00453
00454 vis_fps.append (visualization_fps_.str ()).append (" fps");
00455 comp_fps.append (computation_fps_.str ()).append (" fps");
00456
00457 const std::string str = std::string (comp_fps).append ("\n").append (vis_fps);
00458
00459 font.setPointSize (this->width () / 50);
00460
00461 painter.setFont (font);
00462 painter.drawText (0, 0, this->width (), this->height (), Qt::AlignBottom | Qt::AlignLeft, str.c_str ());
00463 }
00464 }
00465
00467
00468 void
00469 pcl::ihs::InHandScanner::startGrabberImpl ()
00470 {
00471 boost::mutex::scoped_lock lock (mutex_);
00472 starting_grabber_ = true;
00473 lock.unlock ();
00474
00475 try
00476 {
00477 grabber_ = GrabberPtr (new Grabber ());
00478 }
00479 catch (const pcl::PCLException& e)
00480 {
00481 std::cerr << "ERROR in in_hand_scanner.cpp: " << e.what () << std::endl;
00482 exit (EXIT_FAILURE);
00483 }
00484
00485 lock.lock ();
00486 if (destructor_called_) return;
00487
00488 boost::function <void (const CloudXYZRGBAConstPtr&)> new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1);
00489 new_data_connection_ = grabber_->registerCallback (new_data_cb);
00490 grabber_->start ();
00491
00492 starting_grabber_ = false;
00493 }
00494