main_window.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) 2009-2012, 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  * $Id$
00038  *
00039  */
00040 
00041 #include <pcl/apps/in_hand_scanner/main_window.h>
00042 #include "ui_main_window.h"
00043 
00044 #include <limits>
00045 
00046 #include <QDoubleValidator>
00047 #include <QFileDialog>
00048 #include <QHBoxLayout>
00049 #include <QMessageBox>
00050 #include <QString>
00051 #include <QTimer>
00052 
00053 #include <pcl/apps/in_hand_scanner/help_window.h>
00054 #include <pcl/apps/in_hand_scanner/in_hand_scanner.h>
00055 #include <pcl/apps/in_hand_scanner/input_data_processing.h>
00056 #include <pcl/apps/in_hand_scanner/icp.h>
00057 #include <pcl/apps/in_hand_scanner/integration.h>
00058 
00060 
00061 pcl::ihs::MainWindow::MainWindow (QWidget* parent)
00062   : QMainWindow  (parent),
00063     ui_          (new Ui::MainWindow ()),
00064     help_window_ (new HelpWindow (this)),
00065     ihs_         (new InHandScanner ())
00066 {
00067   ui_->setupUi (this);
00068 
00069   QWidget* spacer = new QWidget ();
00070   spacer->setSizePolicy (QSizePolicy::Expanding, QSizePolicy::Expanding);
00071   ui_->toolBar->insertWidget (ui_->actionHelp, spacer);
00072 
00073   const double max = std::numeric_limits <double>::max ();
00074 
00075   // In hand scanner
00076   QHBoxLayout* layout = new QHBoxLayout (ui_->placeholder_in_hand_scanner);
00077   layout->addWidget (ihs_);
00078   // ui_->centralWidget->setLayout (layout);
00079 
00080   QTimer::singleShot (0, ihs_, SLOT (startGrabber ()));
00081 
00082   connect (ui_->toolButton_1, SIGNAL (clicked ()), ihs_, SLOT (showUnprocessedData ()));
00083   connect (ui_->toolButton_2, SIGNAL (clicked ()), ihs_, SLOT (showProcessedData ()));
00084   connect (ui_->toolButton_3, SIGNAL (clicked ()), ihs_, SLOT (registerContinuously ()));
00085   connect (ui_->toolButton_4, SIGNAL (clicked ()), ihs_, SLOT (registerOnce ()));
00086   connect (ui_->toolButton_5, SIGNAL (clicked ()), ihs_, SLOT (showModel ()));
00087   connect (ui_->toolButton_6, SIGNAL (clicked ()), ihs_, SLOT (removeUnfitVertices ()));
00088   connect (ui_->toolButton_0, SIGNAL (clicked ()), ihs_, SLOT (reset ()));
00089 
00090   connect (ui_->actionReset_camera,        SIGNAL (triggered ()), ihs_, SLOT (resetCamera ()));
00091   connect (ui_->actionToggle_coloring,     SIGNAL (triggered ()), ihs_, SLOT (toggleColoring ()));
00092   connect (ui_->actionMesh_representation, SIGNAL (triggered ()), ihs_, SLOT (toggleMeshRepresentation ()));
00093 
00094   connect (ui_->actionSaveAs, SIGNAL (triggered ()), this, SLOT (saveAs ()));
00095 
00096   connect (ihs_, SIGNAL (runningModeChanged (RunningMode)), this, SLOT (runningModeChanged (RunningMode)));
00097 
00098   // Input data processing
00099   const pcl::ihs::InputDataProcessing& idp = ihs_->getInputDataProcessing ();
00100 
00101   ui_->spinBox_x_min->setValue (static_cast <int> (idp.getXMin ()));
00102   ui_->spinBox_x_max->setValue (static_cast <int> (idp.getXMax ()));
00103   ui_->spinBox_y_min->setValue (static_cast <int> (idp.getYMin ()));
00104   ui_->spinBox_y_max->setValue (static_cast <int> (idp.getYMax ()));
00105   ui_->spinBox_z_min->setValue (static_cast <int> (idp.getZMin ()));
00106   ui_->spinBox_z_max->setValue (static_cast <int> (idp.getZMax ()));
00107 
00108   ui_->spinBox_h_min->setValue (static_cast <int> (idp.getHMin ()));
00109   ui_->spinBox_h_max->setValue (static_cast <int> (idp.getHMax ()));
00110   ui_->spinBox_s_min->setValue (static_cast <int> (idp.getSMin () * 100.f));
00111   ui_->spinBox_s_max->setValue (static_cast <int> (idp.getSMax () * 100.f));
00112   ui_->spinBox_v_min->setValue (static_cast <int> (idp.getVMin () * 100.f));
00113   ui_->spinBox_v_max->setValue (static_cast <int> (idp.getVMax () * 100.f));
00114 
00115   ui_->checkBox_color_segmentation_inverted->setChecked (idp.getColorSegmentationInverted ());
00116   ui_->checkBox_color_segmentation_enabled->setChecked (idp.getColorSegmentationEnabled ());
00117 
00118   ui_->spinBox_xyz_erode_size->setValue  (idp.getXYZErodeSize ());
00119   ui_->spinBox_hsv_dilate_size->setValue (idp.getHSVDilateSize ());
00120 
00121   // Registration
00122   ui_->lineEdit_epsilon->setValidator (new QDoubleValidator (0., max, 2));
00123   ui_->lineEdit_max_fitness->setValidator (new QDoubleValidator (0., max, 2));
00124 
00125   ui_->lineEdit_epsilon->setText (QString ().setNum (ihs_->getICP ().getEpsilon ()));
00126   ui_->spinBox_max_iterations->setValue (static_cast <int> (ihs_->getICP ().getMaxIterations ()));
00127   ui_->spinBox_min_overlap->setValue (static_cast <int> (100.f * ihs_->getICP ().getMinOverlap ()));
00128   ui_->lineEdit_max_fitness->setText (QString ().setNum (ihs_->getICP ().getMaxFitness ()));
00129 
00130   ui_->doubleSpinBox_correspondence_rejection_factor->setValue (ihs_->getICP ().getCorrespondenceRejectionFactor ());
00131   ui_->spinBox_correspondence_rejection_max_angle->setValue (static_cast <int> (ihs_->getICP ().getMaxAngle ()));
00132 
00133   // Integration
00134   ui_->lineEdit_max_squared_distance->setValidator (new QDoubleValidator (0., max, 2));
00135 
00136   ui_->lineEdit_max_squared_distance->setText (QString ().setNum (ihs_->getIntegration ().getMaxSquaredDistance ()));
00137   ui_->spinBox_averaging_max_angle->setValue (static_cast <int> (ihs_->getIntegration ().getMaxAngle ()));
00138   ui_->spinBox_max_age->setValue (static_cast <int> (ihs_->getIntegration ().getMaxAge ()));
00139   ui_->spinBox_min_directions->setValue (static_cast <int> (ihs_->getIntegration ().getMinDirections ()));
00140 
00141   // Help
00142   connect (ui_->actionHelp, SIGNAL (triggered ()), this, SLOT (showHelp ()));
00143 }
00144 
00146 
00147 pcl::ihs::MainWindow::~MainWindow ()
00148 {
00149   delete ui_;
00150 }
00151 
00153 
00154 void
00155 pcl::ihs::MainWindow::showHelp ()
00156 {
00157   help_window_->show ();
00158 }
00159 
00161 
00162 void
00163 pcl::ihs::MainWindow::saveAs ()
00164 {
00165   QString filename = QFileDialog::getSaveFileName (this, "Save the model mesh.", "", "Polygon File Format (*.ply);;VTK File Format (*.vtk)");
00166 
00167   if (filename.isEmpty ()) return;
00168 
00169   if      (filename.endsWith ("ply", Qt::CaseInsensitive))
00170     ihs_->saveAs (filename.toStdString (), pcl::ihs::InHandScanner::FT_PLY);
00171   else if (filename.endsWith ("vtk", Qt::CaseInsensitive))
00172     ihs_->saveAs (filename.toStdString (), pcl::ihs::InHandScanner::FT_VTK);
00173 }
00174 
00176 
00177 void
00178 pcl::ihs::MainWindow::runningModeChanged (const RunningMode mode)
00179 {
00180   switch (mode)
00181   {
00182     case InHandScanner::RM_UNPROCESSED:         ui_->toolButton_1->setChecked (true); break;
00183     case InHandScanner::RM_PROCESSED:           ui_->toolButton_2->setChecked (true); break;
00184     case InHandScanner::RM_REGISTRATION_CONT:   ui_->toolButton_3->setChecked (true); break;
00185     case InHandScanner::RM_REGISTRATION_SINGLE:                                       break;
00186     case InHandScanner::RM_SHOW_MODEL:          ui_->toolButton_5->setChecked (true); break;
00187   }
00188 }
00189 
00191 
00192 void
00193 pcl::ihs::MainWindow::keyPressEvent (QKeyEvent* event)
00194 {
00195   ihs_->keyPressEvent (event);
00196 }
00197 
00199 
00200 void
00201 pcl::ihs::MainWindow::setXMin (const int x_min)
00202 {
00203   ihs_->getInputDataProcessing ().setXMin (static_cast <float> (x_min));
00204   ui_->spinBox_x_min->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getXMin ()));
00205 }
00206 
00207 void
00208 pcl::ihs::MainWindow::setXMax (const int x_max)
00209 {
00210   ihs_->getInputDataProcessing ().setXMax (static_cast <float> (x_max));
00211   ui_->spinBox_x_max->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getXMax ()));
00212 }
00213 
00214 void
00215 pcl::ihs::MainWindow::setYMin (const int y_min)
00216 {
00217   ihs_->getInputDataProcessing ().setYMin (static_cast <float> (y_min));
00218   ui_->spinBox_y_min->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getYMin ()));
00219 }
00220 
00221 void
00222 pcl::ihs::MainWindow::setYMax (const int y_max)
00223 {
00224   ihs_->getInputDataProcessing ().setYMax (static_cast <float> (y_max));
00225   ui_->spinBox_y_max->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getYMax ()));
00226 }
00227 
00228 void
00229 pcl::ihs::MainWindow::setZMin (const int z_min)
00230 {
00231   ihs_->getInputDataProcessing ().setZMin (static_cast <float> (z_min));
00232   ui_->spinBox_z_min->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getZMin ()));
00233 }
00234 
00235 void
00236 pcl::ihs::MainWindow::setZMax (const int z_max)
00237 {
00238   ihs_->getInputDataProcessing ().setZMax (static_cast <float> (z_max));
00239   ui_->spinBox_z_max->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getZMax ()));
00240 }
00241 
00243 
00244 void
00245 pcl::ihs::MainWindow::setHMin (const int h_min)
00246 {
00247   ihs_->getInputDataProcessing ().setHMin (static_cast <float> (h_min));
00248   ui_->spinBox_h_min->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getHMin ()));
00249 }
00250 
00251 void
00252 pcl::ihs::MainWindow::setHMax (const int h_max)
00253 {
00254   ihs_->getInputDataProcessing ().setHMax (static_cast <float> (h_max));
00255   ui_->spinBox_h_max->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getHMax ()));
00256 }
00257 
00258 void
00259 pcl::ihs::MainWindow::setSMin (const int s_min)
00260 {
00261   ihs_->getInputDataProcessing ().setSMin (.01f * static_cast <float> (s_min));
00262   ui_->spinBox_s_min->setValue (static_cast <int> (100.f * ihs_->getInputDataProcessing ().getSMin () + 0.5f));
00263 }
00264 
00265 void
00266 pcl::ihs::MainWindow::setSMax (const int s_max)
00267 {
00268   ihs_->getInputDataProcessing ().setSMax (.01f * static_cast <float> (s_max));
00269   ui_->spinBox_s_max->setValue (static_cast <int> (100.f * ihs_->getInputDataProcessing ().getSMax () + 0.5f));
00270 }
00271 
00272 void
00273 pcl::ihs::MainWindow::setVMin (const int v_min)
00274 {
00275   ihs_->getInputDataProcessing ().setVMin (.01f * static_cast <float> (v_min));
00276   ui_->spinBox_v_min->setValue (static_cast <int> (100.f * ihs_->getInputDataProcessing ().getVMin () + 0.5f));
00277 }
00278 
00279 void
00280 pcl::ihs::MainWindow::setVMax (const int v_max)
00281 {
00282   ihs_->getInputDataProcessing ().setVMax (.01f * static_cast <float> (v_max));
00283   ui_->spinBox_v_max->setValue (static_cast <int> (100.f * ihs_->getInputDataProcessing ().getVMax () + 0.5f));
00284 }
00285 
00286 void
00287 pcl::ihs::MainWindow::setColorSegmentationInverted (const bool is_inverted)
00288 {
00289   ihs_->getInputDataProcessing ().setColorSegmentationInverted (is_inverted);
00290   ui_->checkBox_color_segmentation_inverted->setChecked (ihs_->getInputDataProcessing ().getColorSegmentationInverted ());
00291 }
00292 
00293 void
00294 pcl::ihs::MainWindow::setColorSegmentationEnabled (const bool is_enabled)
00295 {
00296   ihs_->getInputDataProcessing ().setColorSegmentationEnabled (is_enabled);
00297   ui_->checkBox_color_segmentation_enabled->setChecked (ihs_->getInputDataProcessing ().getColorSegmentationEnabled ());
00298 }
00299 
00300 void
00301 pcl::ihs::MainWindow::setXYZErodeSize (const int size)
00302 {
00303   ihs_->getInputDataProcessing ().setXYZErodeSize (static_cast <unsigned int> (size));
00304   ui_->spinBox_xyz_erode_size->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getXYZErodeSize ()));
00305 }
00306 
00307 void
00308 pcl::ihs::MainWindow::setHSVDilateSize (const int size)
00309 {
00310   ihs_->getInputDataProcessing ().setHSVDilateSize (static_cast <unsigned int> (size));
00311   ui_->spinBox_hsv_dilate_size->setValue (static_cast <int> (ihs_->getInputDataProcessing ().getHSVDilateSize ()));
00312 }
00313 
00315 
00316 void
00317 pcl::ihs::MainWindow::setEpsilon ()
00318 {
00319   ihs_->getICP ().setEpsilon (ui_->lineEdit_epsilon->text ().toFloat ());
00320   ui_->lineEdit_epsilon->setText (QString ().setNum (ihs_->getICP ().getEpsilon ()));
00321 }
00322 
00323 void
00324 pcl::ihs::MainWindow::setMaxIterations (const int iterations)
00325 {
00326   ihs_->getICP ().setMaxIterations (static_cast <unsigned int> (iterations));
00327   ui_->spinBox_max_iterations->setValue (static_cast <int> (ihs_->getICP ().getMaxIterations ()));
00328 }
00329 
00330 void
00331 pcl::ihs::MainWindow::setMinOverlap (const int overlap)
00332 {
00333   ihs_->getICP ().setMinOverlap (.01f * static_cast <float> (overlap));
00334   ui_->spinBox_min_overlap->setValue (static_cast <int> (100.f * ihs_->getICP ().getMinOverlap () + 0.5f));
00335 }
00336 
00337 void
00338 pcl::ihs::MainWindow::setMaxFitness ()
00339 {
00340   ihs_->getICP ().setMaxFitness (ui_->lineEdit_max_fitness->text ().toFloat ());
00341   ui_->lineEdit_max_fitness->setText (QString ().setNum (ihs_->getICP ().getMaxFitness ()));
00342 }
00343 
00344 void
00345 pcl::ihs::MainWindow::setCorrespondenceRejectionFactor (const double factor)
00346 {
00347   ihs_->getICP ().setCorrespondenceRejectionFactor (static_cast <float> (factor));
00348   ui_->doubleSpinBox_correspondence_rejection_factor->setValue (static_cast <double> (ihs_->getICP ().getCorrespondenceRejectionFactor ()));
00349 }
00350 
00351 void
00352 pcl::ihs::MainWindow::setCorrespondenceRejectionMaxAngle (const int angle)
00353 {
00354   ihs_->getICP ().setMaxAngle (static_cast <float> (angle));
00355   ui_->spinBox_correspondence_rejection_max_angle->setValue (static_cast <int> (ihs_->getICP ().getMaxAngle ()));
00356 }
00357 
00359 
00360 void
00361 pcl::ihs::MainWindow::setMaxSquaredDistance ()
00362 {
00363   ihs_->getIntegration ().setMaxSquaredDistance (ui_->lineEdit_max_squared_distance->text ().toFloat ());
00364   ui_->lineEdit_max_squared_distance->setText (QString ().setNum (ihs_->getIntegration ().getMaxSquaredDistance ()));
00365 }
00366 
00367 void
00368 pcl::ihs::MainWindow::setAveragingMaxAngle (const int angle)
00369 {
00370   ihs_->getIntegration ().setMaxAngle (static_cast <float> (angle));
00371   ui_->spinBox_averaging_max_angle->setValue (static_cast <int> (ihs_->getIntegration ().getMaxAngle ()));
00372 }
00373 
00374 void
00375 pcl::ihs::MainWindow::setMaxAge (const int age)
00376 {
00377   ihs_->getIntegration ().setMaxAge (static_cast <unsigned int> (age));
00378   ui_->spinBox_max_age->setValue (static_cast <int> (ihs_->getIntegration ().getMaxAge ()));
00379 }
00380 
00381 void
00382 pcl::ihs::MainWindow::setMinDirections (const int directions)
00383 {
00384   ihs_->getIntegration ().setMinDirections (static_cast <unsigned int> (directions));
00385   ui_->spinBox_min_directions->setValue (static_cast <int> (ihs_->getIntegration ().getMinDirections ()));
00386 }
00387 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:20