visualization_frame.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <fstream>
00031 
00032 #include <QApplication>
00033 #include <QSplashScreen>
00034 #include <QDockWidget>
00035 #include <QDir>
00036 #include <QCloseEvent>
00037 #include <QToolBar>
00038 #include <QMenuBar>
00039 #include <QMenu>
00040 #include <QMessageBox>
00041 #include <QFileDialog>
00042 #include <QDesktopServices>
00043 #include <QUrl>
00044 #include <QAction>
00045 #include <QTimer>
00046 
00047 #include <boost/filesystem.hpp>
00048 #include <boost/bind.hpp>
00049 #include <boost/algorithm/string/split.hpp>
00050 #include <boost/algorithm/string/trim.hpp>
00051 
00052 #include <ros/package.h>
00053 #include <ros/console.h>
00054 
00055 #include <OGRE/OgreRenderWindow.h>
00056 
00057 #include <ogre_helpers/initialization.h>
00058 
00059 #include "visualization_frame.h"
00060 #include "render_panel.h"
00061 #include "displays_panel.h"
00062 #include "views_panel.h"
00063 #include "time_panel.h"
00064 #include "selection_panel.h"
00065 #include "tool_properties_panel.h"
00066 #include "visualization_manager.h"
00067 #include "tools/tool.h"
00068 #include "loading_dialog.h"
00069 #include "config.h"
00070 #include "panel_dock_widget.h"
00071 #include "new_object_dialog.h"
00072 #include "panel.h"
00073 #include "screenshot_dialog.h"
00074 #include "help_panel.h"
00075 #include "widget_geometry_change_detector.h"
00076 #include "properties/forwards.h" // for StatusCallback
00077 
00078 namespace fs = boost::filesystem;
00079 
00080 #define CONFIG_WINDOW_X "/Window/X"
00081 #define CONFIG_WINDOW_Y "/Window/Y"
00082 #define CONFIG_WINDOW_WIDTH "/Window/Width"
00083 #define CONFIG_WINDOW_HEIGHT "/Window/Height"
00084 // I am not trying to preserve peoples' window layouts from wx to Qt,
00085 // just saving the Qt layout in a new config tag.
00086 #define CONFIG_QMAINWINDOW "/QMainWindow"
00087 #define CONFIG_AUIMANAGER_PERSPECTIVE "/AuiManagerPerspective"
00088 #define CONFIG_AUIMANAGER_PERSPECTIVE_VERSION "/AuiManagerPerspectiveVersion"
00089 #define CONFIG_RECENT_CONFIGS "/RecentConfigs"
00090 #define CONFIG_LAST_DIR "/LastConfigDir"
00091 #define CONFIG_LAST_IMAGE_DIR "/LastImageDir"
00092 
00093 #define CONFIG_EXTENSION "vcg"
00094 #define CONFIG_EXTENSION_WILDCARD "*."CONFIG_EXTENSION
00095 #define PERSPECTIVE_VERSION 2
00096 
00097 #define RECENT_CONFIG_COUNT 10
00098 
00099 #if BOOST_FILESYSTEM_VERSION == 3
00100 #define BOOST_FILENAME_STRING filename().string
00101 #define BOOST_FILE_STRING string
00102 #else
00103 #define BOOST_FILENAME_STRING filename
00104 #define BOOST_FILE_STRING file_string
00105 #endif
00106 
00107 namespace rviz
00108 {
00109 
00110 VisualizationFrame::VisualizationFrame( QWidget* parent )
00111   : QMainWindow( parent )
00112   , render_panel_(NULL)
00113   , displays_panel_(NULL)
00114   , views_panel_(NULL)
00115   , time_panel_(NULL)
00116   , selection_panel_(NULL)
00117   , tool_properties_panel_(NULL)
00118   , help_panel_(NULL)
00119   , show_help_action_(NULL)
00120   , file_menu_(NULL)
00121   , recent_configs_menu_(NULL)
00122   , toolbar_(NULL)
00123   , manager_(NULL)
00124   , position_correction_( 0, 0 )
00125   , num_move_events_( 0 )
00126   , toolbar_actions_( NULL )
00127   , initialized_( false )
00128   , geom_change_detector_( new WidgetGeometryChangeDetector( this ))
00129   , loading_( false )
00130   , post_load_timer_( new QTimer( this ))
00131 {
00132   panel_class_loader_ = new pluginlib::ClassLoader<Panel>( "rviz", "rviz::Panel" );
00133 
00134   installEventFilter( geom_change_detector_ );
00135   connect( geom_change_detector_, SIGNAL( changed() ), this, SLOT( setDisplayConfigModified() ));
00136 
00137   post_load_timer_->setSingleShot( true );
00138   connect( post_load_timer_, SIGNAL( timeout() ), this, SLOT( markLoadingDone() ));
00139 }
00140 
00141 VisualizationFrame::~VisualizationFrame()
00142 {
00143   if( manager_ )
00144   {
00145     manager_->removeAllDisplays();
00146   }
00147 
00148   delete render_panel_;
00149   delete manager_;
00150 
00151   M_PanelRecord::iterator pi;
00152   for( pi = custom_panels_.begin(); pi != custom_panels_.end(); pi++ )
00153   {
00154     delete (*pi).second.dock;
00155   }
00156 
00157   delete panel_class_loader_;
00158 }
00159 
00160 void VisualizationFrame::closeEvent( QCloseEvent* event )
00161 {
00162   if( prepareToExit() )
00163   {
00164     event->accept();
00165   }
00166   else
00167   {
00168     event->ignore();
00169   }
00170 }
00171 
00172 void VisualizationFrame::changeMaster()
00173 {
00174   if( prepareToExit() )
00175   {
00176     QApplication::exit( 255 );
00177   }
00178 }
00179 
00180 void VisualizationFrame::setSplashStatus( const std::string& status )
00181 {
00182   splash_->showMessage( QString::fromStdString( status ), Qt::AlignLeft | Qt::AlignBottom );
00183 }
00184 
00185 void VisualizationFrame::initialize(const std::string& display_config_file,
00186                                     const std::string& fixed_frame,
00187                                     const std::string& target_frame,
00188                                     const std::string& splash_path,
00189                                     const std::string& help_path,
00190                                     bool verbose,
00191                                     bool show_choose_new_master_option )
00192 {
00193   show_choose_new_master_option_ = show_choose_new_master_option;
00194 
00195   initConfigs( display_config_file );
00196 
00197   loadGeneralConfig();
00198 
00199   package_path_ = ros::package::getPath("rviz");
00200 
00201   std::string final_splash_path = splash_path;
00202 
00203   if ( splash_path.empty() )
00204   {
00205     final_splash_path = (fs::path(package_path_) / "images/splash.png").BOOST_FILE_STRING();
00206   }
00207 
00208   help_path_ = help_path;
00209   if ( help_path_.empty() )
00210   {
00211     help_path_ = (fs::path(package_path_) / "help/help.html").BOOST_FILE_STRING();
00212   }
00213   QPixmap splash_image( QString::fromStdString( final_splash_path ));
00214   splash_ = new QSplashScreen( splash_image );
00215   splash_->show();
00216   setSplashStatus( "Initializing" );
00217 
00218   if( !ros::isInitialized() )
00219   {
00220     int argc = 0;
00221     ros::init( argc, 0, "rviz", ros::init_options::AnonymousName );
00222   }
00223 
00224   render_panel_ = new RenderPanel( this );
00225   displays_panel_ = new DisplaysPanel( this );
00226   views_panel_ = new ViewsPanel( this );
00227   time_panel_ = new TimePanel( this );
00228   selection_panel_ = new SelectionPanel( this );
00229   tool_properties_panel_ = new ToolPropertiesPanel( this );
00230 
00231   initMenus();
00232   toolbar_ = addToolBar( "Tools" );
00233   toolbar_->setObjectName( "Tools" );
00234   toolbar_actions_ = new QActionGroup( this );
00235   connect( toolbar_actions_, SIGNAL( triggered( QAction* )), this, SLOT( onToolbarActionTriggered( QAction* )));
00236   view_menu_->addAction( toolbar_->toggleViewAction() );
00237 
00238   setCentralWidget( render_panel_ );
00239 
00240   addPane( "Displays", displays_panel_, Qt::LeftDockWidgetArea, false );
00241   addPane( "Tool Properties", tool_properties_panel_, Qt::RightDockWidgetArea, false );
00242   addPane( "Views", views_panel_, Qt::RightDockWidgetArea, false );
00243   addPane( "Selection", selection_panel_, Qt::RightDockWidgetArea, false );
00244   addPane( "Time", time_panel_, Qt::BottomDockWidgetArea, false );
00245 
00246   manager_ = new VisualizationManager( render_panel_, this );
00247   render_panel_->initialize( manager_->getSceneManager(), manager_ );
00248   displays_panel_->initialize( manager_ );
00249   views_panel_->initialize( manager_ );
00250   time_panel_->initialize(manager_);
00251   selection_panel_->initialize( manager_ );
00252   tool_properties_panel_->initialize( manager_ );
00253 
00254   connect( manager_, SIGNAL( configChanged() ), this, SLOT( setDisplayConfigModified() ));
00255   connect( manager_, SIGNAL( toolAdded( Tool* )), this, SLOT( addTool( Tool* )));
00256   connect( manager_, SIGNAL( toolChanged( Tool* )), this, SLOT( indicateToolIsCurrent( Tool* )));
00257   connect( views_panel_, SIGNAL( configChanged() ), this, SLOT( setDisplayConfigModified() ));
00258 
00259   manager_->initialize( StatusCallback(), verbose );
00260 
00261   loadDisplayConfig( display_config_file_ );
00262 
00263   if( !fixed_frame.empty() )
00264   {
00265     manager_->setFixedFrame( fixed_frame );
00266   }
00267 
00268   if( !target_frame.empty() )
00269   {
00270     manager_->setTargetFrame( target_frame );
00271   }
00272 
00273   setSplashStatus( "Loading perspective" );
00274 
00275   delete splash_;
00276   splash_ = 0;
00277 
00278   manager_->startUpdate();
00279   initialized_ = true;
00280 }
00281 
00282 void VisualizationFrame::initConfigs( const std::string& display_config_file_override )
00283 {
00284   home_dir_ = QDir::toNativeSeparators( QDir::homePath() ).toStdString();
00285 
00286   config_dir_ = (fs::path(home_dir_) / ".rviz").BOOST_FILE_STRING();
00287   general_config_file_ = (fs::path(config_dir_) / "config").BOOST_FILE_STRING();
00288   default_display_config_file_ = (fs::path(config_dir_) / "display_config").BOOST_FILE_STRING();
00289   std::string display_config_file = default_display_config_file_;
00290 
00291   if( display_config_file_override != "" )
00292   {
00293     if( !fs::exists( display_config_file_override ))
00294     {
00295       ROS_ERROR("File [%s] does not exist", display_config_file_override.c_str());
00296     }
00297     else
00298     {
00299       display_config_file = display_config_file_override;
00300       ROS_INFO("Loading display config from [%s]", display_config_file_.c_str());
00301     }
00302   }
00303   setDisplayConfigFile( display_config_file );
00304 
00305   if( fs::is_regular_file( config_dir_ ))
00306   {
00307     ROS_ERROR("Moving file [%s] out of the way to recreate it as a directory.", config_dir_.c_str());
00308     std::string backup_file = config_dir_ + ".bak";
00309 
00310     fs::rename(config_dir_, backup_file);
00311     fs::create_directory(config_dir_);
00312   }
00313   else if (!fs::exists(config_dir_))
00314   {
00315     fs::create_directory(config_dir_);
00316   }
00317 }
00318 
00319 void VisualizationFrame::loadGeneralConfig()
00320 {
00321   ROS_INFO("Loading general config from [%s]", general_config_file_.c_str());
00322   Config general_config;
00323   general_config.readFromFile( general_config_file_ );
00324 
00325   std::string recent;
00326   if( general_config.get( CONFIG_RECENT_CONFIGS, &recent ))
00327   {
00328     boost::trim( recent );
00329     boost::split( recent_configs_, recent, boost::is_any_of (":"), boost::token_compress_on );
00330   }
00331 
00332   general_config.get( CONFIG_LAST_DIR, &last_config_dir_ );
00333   general_config.get( CONFIG_LAST_IMAGE_DIR, &last_image_dir_ );
00334 }
00335 
00336 void VisualizationFrame::saveGeneralConfig()
00337 {
00338   ROS_INFO("Saving general config to [%s]", general_config_file_.c_str());
00339   Config general_config;
00340   {
00341     std::stringstream ss;
00342     D_string::iterator it = recent_configs_.begin();
00343     D_string::iterator end = recent_configs_.end();
00344     for (; it != end; ++it)
00345     {
00346       if (it != recent_configs_.begin())
00347       {
00348         ss << ":";
00349       }
00350       ss << *it;
00351     }
00352     general_config.set( CONFIG_RECENT_CONFIGS, ss.str() );
00353   }
00354   general_config.set( CONFIG_LAST_DIR, last_config_dir_ );
00355   general_config.set( CONFIG_LAST_IMAGE_DIR, last_image_dir_ );
00356   general_config.writeToFile( general_config_file_ );
00357 }
00358 
00359 void VisualizationFrame::initMenus()
00360 {
00361   file_menu_ = menuBar()->addMenu( "&File" );
00362   file_menu_->addAction( "&Open Config", this, SLOT( onOpen() ), QKeySequence( "Ctrl+O" ));
00363   file_menu_->addAction( "&Save Config", this, SLOT( save() ), QKeySequence( "Ctrl+S" ));
00364   file_menu_->addAction( "Save Config &As", this, SLOT( saveAs() ));
00365   recent_configs_menu_ = file_menu_->addMenu( "&Recent Configs" );
00366   file_menu_->addAction( "Save &Image", this, SLOT( onSaveImage() ));
00367   if( show_choose_new_master_option_ )
00368   {
00369     file_menu_->addSeparator();
00370     file_menu_->addAction( "Change &Master", this, SLOT( changeMaster() ));
00371   }
00372   file_menu_->addSeparator();
00373   file_menu_->addAction( "&Quit", this, SLOT( close() ), QKeySequence( "Ctrl+Q" ));
00374 
00375   view_menu_ = menuBar()->addMenu( "&Panels" );
00376   view_menu_->addAction( "Add &New Panel", this, SLOT( openNewPanelDialog() ));
00377   delete_view_menu_ = view_menu_->addMenu( "&Delete Panel" );
00378   delete_view_menu_->setEnabled( false );
00379   view_menu_->addSeparator();
00380 
00386 
00387   QMenu* help_menu = menuBar()->addMenu( "&Help" );
00388   help_menu->addAction( "Show &Help panel", this, SLOT( showHelpPanel() ));
00389   help_menu->addAction( "Open rviz wiki in browser", this, SLOT( onHelpWiki() ));
00390 }
00391 
00392 void VisualizationFrame::openNewPanelDialog()
00393 {
00394   std::string lookup_name;
00395   std::string display_name;
00396 
00397   NewObjectDialog* dialog = new NewObjectDialog( panel_class_loader_,
00398                                                  "Panel",
00399                                                  panel_names_,
00400                                                  &lookup_name,
00401                                                  &display_name,
00402                                                  this );
00403   if( dialog->exec() == QDialog::Accepted )
00404   {
00405     addCustomPanel( display_name, lookup_name );
00406   }
00407 }
00408 
00409 void VisualizationFrame::updateRecentConfigMenu()
00410 {
00411   recent_configs_menu_->clear();
00412 
00413   D_string::iterator it = recent_configs_.begin();
00414   D_string::iterator end = recent_configs_.end();
00415   for (; it != end; ++it)
00416   {
00417     if( *it != "" )
00418     {
00419       std::string display_name = *it;
00420       if( display_name == default_display_config_file_ )
00421       {
00422         display_name += " (default)";
00423       }
00424       if( display_name.find( home_dir_ ) == 0 )
00425       {
00426         display_name = ("~" / fs::path( display_name.substr( home_dir_.size() ))).BOOST_FILE_STRING();
00427       }
00428       QString qdisplay_name = QString::fromStdString( display_name );
00429       QAction* action = new QAction( qdisplay_name, this );
00430       action->setData( QString::fromStdString( *it ));
00431       connect( action, SIGNAL( triggered() ), this, SLOT( onRecentConfigSelected() ));
00432       recent_configs_menu_->addAction( action );
00433     }
00434   }
00435 }
00436 
00437 void VisualizationFrame::markRecentConfig( const std::string& path )
00438 {
00439   D_string::iterator it = std::find( recent_configs_.begin(), recent_configs_.end(), path );
00440   if( it != recent_configs_.end() )
00441   {
00442     recent_configs_.erase( it );
00443   }
00444 
00445   recent_configs_.push_front( path );
00446 
00447   if( recent_configs_.size() > RECENT_CONFIG_COUNT )
00448   {
00449     recent_configs_.pop_back();
00450   }
00451 
00452   updateRecentConfigMenu();
00453 }
00454 
00455 void VisualizationFrame::loadDisplayConfig( const std::string& path )
00456 {
00457   if( !fs::exists( path ) || fs::is_directory( path ) || fs::is_empty( path ))
00458   {
00459     QString message = QString::fromStdString( path  ) + " does not exist!";
00460     QMessageBox::critical( this, "Config file does not exist", message );
00461     return;
00462   }
00463 
00464   // Check if we have unsaved changes to the current config the same
00465   // as we do during exit, with the same option to cancel.
00466   if( !prepareToExit() )
00467   {
00468     return;
00469   }
00470 
00471   setWindowModified( false );
00472   loading_ = true;
00473 
00474   manager_->removeAllDisplays();
00475 
00476   StatusCallback cb;
00477   LoadingDialog* dialog = NULL;
00478   if( !initialized_ )
00479   {
00480     // If this is running during initial load, don't show a loading
00481     // dialog.
00482     cb = boost::bind( &VisualizationFrame::setSplashStatus, this, _1 );
00483   }
00484   else
00485   {
00486     dialog = new LoadingDialog( this );
00487     dialog->show();
00488     cb = boost::bind( &LoadingDialog::setState, dialog, _1 );
00489   }
00490 
00491   boost::shared_ptr<Config> config( new Config );
00492   config->readFromFile( path );
00493 
00494   manager_->loadDisplayConfig( config, cb );
00495   loadCustomPanels( config );
00496   loadWindowGeometry( config );
00497 
00498   markRecentConfig( path );
00499 
00500   setDisplayConfigFile( path );
00501 
00502   last_config_dir_ = fs::path( path ).parent_path().BOOST_FILE_STRING();
00503 
00504   delete dialog;
00505 
00506   post_load_timer_->start( 1000 );
00507 }
00508 
00509 void VisualizationFrame::markLoadingDone()
00510 {
00511   loading_ = false;
00512 }
00513 
00514 void VisualizationFrame::setImageSaveDirectory( const QString& directory )
00515 {
00516   last_image_dir_ = directory.toStdString();
00517 }
00518 
00519 void VisualizationFrame::setDisplayConfigModified()
00520 {
00521   if( !loading_ )
00522   {
00523     setWindowModified( true );
00524   }
00525 }
00526 
00527 void VisualizationFrame::setDisplayConfigFile( const std::string& path )
00528 {
00529   display_config_file_ = path;
00530 
00531   std::string title;
00532   if( path == default_display_config_file_ )
00533   {
00534     title = "RViz[*]";
00535   }
00536   else
00537   {
00538     title = fs::path( path ).BOOST_FILENAME_STRING() + "[*] - RViz";
00539   }
00540   setWindowTitle( QString::fromStdString( title ));
00541 }
00542 
00543 bool VisualizationFrame::saveDisplayConfig( const std::string& path )
00544 {
00545   ROS_INFO( "Saving display config to [%s]", path.c_str() );
00546 
00547   boost::shared_ptr<Config> config( new Config );
00548 
00549   manager_->saveDisplayConfig( config );
00550   saveCustomPanels( config );
00551   saveWindowGeometry( config );
00552 
00553   if( config->writeToFile( path ))
00554   {
00555     error_message_ = "";
00556     setWindowModified( false );
00557     return true;
00558   }
00559   else
00560   {
00561     error_message_ = QString::fromStdString( config->getErrorMessage() );
00562     return false;
00563   }
00564 }
00565 
00566 void VisualizationFrame::loadCustomPanels( const boost::shared_ptr<Config>& config )
00567 {
00568   // First destroy any existing custom panels.
00569   M_PanelRecord::iterator pi;
00570   for( pi = custom_panels_.begin(); pi != custom_panels_.end(); pi++ )
00571   {
00572     delete (*pi).second.dock;
00573     delete (*pi).second.delete_action;
00574   }
00575   custom_panels_.clear();
00576 
00577   // Then load the ones in the config.
00578   int i = 0;
00579   while( true )
00580   {
00581     std::stringstream panel_prefix, panel_name_ss, lookup_name_ss;
00582     panel_prefix << "Panel" << i;
00583     panel_name_ss << "Panel" << i << "/Name";
00584     lookup_name_ss << "Panel" << i << "/ClassLookupName";
00585 
00586     std::string panel_name, lookup_name;
00587     if( !config->get( panel_name_ss.str(), &panel_name ))
00588     {
00589       break;
00590     }
00591 
00592     if( !config->get( lookup_name_ss.str(), &lookup_name ))
00593     {
00594       break;
00595     }
00596 
00597     PanelDockWidget* dock = addCustomPanel( panel_name, lookup_name );
00598     if( dock )
00599     {
00600       Panel* panel = qobject_cast<Panel*>( dock->widget() );
00601       if( panel )
00602       {
00603         panel->loadFromConfig( panel_prefix.str(), config );
00604       }
00605     }
00606 
00607     ++i;
00608   }
00609 }
00610 
00611 void VisualizationFrame::saveCustomPanels( const boost::shared_ptr<Config>& config )
00612 {
00613   int i = 0;
00614   M_PanelRecord::iterator pi;
00615   for( pi = custom_panels_.begin(); pi != custom_panels_.end(); pi++, i++ )
00616   {
00617     PanelRecord record = (*pi).second;
00618     std::stringstream panel_prefix, panel_name_key, lookup_name_key;
00619     panel_prefix << "Panel" << i;
00620     panel_name_key << "Panel" << i << "/Name";
00621     lookup_name_key << "Panel" << i << "/ClassLookupName";
00622     config->set( panel_name_key.str(), record.name );
00623     config->set( lookup_name_key.str(), record.lookup_name );
00624     record.panel->saveToConfig( panel_prefix.str(), config );
00625   }
00626 }
00627 
00628 void VisualizationFrame::moveEvent( QMoveEvent* event )
00629 {
00630 //  GdkRectangle rect;
00631 //  GdkWindow* gdk_window = gdk_window_foreign_new( winId() ); 
00632 //  gdk_window_get_frame_extents( gdk_window, &rect );
00633 //  printf( "gdk x=%d, y=%d\n", rect.x, rect.y );
00634 // the above works!  should I just use gdk??
00635 
00636   // HACK to work around a bug in Qt-for-X11.  The first time we get a
00637   // moveEvent, the position is that of the top-left corner of the
00638   // window frame.  The second time we get one, the position is the
00639   // top-left corner *inside* the frame.  There is no significant time
00640   // lag between the two calls, certainly no user events, so I just
00641   // remember the first position and diff it with the second position
00642   // and remember the diff as a corrective offset for future geometry
00643   // requests.
00644   //
00645   // This seems like it would be brittle to OS, code changes, etc, so
00646   // sometime I should get something better going here.  Maybe call
00647   // out to gdk (as above), which seems to work right.
00648   switch( num_move_events_ )
00649   {
00650   case 0:
00651     first_position_ = pos();
00652     num_move_events_++;
00653     break;
00654   case 1:
00655     position_correction_ = first_position_ - pos();
00656     num_move_events_++;
00657     break;
00658   }
00659 }
00660 
00661 QRect VisualizationFrame::hackedFrameGeometry()
00662 {
00663   QRect geom = frameGeometry();
00664   geom.moveTopLeft( pos() + position_correction_ );
00665   return geom;
00666 }
00667 
00668 void VisualizationFrame::loadWindowGeometry( const boost::shared_ptr<Config>& config )
00669 {
00670   int new_x, new_y, new_width, new_height;
00671   config->get( CONFIG_WINDOW_X, &new_x, x() );
00672   config->get( CONFIG_WINDOW_Y, &new_y, y() );
00673   config->get( CONFIG_WINDOW_WIDTH, &new_width, width() );
00674   config->get( CONFIG_WINDOW_HEIGHT, &new_height, height() );
00675 
00676   move( new_x, new_y );
00677   resize( new_width, new_height );
00678 
00679   std::string main_window_config;
00680   if( config->get( CONFIG_QMAINWINDOW, &main_window_config ))
00681   {
00682     restoreState( QByteArray::fromHex( main_window_config.c_str() ));
00683   }
00684 }
00685 
00686 void VisualizationFrame::saveWindowGeometry( const boost::shared_ptr<Config>& config )
00687 {
00688   QRect geom = hackedFrameGeometry();
00689   config->set( CONFIG_WINDOW_X, geom.x() );
00690   config->set( CONFIG_WINDOW_Y, geom.y() );
00691   config->set( CONFIG_WINDOW_WIDTH, geom.width() );
00692   config->set( CONFIG_WINDOW_HEIGHT, geom.height() );
00693 
00694   QByteArray window_state = saveState().toHex();
00695   config->set( CONFIG_QMAINWINDOW, std::string( window_state.constData() ));
00696 }
00697 
00698 bool VisualizationFrame::prepareToExit()
00699 {
00700   if( !initialized_ )
00701   {
00702     return true;
00703   }
00704 
00705   saveGeneralConfig();
00706 
00707   if( isWindowModified() )
00708   {
00709     QMessageBox box( this );
00710     box.setText( "There are unsaved changes." );
00711     box.setInformativeText( QString::fromStdString( "Save changes to " + display_config_file_ + "?" ));
00712     box.setStandardButtons( QMessageBox::Save | QMessageBox::Discard | QMessageBox::Cancel );
00713     box.setDefaultButton( QMessageBox::Save );
00714     int result = box.exec();
00715     switch( result )
00716     {
00717     case QMessageBox::Save:
00718       if( saveDisplayConfig( display_config_file_ ))
00719       {
00720         return true;
00721       }
00722       else
00723       {
00724         QMessageBox box( this );
00725         box.setWindowTitle( "Failed to save." );
00726         box.setText( getErrorMessage() );
00727         box.setInformativeText( QString::fromStdString( "Save copy of " + display_config_file_ + " to another file?" ));
00728         box.setStandardButtons( QMessageBox::Save | QMessageBox::Discard | QMessageBox::Cancel );
00729         box.setDefaultButton( QMessageBox::Save );
00730         int result = box.exec();
00731         switch( result )
00732         {
00733         case QMessageBox::Save:
00734           saveAs();
00735           return true;
00736         case QMessageBox::Discard:
00737           return true;
00738         default:
00739           return false;
00740         }
00741         
00742       }
00743     case QMessageBox::Discard:
00744       return true;
00745     default:
00746       return false;
00747     }
00748   }
00749   else
00750   {
00751     return true;
00752   }
00753 }
00754 
00755 void VisualizationFrame::onOpen()
00756 {
00757   QString filename = QFileDialog::getOpenFileName( this, "Choose a file to open",
00758                                                    QString::fromStdString( last_config_dir_ ),
00759                                                    "RViz config files (" CONFIG_EXTENSION_WILDCARD ")" );
00760 
00761   if( !filename.isEmpty() )
00762   {
00763     std::string filename_string = filename.toStdString();
00764     loadDisplayConfig( filename_string );
00765   }
00766 }
00767 
00768 void VisualizationFrame::save()
00769 {
00770   if( !initialized_ )
00771   {
00772     return;
00773   }
00774 
00775   saveGeneralConfig();
00776 
00777   if( !saveDisplayConfig( display_config_file_ ))
00778   {
00779     QMessageBox box( this );
00780     box.setWindowTitle( "Failed to save." );
00781     box.setText( getErrorMessage() );
00782     box.setInformativeText( QString::fromStdString( "Save copy of " + display_config_file_ + " to another file?" ));
00783     box.setStandardButtons( QMessageBox::Save | QMessageBox::Cancel );
00784     box.setDefaultButton( QMessageBox::Save );
00785     if( box.exec() == QMessageBox::Save )
00786     {
00787       saveAs();
00788     }
00789   }
00790 }
00791 
00792 void VisualizationFrame::saveAs()
00793 {
00794   QString q_filename = QFileDialog::getSaveFileName( this, "Choose a file to save to",
00795                                                      QString::fromStdString( last_config_dir_ ),
00796                                                      "RViz config files (" CONFIG_EXTENSION_WILDCARD ")" );
00797 
00798   if( !q_filename.isEmpty() )
00799   {
00800     std::string filename = q_filename.toStdString();
00801     fs::path path( filename );
00802     if( path.extension() != "."CONFIG_EXTENSION )
00803     {
00804       filename += "."CONFIG_EXTENSION;
00805     }
00806 
00807     if( !saveDisplayConfig( filename ))
00808     {
00809       QMessageBox::critical( this, "Failed to save.", getErrorMessage() );
00810     }
00811 
00812     markRecentConfig( filename );
00813     last_config_dir_ = fs::path( filename ).parent_path().BOOST_FILE_STRING();
00814     setDisplayConfigFile( filename );
00815   }
00816 }
00817 
00818 void VisualizationFrame::onSaveImage()
00819 {
00820   ScreenshotDialog* dialog = new ScreenshotDialog( this, render_panel_, QString::fromStdString( last_image_dir_ ));
00821   connect( dialog, SIGNAL( savedInDirectory( const QString& )),
00822            this, SLOT( setImageSaveDirectory( const QString& )));
00823   dialog->show();
00824 }
00825 
00826 void VisualizationFrame::onRecentConfigSelected()
00827 {
00828   QAction* action = dynamic_cast<QAction*>( sender() );
00829   if( action )
00830   {
00831     std::string path = action->data().toString().toStdString();
00832     if( !path.empty() )
00833     {
00834       loadDisplayConfig( path );
00835     }
00836   }
00837 }
00838 
00839 void VisualizationFrame::addTool( Tool* tool )
00840 {
00841   QAction* action = new QAction( QString::fromStdString( tool->getName() ), toolbar_actions_ );
00842   action->setCheckable( true );
00843   action->setShortcut( QKeySequence( QString( tool->getShortcutKey() )));
00844   toolbar_->addAction( action );
00845   action_to_tool_map_[ action ] = tool;
00846   tool_to_action_map_[ tool ] = action;
00847 }
00848 
00849 void VisualizationFrame::onToolbarActionTriggered( QAction* action )
00850 {
00851   Tool* tool = action_to_tool_map_[ action ];
00852   if( tool )
00853   {
00854     manager_->setCurrentTool( tool );
00855   }
00856 }
00857 
00858 void VisualizationFrame::indicateToolIsCurrent( Tool* tool )
00859 {
00860   QAction* action = tool_to_action_map_[ tool ];
00861   if( action )
00862   {
00863     action->setChecked( true );
00864   }
00865 }
00866 
00867 void VisualizationFrame::showHelpPanel()
00868 {
00869   if( !show_help_action_ )
00870   {
00871     help_panel_ = new HelpPanel( this );
00872     QDockWidget* dock = addPane( "Help", help_panel_ );
00873     show_help_action_ = dock->toggleViewAction();
00874   }
00875   else
00876   {
00877     // show_help_action_ is a toggle action, so trigger() changes its
00878     // state.  Therefore we must force it to the opposite state from
00879     // what we want before we call trigger().  (I think.)
00880     show_help_action_->setChecked( false );
00881     show_help_action_->trigger();
00882   }
00883   help_panel_->setHelpFile( help_path_ );
00884 }
00885 
00886 void VisualizationFrame::onHelpWiki()
00887 {
00888   QDesktopServices::openUrl( QUrl( "http://www.ros.org/wiki/rviz" ));
00889 }
00890 
00891 QWidget* VisualizationFrame::getParentWindow()
00892 {
00893   return this;
00894 }
00895 
00896 void VisualizationFrame::onDeletePanel()
00897 {
00898   if( QAction* action = qobject_cast<QAction*>( sender() ))
00899   {
00900     std::string panel_name = action->text().toStdString();
00901     M_PanelRecord::iterator pi = custom_panels_.find( panel_name );
00902     if( pi != custom_panels_.end() )
00903     {
00904       delete (*pi).second.dock;
00905       custom_panels_.erase( pi );
00906       setDisplayConfigModified();
00907     }
00908     action->deleteLater();
00909     if( delete_view_menu_->actions().size() == 1 &&
00910         delete_view_menu_->actions().first() == action )
00911     {
00912       delete_view_menu_->setEnabled( false );
00913     }
00914   }
00915 }
00916 
00917 PanelDockWidget* VisualizationFrame::addCustomPanel( const std::string& name,
00918                                                      const std::string& class_lookup_name,
00919                                                      Qt::DockWidgetArea area,
00920                                                      bool floating )
00921 {
00922   try
00923   {
00924     Panel* panel = panel_class_loader_->createClassInstance( class_lookup_name );
00925     connect( panel, SIGNAL( configChanged() ), this, SLOT( setDisplayConfigModified() ));
00926 
00927     PanelRecord record;
00928     record.dock = addPane( name, panel, area, floating );
00929     record.lookup_name = class_lookup_name;
00930     record.panel = panel;
00931     record.name = name;
00932     record.delete_action = delete_view_menu_->addAction( QString::fromStdString( name ), this, SLOT( onDeletePanel() ));
00933     custom_panels_[ name ] = record;
00934     delete_view_menu_->setEnabled( true );
00935 
00936     record.panel->initialize( manager_ );
00937 
00938     return record.dock;
00939   }
00940   catch( pluginlib::LibraryLoadException ex )
00941   {
00942     ROS_ERROR( "Failed to load library for Panel plugin class: %s", ex.what() );
00943     return NULL;
00944   }
00945 }
00946 
00947 PanelDockWidget* VisualizationFrame::addPane( const std::string& name, QWidget* panel, Qt::DockWidgetArea area, bool floating )
00948 {
00949   std::pair<std::set<std::string>::iterator, bool> insert_result = panel_names_.insert( name );
00950   if( insert_result.second == false )
00951   {
00952     ROS_ERROR( "VisualizationFrame::addPane( %s ): name already in use.", name.c_str() );
00953     return 0;
00954   }
00955 
00956   QString q_name = QString::fromStdString( name );
00957   PanelDockWidget *dock;
00958   dock = new PanelDockWidget( q_name, panel );
00959   dock->setWidget( panel );
00960   dock->setFloating( floating );
00961   dock->setObjectName( q_name );
00962   addDockWidget( area, dock );
00963   QAction* toggle_action = dock->toggleViewAction();
00964   view_menu_->addAction( toggle_action );
00965 
00966   connect( dock, SIGNAL( destroyed( QObject* )), this, SLOT( onPanelRemoved( QObject* )));
00967 
00968   // There is a small tricky bug here.  If this is changed from
00969   // triggered(bool) to toggled(bool), minimizing the rviz window
00970   // causes a call to setDisplayConfigModified(), which is wrong.
00971   // With this AS IS, it does not call setDisplayConfigModified() when
00972   // a floating PanelDockWidget is closed by clicking the "x" close
00973   // button in the top right corner.  Probably the solution is to
00974   // leave this as is and implement a custom top bar widget for
00975   // PanelDockWidget which catches the "x" button click separate from
00976   // the visibility change event.  Sigh.
00977   connect( toggle_action, SIGNAL( triggered( bool )), this, SLOT( setDisplayConfigModified() ));
00978 
00979   dock->installEventFilter( geom_change_detector_ );
00980 
00981   return dock;
00982 }
00983 
00984 void VisualizationFrame::onPanelRemoved( QObject* dock )
00985 {
00986   std::string name = dock->objectName().toStdString();
00987   panel_names_.erase( name );
00988 }
00989 
00990 }


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33