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


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Apr 3 2025 02:40:44