parameter_dialog.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/parameter_dialog.h>
00038 #include <pcl/apps/modeler/parameter.h>
00039 
00040 #include <cassert>
00041 #include <fstream>
00042 
00044 void
00045 pcl::modeler::ParameterDialog::addParameter(pcl::modeler::Parameter* parameter)
00046 {
00047   if (name_parameter_map_.find(parameter->getName()) == name_parameter_map_.end())
00048   {
00049     name_parameter_map_.insert(std::make_pair(parameter->getName(), parameter));
00050   }
00051   else
00052   {
00053     assert(false);
00054   }
00055   return;
00056 }
00057 
00059 pcl::modeler::ParameterDialog::ParameterDialog(const std::string& title, QWidget* parent) : QDialog(parent), parameter_model_(NULL)
00060 {
00061   setModal(false);
00062   setWindowTitle(QString(title.c_str())+" Parameters");
00063 }
00064 
00066 int
00067 pcl::modeler::ParameterDialog::exec()
00068 {
00069   pcl::modeler::ParameterModel parameterModel (int (name_parameter_map_.size ()), 2, this);
00070   parameter_model_ = &parameterModel;
00071 
00072   QStringList headerLabels;
00073   headerLabels.push_back("Variable Name");
00074   headerLabels.push_back("Variable Value");
00075   parameterModel.setHorizontalHeaderLabels(headerLabels);
00076 
00077   QTableView tableView(this);
00078   tableView.setModel(&parameterModel);
00079 
00080   size_t currentRow = 0;
00081   for(std::map<std::string, Parameter*>::iterator it = name_parameter_map_.begin();
00082     it != name_parameter_map_.end();
00083     ++ it)
00084   {
00085     QModelIndex name = parameterModel.index(int (currentRow), 0, QModelIndex());
00086     parameterModel.setData(name, QVariant(it->first.c_str()));
00087 
00088     QModelIndex value = parameterModel.index(int (currentRow), 1, QModelIndex());
00089     std::pair<QVariant, int> model_data = it->second->toModelData();
00090     parameterModel.setData(value, model_data.first, model_data.second);
00091 
00092     currentRow ++;
00093   }
00094 
00095   ParameterDelegate parameterDelegate(name_parameter_map_);
00096   tableView.setItemDelegate(&parameterDelegate);
00097 
00098   tableView.horizontalHeader()->setStretchLastSection(true);
00099   tableView.horizontalHeader()->setResizeMode(QHeaderView::ResizeToContents);
00100   tableView.setShowGrid(true);
00101   tableView.verticalHeader()->hide();
00102   tableView.setSelectionBehavior(QAbstractItemView::SelectRows);
00103   tableView.resizeColumnsToContents();
00104 
00105   int totlen = tableView.columnWidth(0) + tableView.columnWidth(1) + frameSize().width();
00106   setMinimumWidth(totlen);
00107 
00108   QPushButton* pushButtonReset = new QPushButton("Reset", this);
00109   QPushButton* pushButtonApply = new QPushButton("Apply", this);
00110   QPushButton* pushButtonCancel = new QPushButton("Cancel", this);
00111 
00112   connect(pushButtonReset, SIGNAL(clicked()), this, SLOT(reset()));
00113   connect(pushButtonApply, SIGNAL(clicked()), this, SLOT(accept()));
00114   connect(pushButtonCancel, SIGNAL(clicked()), this, SLOT(reject()));
00115 
00116   QGridLayout gridLayout(this);
00117   gridLayout.addWidget(&tableView, 0, 0, 1, 3);
00118   gridLayout.addWidget(pushButtonReset, 1, 0);
00119   gridLayout.addWidget(pushButtonApply, 1, 1);
00120   gridLayout.addWidget(pushButtonCancel, 1, 2);
00121   setLayout(&gridLayout);
00122 
00123   int result = QDialog::exec();
00124 
00125   return result;
00126 }
00127 
00129 void
00130 pcl::modeler::ParameterDialog::reset()
00131 {
00132   size_t currentRow = 0;
00133   for (std::map<std::string, Parameter*>::iterator it = name_parameter_map_.begin();
00134     it != name_parameter_map_.end();
00135     ++ it)
00136   {
00137     it->second->reset();
00138 
00139     QModelIndex value = parameter_model_->index(int (currentRow), 1, QModelIndex());
00140     std::pair<QVariant, int> model_data = it->second->toModelData();
00141     parameter_model_->setData(value, model_data.first, model_data.second);
00142 
00143     currentRow ++;
00144   }
00145 
00146   return;
00147 }
00148 
00150 pcl::modeler::Parameter* pcl::modeler::ParameterDelegate::getCurrentParameter(const QModelIndex &index) const
00151 {
00152   std::map<std::string, Parameter*>::iterator currentParameter = parameter_map_.begin();
00153 
00154   size_t currentRow = 0;
00155   while(currentRow < index.row() && currentParameter != parameter_map_.end()) {
00156     ++ currentParameter;
00157     ++ currentRow;
00158   }
00159 
00160   assert(currentParameter != parameter_map_.end());
00161 
00162   return currentParameter->second;
00163 }
00164 
00166 pcl::modeler::ParameterDelegate::ParameterDelegate(std::map<std::string, Parameter*>& parameterMap, QObject *parent):
00167   QStyledItemDelegate(parent),
00168   parameter_map_(parameterMap)
00169 {
00170 }
00171 
00173 QWidget *
00174 pcl::modeler::ParameterDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem &, const QModelIndex &index) const
00175 {
00176   return getCurrentParameter(index)->createEditor(parent);
00177 }
00178 
00180 void
00181 pcl::modeler::ParameterDelegate::setEditorData(QWidget *editor, const QModelIndex &index) const
00182 {
00183   getCurrentParameter(index)->setEditorData(editor);
00184 }
00185 
00187 void
00188 pcl::modeler::ParameterDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const
00189 {
00190   getCurrentParameter(index)->setModelData(editor, model, index);
00191 }
00192 
00194 void
00195 pcl::modeler::ParameterDelegate::updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &) const
00196 {
00197   editor->setGeometry(option.rect);
00198 }
00199 
00201 void
00202 pcl::modeler::ParameterDelegate::initStyleOption(QStyleOptionViewItem *option, const QModelIndex &index) const
00203 {
00204   option->displayAlignment |= Qt::AlignHCenter;
00205   QStyledItemDelegate::initStyleOption(option, index);
00206 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:33