PostProcessingDialog.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "PostProcessingDialog.h"
00029 #include "ui_postProcessingDialog.h"
00030 
00031 #include <QPushButton>
00032 #include <rtabmap/core/Optimizer.h>
00033 
00034 namespace rtabmap {
00035 
00036 PostProcessingDialog::PostProcessingDialog(QWidget * parent) :
00037         QDialog(parent)
00038 {
00039         _ui = new Ui_PostProcessingDialog();
00040         _ui->setupUi(this);
00041 
00042         if(!Optimizer::isAvailable(Optimizer::kTypeCVSBA) && !Optimizer::isAvailable(Optimizer::kTypeG2O))
00043         {
00044                 _ui->sba->setEnabled(false);
00045                 _ui->sba->setChecked(false);
00046         }
00047         else if(!Optimizer::isAvailable(Optimizer::kTypeCVSBA))
00048         {
00049                 _ui->comboBox_sbaType->setItemData(1, 0, Qt::UserRole - 1);
00050                 _ui->comboBox_sbaType->setCurrentIndex(0);
00051         }
00052         else if(!Optimizer::isAvailable(Optimizer::kTypeG2O))
00053         {
00054                 _ui->comboBox_sbaType->setItemData(0, 0, Qt::UserRole - 1);
00055                 _ui->comboBox_sbaType->setCurrentIndex(1);
00056         }
00057 
00058         restoreDefaults();
00059 
00060         connect(_ui->detectMoreLoopClosures, SIGNAL(clicked(bool)), this, SLOT(updateButtonBox()));
00061         connect(_ui->refineNeighborLinks, SIGNAL(stateChanged(int)), this, SLOT(updateButtonBox()));
00062         connect(_ui->refineLoopClosureLinks, SIGNAL(stateChanged(int)), this, SLOT(updateButtonBox()));
00063         connect(_ui->sba, SIGNAL(clicked(bool)), this, SLOT(updateButtonBox()));
00064         connect(_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()), this, SLOT(restoreDefaults()));
00065 
00066         connect(_ui->detectMoreLoopClosures, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00067         connect(_ui->clusterRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00068         connect(_ui->clusterAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00069         connect(_ui->iterations, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00070         connect(_ui->refineNeighborLinks, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00071         connect(_ui->refineLoopClosureLinks, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00072 
00073         connect(_ui->sba, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00074         connect(_ui->sba_iterations, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00075         connect(_ui->sba_epsilon, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00076         connect(_ui->comboBox_sbaType, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00077         connect(_ui->comboBox_sbaType, SIGNAL(currentIndexChanged(int)), this, SLOT(updateVisibility()));
00078 
00079         updateVisibility();
00080 }
00081 
00082 PostProcessingDialog::~PostProcessingDialog()
00083 {
00084         delete _ui;
00085 }
00086 
00087 void PostProcessingDialog::updateVisibility()
00088 {
00089         _ui->sba_variance->setVisible(_ui->comboBox_sbaType->currentIndex() == 0);
00090         _ui->label_variance->setVisible(_ui->comboBox_sbaType->currentIndex() == 0);
00091 }
00092 
00093 void PostProcessingDialog::saveSettings(QSettings & settings, const QString & group) const
00094 {
00095         if(!group.isEmpty())
00096         {
00097                 settings.beginGroup(group);
00098         }
00099         settings.setValue("detect_more_lc", this->isDetectMoreLoopClosures());
00100         settings.setValue("cluster_radius", this->clusterRadius());
00101         settings.setValue("cluster_angle", this->clusterAngle());
00102         settings.setValue("iterations", this->iterations());
00103         settings.setValue("refine_neigbors", this->isRefineNeighborLinks());
00104         settings.setValue("refine_lc", this->isRefineLoopClosureLinks());
00105         settings.setValue("sba", this->isSBA());
00106         settings.setValue("sba_iterations", this->sbaIterations());
00107         settings.setValue("sba_epsilon", this->sbaEpsilon());
00108         settings.setValue("sba_type", this->sbaType());
00109         settings.setValue("sba_variance", this->sbaVariance());
00110         if(!group.isEmpty())
00111         {
00112                 settings.endGroup();
00113         }
00114 }
00115 
00116 void PostProcessingDialog::loadSettings(QSettings & settings, const QString & group)
00117 {
00118         if(!group.isEmpty())
00119         {
00120                 settings.beginGroup(group);
00121         }
00122         this->setDetectMoreLoopClosures(settings.value("detect_more_lc", this->isDetectMoreLoopClosures()).toBool());
00123         this->setClusterRadius(settings.value("cluster_radius", this->clusterRadius()).toDouble());
00124         this->setClusterAngle(settings.value("cluster_angle", this->clusterAngle()).toDouble());
00125         this->setIterations(settings.value("iterations", this->iterations()).toInt());
00126         this->setRefineNeighborLinks(settings.value("refine_neigbors", this->isRefineNeighborLinks()).toBool());
00127         this->setRefineLoopClosureLinks(settings.value("refine_lc", this->isRefineLoopClosureLinks()).toBool());
00128         this->setSBA(settings.value("sba", this->isSBA()).toBool());
00129         this->setSBAIterations(settings.value("sba_iterations", this->sbaIterations()).toInt());
00130         this->setSBAEpsilon(settings.value("sba_epsilon", this->sbaEpsilon()).toDouble());
00131         this->setSBAType((Optimizer::Type)settings.value("sba_type", this->sbaType()).toInt());
00132         this->setSBAVariance(settings.value("sba_variance", this->sbaVariance()).toDouble());
00133         if(!group.isEmpty())
00134         {
00135                 settings.endGroup();
00136         }
00137 }
00138 
00139 void PostProcessingDialog::restoreDefaults()
00140 {
00141         setDetectMoreLoopClosures(true);
00142         setClusterRadius(0.5);
00143         setClusterAngle(30);
00144         setIterations(1);
00145         setRefineNeighborLinks(false);
00146         setRefineLoopClosureLinks(false);
00147         setSBA(false);
00148         setSBAIterations(20);
00149         setSBAEpsilon(0.0);
00150         setSBAType(!Optimizer::isAvailable(Optimizer::kTypeG2O)&&Optimizer::isAvailable(Optimizer::kTypeCVSBA)?Optimizer::kTypeCVSBA:Optimizer::kTypeG2O);
00151         setSBAVariance(1.0);
00152 }
00153 
00154 void PostProcessingDialog::updateButtonBox()
00155 {
00156         _ui->buttonBox->button(QDialogButtonBox::Ok)->setEnabled(
00157                         isDetectMoreLoopClosures() || isRefineNeighborLinks() || isRefineLoopClosureLinks() || isSBA());
00158 }
00159 
00160 bool PostProcessingDialog::isDetectMoreLoopClosures() const
00161 {
00162         return _ui->detectMoreLoopClosures->isChecked();
00163 }
00164 
00165 double PostProcessingDialog::clusterRadius() const
00166 {
00167         return _ui->clusterRadius->value();
00168 }
00169 
00170 double PostProcessingDialog::clusterAngle() const
00171 {
00172         return _ui->clusterAngle->value();
00173 }
00174 
00175 int PostProcessingDialog::iterations() const
00176 {
00177         return _ui->iterations->value();
00178 }
00179 
00180 bool PostProcessingDialog::isRefineNeighborLinks() const
00181 {
00182         return _ui->refineNeighborLinks->isChecked();
00183 }
00184 
00185 bool PostProcessingDialog::isRefineLoopClosureLinks() const
00186 {
00187         return _ui->refineLoopClosureLinks->isChecked();
00188 }
00189 
00190 bool PostProcessingDialog::isSBA() const
00191 {
00192         return _ui->sba->isChecked();
00193 }
00194 
00195 int PostProcessingDialog::sbaIterations() const
00196 {
00197         return _ui->sba_iterations->value();
00198 }
00199 double PostProcessingDialog::sbaEpsilon() const
00200 {
00201         return _ui->sba_epsilon->value();
00202 }
00203 double PostProcessingDialog::sbaVariance() const
00204 {
00205         return _ui->sba_variance->value();
00206 }
00207 Optimizer::Type PostProcessingDialog::sbaType() const
00208 {
00209         return _ui->comboBox_sbaType->currentIndex()==0?Optimizer::kTypeG2O:Optimizer::kTypeCVSBA;
00210 }
00211 
00212 //setters
00213 void PostProcessingDialog::setDetectMoreLoopClosures(bool on)
00214 {
00215         _ui->detectMoreLoopClosures->setChecked(on);
00216 }
00217 void PostProcessingDialog::setClusterRadius(double radius)
00218 {
00219         _ui->clusterRadius->setValue(radius);
00220 }
00221 void PostProcessingDialog::setClusterAngle(double angle)
00222 {
00223         _ui->clusterAngle->setValue(angle);
00224 }
00225 void PostProcessingDialog::setIterations(int iterations)
00226 {
00227         _ui->iterations->setValue(iterations);
00228 }
00229 void PostProcessingDialog::setRefineNeighborLinks(bool on)
00230 {
00231         _ui->refineNeighborLinks->setChecked(on);
00232 }
00233 void PostProcessingDialog::setRefineLoopClosureLinks(bool on)
00234 {
00235         _ui->refineLoopClosureLinks->setChecked(on);
00236 }
00237 void PostProcessingDialog::setSBA(bool on)
00238 {
00239         _ui->sba->setChecked(Optimizer::isAvailable(Optimizer::kTypeCVSBA) && on);
00240 }
00241 void PostProcessingDialog::setSBAIterations(int iterations)
00242 {
00243         _ui->sba_iterations->setValue(iterations);
00244 }
00245 void PostProcessingDialog::setSBAEpsilon(double epsilon)
00246 {
00247         _ui->sba_epsilon->setValue(epsilon);
00248 }
00249 void PostProcessingDialog::setSBAVariance(double variance)
00250 {
00251         _ui->sba_variance->setValue(variance);
00252 }
00253 void PostProcessingDialog::setSBAType(Optimizer::Type type)
00254 {
00255         if(type == Optimizer::kTypeCVSBA)
00256         {
00257                 _ui->comboBox_sbaType->setCurrentIndex(1);
00258         }
00259         else
00260         {
00261                 _ui->comboBox_sbaType->setCurrentIndex(0);
00262         }
00263 }
00264 
00265 
00266 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17