filter_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-, Open Perception, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the copyright holder(s) nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES  (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #include <pcl/apps/optronic_viewer/filter_window.h>
00039 
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/fotonic_grabber.h>
00042 
00043 #include <fz_api.h>
00044 #include <fz_internal.h>
00045 
00046 #include <QFileInfo>
00047 #include <vtkActor.h>
00048 #include <vtkRenderer.h>
00049 
00050 
00052 pcl::apps::optronic_viewer::
00053 FilterWindow::
00054 FilterWindow (std::vector<CloudFilterFactory*> & filter_factories, std::vector<CloudFilter*> & filter_list)
00055 : filter_factories_ (filter_factories)
00056 , filter_selection_combo_box_ (NULL)
00057 , filter_list_ (&filter_list)
00058 , filter_ (NULL)
00059 {
00060   this->setOption (QWizard::IndependentPages, true);
00061 
00062   createFilterSelectionPage ();
00063 
00064   filter_ = filter_factories_[0]->create ();
00065 
00066   QString name (filter_factories_[0]->getName ().c_str ());
00067   filter_name_line_edit_->setText (name);
00068 
00069   if (filter_factories.size () > 0)
00070     last_added_page_id_ = this->addPage (filter_->getParameterPage ());
00071 
00072   connect (this->button (FinishButton), SIGNAL (released ()),this, SLOT (finished ()));
00073 }
00074 
00076 pcl::apps::optronic_viewer::
00077 FilterWindow::
00078 ~FilterWindow ()
00079 {
00080 }
00081 
00083 void
00084 pcl::apps::optronic_viewer::
00085 FilterWindow::
00086 itemSelected (int id)
00087 {
00088   std::cerr << "item " << id << " selected" << std::endl;
00089 
00090   delete filter_;
00091   filter_ = filter_factories_[id]->create ();
00092 
00093   QString name (filter_factories_[id]->getName ().c_str ());
00094   filter_name_line_edit_->setText (name);
00095 
00096   int tmp = this->addPage (filter_->getParameterPage ());
00097   this->removePage (last_added_page_id_);
00098   last_added_page_id_ = tmp;
00099   this->update ();
00100 }
00101 
00103 void
00104 pcl::apps::optronic_viewer::
00105 FilterWindow::
00106 finished ()
00107 {
00108   std::cerr << "finished" << std::endl;
00109 
00110   filter_->setName (filter_name_line_edit_->text ().toStdString ());
00111   filter_list_->push_back (filter_);
00112 
00113   emit filterCreated ();
00114 }
00115 
00117 void
00118 pcl::apps::optronic_viewer::
00119 FilterWindow::
00120 next ()
00121 {
00122   std::cerr << "next" << std::endl;
00123   this->QWizard::next ();
00124 }
00125 
00127 void
00128 pcl::apps::optronic_viewer::
00129 FilterWindow::
00130 createFilterSelectionPage ()
00131 {
00132   QWizardPage * filter_selection_page = new QWizardPage ();
00133 
00134   QLabel * select_filter_label = new QLabel (tr ("Select Filter:"));
00135   filter_selection_combo_box_ = new QComboBox ();
00136 
00137   if (filter_factories_.empty ())
00138     filter_selection_combo_box_->addItem (tr ("none"));
00139   else
00140     fillFilterSelectionComboBox (filter_selection_combo_box_);
00141 
00142   connect (filter_selection_combo_box_, SIGNAL (currentIndexChanged (int)),this, SLOT (itemSelected (int)));
00143 
00144   QLabel * filter_name_label = new QLabel (tr ("Filter Name:"));
00145   filter_name_line_edit_ = new QLineEdit ();
00146 
00147   QVBoxLayout * main_layout = new QVBoxLayout (filter_selection_page);
00148   main_layout->addWidget (select_filter_label);
00149   main_layout->addWidget (filter_selection_combo_box_);
00150   main_layout->addWidget (filter_name_label);
00151   main_layout->addWidget (filter_name_line_edit_);
00152 
00153   this->addPage (filter_selection_page);
00154 }
00155 
00157 void
00158 pcl::apps::optronic_viewer::
00159 FilterWindow::
00160 fillFilterSelectionComboBox (QComboBox * combo_box)
00161 {
00162   for (int factory_index = 0; factory_index < filter_factories_.size (); ++factory_index)
00163   {
00164     std::string name = filter_factories_[factory_index]->getName ();
00165 
00166     combo_box->addItem (tr (name.c_str ()));
00167   }
00168 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:08