ViewerGui.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of OctoMap - An Efficient Probabilistic 3D Mapping
3  * Framework Based on Octrees
4  * http://octomap.github.io
5  *
6  * Copyright (c) 2009-2014, K.M. Wurm and A. Hornung, University of Freiburg
7  * All rights reserved. License for the viewer octovis: GNU GPL v2
8  * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt
9  *
10  *
11  * This program is free software; you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation; either version 2 of the License, or
14  * (at your option) any later version.
15  *
16  * This program is distributed in the hope that it will be useful, but
17  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
18  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
19  * for more details.
20  *
21  * You should have received a copy of the GNU General Public License
22  * along with this program. If not, see http://www.gnu.org/licenses/.
23  */
24 
25 #include <iostream>
26 #include <fstream>
27 //#include <octomap/octomap_timing.h>
28 
29 #include <octovis/ViewerGui.h>
31 #include <octomap/MapCollection.h>
32 
33 
34 #define _MAXRANGE_URG 5.1
35 #define _MAXRANGE_SICK 50.0
36 
37 namespace octomap{
38 
39 ViewerGui::ViewerGui(const std::string& filename, QWidget *parent)
40 : QMainWindow(parent), m_scanGraph(NULL),
41  m_trajectoryDrawer(NULL), m_pointcloudDrawer(NULL),
42  m_cameraFollowMode(NULL),
43  m_octreeResolution(0.1), m_laserMaxRange(-1.), m_occupancyThresh(0.5),
44  m_max_tree_depth(16), m_laserType(LASERTYPE_SICK),
45  m_cameraStored(false), m_filename("") {
46 
47  ui.setupUi(this);
48  m_glwidget = new ViewerWidget(this);
49  this->setCentralWidget(m_glwidget);
50 
51  // Settings panel at the right side
52  ViewerSettingsPanel* settingsPanel = new ViewerSettingsPanel(this);
53  QDockWidget* settingsDock = new QDockWidget("Octree / Scan graph settings", this);
54  settingsDock->setWidget(settingsPanel);
55  this->addDockWidget(Qt::RightDockWidgetArea, settingsDock);
56  ui.menuShow->addAction(settingsDock->toggleViewAction());
57 
58  // Camera settings panel at the right side
59  ViewerSettingsPanelCamera* settingsCameraPanel = new ViewerSettingsPanelCamera(this);
60  QDockWidget *settingsCameraDock = new QDockWidget("Camera settings", this);
61  settingsCameraDock->setWidget(settingsCameraPanel);
62  this->addDockWidget(Qt::RightDockWidgetArea, settingsCameraDock);
63  this->tabifyDockWidget(settingsDock, settingsCameraDock);
64  settingsDock->raise();
65  ui.menuShow->addAction(settingsCameraDock->toggleViewAction());
66 
67  // status bar
68  m_mapSizeStatus = new QLabel("Map size", this);
69  m_mapMemoryStatus = new QLabel("Memory consumption", this);
70  m_mapSizeStatus->setFrameStyle(QFrame::Panel | QFrame::Sunken);
71  m_mapMemoryStatus->setFrameStyle(QFrame::Panel | QFrame::Sunken);
72  statusBar()->addPermanentWidget(m_mapSizeStatus);
73  statusBar()->addPermanentWidget(m_mapMemoryStatus);
74 
76 
77  connect(this, SIGNAL(updateStatusBar(QString, int)), statusBar(), SLOT(showMessage(QString, int)));
78 
79  connect(settingsPanel, SIGNAL(treeDepthChanged(int)), this, SLOT(changeTreeDepth(int)));
80  connect(settingsPanel, SIGNAL(addNextScans(unsigned)), this, SLOT(addNextScans(unsigned)));
81  connect(settingsPanel, SIGNAL(gotoFirstScan()), this, SLOT(gotoFirstScan()));
82 
83  connect(settingsCameraPanel, SIGNAL(jumpToFrame(unsigned)), m_cameraFollowMode, SLOT(jumpToFrame(unsigned)));
84  connect(settingsCameraPanel, SIGNAL(play()), m_cameraFollowMode, SLOT(play()));
85  connect(settingsCameraPanel, SIGNAL(pause()), m_cameraFollowMode, SLOT(pause()));
86  connect(settingsCameraPanel, SIGNAL(clearCameraPath()), m_cameraFollowMode, SLOT(clearCameraPath()));
87  connect(settingsCameraPanel, SIGNAL(saveToCameraPath()), m_cameraFollowMode, SLOT(saveToCameraPath()));
88  connect(settingsCameraPanel, SIGNAL(removeFromCameraPath()), m_cameraFollowMode, SLOT(removeFromCameraPath()));
89  connect(settingsCameraPanel, SIGNAL(addToCameraPath()), m_cameraFollowMode, SLOT(addToCameraPath()));
90  connect(settingsCameraPanel, SIGNAL(followCameraPath()), m_cameraFollowMode, SLOT(followCameraPath()));
91  connect(settingsCameraPanel, SIGNAL(followRobotPath()), m_cameraFollowMode, SLOT(followRobotPath()));
92 
93  connect(m_cameraFollowMode, SIGNAL(changeNumberOfFrames(unsigned)), settingsCameraPanel, SLOT(setNumberOfFrames(unsigned)));
94  connect(m_cameraFollowMode, SIGNAL(frameChanged(unsigned)), settingsCameraPanel, SLOT(setCurrentFrame(unsigned)));
95  connect(m_cameraFollowMode, SIGNAL(stopped()), settingsCameraPanel, SLOT(setStopped()));
96  connect(m_cameraFollowMode, SIGNAL(scanGraphAvailable(bool)), settingsCameraPanel, SLOT(setRobotTrajectoryAvailable(bool)));
97 
98  connect(m_cameraFollowMode, SIGNAL(deleteCameraPath(int)), m_glwidget, SLOT(deleteCameraPath(int)));
99  connect(m_cameraFollowMode, SIGNAL(removeFromCameraPath(int,int)), m_glwidget, SLOT(removeFromCameraPath(int,int)));
100  connect(m_cameraFollowMode, SIGNAL(appendToCameraPath(int, const octomath::Pose6D&)), m_glwidget, SLOT(appendToCameraPath(int, const octomath::Pose6D&)));
101  connect(m_cameraFollowMode, SIGNAL(appendCurrentToCameraPath(int)), m_glwidget, SLOT(appendCurrentToCameraPath(int)));
102  connect(m_cameraFollowMode, SIGNAL(addCurrentToCameraPath(int,int)), m_glwidget, SLOT(addCurrentToCameraPath(int,int)));
103  connect(m_cameraFollowMode, SIGNAL(updateCameraPath(int,int)), m_glwidget, SLOT(updateCameraPath(int,int)));
104  connect(m_cameraFollowMode, SIGNAL(playCameraPath(int,int)), m_glwidget, SLOT(playCameraPath(int,int)));
105  connect(m_cameraFollowMode, SIGNAL(stopCameraPath(int)), m_glwidget, SLOT(stopCameraPath(int)));
106  connect(m_cameraFollowMode, SIGNAL(jumpToCamFrame(int, int)), m_glwidget, SLOT(jumpToCamFrame(int, int)));
107  connect(m_glwidget, SIGNAL(cameraPathStopped(int)), m_cameraFollowMode, SLOT(cameraPathStopped(int)));
108  connect(m_glwidget, SIGNAL(cameraPathFrameChanged(int, int)), m_cameraFollowMode, SLOT(cameraPathFrameChanged(int, int)));
109 
110  connect(this, SIGNAL(changeNumberOfScans(unsigned)), settingsPanel, SLOT(setNumberOfScans(unsigned)));
111  connect(this, SIGNAL(changeCurrentScan(unsigned)), settingsPanel, SLOT(setCurrentScan(unsigned)));
112  connect(this, SIGNAL(changeResolution(double)), settingsPanel, SLOT(setResolution(double)));
113 
114  connect(settingsCameraPanel, SIGNAL(changeCamPosition(double, double, double, double, double, double)),
115  m_glwidget, SLOT(setCamPosition(double, double, double, double, double, double)));
116  connect(m_cameraFollowMode, SIGNAL(changeCamPose(const octomath::Pose6D&)),
117  m_glwidget, SLOT(setCamPose(const octomath::Pose6D&)));
118 
119  connect(ui.actionReset_view, SIGNAL(triggered()), m_glwidget, SLOT(resetView()));
120 
121  if (filename != ""){
122  m_filename = filename;
123  openFile();
124  }
125 }
126 
128  if (m_trajectoryDrawer){
130  delete m_trajectoryDrawer;
131  m_trajectoryDrawer = NULL;
132  }
133 
134  if (m_pointcloudDrawer){
136  delete m_pointcloudDrawer;
137  m_pointcloudDrawer = NULL;
138  }
139 
140  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
141  m_glwidget->removeSceneObject(it->second.octree_drawer);
142  delete (it->second.octree_drawer);
143  delete (it->second.octree);
144  }
145  m_octrees.clear();
146 
147  if(m_cameraFollowMode) {
148  delete m_cameraFollowMode;
149  m_cameraFollowMode = NULL;
150  }
151 }
152 
154  return m_glwidget->isVisible();
155 }
156 
157 void ViewerGui::showInfo(QString string, bool newline) {
158  std::cerr << string.toLocal8Bit().data();
159  if (newline) std::cerr << std::endl;
160  else std::cerr << std::flush;
161  int duration = 0;
162  if (newline)
163  duration = 3000;
164  emit updateStatusBar(string, duration);
165 }
166 
168  std::map<int, OcTreeRecord>::iterator it = m_octrees.find(id);
169  if( it != m_octrees.end() ) {
170  otr = &(it->second);
171  return true;
172  }
173  else {
174  return false;
175  }
176 }
177 
179  // is id in use?
180  OcTreeRecord* r;
181  bool foundRecord = getOctreeRecord(id, r);
182  if (foundRecord && r->octree->getTreeType().compare(tree->getTreeType()) !=0){
183  // delete old drawer, create new
184  delete r->octree_drawer;
185  if (dynamic_cast<OcTree*>(tree)) {
186  r->octree_drawer = new OcTreeDrawer();
187  // fprintf(stderr, "adding new OcTreeDrawer for node %d\n", id);
188  }
189  else if (dynamic_cast<ColorOcTree*>(tree)) {
190  r->octree_drawer = new ColorOcTreeDrawer();
191  } else{
192  OCTOMAP_ERROR("Could not create drawer for tree type %s\n", tree->getTreeType().c_str());
193  }
194 
195  delete r->octree;
196  r->octree = tree;
197  r->origin = origin;
198 
199  } else if (foundRecord && r->octree->getTreeType().compare(tree->getTreeType()) ==0) {
200  // only swap out tree
201 
202  delete r->octree;
203  r->octree = tree;
204  r->origin = origin;
205  } else {
206  // add new record
207  OcTreeRecord otr;
208  otr.id = id;
209  if (dynamic_cast<OcTree*>(tree)) {
210  otr.octree_drawer = new OcTreeDrawer();
211  // fprintf(stderr, "adding new OcTreeDrawer for node %d\n", id);
212  }
213  else if (dynamic_cast<ColorOcTree*>(tree)) {
214  otr.octree_drawer = new ColorOcTreeDrawer();
215  } else{
216  OCTOMAP_ERROR("Could not create drawer for tree type %s\n", tree->getTreeType().c_str());
217  }
218  otr.octree = tree;
219  otr.origin = origin;
220  m_octrees[id] = otr;
222  }
223 }
224 
226  octomap::pose6d o; // initialized to (0,0,0) , (0,0,0,1) by default
227  addOctree(tree, id, o);
228 }
229 
231 
232  // update viewer stat
233  double minX, minY, minZ, maxX, maxY, maxZ;
234  minX = minY = minZ = -10; // min bbx for drawing
235  maxX = maxY = maxZ = 10; // max bbx for drawing
236  double sizeX, sizeY, sizeZ;
237  sizeX = sizeY = sizeZ = 0.;
238  size_t memoryUsage = 0;
239  size_t num_nodes = 0;
240  size_t memorySingleNode = 0;
241 
242 
243  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
244  // get map bbx
245  double lminX, lminY, lminZ, lmaxX, lmaxY, lmaxZ;
246  it->second.octree->getMetricMin(lminX, lminY, lminZ);
247  it->second.octree->getMetricMax(lmaxX, lmaxY, lmaxZ);
248  // transform to world coords using map origin
249  octomap::point3d pmin(lminX, lminY, lminZ);
250  octomap::point3d pmax(lmaxX, lmaxY, lmaxZ);
251  pmin = it->second.origin.transform(pmin);
252  pmax = it->second.origin.transform(pmax);
253  lminX = pmin.x(); lminY = pmin.y(); lminZ = pmin.z();
254  lmaxX = pmax.x(); lmaxY = pmax.y(); lmaxZ = pmax.z();
255  // update global bbx
256  if (lminX < minX) minX = lminX;
257  if (lminY < minY) minY = lminY;
258  if (lminZ < minZ) minZ = lminZ;
259  if (lmaxX > maxX) maxX = lmaxX;
260  if (lmaxY > maxY) maxY = lmaxY;
261  if (lmaxZ > maxZ) maxZ = lmaxZ;
262  double lsizeX, lsizeY, lsizeZ;
263  // update map stats
264  it->second.octree->getMetricSize(lsizeX, lsizeY, lsizeZ);
265  if (lsizeX > sizeX) sizeX = lsizeX;
266  if (lsizeY > sizeY) sizeY = lsizeY;
267  if (lsizeZ > sizeZ) sizeZ = lsizeZ;
268  memoryUsage += it->second.octree->memoryUsage();
269  num_nodes += it->second.octree->size();
270  memorySingleNode = std::max(memorySingleNode, it->second.octree->memoryUsageNode());
271  }
272 
273  m_glwidget->setSceneBoundingBox(qglviewer::Vec(minX, minY, minZ), qglviewer::Vec(maxX, maxY, maxZ));
274 
275  //if (m_octrees.size()) {
276  QString size = QString("%L1 x %L2 x %L3 m^3; %L4 nodes").arg(sizeX).arg(sizeY).arg(sizeZ).arg(unsigned(num_nodes));
277  QString memory = QString("Single node: %L1 B; ").arg(memorySingleNode)
278  + QString ("Octree: %L1 B (%L2 MB)").arg(memoryUsage).arg((double) memoryUsage/(1024.*1024.), 0, 'f', 3);
279  m_mapMemoryStatus->setText(memory);
280  m_mapSizeStatus->setText(size);
281  //}
282 
283  m_glwidget->updateGL();
284 
285  // generate cubes -> display
286  // timeval start;
287  // timeval stop;
288  // gettimeofday(&start, NULL); // start timer
289  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
290  it->second.octree_drawer->setMax_tree_depth(m_max_tree_depth);
291  it->second.octree_drawer->setOcTree(*it->second.octree, it->second.origin, it->second.id);
292  }
293  // gettimeofday(&stop, NULL); // stop timer
294  // double time_to_generate = (stop.tv_sec - start.tv_sec) + 1.0e-6 *(stop.tv_usec - start.tv_usec);
295  // fprintf(stderr, "setOcTree took %f sec\n", time_to_generate);
296  m_glwidget->updateGL();
297 }
298 
299 
301 
302  if (m_scanGraph) {
303 
304  QApplication::setOverrideCursor(Qt::WaitCursor);
305 
306  showInfo("Generating OcTree... ");
307  std::cerr << std::endl;
308 
309  //if (m_ocTree) delete m_ocTree;
311 
313  unsigned numScans = m_scanGraph->size();
314  unsigned currentScan = 1;
315  for (it = m_scanGraph->begin(); it != m_nextScanToAdd; it++) {
316  tree->insertPointCloud(**it, m_laserMaxRange);
317  fprintf(stderr, "generateOctree:: inserting scan node with %d points, origin: %.2f ,%.2f , %.2f.\n",
318  (unsigned int) (*it)->scan->size(), (*it)->pose.x(), (*it)->pose.y(), (*it)->pose.z() );
319 
320  std::cout << " S ("<<currentScan<<"/"<<numScans<<") " << std::flush;
321  currentScan++;
322  }
323 
324  this->addOctree(tree, DEFAULT_OCTREE_ID);
325  this->showOcTree();
326 
327  showInfo("Done.", true);
328  QApplication::restoreOverrideCursor();
329  }
330  else {
331  std::cerr << "generateOctree called but no ScanGraph present!\n";
332  }
333 
334 }
335 
336 // == incremental graph generation =======================
337 
339  if (m_scanGraph){
340  showInfo("Inserting first scan node into tree... ", true);
341  QApplication::setOverrideCursor(Qt::WaitCursor);
342 
344 
345  // if (m_ocTree) delete m_ocTree;
346  // m_ocTree = new octomap::OcTree(m_octreeResolution);
348  this->addOctree(tree, DEFAULT_OCTREE_ID);
349 
350  addNextScan();
351 
352  QApplication::restoreOverrideCursor();
353  showOcTree();
354  }
355 }
356 
358 
359  if (m_scanGraph){
360  showInfo("Inserting next scan node into tree... ", true);
361 
362  QApplication::setOverrideCursor(Qt::WaitCursor);
363  if (m_nextScanToAdd != m_scanGraph->end()){
364  OcTreeRecord* r;
366  fprintf(stderr, "ERROR: OctreeRecord for id %d not found!\n", DEFAULT_OCTREE_ID);
367  return;
368  }
369  // not used with ColorOcTrees, omitting casts
370  ((OcTree*) r->octree)->insertPointCloud(**m_nextScanToAdd, m_laserMaxRange);
371  m_nextScanToAdd++;
372  }
373 
374  QApplication::restoreOverrideCursor();
375  showOcTree();
376 
377  }
378 }
379 
380 
381 void ViewerGui::addNextScans(unsigned scans){
382  for (unsigned i = 0; i < scans; ++i){
383  addNextScan();
384  }
385 }
386 
387 
388 // == file I/O ===========================================
389 
391  if (!m_filename.empty()){
392  m_glwidget->clearAll();
393 
394  QString temp = QString(m_filename.c_str());
395  QFileInfo fileinfo(temp);
396  if (fileinfo.suffix() == "graph"){
397  openGraph();
398  }else if (fileinfo.suffix() == "bt"){
399  openTree();
400  }
401  else if (fileinfo.suffix() == "ot")
402  {
403  openOcTree();
404  }
405  else if (fileinfo.suffix() == "hot"){
407  }
408  else if (fileinfo.suffix() == "dat"){
409  openPointcloud();
410  }
411  else {
412  QMessageBox::warning(this, "Unknown file", "Cannot open file, unknown extension: "+fileinfo.suffix(), QMessageBox::Ok);
413  }
414  }
415 }
416 
417 
418 void ViewerGui::openGraph(bool completeGraph){
419 
420  QApplication::setOverrideCursor(Qt::WaitCursor);
421  showInfo("Loading scan graph from file " + QString(m_filename.c_str()) );
422 
423  if (m_scanGraph) delete m_scanGraph;
426 
427  loadGraph(completeGraph);
428 }
429 
430 
432 
433  QApplication::setOverrideCursor(Qt::WaitCursor);
434  showInfo("Loading ASCII pointcloud from file "+QString(m_filename.c_str()) + "...");
435 
436  if (m_scanGraph) delete m_scanGraph;
438 
439 
440  // read pointcloud from file
441  std::ifstream s(m_filename.c_str());
442  Pointcloud* pc = new Pointcloud();
443 
444  if (!s) {
445  std::cout <<"ERROR: could not read " << m_filename << std::endl;
446  return;
447  }
448 
449  pc->read(s);
450 
451  pose6d laser_pose(0,0,0,0,0,0);
452  m_scanGraph->addNode(pc, laser_pose);
453 
454  loadGraph(true);
455  showInfo("Done.", true);
456 }
457 
458 
460  ui.actionPointcloud->setChecked(false);
461  ui.actionPointcloud->setEnabled(false);
462  ui.actionOctree_cells->setChecked(true);
463  ui.actionOctree_cells->setEnabled(true);
464  ui.actionFree->setChecked(false);
465  ui.actionFree->setEnabled(true);
466  ui.actionOctree_structure->setEnabled(true);
467  ui.actionOctree_structure->setChecked(false);
468  ui.actionTrajectory->setEnabled(false);
469  ui.actionConvert_ml_tree->setEnabled(true);
470  ui.actionReload_Octree->setEnabled(true);
471  ui.actionSettings->setEnabled(false);
472 }
473 
475  OcTree* tree = new octomap::OcTree(m_filename);
476  this->addOctree(tree, DEFAULT_OCTREE_ID);
477 
480 
482  showOcTree();
484 }
485 
488 
489  if (tree){
490  this->addOctree(tree, DEFAULT_OCTREE_ID);
491 
494 
496  showOcTree();
498 
499  if (tree->getTreeType() == "ColorOcTree"){
500  // map color and height map share the same color array and QAction
501  ui.actionHeight_map->setText ("Map color"); // rename QAction in Menu
502  this->on_actionHeight_map_toggled(true); // enable color view
503  ui.actionHeight_map->setChecked(true);
504  }
505  }
506  else {
507  QMessageBox::warning(this, "File error", "Cannot open OcTree file", QMessageBox::Ok);
508  }
509 }
510 
511 
512 // EXPERIMENTAL
514 
515  OCTOMAP_DEBUG("Opening hierarchy from %s...\n", m_filename.c_str());
516 
517  std::ifstream infile(m_filename.c_str(), std::ios_base::in |std::ios_base::binary);
518  if (!infile.is_open()) {
519  QMessageBox::warning(this, "File error", "Cannot open OcTree file", QMessageBox::Ok);
520  return;
521  }
522  infile.close();
523 
525  int i=0;
526  for (MapCollection<MapNode<OcTree> >::iterator it = collection.begin();
527  it != collection.end(); ++it) {
528  OCTOMAP_DEBUG("Adding hierarchy node %s\n", (*it)->getId().c_str());
529  OcTree* tree = (*it)->getMap();
530  if (!tree)
531  OCTOMAP_ERROR("Error while reading node %s\n", (*it)->getId().c_str());
532  else {
533  OCTOMAP_DEBUG("Read tree with %zu tree nodes\n", tree->size());
534  }
535  pose6d origin = (*it)->getOrigin();
536  this->addOctree(tree, i, origin);
537  ++i;
538  }
540  showOcTree();
542  OCTOMAP_DEBUG("done\n");
543 }
544 
545 void ViewerGui::loadGraph(bool completeGraph) {
546 
547  ui.actionSettings->setEnabled(true);
548  ui.actionPointcloud->setEnabled(true);
549  ui.actionPointcloud->setChecked(false);
550  ui.actionTrajectory->setEnabled(true);
551  ui.actionOctree_cells->setEnabled(true);
552  ui.actionOctree_cells->setChecked(true);
553  ui.actionOctree_structure->setEnabled(true);
554  ui.actionOctree_structure->setChecked(false);
555  ui.actionFree->setChecked(false);
556  ui.actionFree->setEnabled(true);
557  ui.actionReload_Octree->setEnabled(true);
558  ui.actionConvert_ml_tree->setEnabled(true);
559 
560  unsigned graphSize = m_scanGraph->size();
561  unsigned currentScan;
562 
563  if (completeGraph){
564  fprintf(stderr, "loadGraph:: generating octree from complete graph.\n" );
566  generateOctree();
567  currentScan = graphSize;
568  }
569  else{
571 
572  //if (m_ocTree) delete m_ocTree;
573  //m_ocTree = new octomap::OcTree(m_octreeResolution);
575  this->addOctree(tree, DEFAULT_OCTREE_ID);
576 
577  addNextScan();
578 
579  currentScan = 1;
580  }
581 
583  QApplication::restoreOverrideCursor();
584 
585  emit changeNumberOfScans(graphSize);
586  emit changeCurrentScan(currentScan);
587  showInfo("Done (" +QString::number(currentScan)+ " of "+ QString::number(graphSize)+" nodes)", true);
588 
589  if (!m_trajectoryDrawer){
591  }
593 
594  if (!m_pointcloudDrawer){
596  }
598 
600 
601  if (ui.actionTrajectory->isChecked())
603 
604  if (ui.actionPointcloud->isChecked())
606 }
607 
609  // range check:
610  if (depth < 1 || depth > 16)
611  return;
612 
613  m_max_tree_depth = unsigned(depth);
614 
615  if (m_octrees.size() > 0)
616  showOcTree();
617 }
618 
619 
621  this->close();
622 }
623 
625  m_glwidget->help();
626 }
627 
629 
630  ViewerSettings dialog(this);
632  dialog.setLaserType(m_laserType);
634 
635 
636  if (dialog.exec()){
637 
638  double oldResolution = m_octreeResolution;
639  double oldLaserMaxRange = m_laserMaxRange;
640  double oldType = m_laserType;
641 
643  m_laserType = dialog.getLaserType();
644  m_laserMaxRange = dialog.getMaxRange();
645 
646  // apply new settings
647  bool resolutionChanged = (std::abs(oldResolution - m_octreeResolution) > 1e-5);
648  bool maxRangeChanged = (std::abs(oldLaserMaxRange - m_laserMaxRange) > 1e-5);
649 
650  if (resolutionChanged)
652 
653  if (oldType != m_laserType){ // parameters changed, reload file:
654  openFile();
655  } else if (resolutionChanged || maxRangeChanged){
656  generateOctree();
657  }
658 
659  }
660 }
661 
663  QString filename = QFileDialog::getOpenFileName(this,
664  tr("Open data file"), "",
665  "All supported files (*.graph *.bt *.ot *.dat);;OcTree file (*.ot);;Bonsai tree file (*.bt);;Binary scan graph (*.graph);;Pointcloud (*.dat);;All files (*)");
666  if (!filename.isEmpty()){
667 #ifdef _WIN32
668  m_filename = std::string(filename.toLocal8Bit().data());
669 #else
670  m_filename = filename.toStdString();
671 #endif
672  openFile();
673  }
674 }
675 
676 
678  QString filename = QFileDialog::getOpenFileName(this,
679  tr("Open graph file incrementally (at start)"), "",
680  "Binary scan graph (*.graph)");
681  if (!filename.isEmpty()){
682  m_glwidget->clearAll();
683 
684 #ifdef _WIN32
685  m_filename = std::string(filename.toLocal8Bit().data());
686 #else
687  m_filename = filename.toStdString();
688 #endif
689 
690  openGraph(false);
691  }
692 }
693 
695 
696  OcTreeRecord* r;
698  fprintf(stderr, "ERROR: OctreeRecord for id %d not found!\n", DEFAULT_OCTREE_ID);
699  QMessageBox::warning(this, tr("3D Mapping Viewer"),
700  "Error: No OcTree present.",
701  QMessageBox::Ok);
702  return;
703  }
704 
705  QString filename = QFileDialog::getSaveFileName(this, tr("Save octree file"),
706  "", tr("Full OcTree (*.ot);;Bonsai Tree file (*.bt);;"));
707 
708  if (filename != ""){
709  QApplication::setOverrideCursor(Qt::WaitCursor);
710  showInfo("Writing file... ", false);
711 
712  QFileInfo fileinfo(filename);
713  std::string std_filename;
714 #ifdef _WIN32
715  std_filename = filename.toLocal8Bit().data();
716 #else
717  std_filename = filename.toStdString();
718 #endif
719 
720  AbstractOcTree* t = r->octree;
721 
722  if (fileinfo.suffix() == "bt") {
723  AbstractOccupancyOcTree* ot = dynamic_cast<AbstractOccupancyOcTree*> (t);
724  if (ot)
725  ot->writeBinaryConst(std_filename);
726  else{
727  QMessageBox::warning(this, "Unknown tree type",
728  "Could not convert to occupancy tree for writing .bt file",
729  QMessageBox::Ok);
730  }
731  }
732  else if (fileinfo.suffix() == "ot"){
733  r->octree->write(std_filename);
734  }
735  else {
736  QMessageBox::warning(this, "Unknown file",
737  "Cannot write file, unknown extension: "+fileinfo.suffix(),
738  QMessageBox::Ok);
739  }
740 
741  QApplication::restoreOverrideCursor();
742  showInfo("Done.", true);
743  }
744 }
745 
747  point3d min, max;
748  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
749  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
750 
751  updateNodesInBBX(min, max, false);
752 }
753 
755  point3d min, max;
756  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
757  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
758 
759  setNodesInBBX(min, max, false);
760 }
761 
763 {
764  point3d min, max;
765  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
766  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
767 
768  setNonNodesInBBX(min, max, false);
769 }
770 
772 {
773  point3d min, max;
774  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
775  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
776 
777  setNonNodesInBBX(min, max, true);
778 }
779 
781  point3d min, max;
782  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
783  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
784 
785  setNodesInBBX(min, max, true);
786 }
787 
789  point3d min, max;
790  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
791  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
792 
793  updateNodesInBBX(min, max, true);
794 }
795 
797  point3d min, max;
798  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
799  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
800 
801  for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
802  OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
803 
804  if (octree){
805  for(OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(min,max),
806  end=octree->end_leafs_bbx(); it!= end; ++it){
807  octree->deleteNode(it.getKey(), it.getDepth());
808  }
809  } else{
810  QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
811  QMessageBox::Ok);
812 
813  }
814  }
815 
816  showOcTree();
817 }
818 
820  point3d min, max;
821  m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
822  m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
823 
824  for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
825  OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
826 
827  if (octree){
828  octomap::OcTreeKey minKey, maxKey;
829 
830  if (!octree->coordToKeyChecked(min, minKey) || !octree->coordToKeyChecked(max, maxKey)){
831  return;
832  }
833 
834  for(OcTree::leaf_iterator it = octree->begin_leafs(),
835  end=octree->end_leafs(); it!= end; ++it){
836  // check if outside of bbx:
837  OcTreeKey k = it.getKey();
838  if (k[0] < minKey[0] || k[1] < minKey[1] || k[2] < minKey[2]
839  || k[0] > maxKey[0] || k[1] > maxKey[1] || k[2] > maxKey[2])
840  {
841  octree->deleteNode(k, it.getDepth());
842  }
843  }
844  } else
845  QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
846  QMessageBox::Ok);
847  }
848 
849  showOcTree();
850 }
851 
852 void ViewerGui::updateNodesInBBX(const point3d& min, const point3d& max, bool occupied){
853  for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
854  OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
855 
856  if (octree){
857  float logodds;
858  if (occupied)
859  logodds = octree->getClampingThresMaxLog();
860  else
861  logodds = octree->getClampingThresMinLog();
862 
863  for(OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(min,max),
864  end=octree->end_leafs_bbx(); it!= end; ++it)
865  {
866  // directly set values of leafs:
867  it->setLogOdds(logodds);
868  }
869 
870  // update inner nodes to make tree consistent:
871  octree->updateInnerOccupancy();
872 
873  } else
874  QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
875  QMessageBox::Ok);
876 
877  }
878 
879  showOcTree();
880 }
881 
882 
883 void ViewerGui::setNodesInBBX(const point3d& min, const point3d& max, bool occupied){
884  for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
885  OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
886 
887  if (octree){
888  float logodds = octree->getClampingThresMaxLog() - octree->getClampingThresMinLog();
889  if (!occupied)
890  logodds *= -1;
891 
892  OcTreeKey minKey(0,0,0);
893  OcTreeKey maxKey(0,0,0);
894  octree->coordToKeyChecked(min, minKey);
895  octree->coordToKeyChecked(max, maxKey);
896  OcTreeKey k;
897  for (k[0] = minKey[0]; k[0] < maxKey[0]; ++k[0]){
898  for (k[1] = minKey[1]; k[1] < maxKey[1]; ++k[1]){
899  for (k[2] = minKey[2]; k[2] < maxKey[2]; ++k[2]){
900  octree->updateNode(k, logodds);
901  }
902  }
903  }
904  }
905 
906  }
907 
908  showOcTree();
909 }
910 
911 void ViewerGui::setNonNodesInBBX(const point3d& min, const point3d& max, bool occupied) {
912  for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
913  OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
914 
915  if (octree){
916  float logodds = octree->getClampingThresMaxLog() - octree->getClampingThresMinLog();
917  if (!occupied)
918  logodds *= -1;
919 
920  OcTreeKey minKey(0,0,0);
921  OcTreeKey maxKey(0,0,0);
922  octree->coordToKeyChecked(min, minKey);
923  octree->coordToKeyChecked(max, maxKey);
924  OcTreeKey k;
925  for (k[0] = minKey[0]; k[0] < maxKey[0]; ++k[0]){
926  for (k[1] = minKey[1]; k[1] < maxKey[1]; ++k[1]){
927  for (k[2] = minKey[2]; k[2] < maxKey[2]; ++k[2]){
928  OcTreeNode* n = octree->search(k);
929  if(!n)
930  octree->updateNode(k, logodds);
931  }
932  }
933  }
934  }
935 
936  }
937 
938  showOcTree();
939 }
940 
943  m_glwidget->saveSnapshot(false);
944 }
945 
947  if(checked) {
949  m_glwidget->saveSnapshot(false);
951  connect(m_glwidget, SIGNAL(drawFinished(bool)), m_glwidget, SLOT(saveSnapshot(bool)));
952  } else {
953  ui.actionExport_sequence->setChecked(false);
954  }
955  } else {
956  disconnect(m_glwidget, SIGNAL(drawFinished(bool)), m_glwidget, SLOT(saveSnapshot(bool)));
957  }
958 }
959 
961  if (checked) {
962  ui.actionHeight_map->setChecked(false);
963  ui.actionSemanticColoring->setChecked(false);
964  }
965 
966  m_glwidget->enablePrintoutMode(checked);
967 }
968 
970 
971  ui.menuDelete_nodes->setEnabled(checked);
972  ui.menuFill_selection->setEnabled(checked);
973  ui.menuChange_nodes_in_selection->setEnabled(checked);
974 
975 
976  m_glwidget->enableSelectionBox(checked);
977 
978 
979  m_glwidget->updateGL();
980 }
981 
983  if (checked) {
984  ui.actionPrintout_mode->setChecked(false);
985  ui.actionSemanticColoring->setChecked(false);
986  }
988 }
989 
991  if (checked) {
992  ui.actionHeight_map->setChecked(false);
993  ui.actionPrintout_mode->setChecked(false);
994  }
995 
997 }
998 
999 
1001  m_glwidget->camera()->deletePath(0);
1003  m_cameraStored = true;
1004  ui.actionRestore_camera->setEnabled(true);
1005 }
1006 
1008  if (m_cameraStored){
1009  m_glwidget->camera()->playPath(0);
1010  }
1011 }
1012 
1014  if (m_pointcloudDrawer){
1015  if (checked)
1017  else
1019  }
1020 }
1021 
1023  if (m_trajectoryDrawer){
1024  if (checked)
1026  else
1028  }
1029 }
1030 
1032  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1033  it != m_octrees.end(); ++it) {
1034  it->second.octree_drawer->enableAxes(checked);
1035  }
1036  m_glwidget->updateGL();
1037 }
1038 
1040  OcTreeRecord* r;
1042  if (checked) m_glwidget->removeSceneObject(r->octree_drawer);
1044  m_glwidget->updateGL();
1045  }
1046 }
1047 
1049  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1050  it != m_octrees.end(); ++it) {
1051  m_glwidget->removeSceneObject(it->second.octree_drawer);
1052  delete (it->second.octree_drawer);
1053  delete (it->second.octree);
1054  }
1055  m_octrees.clear();
1056  showOcTree();
1057 }
1058 
1060 
1061 }
1062 
1064  if (m_scanGraph) {
1065  generateOctree();
1066  } else {
1067  openFile();
1068  }
1069 }
1070 
1072  QApplication::setOverrideCursor(Qt::WaitCursor);
1073  if (m_octrees.size()) {
1074  showInfo("Converting OcTree to maximum Likelihood map... ");
1075  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1076  it != m_octrees.end(); ++it) {
1077  AbstractOcTree* t = it->second.octree;
1078  if (dynamic_cast<OcTree*>(t)) {
1079  ((OcTree*) t)->toMaxLikelihood();
1080  }
1081  else if (dynamic_cast<OcTree*>(t)) {
1082  ((ColorOcTree*) t)->toMaxLikelihood();
1083  }
1084  }
1085  showInfo("Done.", true);
1086  showOcTree();
1087  QApplication::restoreOverrideCursor();
1088  }
1089 }
1090 
1091 
1093  QApplication::setOverrideCursor(Qt::WaitCursor);
1094  if (m_octrees.size()) {
1095  showInfo("Pruning OcTree... ");
1096  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1097  it != m_octrees.end(); ++it) {
1098  it->second.octree->prune();
1099  }
1100  showOcTree();
1101  showInfo("Done.", true);
1102  }
1103  QApplication::restoreOverrideCursor();
1104 }
1105 
1106 
1108 
1109  QApplication::setOverrideCursor(Qt::WaitCursor);
1110 
1111  // if (m_ocTree) {
1112  if (m_octrees.size()) {
1113  showInfo("Expanding OcTree... ");
1114  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1115  it != m_octrees.end(); ++it) {
1116  it->second.octree->expand();
1117  }
1118  showOcTree();
1119 
1120  showInfo("Done.", true);
1121  }
1122  QApplication::restoreOverrideCursor();
1123 }
1124 
1125 
1127  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1128  it != m_octrees.end(); ++it) {
1129  it->second.octree_drawer->enableOcTreeCells(enabled);
1130  }
1131  m_glwidget->updateGL();
1132 }
1133 
1135  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1136  it != m_octrees.end(); ++it) {
1137  it->second.octree_drawer->enableOcTree(enabled);
1138  }
1139  m_glwidget->updateGL();
1140 }
1141 
1143  for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
1144  it != m_octrees.end(); ++it) {
1145  it->second.octree_drawer->enableFreespace(enabled);
1146  }
1147  m_glwidget->updateGL();
1148 
1149 }
1150 
1152  // if(m_octreeDrawer) {
1153  // m_octreeDrawer->enableSelection(enabled);
1154 
1155  // // just for testing, you should set the selection somewhere else and only enable it here:
1156  // if (enabled){
1157  // std::list<OcTreeVolume> selection;
1158  // std::pair<octomath::Vector3, double> volume(octomath::Vector3(0.0, 0.0, 0.0), 0.2);
1159  // selection.push_back(volume);
1160  // m_octreeDrawer->setOcTreeSelection(selection);
1161 
1162  // } else{
1163  // m_octreeDrawer->clearOcTreeSelection();
1164  // }
1165  // m_glwidget->updateGL();
1166  // }
1167 }
1168 
1169 
1171  m_glwidget->setBackgroundColor( QColor(0,0,0) );
1172  m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
1173 }
1174 
1176  m_glwidget->setBackgroundColor( QColor(255,255,255) );
1177  m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
1178 }
1179 
1181  m_glwidget->setBackgroundColor( QColor(117,117,117) );
1182  m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
1183 }
1184 
1186  QString filename = QFileDialog::getSaveFileName(this, "Save Viewer State", "camera.xml", "Camera/State file (*.xml)");
1187  if (!filename.isEmpty()) {
1188  saveCameraPosition(filename.toAscii().constData());
1189  }
1190 }
1191 
1193  QString filename = QFileDialog::getOpenFileName(this, "Load Viewer State", "camera.xml", "Camera/State file (*.xml)");
1194  if (!filename.isEmpty()) {
1195  loadCameraPosition(filename.toAscii().constData());
1196  }
1197 }
1198 
1199 
1200 
1201 void ViewerGui::saveCameraPosition(const char* filename) const {
1202  // HACK get non-const pointer to myself
1203  ViewerWidget* aux = const_cast<ViewerWidget*>( m_glwidget);
1204  aux->setStateFileName(QString(filename));
1205  aux->saveStateToFile();
1206  aux->setStateFileName(QString::null);
1207 }
1208 
1209 void ViewerGui::loadCameraPosition(const char* filename) {
1210  m_glwidget->setStateFileName(QString(filename));
1212  m_glwidget->setStateFileName(QString::null);
1213 }
1214 
1215 
1216 }
1217 
1218 
size_t size() const
ScanNode * addNode(Pointcloud *scan, pose6d pose)
void on_actionRestore_camera_triggered()
Definition: ViewerGui.cpp:1007
QLabel * m_mapMemoryStatus
Definition: ViewerGui.h:211
ViewerWidget * m_glwidget
Definition: ViewerGui.h:200
virtual std::string getTreeType() const =0
ScanGraph::iterator m_nextScanToAdd
Definition: ViewerGui.h:197
void on_actionStore_camera_triggered()
Definition: ViewerGui.cpp:1000
void on_actionOctree_cells_toggled(bool enabled)
Definition: ViewerGui.cpp:1126
std::istream & readBinary(std::ifstream &s)
void openOcTree()
open "regular" file containing an octree
Definition: ViewerGui.cpp:486
void on_action_bg_black_triggered()
Definition: ViewerGui.cpp:1170
virtual void setSceneBoundingBox(const qglviewer::Vec &min, const qglviewer::Vec &max)
double m_octreeResolution
Definition: ViewerGui.h:204
void on_actionTest_triggered()
Definition: ViewerGui.cpp:1059
void enablePrintoutMode(bool enabled=true)
void loadGraph(bool completeGraph=true)
Definition: ViewerGui.cpp:545
void openGraph(bool completeGraph=true)
Definition: ViewerGui.cpp:418
void enableSelectionBox(bool enabled=true)
static AbstractOcTree * read(const std::string &filename)
void changeCurrentScan(unsigned scans)
#define OCTOMAP_DEBUG(...)
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
void on_actionClear_selection_triggered()
Definition: ViewerGui.cpp:754
void addNextScans(unsigned scans)
Definition: ViewerGui.cpp:381
void on_actionClear_unknown_in_selection_triggered()
Definition: ViewerGui.cpp:762
void on_action_bg_white_triggered()
Definition: ViewerGui.cpp:1175
void removeSceneObject(SceneObject *obj)
void on_actionReload_Octree_triggered()
Definition: ViewerGui.cpp:1063
void on_actionSemanticColoring_toggled(bool checked)
Definition: ViewerGui.cpp:990
void saveCameraPosition(const char *filename) const
Definition: ViewerGui.cpp:1201
void changeNumberOfScans(unsigned scans)
virtual void saveStateToFile()
Definition: qglviewer.cpp:3399
void on_actionFill_nodes_in_selection_triggered()
Definition: ViewerGui.cpp:788
void on_actionSave_file_triggered()
Definition: ViewerGui.cpp:694
virtual void setScanGraph(const octomap::ScanGraph &graph)
bool deleteNode(double x, double y, double z, unsigned int depth=0)
void on_actionFree_toggled(bool enabled)
Definition: ViewerGui.cpp:1142
std::string m_filename
Filename of last loaded file, in case it is necessary to reload it.
Definition: ViewerGui.h:214
virtual void deletePath(unsigned int i)
Definition: camera.cpp:1762
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
void on_actionHideBackground_toggled(bool checked)
Definition: ViewerGui.cpp:1039
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
void on_actionClear_nodes_in_selection_triggered()
Definition: ViewerGui.cpp:746
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
void updateNodesInBBX(const point3d &min, const point3d &max, bool occupied)
Definition: ViewerGui.cpp:852
unsigned int getLaserType()
void on_actionDelete_nodes_outside_of_selection_triggered()
Definition: ViewerGui.cpp:819
TrajectoryDrawer * m_trajectoryDrawer
Definition: ViewerGui.h:201
Ui::ViewerGuiClass ui
Definition: ViewerGui.h:199
void enableHeightColorMode(bool enabled=true)
void on_actionAxes_toggled(bool checked)
Definition: ViewerGui.cpp:1031
virtual void insertPointCloud(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
void showInfo(QString string, bool newline=false)
Definition: ViewerGui.cpp:157
void enableSemanticColoring(bool enabled=true)
std::vector< ScanNode * >::iterator iterator
ViewerGui(const std::string &filename="", QWidget *parent=0)
Definition: ViewerGui.cpp:39
void on_actionClear_triggered()
Definition: ViewerGui.cpp:1048
void on_actionFill_selection_triggered()
Definition: ViewerGui.cpp:780
void addOctree(AbstractOcTree *tree, int id, pose6d origin)
Definition: ViewerGui.cpp:178
void on_actionExport_view_triggered()
Definition: ViewerGui.cpp:941
double m_laserMaxRange
Definition: ViewerGui.h:205
const SelectionBox & selectionBox() const
Definition: ViewerWidget.h:75
The Vec class represents 3D positions and 3D vectors.
Definition: vec.h:65
void on_actionHeight_map_toggled(bool checked)
Definition: ViewerGui.cpp:982
virtual double getResolution() const =0
void getBBXMax(float &x, float &y, float &z) const
void on_action_bg_gray_triggered()
Definition: ViewerGui.cpp:1180
bool openSnapshotFormatDialog()
unsigned int m_laserType
Definition: ViewerGui.h:208
void changeResolution(double resolution)
QColor backgroundColor() const
Definition: qglviewer.h:168
void addSceneObject(SceneObject *obj)
void setLaserType(int type)
void on_savecampose_triggered()
Definition: ViewerGui.cpp:1185
void setScanGraph(octomap::ScanGraph *graph)
bool writeBinaryConst(const std::string &filename) const
void on_actionSelection_box_toggled(bool checked)
Definition: ViewerGui.cpp:969
void setNonNodesInBBX(const point3d &min, const point3d &max, bool occupied)
Definition: ViewerGui.cpp:911
unsigned int m_max_tree_depth
Definition: ViewerGui.h:207
bool write(const std::string &filename) const
void on_actionPrune_tree_triggered()
Definition: ViewerGui.cpp:1092
void on_actionExport_sequence_triggered(bool checked)
Definition: ViewerGui.cpp:946
void on_actionDelete_nodes_in_selection_triggered()
Definition: ViewerGui.cpp:796
void on_actionTrajectory_toggled(bool checked)
Definition: ViewerGui.cpp:1022
QLabel * m_mapSizeStatus
Definition: ViewerGui.h:210
void on_actionOpen_graph_incremental_triggered()
Definition: ViewerGui.cpp:677
ScanGraph * m_scanGraph
Definition: ViewerGui.h:196
void getBBXMin(float &x, float &y, float &z) const
void setStateFileName(const QString &name)
Definition: qglviewer.h:1059
void on_actionSettings_triggered()
Definition: ViewerGui.cpp:628
void on_actionExit_triggered()
Definition: ViewerGui.cpp:620
CameraFollowMode * m_cameraFollowMode
Definition: ViewerGui.h:203
void setBackgroundColor(const QColor &color)
Definition: qglviewer.h:186
virtual void addKeyFrameToPath(unsigned int i)
Definition: camera.cpp:1710
void updateStatusBar(QString message, int duration)
void setOcTreeUISwitches()
Definition: ViewerGui.cpp:459
void on_loadcampose_triggered()
Definition: ViewerGui.cpp:1192
virtual bool restoreStateFromFile()
Definition: qglviewer.cpp:3460
void setMaxRange(double range)
PointcloudDrawer * m_pointcloudDrawer
Definition: ViewerGui.h:202
void on_actionOpen_file_triggered()
Definition: ViewerGui.cpp:662
void on_actionSelected_toggled(bool enabled)
Definition: ViewerGui.cpp:1151
void on_actionOctree_structure_toggled(bool enabled)
Definition: ViewerGui.cpp:1134
static const unsigned int DEFAULT_OCTREE_ID
Definition: ViewerGui.h:61
void setNodesInBBX(const point3d &min, const point3d &max, bool occupied)
Definition: ViewerGui.cpp:883
double getResolution()
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
AbstractOcTree * octree
Definition: OcTreeRecord.h:34
OcTreeDrawer * octree_drawer
Definition: OcTreeRecord.h:35
double getMaxRange()
void loadCameraPosition(const char *filename)
Definition: ViewerGui.cpp:1209
std::map< int, OcTreeRecord > m_octrees
Definition: ViewerGui.h:194
void setResolution(double resolution)
float logodds(double probability)
virtual void playPath(unsigned int i)
Definition: camera.cpp:1726
virtual void setScanGraph(const ScanGraph &graph)
#define OCTOMAP_ERROR(...)
void on_actionPrintout_mode_toggled(bool checked)
Definition: ViewerGui.cpp:960
void on_actionFill_unknown_in_selection_triggered()
Definition: ViewerGui.cpp:771
virtual void help()
Definition: qglviewer.cpp:1975
void openMapCollection()
Definition: ViewerGui.cpp:513
void saveSnapshot(bool automatic=true, bool overwrite=false)
void on_actionHelp_triggered()
Definition: ViewerGui.cpp:624
void setSnapshotCounter(int counter)
Definition: qglviewer.h:516
void changeTreeDepth(int depth)
Definition: ViewerGui.cpp:608
bool getOctreeRecord(int id, OcTreeRecord *&otr)
Definition: ViewerGui.cpp:167
void on_actionConvert_ml_tree_triggered()
Definition: ViewerGui.cpp:1071
void changeCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ)
void on_actionPointcloud_toggled(bool checked)
Definition: ViewerGui.cpp:1013
void on_actionExpand_tree_triggered()
Definition: ViewerGui.cpp:1107
qglviewer::Camera * camera() const
Definition: qglviewer.h:250
void openTree()
open binary format OcTree
Definition: ViewerGui.cpp:474


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Wed Jun 5 2019 19:26:39