00001 /* 00002 * This file is part of OctoMap - An Efficient Probabilistic 3D Mapping 00003 * Framework Based on Octrees 00004 * http://octomap.github.io 00005 * 00006 * Copyright (c) 2009-2014, K.M. Wurm and A. Hornung, University of Freiburg 00007 * All rights reserved. License for the viewer octovis: GNU GPL v2 00008 * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt 00009 * 00010 * 00011 * This program is free software; you can redistribute it and/or modify 00012 * it under the terms of the GNU General Public License as published by 00013 * the Free Software Foundation; either version 2 of the License, or 00014 * (at your option) any later version. 00015 * 00016 * This program is distributed in the hope that it will be useful, but 00017 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY 00018 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License 00019 * for more details. 00020 * 00021 * You should have received a copy of the GNU General Public License 00022 * along with this program. If not, see http://www.gnu.org/licenses/. 00023 */ 00024 00025 #include <octovis/ViewerSettingsPanel.h> 00026 00027 ViewerSettingsPanel::ViewerSettingsPanel(QWidget *parent) 00028 : QWidget(parent), m_currentScan(0), m_numberScans(0), m_treeDepth(_TREE_MAX_DEPTH), m_resolution(0.1) 00029 { 00030 ui.setupUi(this); 00031 connect(ui.treeDepth, SIGNAL(valueChanged(int)), this, SLOT(setTreeDepth(int))); 00032 00033 scanProgressChanged(); 00034 leafSizeChanged(); 00035 } 00036 00037 ViewerSettingsPanel::~ViewerSettingsPanel() 00038 { 00039 00040 } 00041 00042 void ViewerSettingsPanel::on_nextScanButton_clicked(){ 00043 if (m_currentScan < m_numberScans){ 00044 m_currentScan++; 00045 scanProgressChanged(); 00046 emit addNextScans(1); 00047 } 00048 } 00049 00050 void ViewerSettingsPanel::on_fastFwdScanButton_clicked(){ 00051 unsigned increase = int(m_numberScans)-int(m_currentScan); 00052 if (increase > 5) increase = 5; 00053 m_currentScan += increase; 00054 scanProgressChanged(); 00055 emit addNextScans(increase); 00056 } 00057 00058 void ViewerSettingsPanel::on_lastScanButton_clicked(){ 00059 unsigned increase = int(m_numberScans)-int(m_currentScan); 00060 m_currentScan += increase; 00061 scanProgressChanged(); 00062 emit addNextScans(increase); 00063 } 00064 00065 void ViewerSettingsPanel::on_firstScanButton_clicked(){ 00066 m_currentScan = 1; 00067 scanProgressChanged(); 00068 emit gotoFirstScan(); 00069 } 00070 00071 void ViewerSettingsPanel::scanProgressChanged(){ 00072 if (int(m_numberScans) > 1) 00073 ui.scanProgressBar->setMaximum(int(m_numberScans)); 00074 else 00075 ui.scanProgressBar->setMaximum(1); 00076 00077 if (m_currentScan == m_numberScans){ 00078 ui.nextScanButton->setEnabled(false); 00079 ui.fastFwdScanButton->setEnabled(false); 00080 ui.lastScanButton->setEnabled(false); 00081 00082 } else{ 00083 ui.nextScanButton->setEnabled(true); 00084 ui.fastFwdScanButton->setEnabled(true); 00085 ui.lastScanButton->setEnabled(true); 00086 } 00087 00088 if (m_currentScan < 2){ 00089 ui.firstScanButton->setEnabled(false); 00090 } else{ 00091 ui.firstScanButton->setEnabled(true); 00092 } 00093 00094 ui.scanProgressBar->setValue(m_currentScan); 00095 // queue a redraw: 00096 ui.scanProgressBar->update(); 00097 } 00098 00099 void ViewerSettingsPanel::setNumberOfScans(unsigned scans){ 00100 m_numberScans = scans; 00101 scanProgressChanged(); 00102 } 00103 00104 void ViewerSettingsPanel::setCurrentScan(unsigned scan){ 00105 m_currentScan = scan; 00106 scanProgressChanged(); 00107 } 00108 00109 void ViewerSettingsPanel::setResolution(double resolution){ 00110 m_resolution = resolution; 00111 leafSizeChanged(); 00112 } 00113 00114 void ViewerSettingsPanel::setTreeDepth(int depth){ 00115 emit treeDepthChanged(depth); 00116 m_treeDepth = depth; 00117 leafSizeChanged(); 00118 } 00119 00120 void ViewerSettingsPanel::leafSizeChanged(){ 00121 double leafSize = m_resolution * pow(2.0, (int) (_TREE_MAX_DEPTH-m_treeDepth)); 00122 ui.leafSize->setText(QString::number(leafSize)+" m"); 00123 }