34 #define _MAXRANGE_URG 5.1 35 #define _MAXRANGE_SICK 50.0 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(
"") {
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());
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());
77 connect(
this, SIGNAL(
updateStatusBar(QString,
int)), statusBar(), SLOT(showMessage(QString,
int)));
79 connect(settingsPanel, SIGNAL(treeDepthChanged(
int)),
this, SLOT(
changeTreeDepth(
int)));
83 connect(settingsCameraPanel, SIGNAL(jumpToFrame(
unsigned)),
m_cameraFollowMode, SLOT(jumpToFrame(
unsigned)));
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()));
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)));
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)));
114 connect(settingsCameraPanel, SIGNAL(
changeCamPosition(
double,
double,
double,
double,
double,
double)),
115 m_glwidget, SLOT(setCamPosition(
double,
double,
double,
double,
double,
double)));
119 connect(
ui.actionReset_view, SIGNAL(triggered()),
m_glwidget, SLOT(resetView()));
140 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin(); it !=
m_octrees.end(); ++it) {
142 delete (it->second.octree_drawer);
143 delete (it->second.octree);
158 std::cerr <<
string.toLocal8Bit().data();
159 if (newline) std::cerr << std::endl;
160 else std::cerr << std::flush;
168 std::map<int, OcTreeRecord>::iterator it =
m_octrees.find(
id);
185 if (dynamic_cast<OcTree*>(tree)) {
189 else if (dynamic_cast<ColorOcTree*>(tree)) {
209 if (dynamic_cast<OcTree*>(tree)) {
213 else if (dynamic_cast<ColorOcTree*>(tree)) {
233 double minX, minY, minZ, maxX, maxY, maxZ;
234 minX = minY = minZ = -10;
235 maxX = maxY = maxZ = 10;
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;
243 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin(); it !=
m_octrees.end(); ++it) {
245 double lminX, lminY, lminZ, lmaxX, lmaxY, lmaxZ;
246 it->second.octree->getMetricMin(lminX, lminY, lminZ);
247 it->second.octree->getMetricMax(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();
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;
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());
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);
289 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin(); it !=
m_octrees.end(); ++it) {
291 it->second.octree_drawer->setOcTree(*it->second.octree, it->second.origin, it->second.id);
304 QApplication::setOverrideCursor(Qt::WaitCursor);
307 std::cerr << std::endl;
314 unsigned currentScan = 1;
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() );
320 std::cout <<
" S ("<<currentScan<<
"/"<<numScans<<
") " << std::flush;
328 QApplication::restoreOverrideCursor();
331 std::cerr <<
"generateOctree called but no ScanGraph present!\n";
340 showInfo(
"Inserting first scan node into tree... ",
true);
341 QApplication::setOverrideCursor(Qt::WaitCursor);
352 QApplication::restoreOverrideCursor();
360 showInfo(
"Inserting next scan node into tree... ",
true);
362 QApplication::setOverrideCursor(Qt::WaitCursor);
366 fprintf(stderr,
"ERROR: OctreeRecord for id %d not found!\n",
DEFAULT_OCTREE_ID);
374 QApplication::restoreOverrideCursor();
382 for (
unsigned i = 0; i < scans; ++i){
395 QFileInfo fileinfo(temp);
396 if (fileinfo.suffix() ==
"graph"){
398 }
else if (fileinfo.suffix() ==
"bt"){
401 else if (fileinfo.suffix() ==
"ot")
405 else if (fileinfo.suffix() ==
"hot"){
408 else if (fileinfo.suffix() ==
"dat"){
412 QMessageBox::warning(
this,
"Unknown file",
"Cannot open file, unknown extension: "+fileinfo.suffix(), QMessageBox::Ok);
420 QApplication::setOverrideCursor(Qt::WaitCursor);
433 QApplication::setOverrideCursor(Qt::WaitCursor);
445 std::cout <<
"ERROR: could not read " <<
m_filename << std::endl;
451 pose6d laser_pose(0,0,0,0,0,0);
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);
501 ui.actionHeight_map->setText (
"Map color");
503 ui.actionHeight_map->setChecked(
true);
507 QMessageBox::warning(
this,
"File error",
"Cannot open OcTree file", QMessageBox::Ok);
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);
527 it != collection.
end(); ++it) {
528 OCTOMAP_DEBUG(
"Adding hierarchy node %s\n", (*it)->getId().c_str());
529 OcTree* tree = (*it)->getMap();
531 OCTOMAP_ERROR(
"Error while reading node %s\n", (*it)->getId().c_str());
533 OCTOMAP_DEBUG(
"Read tree with %zu tree nodes\n", tree->size());
535 pose6d origin = (*it)->getOrigin();
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);
561 unsigned currentScan;
564 fprintf(stderr,
"loadGraph:: generating octree from complete graph.\n" );
567 currentScan = graphSize;
583 QApplication::restoreOverrideCursor();
587 showInfo(
"Done (" +QString::number(currentScan)+
" of "+ QString::number(graphSize)+
" nodes)",
true);
601 if (
ui.actionTrajectory->isChecked())
604 if (
ui.actionPointcloud->isChecked())
610 if (depth < 1 || depth > 16)
648 bool maxRangeChanged = (std::abs(oldLaserMaxRange -
m_laserMaxRange) > 1e-5);
650 if (resolutionChanged)
655 }
else if (resolutionChanged || maxRangeChanged){
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()){
668 m_filename = std::string(filename.toLocal8Bit().data());
678 QString filename = QFileDialog::getOpenFileName(
this,
679 tr(
"Open graph file incrementally (at start)"),
"",
680 "Binary scan graph (*.graph)");
681 if (!filename.isEmpty()){
685 m_filename = std::string(filename.toLocal8Bit().data());
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.",
705 QString filename = QFileDialog::getSaveFileName(
this, tr(
"Save octree file"),
706 "", tr(
"Full OcTree (*.ot);;Bonsai Tree file (*.bt);;"));
709 QApplication::setOverrideCursor(Qt::WaitCursor);
710 showInfo(
"Writing file... ",
false);
712 QFileInfo fileinfo(filename);
713 std::string std_filename;
715 std_filename = filename.toLocal8Bit().data();
717 std_filename = filename.toStdString();
722 if (fileinfo.suffix() ==
"bt") {
727 QMessageBox::warning(
this,
"Unknown tree type",
728 "Could not convert to occupancy tree for writing .bt file",
732 else if (fileinfo.suffix() ==
"ot"){
736 QMessageBox::warning(
this,
"Unknown file",
737 "Cannot write file, unknown extension: "+fileinfo.suffix(),
741 QApplication::restoreOverrideCursor();
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);
807 octree->
deleteNode(it.getKey(), it.getDepth());
810 QMessageBox::warning(
this,
"Not implemented",
"Functionality not yet implemented for this octree type",
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);
834 for(OcTree::leaf_iterator it = octree->
begin_leafs(),
835 end=octree->
end_leafs(); it!= end; ++it){
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])
845 QMessageBox::warning(
this,
"Not implemented",
"Functionality not yet implemented for this octree type",
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);
867 it->setLogOdds(logodds);
874 QMessageBox::warning(
this,
"Not implemented",
"Functionality not yet implemented for this octree type",
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);
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]){
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);
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]){
953 ui.actionExport_sequence->setChecked(
false);
962 ui.actionHeight_map->setChecked(
false);
963 ui.actionSemanticColoring->setChecked(
false);
971 ui.menuDelete_nodes->setEnabled(checked);
972 ui.menuFill_selection->setEnabled(checked);
973 ui.menuChange_nodes_in_selection->setEnabled(checked);
984 ui.actionPrintout_mode->setChecked(
false);
985 ui.actionSemanticColoring->setChecked(
false);
992 ui.actionHeight_map->setChecked(
false);
993 ui.actionPrintout_mode->setChecked(
false);
1004 ui.actionRestore_camera->setEnabled(
true);
1032 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1034 it->second.octree_drawer->enableAxes(checked);
1049 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1052 delete (it->second.octree_drawer);
1053 delete (it->second.octree);
1072 QApplication::setOverrideCursor(Qt::WaitCursor);
1074 showInfo(
"Converting OcTree to maximum Likelihood map... ");
1075 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1078 if (dynamic_cast<OcTree*>(t)) {
1079 ((
OcTree*) t)->toMaxLikelihood();
1081 else if (dynamic_cast<OcTree*>(t)) {
1087 QApplication::restoreOverrideCursor();
1093 QApplication::setOverrideCursor(Qt::WaitCursor);
1096 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1098 it->second.octree->prune();
1103 QApplication::restoreOverrideCursor();
1109 QApplication::setOverrideCursor(Qt::WaitCursor);
1114 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1116 it->second.octree->expand();
1122 QApplication::restoreOverrideCursor();
1127 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1129 it->second.octree_drawer->enableOcTreeCells(enabled);
1135 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1137 it->second.octree_drawer->enableOcTree(enabled);
1143 for (std::map<int, OcTreeRecord>::iterator it =
m_octrees.begin();
1145 it->second.octree_drawer->enableFreespace(enabled);
1186 QString filename = QFileDialog::getSaveFileName(
this,
"Save Viewer State",
"camera.xml",
"Camera/State file (*.xml)");
1187 if (!filename.isEmpty()) {
1193 QString filename = QFileDialog::getOpenFileName(
this,
"Load Viewer State",
"camera.xml",
"Camera/State file (*.xml)");
1194 if (!filename.isEmpty()) {
ScanNode * addNode(Pointcloud *scan, pose6d pose)
void on_actionRestore_camera_triggered()
QLabel * m_mapMemoryStatus
ViewerWidget * m_glwidget
virtual std::string getTreeType() const =0
void updateInnerOccupancy()
ScanGraph::iterator m_nextScanToAdd
void on_actionStore_camera_triggered()
void on_actionOctree_cells_toggled(bool enabled)
std::istream & readBinary(std::ifstream &s)
void openOcTree()
open "regular" file containing an octree
void on_action_bg_black_triggered()
double m_octreeResolution
void on_actionTest_triggered()
void loadGraph(bool completeGraph=true)
void openGraph(bool completeGraph=true)
float getClampingThresMaxLog() const
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()
void addNextScans(unsigned scans)
void on_actionClear_unknown_in_selection_triggered()
void on_action_bg_white_triggered()
void on_actionReload_Octree_triggered()
void on_actionSemanticColoring_toggled(bool checked)
void saveCameraPosition(const char *filename) const
const leaf_iterator end_leafs() const
void changeNumberOfScans(unsigned scans)
virtual void saveStateToFile()
void on_actionFill_nodes_in_selection_triggered()
void on_actionSave_file_triggered()
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)
std::string m_filename
Filename of last loaded file, in case it is necessary to reload it.
virtual void deletePath(unsigned int i)
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
void on_actionHideBackground_toggled(bool checked)
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
void on_actionClear_nodes_in_selection_triggered()
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
void updateNodesInBBX(const point3d &min, const point3d &max, bool occupied)
unsigned int getLaserType()
void on_actionDelete_nodes_outside_of_selection_triggered()
TrajectoryDrawer * m_trajectoryDrawer
void on_actionAxes_toggled(bool checked)
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)
std::vector< ScanNode * >::iterator iterator
ViewerGui(const std::string &filename="", QWidget *parent=0)
void on_actionClear_triggered()
void on_actionFill_selection_triggered()
void addOctree(AbstractOcTree *tree, int id, pose6d origin)
void on_actionExport_view_triggered()
The Vec class represents 3D positions and 3D vectors.
void on_actionHeight_map_toggled(bool checked)
virtual double getResolution() const =0
void getBBXMax(float &x, float &y, float &z) const
void on_action_bg_gray_triggered()
bool openSnapshotFormatDialog()
void changeResolution(double resolution)
QColor backgroundColor() const
void setLaserType(int type)
void on_savecampose_triggered()
void setScanGraph(octomap::ScanGraph *graph)
bool writeBinaryConst(const std::string &filename) const
void on_actionSelection_box_toggled(bool checked)
void setNonNodesInBBX(const point3d &min, const point3d &max, bool occupied)
unsigned int m_max_tree_depth
bool write(const std::string &filename) const
void on_actionPrune_tree_triggered()
void on_actionExport_sequence_triggered(bool checked)
void on_actionDelete_nodes_in_selection_triggered()
void on_actionTrajectory_toggled(bool checked)
void on_actionOpen_graph_incremental_triggered()
void getBBXMin(float &x, float &y, float &z) const
void setStateFileName(const QString &name)
void on_actionSettings_triggered()
void on_actionExit_triggered()
CameraFollowMode * m_cameraFollowMode
void setBackgroundColor(const QColor &color)
virtual void addKeyFrameToPath(unsigned int i)
void updateStatusBar(QString message, int duration)
void setOcTreeUISwitches()
void on_loadcampose_triggered()
virtual bool restoreStateFromFile()
void setMaxRange(double range)
PointcloudDrawer * m_pointcloudDrawer
double getResolution() const
void on_actionOpen_file_triggered()
void on_actionSelected_toggled(bool enabled)
void on_actionOctree_structure_toggled(bool enabled)
static const unsigned int DEFAULT_OCTREE_ID
void setNodesInBBX(const point3d &min, const point3d &max, bool occupied)
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
OcTreeDrawer * octree_drawer
void loadCameraPosition(const char *filename)
std::map< int, OcTreeRecord > m_octrees
void setResolution(double resolution)
float logodds(double probability)
virtual void playPath(unsigned int i)
virtual void setScanGraph(const ScanGraph &graph)
#define OCTOMAP_ERROR(...)
void on_actionPrintout_mode_toggled(bool checked)
void on_actionFill_unknown_in_selection_triggered()
const leaf_bbx_iterator end_leafs_bbx() const
void saveSnapshot(bool automatic=true, bool overwrite=false)
void on_actionHelp_triggered()
float getClampingThresMinLog() const
void setSnapshotCounter(int counter)
void changeTreeDepth(int depth)
bool getOctreeRecord(int id, OcTreeRecord *&otr)
void on_actionConvert_ml_tree_triggered()
void changeCamPosition(double x, double y, double z, double lookX, double lookY, double lookZ)
void on_actionPointcloud_toggled(bool checked)
void on_actionExpand_tree_triggered()
qglviewer::Camera * camera() const
void openTree()
open binary format OcTree