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) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  */
00036 
00037 #include <pcl/apps/modeler/main_window.h>
00038 
00039 #include <pcl/apps/modeler/scene_tree.h>
00040 #include <pcl/apps/modeler/dock_widget.h>
00041 #include <pcl/apps/modeler/render_window.h>
00042 #include <pcl/apps/modeler/render_window_item.h>
00043 
00044 #include <QFileInfo>
00045 #include <vtkActor.h>
00046 #include <vtkRenderer.h>
00047 
00048 
00050 pcl::modeler::MainWindow::MainWindow()
00051   : ui_(new Ui::MainWindow)
00052 {
00053   ui_->setupUi(this);
00054 
00055   RenderWindowItem* central_render_window_item = new RenderWindowItem(ui_->scene_tree_);
00056   central_render_window_item->getRenderWindow()->setParent(this);
00057   setCentralWidget(central_render_window_item->getRenderWindow());
00058   ui_->scene_tree_->addTopLevelItem(central_render_window_item);
00059 
00060   connectFileMenuActions();
00061   connectViewMenuActions();
00062   connectEditMenuActions();
00063 
00064   loadGlobalSettings();
00065 
00066   showMaximized();
00067 }
00068 
00070 pcl::modeler::MainWindow::~MainWindow()
00071 {
00072   saveGlobalSettings();
00073 }
00074 
00076 void 
00077 pcl::modeler::MainWindow::connectFileMenuActions()
00078 {
00079   connect(ui_->actionOpenPointCloud, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotOpenPointCloud()));
00080   connect(ui_->actionImportPointCloud, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotImportPointCloud()));
00081   connect(ui_->actionSavePointCloud, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotSavePointCloud()));
00082   connect(ui_->actionClosePointCloud, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotClosePointCloud()));
00083   connect(ui_->scene_tree_, SIGNAL(fileOpened(QString)), this, SLOT(slotUpdateRecentFile(QString)));
00084   createRecentPointCloudActions();
00085 
00086   connect(ui_->actionOpenProject, SIGNAL(triggered()), this, SLOT(slotOpenProject()));
00087   connect(ui_->actionSaveProject, SIGNAL(triggered()), this, SLOT(slotSaveProject()));
00088   connect(ui_->actionCloseProject, SIGNAL(triggered()), this, SLOT(slotCloseProject()));
00089   createRecentProjectActions();
00090 
00091   connect(ui_->actionExit, SIGNAL(triggered()), this, SLOT(slotExit()));
00092 }
00093 
00095 void 
00096 pcl::modeler::MainWindow::connectViewMenuActions()
00097 {
00098   connect(ui_->actionCreateRenderWindow, SIGNAL(triggered()), this, SLOT(slotCreateRenderWindow()));
00099   connect(ui_->actionCloseRenderWindow, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotCloseRenderWindow()));
00100 }
00101 
00103 void 
00104 pcl::modeler::MainWindow::connectEditMenuActions()
00105 {
00106   connect(ui_->actionICPRegistration, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotICPRegistration()));
00107   connect(ui_->actionVoxelGridDownsample, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotVoxelGridDownsampleFilter()));
00108   connect(ui_->actionStatisticalOutlierRemoval, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotStatisticalOutlierRemovalFilter()));
00109   connect(ui_->actionEstimateNormals, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotEstimateNormal()));
00110   connect(ui_->actionPoissonReconstruction, SIGNAL(triggered()), ui_->scene_tree_, SLOT(slotPoissonReconstruction()));
00111 }
00112 
00114 void 
00115 pcl::modeler::MainWindow::slotOpenProject()
00116 {
00117 
00118 }
00119 
00121 void 
00122 pcl::modeler::MainWindow::slotSaveProject()
00123 {
00124 
00125 }
00126 
00128 void 
00129 pcl::modeler::MainWindow::slotCloseProject()
00130 {
00131 
00132 }
00133 
00135 void
00136 pcl::modeler::MainWindow::slotExit() {
00137     saveGlobalSettings();
00138     qApp->exit();
00139 }
00140 
00142 void
00143 pcl::modeler::MainWindow::slotUpdateRecentFile(const QString& filename)
00144 {
00145   recent_files_.removeAll(filename);
00146   recent_files_.prepend(filename);
00147 }
00148 
00150 pcl::modeler::RenderWindowItem*
00151 pcl::modeler::MainWindow::createRenderWindow()
00152 {
00153   DockWidget* dock_widget = new DockWidget(this);
00154   addDockWidget(Qt::RightDockWidgetArea, dock_widget);
00155   dock_widget->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea);
00156 
00157   RenderWindowItem* render_window_item = new RenderWindowItem(ui_->scene_tree_);
00158   render_window_item->getRenderWindow()->setParent(dock_widget);
00159   dock_widget->setWidget(render_window_item->getRenderWindow());
00160   ui_->scene_tree_->addTopLevelItem(render_window_item);
00161 
00162   // add the toggle action to view menu
00163   QList<QAction *> actions = ui_->menuView->actions();
00164   ui_->menuView->insertAction(actions[actions.size()-2], dock_widget->toggleViewAction());
00165 
00166   return render_window_item;
00167 }
00168 
00170 void
00171 pcl::modeler::MainWindow::slotCreateRenderWindow()
00172 {
00173   createRenderWindow();
00174 
00175   return;
00176 }
00177 
00179 void 
00180 pcl::modeler::MainWindow::slotOpenRecentPointCloud()
00181 {
00182   QAction* action = qobject_cast<QAction*>(sender());
00183   if (action)
00184     ui_->scene_tree_->openPointCloud(action->data().toString());
00185 
00186   return;
00187 }
00188 
00190 void 
00191 pcl::modeler::MainWindow::slotOpenRecentProject()
00192 {
00193   QAction* action = qobject_cast<QAction*>(sender());
00194   if (action)
00195     openProjectImpl(action->data().toString());
00196 
00197   return;
00198 }
00199 
00201 void 
00202 pcl::modeler::MainWindow::createRecentPointCloudActions()
00203 {
00204   for (size_t i = 0; i < MAX_RECENT_NUMBER; ++ i)
00205   {
00206     recent_pointcloud_actions_.push_back(boost::shared_ptr<QAction>(new QAction(this)));
00207     ui_->menuRecentPointClouds->addAction(recent_pointcloud_actions_[i].get());
00208     recent_pointcloud_actions_[i]->setVisible(false);
00209     connect(recent_pointcloud_actions_[i].get(), SIGNAL(triggered()), this, SLOT(slotOpenRecentPointCloud()));
00210   }
00211 
00212   return;
00213 }
00214 
00216 void 
00217 pcl::modeler::MainWindow::updateRecentPointCloudActions()
00218 {
00219   updateRecentActions(recent_pointcloud_actions_, recent_files_);
00220 
00221   return;
00222 }
00223 
00225 void 
00226 pcl::modeler::MainWindow::createRecentProjectActions()
00227 {
00228   for (size_t i = 0; i < MAX_RECENT_NUMBER; ++ i)
00229   {
00230     recent_project_actions_.push_back(boost::shared_ptr<QAction>(new QAction(this)));
00231     ui_->menuRecentPointClouds->addAction(recent_project_actions_[i].get());
00232     recent_project_actions_[i]->setVisible(false);
00233     connect(recent_project_actions_[i].get(), SIGNAL(triggered()), this, SLOT(slotOpenRecentProject()));
00234   }
00235 
00236   return;
00237 }
00238 
00240 void 
00241 pcl::modeler::MainWindow::updateRecentProjectActions()
00242 {
00243   updateRecentActions(recent_project_actions_, recent_projects_);
00244 
00245   return;
00246 }
00247 
00249 bool 
00250 pcl::modeler::MainWindow::openProjectImpl (const QString&)
00251 {
00252   return (true);
00253 }
00254 
00256 void 
00257 pcl::modeler::MainWindow::updateRecentActions (std::vector<boost::shared_ptr<QAction> >& recent_actions, QStringList& recent_items)
00258 {
00259   QMutableStringListIterator recent_items_it (recent_items);
00260   while (recent_items_it.hasNext ())
00261   {
00262     if (!QFile::exists (recent_items_it.next ()))
00263       recent_items_it.remove ();
00264   }
00265 
00266   recent_items.removeDuplicates ();
00267   int recent_number = std::min (int (MAX_RECENT_NUMBER), recent_items.size ());
00268   for (int i = 0; i < recent_number; ++ i)
00269   {
00270     QString text = tr ("%1 %2").arg (i + 1).arg (recent_items[i]);
00271     recent_actions[i]->setText (text);
00272     recent_actions[i]->setData (recent_items[i]);
00273     recent_actions[i]->setVisible (true);
00274   }
00275 
00276   for (size_t i = recent_number, i_end = recent_actions.size (); i < i_end; ++ i)
00277     recent_actions[i]->setVisible (false);
00278 
00279   while (recent_items.size () > recent_number)
00280     recent_items.pop_back ();
00281 }
00282 
00284 QString 
00285 pcl::modeler::MainWindow::getRecentFolder()
00286 {
00287   QString recent_filename;
00288   if (!recent_projects_.empty())
00289     recent_filename = recent_projects_.front();
00290   else if (!recent_files_.empty())
00291     recent_filename = recent_files_.front();
00292 
00293   if (!recent_filename.isEmpty())
00294     return QFileInfo(recent_filename).path();
00295 
00296   return (QString("."));
00297 }
00298 
00300 void 
00301 pcl::modeler::MainWindow::loadGlobalSettings()
00302 {
00303   QSettings global_settings("PCL", "Modeler");
00304 
00305   recent_files_ = global_settings.value("recent_pointclouds").toStringList();
00306   updateRecentPointCloudActions();
00307 
00308   recent_projects_ = global_settings.value("recent_projects").toStringList();
00309   updateRecentProjectActions();
00310 
00311   return;
00312 }
00313 
00315 void 
00316 pcl::modeler::MainWindow::saveGlobalSettings()
00317 {
00318   QSettings global_settings("PCL", "Modeler");
00319 
00320   global_settings.setValue("recent_pointclouds", recent_files_);
00321 
00322   global_settings.setValue("recent_projects", recent_projects_);
00323 
00324   return;
00325 }
00326 
00328 void 
00329 pcl::modeler::MainWindow::slotOnWorkerStarted()
00330 {
00331   statusBar()->showMessage(QString("Working thread running..."));
00332 }
00333 
00335 void 
00336 pcl::modeler::MainWindow::slotOnWorkerFinished()
00337 {
00338   statusBar()->showMessage(QString("Working thread finished..."));
00339 }


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