00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #include <iostream>
00026 #include <fstream>
00027
00028
00029 #include <octovis/ViewerGui.h>
00030 #include <octovis/ColorOcTreeDrawer.h>
00031 #include <octomap/MapCollection.h>
00032
00033
00034 #define _MAXRANGE_URG 5.1
00035 #define _MAXRANGE_SICK 50.0
00036
00037 namespace octomap{
00038
00039 ViewerGui::ViewerGui(const std::string& filename, QWidget *parent)
00040 : QMainWindow(parent), m_scanGraph(NULL),
00041 m_trajectoryDrawer(NULL), m_pointcloudDrawer(NULL),
00042 m_cameraFollowMode(NULL),
00043 m_octreeResolution(0.1), m_laserMaxRange(-1.), m_occupancyThresh(0.5),
00044 m_max_tree_depth(16), m_laserType(LASERTYPE_SICK),
00045 m_cameraStored(false), m_filename("") {
00046
00047 ui.setupUi(this);
00048 m_glwidget = new ViewerWidget(this);
00049 this->setCentralWidget(m_glwidget);
00050
00051
00052 ViewerSettingsPanel* settingsPanel = new ViewerSettingsPanel(this);
00053 QDockWidget* settingsDock = new QDockWidget("Octree / Scan graph settings", this);
00054 settingsDock->setWidget(settingsPanel);
00055 this->addDockWidget(Qt::RightDockWidgetArea, settingsDock);
00056 ui.menuShow->addAction(settingsDock->toggleViewAction());
00057
00058
00059 ViewerSettingsPanelCamera* settingsCameraPanel = new ViewerSettingsPanelCamera(this);
00060 QDockWidget *settingsCameraDock = new QDockWidget("Camera settings", this);
00061 settingsCameraDock->setWidget(settingsCameraPanel);
00062 this->addDockWidget(Qt::RightDockWidgetArea, settingsCameraDock);
00063 this->tabifyDockWidget(settingsDock, settingsCameraDock);
00064 settingsDock->raise();
00065 ui.menuShow->addAction(settingsCameraDock->toggleViewAction());
00066
00067
00068 m_mapSizeStatus = new QLabel("Map size", this);
00069 m_mapMemoryStatus = new QLabel("Memory consumption", this);
00070 m_mapSizeStatus->setFrameStyle(QFrame::Panel | QFrame::Sunken);
00071 m_mapMemoryStatus->setFrameStyle(QFrame::Panel | QFrame::Sunken);
00072 statusBar()->addPermanentWidget(m_mapSizeStatus);
00073 statusBar()->addPermanentWidget(m_mapMemoryStatus);
00074
00075 m_cameraFollowMode = new CameraFollowMode();
00076
00077 connect(this, SIGNAL(updateStatusBar(QString, int)), statusBar(), SLOT(showMessage(QString, int)));
00078
00079 connect(settingsPanel, SIGNAL(treeDepthChanged(int)), this, SLOT(changeTreeDepth(int)));
00080 connect(settingsPanel, SIGNAL(addNextScans(unsigned)), this, SLOT(addNextScans(unsigned)));
00081 connect(settingsPanel, SIGNAL(gotoFirstScan()), this, SLOT(gotoFirstScan()));
00082
00083 connect(settingsCameraPanel, SIGNAL(jumpToFrame(unsigned)), m_cameraFollowMode, SLOT(jumpToFrame(unsigned)));
00084 connect(settingsCameraPanel, SIGNAL(play()), m_cameraFollowMode, SLOT(play()));
00085 connect(settingsCameraPanel, SIGNAL(pause()), m_cameraFollowMode, SLOT(pause()));
00086 connect(settingsCameraPanel, SIGNAL(clearCameraPath()), m_cameraFollowMode, SLOT(clearCameraPath()));
00087 connect(settingsCameraPanel, SIGNAL(saveToCameraPath()), m_cameraFollowMode, SLOT(saveToCameraPath()));
00088 connect(settingsCameraPanel, SIGNAL(removeFromCameraPath()), m_cameraFollowMode, SLOT(removeFromCameraPath()));
00089 connect(settingsCameraPanel, SIGNAL(addToCameraPath()), m_cameraFollowMode, SLOT(addToCameraPath()));
00090 connect(settingsCameraPanel, SIGNAL(followCameraPath()), m_cameraFollowMode, SLOT(followCameraPath()));
00091 connect(settingsCameraPanel, SIGNAL(followRobotPath()), m_cameraFollowMode, SLOT(followRobotPath()));
00092
00093 connect(m_cameraFollowMode, SIGNAL(changeNumberOfFrames(unsigned)), settingsCameraPanel, SLOT(setNumberOfFrames(unsigned)));
00094 connect(m_cameraFollowMode, SIGNAL(frameChanged(unsigned)), settingsCameraPanel, SLOT(setCurrentFrame(unsigned)));
00095 connect(m_cameraFollowMode, SIGNAL(stopped()), settingsCameraPanel, SLOT(setStopped()));
00096 connect(m_cameraFollowMode, SIGNAL(scanGraphAvailable(bool)), settingsCameraPanel, SLOT(setRobotTrajectoryAvailable(bool)));
00097
00098 connect(m_cameraFollowMode, SIGNAL(deleteCameraPath(int)), m_glwidget, SLOT(deleteCameraPath(int)));
00099 connect(m_cameraFollowMode, SIGNAL(removeFromCameraPath(int,int)), m_glwidget, SLOT(removeFromCameraPath(int,int)));
00100 connect(m_cameraFollowMode, SIGNAL(appendToCameraPath(int, const octomath::Pose6D&)), m_glwidget, SLOT(appendToCameraPath(int, const octomath::Pose6D&)));
00101 connect(m_cameraFollowMode, SIGNAL(appendCurrentToCameraPath(int)), m_glwidget, SLOT(appendCurrentToCameraPath(int)));
00102 connect(m_cameraFollowMode, SIGNAL(addCurrentToCameraPath(int,int)), m_glwidget, SLOT(addCurrentToCameraPath(int,int)));
00103 connect(m_cameraFollowMode, SIGNAL(updateCameraPath(int,int)), m_glwidget, SLOT(updateCameraPath(int,int)));
00104 connect(m_cameraFollowMode, SIGNAL(playCameraPath(int,int)), m_glwidget, SLOT(playCameraPath(int,int)));
00105 connect(m_cameraFollowMode, SIGNAL(stopCameraPath(int)), m_glwidget, SLOT(stopCameraPath(int)));
00106 connect(m_cameraFollowMode, SIGNAL(jumpToCamFrame(int, int)), m_glwidget, SLOT(jumpToCamFrame(int, int)));
00107 connect(m_glwidget, SIGNAL(cameraPathStopped(int)), m_cameraFollowMode, SLOT(cameraPathStopped(int)));
00108 connect(m_glwidget, SIGNAL(cameraPathFrameChanged(int, int)), m_cameraFollowMode, SLOT(cameraPathFrameChanged(int, int)));
00109
00110 connect(this, SIGNAL(changeNumberOfScans(unsigned)), settingsPanel, SLOT(setNumberOfScans(unsigned)));
00111 connect(this, SIGNAL(changeCurrentScan(unsigned)), settingsPanel, SLOT(setCurrentScan(unsigned)));
00112 connect(this, SIGNAL(changeResolution(double)), settingsPanel, SLOT(setResolution(double)));
00113
00114 connect(settingsCameraPanel, SIGNAL(changeCamPosition(double, double, double, double, double, double)),
00115 m_glwidget, SLOT(setCamPosition(double, double, double, double, double, double)));
00116 connect(m_cameraFollowMode, SIGNAL(changeCamPose(const octomath::Pose6D&)),
00117 m_glwidget, SLOT(setCamPose(const octomath::Pose6D&)));
00118
00119 connect(ui.actionReset_view, SIGNAL(triggered()), m_glwidget, SLOT(resetView()));
00120
00121 if (filename != ""){
00122 m_filename = filename;
00123 openFile();
00124 }
00125 }
00126
00127 ViewerGui::~ViewerGui() {
00128 if (m_trajectoryDrawer){
00129 m_glwidget->removeSceneObject(m_trajectoryDrawer);
00130 delete m_trajectoryDrawer;
00131 m_trajectoryDrawer = NULL;
00132 }
00133
00134 if (m_pointcloudDrawer){
00135 m_glwidget->removeSceneObject(m_pointcloudDrawer);
00136 delete m_pointcloudDrawer;
00137 m_pointcloudDrawer = NULL;
00138 }
00139
00140 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
00141 m_glwidget->removeSceneObject(it->second.octree_drawer);
00142 delete (it->second.octree_drawer);
00143 delete (it->second.octree);
00144 }
00145 m_octrees.clear();
00146
00147 if(m_cameraFollowMode) {
00148 delete m_cameraFollowMode;
00149 m_cameraFollowMode = NULL;
00150 }
00151 }
00152
00153 bool ViewerGui::isShown() {
00154 return m_glwidget->isVisible();
00155 }
00156
00157 void ViewerGui::showInfo(QString string, bool newline) {
00158 std::cerr << string.toLocal8Bit().data();
00159 if (newline) std::cerr << std::endl;
00160 else std::cerr << std::flush;
00161 int duration = 0;
00162 if (newline)
00163 duration = 3000;
00164 emit updateStatusBar(string, duration);
00165 }
00166
00167 bool ViewerGui::getOctreeRecord(int id, OcTreeRecord*& otr) {
00168 std::map<int, OcTreeRecord>::iterator it = m_octrees.find(id);
00169 if( it != m_octrees.end() ) {
00170 otr = &(it->second);
00171 return true;
00172 }
00173 else {
00174 return false;
00175 }
00176 }
00177
00178 void ViewerGui::addOctree(octomap::AbstractOcTree* tree, int id, octomap::pose6d origin) {
00179
00180 OcTreeRecord* r;
00181 bool foundRecord = getOctreeRecord(id, r);
00182 if (foundRecord && r->octree->getTreeType().compare(tree->getTreeType()) !=0){
00183
00184 delete r->octree_drawer;
00185 if (dynamic_cast<OcTree*>(tree)) {
00186 r->octree_drawer = new OcTreeDrawer();
00187
00188 }
00189 else if (dynamic_cast<ColorOcTree*>(tree)) {
00190 r->octree_drawer = new ColorOcTreeDrawer();
00191 } else{
00192 OCTOMAP_ERROR("Could not create drawer for tree type %s\n", tree->getTreeType().c_str());
00193 }
00194
00195 delete r->octree;
00196 r->octree = tree;
00197 r->origin = origin;
00198
00199 } else if (foundRecord && r->octree->getTreeType().compare(tree->getTreeType()) ==0) {
00200
00201
00202 delete r->octree;
00203 r->octree = tree;
00204 r->origin = origin;
00205 } else {
00206
00207 OcTreeRecord otr;
00208 otr.id = id;
00209 if (dynamic_cast<OcTree*>(tree)) {
00210 otr.octree_drawer = new OcTreeDrawer();
00211
00212 }
00213 else if (dynamic_cast<ColorOcTree*>(tree)) {
00214 otr.octree_drawer = new ColorOcTreeDrawer();
00215 } else{
00216 OCTOMAP_ERROR("Could not create drawer for tree type %s\n", tree->getTreeType().c_str());
00217 }
00218 otr.octree = tree;
00219 otr.origin = origin;
00220 m_octrees[id] = otr;
00221 m_glwidget->addSceneObject(otr.octree_drawer);
00222 }
00223 }
00224
00225 void ViewerGui::addOctree(octomap::AbstractOcTree* tree, int id) {
00226 octomap::pose6d o;
00227 addOctree(tree, id, o);
00228 }
00229
00230 void ViewerGui::showOcTree() {
00231
00232
00233 double minX, minY, minZ, maxX, maxY, maxZ;
00234 minX = minY = minZ = -10;
00235 maxX = maxY = maxZ = 10;
00236 double sizeX, sizeY, sizeZ;
00237 sizeX = sizeY = sizeZ = 0.;
00238 size_t memoryUsage = 0;
00239 size_t num_nodes = 0;
00240 size_t memorySingleNode = 0;
00241
00242
00243 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
00244
00245 double lminX, lminY, lminZ, lmaxX, lmaxY, lmaxZ;
00246 it->second.octree->getMetricMin(lminX, lminY, lminZ);
00247 it->second.octree->getMetricMax(lmaxX, lmaxY, lmaxZ);
00248
00249 octomap::point3d pmin(lminX, lminY, lminZ);
00250 octomap::point3d pmax(lmaxX, lmaxY, lmaxZ);
00251 pmin = it->second.origin.transform(pmin);
00252 pmax = it->second.origin.transform(pmax);
00253 lminX = pmin.x(); lminY = pmin.y(); lminZ = pmin.z();
00254 lmaxX = pmax.x(); lmaxY = pmax.y(); lmaxZ = pmax.z();
00255
00256 if (lminX < minX) minX = lminX;
00257 if (lminY < minY) minY = lminY;
00258 if (lminZ < minZ) minZ = lminZ;
00259 if (lmaxX > maxX) maxX = lmaxX;
00260 if (lmaxY > maxY) maxY = lmaxY;
00261 if (lmaxZ > maxZ) maxZ = lmaxZ;
00262 double lsizeX, lsizeY, lsizeZ;
00263
00264 it->second.octree->getMetricSize(lsizeX, lsizeY, lsizeZ);
00265 if (lsizeX > sizeX) sizeX = lsizeX;
00266 if (lsizeY > sizeY) sizeY = lsizeY;
00267 if (lsizeZ > sizeZ) sizeZ = lsizeZ;
00268 memoryUsage += it->second.octree->memoryUsage();
00269 num_nodes += it->second.octree->size();
00270 memorySingleNode = std::max(memorySingleNode, it->second.octree->memoryUsageNode());
00271 }
00272
00273 m_glwidget->setSceneBoundingBox(qglviewer::Vec(minX, minY, minZ), qglviewer::Vec(maxX, maxY, maxZ));
00274
00275
00276 QString size = QString("%L1 x %L2 x %L3 m^3; %L4 nodes").arg(sizeX).arg(sizeY).arg(sizeZ).arg(unsigned(num_nodes));
00277 QString memory = QString("Single node: %L1 B; ").arg(memorySingleNode)
00278 + QString ("Octree: %L1 B (%L2 MB)").arg(memoryUsage).arg((double) memoryUsage/(1024.*1024.), 0, 'f', 3);
00279 m_mapMemoryStatus->setText(memory);
00280 m_mapSizeStatus->setText(size);
00281
00282
00283 m_glwidget->updateGL();
00284
00285
00286
00287
00288
00289 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin(); it != m_octrees.end(); ++it) {
00290 it->second.octree_drawer->setMax_tree_depth(m_max_tree_depth);
00291 it->second.octree_drawer->setOcTree(*it->second.octree, it->second.origin, it->second.id);
00292 }
00293
00294
00295
00296 m_glwidget->updateGL();
00297 }
00298
00299
00300 void ViewerGui::generateOctree() {
00301
00302 if (m_scanGraph) {
00303
00304 QApplication::setOverrideCursor(Qt::WaitCursor);
00305
00306 showInfo("Generating OcTree... ");
00307 std::cerr << std::endl;
00308
00309
00310 OcTree* tree = new octomap::OcTree(m_octreeResolution);
00311
00312 octomap::ScanGraph::iterator it;
00313 unsigned numScans = m_scanGraph->size();
00314 unsigned currentScan = 1;
00315 for (it = m_scanGraph->begin(); it != m_nextScanToAdd; it++) {
00316 tree->insertPointCloud(**it, m_laserMaxRange);
00317 fprintf(stderr, "generateOctree:: inserting scan node with %d points, origin: %.2f ,%.2f , %.2f.\n",
00318 (unsigned int) (*it)->scan->size(), (*it)->pose.x(), (*it)->pose.y(), (*it)->pose.z() );
00319
00320 std::cout << " S ("<<currentScan<<"/"<<numScans<<") " << std::flush;
00321 currentScan++;
00322 }
00323
00324 this->addOctree(tree, DEFAULT_OCTREE_ID);
00325 this->showOcTree();
00326
00327 showInfo("Done.", true);
00328 QApplication::restoreOverrideCursor();
00329 }
00330 else {
00331 std::cerr << "generateOctree called but no ScanGraph present!\n";
00332 }
00333
00334 }
00335
00336
00337
00338 void ViewerGui::gotoFirstScan(){
00339 if (m_scanGraph){
00340 showInfo("Inserting first scan node into tree... ", true);
00341 QApplication::setOverrideCursor(Qt::WaitCursor);
00342
00343 m_nextScanToAdd = m_scanGraph->begin();
00344
00345
00346
00347 OcTree* tree = new octomap::OcTree(m_octreeResolution);
00348 this->addOctree(tree, DEFAULT_OCTREE_ID);
00349
00350 addNextScan();
00351
00352 QApplication::restoreOverrideCursor();
00353 showOcTree();
00354 }
00355 }
00356
00357 void ViewerGui::addNextScan(){
00358
00359 if (m_scanGraph){
00360 showInfo("Inserting next scan node into tree... ", true);
00361
00362 QApplication::setOverrideCursor(Qt::WaitCursor);
00363 if (m_nextScanToAdd != m_scanGraph->end()){
00364 OcTreeRecord* r;
00365 if (!getOctreeRecord(DEFAULT_OCTREE_ID, r)) {
00366 fprintf(stderr, "ERROR: OctreeRecord for id %d not found!\n", DEFAULT_OCTREE_ID);
00367 return;
00368 }
00369
00370 ((OcTree*) r->octree)->insertPointCloud(**m_nextScanToAdd, m_laserMaxRange);
00371 m_nextScanToAdd++;
00372 }
00373
00374 QApplication::restoreOverrideCursor();
00375 showOcTree();
00376
00377 }
00378 }
00379
00380
00381 void ViewerGui::addNextScans(unsigned scans){
00382 for (unsigned i = 0; i < scans; ++i){
00383 addNextScan();
00384 }
00385 }
00386
00387
00388
00389
00390 void ViewerGui::openFile(){
00391 if (!m_filename.empty()){
00392 m_glwidget->clearAll();
00393
00394 QString temp = QString(m_filename.c_str());
00395 QFileInfo fileinfo(temp);
00396 if (fileinfo.suffix() == "graph"){
00397 openGraph();
00398 }else if (fileinfo.suffix() == "bt"){
00399 openTree();
00400 }
00401 else if (fileinfo.suffix() == "ot")
00402 {
00403 openOcTree();
00404 }
00405 else if (fileinfo.suffix() == "hot"){
00406 openMapCollection();
00407 }
00408 else if (fileinfo.suffix() == "dat"){
00409 openPointcloud();
00410 }
00411 else {
00412 QMessageBox::warning(this, "Unknown file", "Cannot open file, unknown extension: "+fileinfo.suffix(), QMessageBox::Ok);
00413 }
00414 }
00415 }
00416
00417
00418 void ViewerGui::openGraph(bool completeGraph){
00419
00420 QApplication::setOverrideCursor(Qt::WaitCursor);
00421 showInfo("Loading scan graph from file " + QString(m_filename.c_str()) );
00422
00423 if (m_scanGraph) delete m_scanGraph;
00424 m_scanGraph = new octomap::ScanGraph();
00425 m_scanGraph->readBinary(m_filename);
00426
00427 loadGraph(completeGraph);
00428 }
00429
00430
00431 void ViewerGui::openPointcloud(){
00432
00433 QApplication::setOverrideCursor(Qt::WaitCursor);
00434 showInfo("Loading ASCII pointcloud from file "+QString(m_filename.c_str()) + "...");
00435
00436 if (m_scanGraph) delete m_scanGraph;
00437 m_scanGraph = new octomap::ScanGraph();
00438
00439
00440
00441 std::ifstream s(m_filename.c_str());
00442 Pointcloud* pc = new Pointcloud();
00443
00444 if (!s) {
00445 std::cout <<"ERROR: could not read " << m_filename << std::endl;
00446 return;
00447 }
00448
00449 pc->read(s);
00450
00451 pose6d laser_pose(0,0,0,0,0,0);
00452 m_scanGraph->addNode(pc, laser_pose);
00453
00454 loadGraph(true);
00455 showInfo("Done.", true);
00456 }
00457
00458
00459 void ViewerGui::setOcTreeUISwitches() {
00460 ui.actionPointcloud->setChecked(false);
00461 ui.actionPointcloud->setEnabled(false);
00462 ui.actionOctree_cells->setChecked(true);
00463 ui.actionOctree_cells->setEnabled(true);
00464 ui.actionFree->setChecked(false);
00465 ui.actionFree->setEnabled(true);
00466 ui.actionOctree_structure->setEnabled(true);
00467 ui.actionOctree_structure->setChecked(false);
00468 ui.actionTrajectory->setEnabled(false);
00469 ui.actionConvert_ml_tree->setEnabled(true);
00470 ui.actionReload_Octree->setEnabled(true);
00471 ui.actionSettings->setEnabled(false);
00472 }
00473
00474 void ViewerGui::openTree(){
00475 OcTree* tree = new octomap::OcTree(m_filename);
00476 this->addOctree(tree, DEFAULT_OCTREE_ID);
00477
00478 m_octreeResolution = tree->getResolution();
00479 emit changeResolution(m_octreeResolution);
00480
00481 setOcTreeUISwitches();
00482 showOcTree();
00483 m_glwidget->resetView();
00484 }
00485
00486 void ViewerGui::openOcTree(){
00487 AbstractOcTree* tree = AbstractOcTree::read(m_filename);
00488
00489 if (tree){
00490 this->addOctree(tree, DEFAULT_OCTREE_ID);
00491
00492 m_octreeResolution = tree->getResolution();
00493 emit changeResolution(m_octreeResolution);
00494
00495 setOcTreeUISwitches();
00496 showOcTree();
00497 m_glwidget->resetView();
00498
00499 if (tree->getTreeType() == "ColorOcTree"){
00500
00501 ui.actionHeight_map->setText ("Map color");
00502 this->on_actionHeight_map_toggled(true);
00503 ui.actionHeight_map->setChecked(true);
00504 }
00505 }
00506 else {
00507 QMessageBox::warning(this, "File error", "Cannot open OcTree file", QMessageBox::Ok);
00508 }
00509 }
00510
00511
00512
00513 void ViewerGui::openMapCollection() {
00514
00515 OCTOMAP_DEBUG("Opening hierarchy from %s...\n", m_filename.c_str());
00516
00517 std::ifstream infile(m_filename.c_str(), std::ios_base::in |std::ios_base::binary);
00518 if (!infile.is_open()) {
00519 QMessageBox::warning(this, "File error", "Cannot open OcTree file", QMessageBox::Ok);
00520 return;
00521 }
00522 infile.close();
00523
00524 MapCollection<MapNode<OcTree> > collection(m_filename);
00525 int i=0;
00526 for (MapCollection<MapNode<OcTree> >::iterator it = collection.begin();
00527 it != collection.end(); ++it) {
00528 OCTOMAP_DEBUG("Adding hierarchy node %s\n", (*it)->getId().c_str());
00529 OcTree* tree = (*it)->getMap();
00530 if (!tree)
00531 OCTOMAP_ERROR("Error while reading node %s\n", (*it)->getId().c_str());
00532 else {
00533 OCTOMAP_DEBUG("Read tree with %zu tree nodes\n", tree->size());
00534 }
00535 pose6d origin = (*it)->getOrigin();
00536 this->addOctree(tree, i, origin);
00537 ++i;
00538 }
00539 setOcTreeUISwitches();
00540 showOcTree();
00541 m_glwidget->resetView();
00542 OCTOMAP_DEBUG("done\n");
00543 }
00544
00545 void ViewerGui::loadGraph(bool completeGraph) {
00546
00547 ui.actionSettings->setEnabled(true);
00548 ui.actionPointcloud->setEnabled(true);
00549 ui.actionPointcloud->setChecked(false);
00550 ui.actionTrajectory->setEnabled(true);
00551 ui.actionOctree_cells->setEnabled(true);
00552 ui.actionOctree_cells->setChecked(true);
00553 ui.actionOctree_structure->setEnabled(true);
00554 ui.actionOctree_structure->setChecked(false);
00555 ui.actionFree->setChecked(false);
00556 ui.actionFree->setEnabled(true);
00557 ui.actionReload_Octree->setEnabled(true);
00558 ui.actionConvert_ml_tree->setEnabled(true);
00559
00560 unsigned graphSize = m_scanGraph->size();
00561 unsigned currentScan;
00562
00563 if (completeGraph){
00564 fprintf(stderr, "loadGraph:: generating octree from complete graph.\n" );
00565 m_nextScanToAdd = m_scanGraph->end();
00566 generateOctree();
00567 currentScan = graphSize;
00568 }
00569 else{
00570 m_nextScanToAdd = m_scanGraph->begin();
00571
00572
00573
00574 OcTree* tree = new octomap::OcTree(m_octreeResolution);
00575 this->addOctree(tree, DEFAULT_OCTREE_ID);
00576
00577 addNextScan();
00578
00579 currentScan = 1;
00580 }
00581
00582 m_glwidget->resetView();
00583 QApplication::restoreOverrideCursor();
00584
00585 emit changeNumberOfScans(graphSize);
00586 emit changeCurrentScan(currentScan);
00587 showInfo("Done (" +QString::number(currentScan)+ " of "+ QString::number(graphSize)+" nodes)", true);
00588
00589 if (!m_trajectoryDrawer){
00590 m_trajectoryDrawer = new TrajectoryDrawer();
00591 }
00592 m_trajectoryDrawer->setScanGraph(*m_scanGraph);
00593
00594 if (!m_pointcloudDrawer){
00595 m_pointcloudDrawer = new PointcloudDrawer();
00596 }
00597 m_pointcloudDrawer->setScanGraph(*m_scanGraph);
00598
00599 m_cameraFollowMode->setScanGraph(m_scanGraph);
00600
00601 if (ui.actionTrajectory->isChecked())
00602 m_glwidget->addSceneObject(m_trajectoryDrawer);
00603
00604 if (ui.actionPointcloud->isChecked())
00605 m_glwidget->addSceneObject(m_pointcloudDrawer);
00606 }
00607
00608 void ViewerGui::changeTreeDepth(int depth){
00609
00610 if (depth < 1 || depth > 16)
00611 return;
00612
00613 m_max_tree_depth = unsigned(depth);
00614
00615 if (m_octrees.size() > 0)
00616 showOcTree();
00617 }
00618
00619
00620 void ViewerGui::on_actionExit_triggered(){
00621 this->close();
00622 }
00623
00624 void ViewerGui::on_actionHelp_triggered(){
00625 m_glwidget->help();
00626 }
00627
00628 void ViewerGui::on_actionSettings_triggered(){
00629
00630 ViewerSettings dialog(this);
00631 dialog.setResolution(m_octreeResolution);
00632 dialog.setLaserType(m_laserType);
00633 dialog.setMaxRange(m_laserMaxRange);
00634
00635
00636 if (dialog.exec()){
00637
00638 double oldResolution = m_octreeResolution;
00639 double oldLaserMaxRange = m_laserMaxRange;
00640 double oldType = m_laserType;
00641
00642 m_octreeResolution = dialog.getResolution();
00643 m_laserType = dialog.getLaserType();
00644 m_laserMaxRange = dialog.getMaxRange();
00645
00646
00647 bool resolutionChanged = (std::abs(oldResolution - m_octreeResolution) > 1e-5);
00648 bool maxRangeChanged = (std::abs(oldLaserMaxRange - m_laserMaxRange) > 1e-5);
00649
00650 if (resolutionChanged)
00651 emit changeResolution(m_octreeResolution);
00652
00653 if (oldType != m_laserType){
00654 openFile();
00655 } else if (resolutionChanged || maxRangeChanged){
00656 generateOctree();
00657 }
00658
00659 }
00660 }
00661
00662 void ViewerGui::on_actionOpen_file_triggered(){
00663 QString filename = QFileDialog::getOpenFileName(this,
00664 tr("Open data file"), "",
00665 "All supported files (*.graph *.bt *.ot *.dat);;OcTree file (*.ot);;Bonsai tree file (*.bt);;Binary scan graph (*.graph);;Pointcloud (*.dat);;All files (*)");
00666 if (!filename.isEmpty()){
00667 #ifdef _WIN32
00668 m_filename = std::string(filename.toLocal8Bit().data());
00669 #else
00670 m_filename = filename.toStdString();
00671 #endif
00672 openFile();
00673 }
00674 }
00675
00676
00677 void ViewerGui::on_actionOpen_graph_incremental_triggered(){
00678 QString filename = QFileDialog::getOpenFileName(this,
00679 tr("Open graph file incrementally (at start)"), "",
00680 "Binary scan graph (*.graph)");
00681 if (!filename.isEmpty()){
00682 m_glwidget->clearAll();
00683
00684 #ifdef _WIN32
00685 m_filename = std::string(filename.toLocal8Bit().data());
00686 #else
00687 m_filename = filename.toStdString();
00688 #endif
00689
00690 openGraph(false);
00691 }
00692 }
00693
00694 void ViewerGui::on_actionSave_file_triggered(){
00695
00696 OcTreeRecord* r;
00697 if (!getOctreeRecord(DEFAULT_OCTREE_ID, r)) {
00698 fprintf(stderr, "ERROR: OctreeRecord for id %d not found!\n", DEFAULT_OCTREE_ID);
00699 QMessageBox::warning(this, tr("3D Mapping Viewer"),
00700 "Error: No OcTree present.",
00701 QMessageBox::Ok);
00702 return;
00703 }
00704
00705 QString filename = QFileDialog::getSaveFileName(this, tr("Save octree file"),
00706 "", tr("Full OcTree (*.ot);;Bonsai Tree file (*.bt);;"));
00707
00708 if (filename != ""){
00709 QApplication::setOverrideCursor(Qt::WaitCursor);
00710 showInfo("Writing file... ", false);
00711
00712 QFileInfo fileinfo(filename);
00713 std::string std_filename;
00714 #ifdef _WIN32
00715 std_filename = filename.toLocal8Bit().data();
00716 #else
00717 std_filename = filename.toStdString();
00718 #endif
00719
00720 AbstractOcTree* t = r->octree;
00721
00722 if (fileinfo.suffix() == "bt") {
00723 AbstractOccupancyOcTree* ot = dynamic_cast<AbstractOccupancyOcTree*> (t);
00724 if (ot)
00725 ot->writeBinaryConst(std_filename);
00726 else{
00727 QMessageBox::warning(this, "Unknown tree type",
00728 "Could not convert to occupancy tree for writing .bt file",
00729 QMessageBox::Ok);
00730 }
00731 }
00732 else if (fileinfo.suffix() == "ot"){
00733 r->octree->write(std_filename);
00734 }
00735 else {
00736 QMessageBox::warning(this, "Unknown file",
00737 "Cannot write file, unknown extension: "+fileinfo.suffix(),
00738 QMessageBox::Ok);
00739 }
00740
00741 QApplication::restoreOverrideCursor();
00742 showInfo("Done.", true);
00743 }
00744 }
00745
00746 void ViewerGui::on_actionClear_nodes_in_selection_triggered(){
00747 point3d min, max;
00748 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00749 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00750
00751 updateNodesInBBX(min, max, false);
00752 }
00753
00754 void ViewerGui::on_actionClear_selection_triggered(){
00755 point3d min, max;
00756 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00757 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00758
00759 setNodesInBBX(min, max, false);
00760 }
00761
00762 void ViewerGui::on_actionClear_unknown_in_selection_triggered()
00763 {
00764 point3d min, max;
00765 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00766 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00767
00768 setNonNodesInBBX(min, max, false);
00769 }
00770
00771 void ViewerGui::on_actionFill_unknown_in_selection_triggered()
00772 {
00773 point3d min, max;
00774 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00775 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00776
00777 setNonNodesInBBX(min, max, true);
00778 }
00779
00780 void ViewerGui::on_actionFill_selection_triggered(){
00781 point3d min, max;
00782 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00783 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00784
00785 setNodesInBBX(min, max, true);
00786 }
00787
00788 void ViewerGui::on_actionFill_nodes_in_selection_triggered(){
00789 point3d min, max;
00790 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00791 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00792
00793 updateNodesInBBX(min, max, true);
00794 }
00795
00796 void ViewerGui::on_actionDelete_nodes_in_selection_triggered(){
00797 point3d min, max;
00798 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00799 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00800
00801 for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
00802 OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
00803
00804 if (octree){
00805 for(OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(min,max),
00806 end=octree->end_leafs_bbx(); it!= end; ++it){
00807 octree->deleteNode(it.getKey(), it.getDepth());
00808 }
00809 } else{
00810 QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
00811 QMessageBox::Ok);
00812
00813 }
00814 }
00815
00816 showOcTree();
00817 }
00818
00819 void ViewerGui::on_actionDelete_nodes_outside_of_selection_triggered(){
00820 point3d min, max;
00821 m_glwidget->selectionBox().getBBXMin(min.x(), min.y(), min.z());
00822 m_glwidget->selectionBox().getBBXMax(max.x(), max.y(), max.z());
00823
00824 for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
00825 OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
00826
00827 if (octree){
00828 octomap::OcTreeKey minKey, maxKey;
00829
00830 if (!octree->coordToKeyChecked(min, minKey) || !octree->coordToKeyChecked(max, maxKey)){
00831 return;
00832 }
00833
00834 for(OcTree::leaf_iterator it = octree->begin_leafs(),
00835 end=octree->end_leafs(); it!= end; ++it){
00836
00837 OcTreeKey k = it.getKey();
00838 if (k[0] < minKey[0] || k[1] < minKey[1] || k[2] < minKey[2]
00839 || k[0] > maxKey[0] || k[1] > maxKey[1] || k[2] > maxKey[2])
00840 {
00841 octree->deleteNode(k, it.getDepth());
00842 }
00843 }
00844 } else
00845 QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
00846 QMessageBox::Ok);
00847 }
00848
00849 showOcTree();
00850 }
00851
00852 void ViewerGui::updateNodesInBBX(const point3d& min, const point3d& max, bool occupied){
00853 for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
00854 OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
00855
00856 if (octree){
00857 float logodds;
00858 if (occupied)
00859 logodds = octree->getClampingThresMaxLog();
00860 else
00861 logodds = octree->getClampingThresMinLog();
00862
00863 for(OcTree::leaf_bbx_iterator it = octree->begin_leafs_bbx(min,max),
00864 end=octree->end_leafs_bbx(); it!= end; ++it)
00865 {
00866
00867 it->setLogOdds(logodds);
00868 }
00869
00870
00871 octree->updateInnerOccupancy();
00872
00873 } else
00874 QMessageBox::warning(this, "Not implemented", "Functionality not yet implemented for this octree type",
00875 QMessageBox::Ok);
00876
00877 }
00878
00879 showOcTree();
00880 }
00881
00882
00883 void ViewerGui::setNodesInBBX(const point3d& min, const point3d& max, bool occupied){
00884 for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
00885 OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
00886
00887 if (octree){
00888 float logodds = octree->getClampingThresMaxLog() - octree->getClampingThresMinLog();
00889 if (!occupied)
00890 logodds *= -1;
00891
00892 OcTreeKey minKey(0,0,0);
00893 OcTreeKey maxKey(0,0,0);
00894 octree->coordToKeyChecked(min, minKey);
00895 octree->coordToKeyChecked(max, maxKey);
00896 OcTreeKey k;
00897 for (k[0] = minKey[0]; k[0] < maxKey[0]; ++k[0]){
00898 for (k[1] = minKey[1]; k[1] < maxKey[1]; ++k[1]){
00899 for (k[2] = minKey[2]; k[2] < maxKey[2]; ++k[2]){
00900 octree->updateNode(k, logodds);
00901 }
00902 }
00903 }
00904 }
00905
00906 }
00907
00908 showOcTree();
00909 }
00910
00911 void ViewerGui::setNonNodesInBBX(const point3d& min, const point3d& max, bool occupied) {
00912 for (std::map<int, OcTreeRecord>::iterator t_it = m_octrees.begin(); t_it != m_octrees.end(); ++t_it) {
00913 OcTree* octree = dynamic_cast<OcTree*>(t_it->second.octree);
00914
00915 if (octree){
00916 float logodds = octree->getClampingThresMaxLog() - octree->getClampingThresMinLog();
00917 if (!occupied)
00918 logodds *= -1;
00919
00920 OcTreeKey minKey(0,0,0);
00921 OcTreeKey maxKey(0,0,0);
00922 octree->coordToKeyChecked(min, minKey);
00923 octree->coordToKeyChecked(max, maxKey);
00924 OcTreeKey k;
00925 for (k[0] = minKey[0]; k[0] < maxKey[0]; ++k[0]){
00926 for (k[1] = minKey[1]; k[1] < maxKey[1]; ++k[1]){
00927 for (k[2] = minKey[2]; k[2] < maxKey[2]; ++k[2]){
00928 OcTreeNode* n = octree->search(k);
00929 if(!n)
00930 octree->updateNode(k, logodds);
00931 }
00932 }
00933 }
00934 }
00935
00936 }
00937
00938 showOcTree();
00939 }
00940
00941 void ViewerGui::on_actionExport_view_triggered(){
00942 m_glwidget->openSnapshotFormatDialog();
00943 m_glwidget->saveSnapshot(false);
00944 }
00945
00946 void ViewerGui::on_actionExport_sequence_triggered(bool checked){
00947 if(checked) {
00948 if(m_glwidget->openSnapshotFormatDialog()) {
00949 m_glwidget->saveSnapshot(false);
00950 m_glwidget->setSnapshotCounter(0);
00951 connect(m_glwidget, SIGNAL(drawFinished(bool)), m_glwidget, SLOT(saveSnapshot(bool)));
00952 } else {
00953 ui.actionExport_sequence->setChecked(false);
00954 }
00955 } else {
00956 disconnect(m_glwidget, SIGNAL(drawFinished(bool)), m_glwidget, SLOT(saveSnapshot(bool)));
00957 }
00958 }
00959
00960 void ViewerGui::on_actionPrintout_mode_toggled(bool checked){
00961 if (checked) {
00962 ui.actionHeight_map->setChecked(false);
00963 ui.actionSemanticColoring->setChecked(false);
00964 }
00965
00966 m_glwidget->enablePrintoutMode(checked);
00967 }
00968
00969 void ViewerGui::on_actionSelection_box_toggled(bool checked){
00970
00971 ui.menuDelete_nodes->setEnabled(checked);
00972 ui.menuFill_selection->setEnabled(checked);
00973 ui.menuChange_nodes_in_selection->setEnabled(checked);
00974
00975
00976 m_glwidget->enableSelectionBox(checked);
00977
00978
00979 m_glwidget->updateGL();
00980 }
00981
00982 void ViewerGui::on_actionHeight_map_toggled(bool checked){
00983 if (checked) {
00984 ui.actionPrintout_mode->setChecked(false);
00985 ui.actionSemanticColoring->setChecked(false);
00986 }
00987 m_glwidget->enableHeightColorMode(checked);
00988 }
00989
00990 void ViewerGui::on_actionSemanticColoring_toggled(bool checked) {
00991 if (checked) {
00992 ui.actionHeight_map->setChecked(false);
00993 ui.actionPrintout_mode->setChecked(false);
00994 }
00995
00996 m_glwidget->enableSemanticColoring(checked);
00997 }
00998
00999
01000 void ViewerGui::on_actionStore_camera_triggered(){
01001 m_glwidget->camera()->deletePath(0);
01002 m_glwidget->camera()->addKeyFrameToPath(0);
01003 m_cameraStored = true;
01004 ui.actionRestore_camera->setEnabled(true);
01005 }
01006
01007 void ViewerGui::on_actionRestore_camera_triggered(){
01008 if (m_cameraStored){
01009 m_glwidget->camera()->playPath(0);
01010 }
01011 }
01012
01013 void ViewerGui::on_actionPointcloud_toggled(bool checked){
01014 if (m_pointcloudDrawer){
01015 if (checked)
01016 m_glwidget->addSceneObject(m_pointcloudDrawer);
01017 else
01018 m_glwidget->removeSceneObject(m_pointcloudDrawer);
01019 }
01020 }
01021
01022 void ViewerGui::on_actionTrajectory_toggled(bool checked){
01023 if (m_trajectoryDrawer){
01024 if (checked)
01025 m_glwidget->addSceneObject(m_trajectoryDrawer);
01026 else
01027 m_glwidget->removeSceneObject(m_trajectoryDrawer);
01028 }
01029 }
01030
01031 void ViewerGui::on_actionAxes_toggled(bool checked){
01032 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01033 it != m_octrees.end(); ++it) {
01034 it->second.octree_drawer->enableAxes(checked);
01035 }
01036 m_glwidget->updateGL();
01037 }
01038
01039 void ViewerGui::on_actionHideBackground_toggled(bool checked) {
01040 OcTreeRecord* r;
01041 if (getOctreeRecord(DEFAULT_OCTREE_ID, r)) {
01042 if (checked) m_glwidget->removeSceneObject(r->octree_drawer);
01043 else m_glwidget->addSceneObject(r->octree_drawer);
01044 m_glwidget->updateGL();
01045 }
01046 }
01047
01048 void ViewerGui::on_actionClear_triggered() {
01049 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01050 it != m_octrees.end(); ++it) {
01051 m_glwidget->removeSceneObject(it->second.octree_drawer);
01052 delete (it->second.octree_drawer);
01053 delete (it->second.octree);
01054 }
01055 m_octrees.clear();
01056 showOcTree();
01057 }
01058
01059 void ViewerGui::on_actionTest_triggered(){
01060
01061 }
01062
01063 void ViewerGui::on_actionReload_Octree_triggered(){
01064 if (m_scanGraph) {
01065 generateOctree();
01066 } else {
01067 openFile();
01068 }
01069 }
01070
01071 void ViewerGui::on_actionConvert_ml_tree_triggered(){
01072 QApplication::setOverrideCursor(Qt::WaitCursor);
01073 if (m_octrees.size()) {
01074 showInfo("Converting OcTree to maximum Likelihood map... ");
01075 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01076 it != m_octrees.end(); ++it) {
01077 AbstractOcTree* t = it->second.octree;
01078 if (dynamic_cast<OcTree*>(t)) {
01079 ((OcTree*) t)->toMaxLikelihood();
01080 }
01081 else if (dynamic_cast<OcTree*>(t)) {
01082 ((ColorOcTree*) t)->toMaxLikelihood();
01083 }
01084 }
01085 showInfo("Done.", true);
01086 showOcTree();
01087 QApplication::restoreOverrideCursor();
01088 }
01089 }
01090
01091
01092 void ViewerGui::on_actionPrune_tree_triggered(){
01093 QApplication::setOverrideCursor(Qt::WaitCursor);
01094 if (m_octrees.size()) {
01095 showInfo("Pruning OcTree... ");
01096 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01097 it != m_octrees.end(); ++it) {
01098 it->second.octree->prune();
01099 }
01100 showOcTree();
01101 showInfo("Done.", true);
01102 }
01103 QApplication::restoreOverrideCursor();
01104 }
01105
01106
01107 void ViewerGui::on_actionExpand_tree_triggered(){
01108
01109 QApplication::setOverrideCursor(Qt::WaitCursor);
01110
01111
01112 if (m_octrees.size()) {
01113 showInfo("Expanding OcTree... ");
01114 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01115 it != m_octrees.end(); ++it) {
01116 it->second.octree->expand();
01117 }
01118 showOcTree();
01119
01120 showInfo("Done.", true);
01121 }
01122 QApplication::restoreOverrideCursor();
01123 }
01124
01125
01126 void ViewerGui::on_actionOctree_cells_toggled(bool enabled) {
01127 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01128 it != m_octrees.end(); ++it) {
01129 it->second.octree_drawer->enableOcTreeCells(enabled);
01130 }
01131 m_glwidget->updateGL();
01132 }
01133
01134 void ViewerGui::on_actionOctree_structure_toggled(bool enabled) {
01135 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01136 it != m_octrees.end(); ++it) {
01137 it->second.octree_drawer->enableOcTree(enabled);
01138 }
01139 m_glwidget->updateGL();
01140 }
01141
01142 void ViewerGui::on_actionFree_toggled(bool enabled) {
01143 for (std::map<int, OcTreeRecord>::iterator it = m_octrees.begin();
01144 it != m_octrees.end(); ++it) {
01145 it->second.octree_drawer->enableFreespace(enabled);
01146 }
01147 m_glwidget->updateGL();
01148
01149 }
01150
01151 void ViewerGui::on_actionSelected_toggled(bool enabled) {
01152
01153
01154
01155
01156
01157
01158
01159
01160
01161
01162
01163
01164
01165
01166
01167 }
01168
01169
01170 void ViewerGui::on_action_bg_black_triggered() {
01171 m_glwidget->setBackgroundColor( QColor(0,0,0) );
01172 m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
01173 }
01174
01175 void ViewerGui::on_action_bg_white_triggered() {
01176 m_glwidget->setBackgroundColor( QColor(255,255,255) );
01177 m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
01178 }
01179
01180 void ViewerGui::on_action_bg_gray_triggered() {
01181 m_glwidget->setBackgroundColor( QColor(117,117,117) );
01182 m_glwidget->qglClearColor( m_glwidget->backgroundColor() );
01183 }
01184
01185 void ViewerGui::on_savecampose_triggered() {
01186 QString filename = QFileDialog::getSaveFileName(this, "Save Viewer State", "camera.xml", "Camera/State file (*.xml)");
01187 if (!filename.isEmpty()) {
01188 saveCameraPosition(filename.toAscii().constData());
01189 }
01190 }
01191
01192 void ViewerGui::on_loadcampose_triggered() {
01193 QString filename = QFileDialog::getOpenFileName(this, "Load Viewer State", "camera.xml", "Camera/State file (*.xml)");
01194 if (!filename.isEmpty()) {
01195 loadCameraPosition(filename.toAscii().constData());
01196 }
01197 }
01198
01199
01200
01201 void ViewerGui::saveCameraPosition(const char* filename) const {
01202
01203 ViewerWidget* aux = const_cast<ViewerWidget*>( m_glwidget);
01204 aux->setStateFileName(QString(filename));
01205 aux->saveStateToFile();
01206 aux->setStateFileName(QString::null);
01207 }
01208
01209 void ViewerGui::loadCameraPosition(const char* filename) {
01210 m_glwidget->setStateFileName(QString(filename));
01211 m_glwidget->restoreStateFromFile();
01212 m_glwidget->setStateFileName(QString::null);
01213 }
01214
01215
01216 }
01217
01218