visualizer_app.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 <QApplication>
00031 #include <QTimer>
00032 
00033 #include <boost/program_options.hpp>
00034 
00035 #include <OgreMaterialManager.h>
00036 #include <OgreGpuProgramManager.h>
00037 #include <OgreHighLevelGpuProgramManager.h>
00038 #include <std_srvs/Empty.h>
00039 
00040 #ifdef Q_OS_MAC
00041 #include <ApplicationServices/ApplicationServices.h>
00042 // Apparently OSX #defines 'check' to be an empty string somewhere.
00043 // That was fun to figure out.
00044 #undef check
00045 #endif
00046 
00047 #include <ros/console.h>
00048 #include <ros/ros.h>
00049 
00050 #include "rviz/selection/selection_manager.h"
00051 #include "rviz/env_config.h"
00052 #include "rviz/ogre_helpers/ogre_logging.h"
00053 #include "rviz/visualization_frame.h"
00054 #include "rviz/visualization_manager.h"
00055 #include "rviz/wait_for_master_dialog.h"
00056 #include "rviz/ogre_helpers/render_system.h"
00057 
00058 #include "rviz/visualizer_app.h"
00059 
00060 #define CATCH_EXCEPTIONS 0
00061 
00062 namespace po = boost::program_options;
00063 
00064 namespace rviz
00065 {
00066 
00067 bool reloadShaders(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00068 {
00069   ROS_INFO("Reloading materials.");
00070   {
00071   Ogre::ResourceManager::ResourceMapIterator it = Ogre::MaterialManager::getSingleton().getResourceIterator();
00072   while (it.hasMoreElements())
00073   {
00074     Ogre::ResourcePtr resource = it.getNext();
00075     resource->reload();
00076   }
00077   }
00078   ROS_INFO("Reloading high-level gpu shaders.");
00079   {
00080   Ogre::ResourceManager::ResourceMapIterator it = Ogre::HighLevelGpuProgramManager::getSingleton().getResourceIterator();
00081   while (it.hasMoreElements())
00082   {
00083     Ogre::ResourcePtr resource = it.getNext();
00084     resource->reload();
00085   }
00086   }
00087   ROS_INFO("Reloading gpu shaders.");
00088   {
00089   Ogre::ResourceManager::ResourceMapIterator it = Ogre::GpuProgramManager::getSingleton().getResourceIterator();
00090   while (it.hasMoreElements())
00091   {
00092     Ogre::ResourcePtr resource = it.getNext();
00093     resource->reload();
00094   }
00095   }
00096   return true;
00097 }
00098 
00099 VisualizerApp::VisualizerApp()
00100   : app_( 0 )
00101   , continue_timer_( 0 )
00102   , frame_( 0 )
00103 {
00104 }
00105 
00106 void VisualizerApp::setApp( QApplication * app )
00107 {
00108   app_ = app;
00109 }
00110 
00111 bool VisualizerApp::init( int argc, char** argv )
00112 {
00113   ROS_INFO( "rviz version %s", get_version().c_str() );
00114   ROS_INFO( "compiled against Qt version " QT_VERSION_STR );
00115   ROS_INFO( "compiled against OGRE version %d.%d.%d%s (%s)",
00116             OGRE_VERSION_MAJOR, OGRE_VERSION_MINOR, OGRE_VERSION_PATCH,
00117             OGRE_VERSION_SUFFIX, OGRE_VERSION_NAME );
00118 
00119 #ifdef Q_OS_MAC
00120   ProcessSerialNumber PSN;
00121   GetCurrentProcess(&PSN);
00122   TransformProcessType(&PSN,kProcessTransformToForegroundApplication);
00123   SetFrontProcess(&PSN);
00124 #endif
00125 
00126 #if CATCH_EXCEPTIONS
00127   try
00128   {
00129 #endif
00130     ros::init( argc, argv, "rviz", ros::init_options::AnonymousName );
00131 
00132     startContinueChecker();
00133 
00134     po::options_description options;
00135     options.add_options()
00136       ("help,h", "Produce this help message")
00137       ("splash-screen,s", po::value<std::string>(), "A custom splash-screen image to display")
00138       ("help-file", po::value<std::string>(), "A custom html file to show as the help screen")
00139       ("display-config,d", po::value<std::string>(), "A display config file (.rviz) to load")
00140       ("fixed-frame,f", po::value<std::string>(), "Set the fixed frame")
00141       ("ogre-log,l", "Enable the Ogre.log file (output in cwd) and console output.")
00142       ("in-mc-wrapper", "Signal that this is running inside a master-chooser wrapper")
00143       ("opengl", po::value<int>(), "Force OpenGL version (use '--opengl 210' for OpenGL 2.1 compatibility mode)")
00144       ("disable-anti-aliasing", "Prevent rviz from trying to use anti-aliasing when rendering.")
00145       ("no-stereo", "Disable the use of stereo rendering.")
00146       ("verbose,v", "Enable debug visualizations")
00147       ("log-level-debug", "Sets the ROS logger level to debug.");
00148     po::variables_map vm;
00149     std::string display_config, fixed_frame, splash_path, help_path;
00150     bool enable_ogre_log = false;
00151     bool in_mc_wrapper = false;
00152     bool verbose = false;
00153     int force_gl_version = 0;
00154     bool disable_anti_aliasing = false;
00155     bool disable_stereo = false;
00156     try
00157     {
00158       po::store( po::parse_command_line( argc, argv, options ), vm );
00159       po::notify( vm );
00160 
00161       if( vm.count( "help" ))
00162       {
00163         std::cout << "rviz command line options:\n" << options;
00164         return false;
00165       }
00166 
00167       if( vm.count( "in-mc-wrapper" ))
00168       {
00169         in_mc_wrapper = true;
00170       }
00171 
00172       if (vm.count("display-config"))
00173       {
00174         display_config = vm["display-config"].as<std::string>();
00175         if( display_config.substr( display_config.size() - 4, 4 ) == ".vcg" )
00176         {
00177           std::cerr << "ERROR: the config file '" << display_config << "' is a .vcg file, which is the old rviz config format." << std::endl;
00178           std::cerr << "       New config files have a .rviz extension and use YAML formatting.  The format changed" << std::endl;
00179           std::cerr << "       between Fuerte and Groovy.  There is not (yet) an automated conversion program." << std::endl;
00180           return false;
00181         }
00182       }
00183 
00184       if (vm.count("splash-screen"))
00185       {
00186         splash_path = vm["splash-screen"].as<std::string>();
00187       }
00188 
00189       if (vm.count("help-file"))
00190       {
00191         help_path = vm["help-file"].as<std::string>();
00192       }
00193 
00194       if (vm.count("fixed-frame"))
00195       {
00196         fixed_frame = vm["fixed-frame"].as<std::string>();
00197       }
00198 
00199       if (vm.count("ogre-log"))
00200       {
00201         enable_ogre_log = true;
00202       }
00203 
00204       if (vm.count("no-stereo"))
00205       {
00206         disable_stereo = true;
00207       }
00208 
00209       if (vm.count("opengl"))
00210       {
00211         //std::cout << vm["opengl"].as<std::string>() << std::endl;
00212         force_gl_version = vm["opengl"].as<int>();
00213       }
00214 
00215       if (vm.count("disable-anti-aliasing"))
00216       {
00217         disable_anti_aliasing = true;
00218       }
00219 
00220       if (vm.count("verbose"))
00221       {
00222         verbose = true;
00223       }
00224 
00225       if (vm.count("log-level-debug"))
00226       {
00227         if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) )
00228         {
00229           ros::console::notifyLoggerLevelsChanged();
00230         }
00231       }
00232     }
00233     catch (std::exception& e)
00234     {
00235       ROS_ERROR("Error parsing command line: %s", e.what());
00236       return false;
00237     }
00238 
00239     if( !ros::master::check() )
00240     {
00241       WaitForMasterDialog* dialog = new WaitForMasterDialog;
00242       if( dialog->exec() != QDialog::Accepted )
00243       {
00244         return false;
00245       }
00246     }
00247 
00248     nh_.reset( new ros::NodeHandle );
00249 
00250     if( enable_ogre_log )
00251     {
00252       OgreLogging::useRosLog();
00253     }
00254 
00255     if ( force_gl_version )
00256     {
00257       RenderSystem::forceGlVersion( force_gl_version );
00258     }
00259 
00260     if (disable_anti_aliasing)
00261     {
00262       RenderSystem::disableAntiAliasing();
00263     }
00264 
00265     if ( disable_stereo )
00266     {
00267       RenderSystem::forceNoStereo();
00268     }
00269 
00270     frame_ = new VisualizationFrame();
00271     frame_->setApp( this->app_ );
00272     if( help_path != "" )
00273     {
00274       frame_->setHelpPath( QString::fromStdString( help_path ));
00275     }
00276     frame_->setShowChooseNewMaster( in_mc_wrapper );
00277     if( splash_path != "" )
00278     {
00279       frame_->setSplashPath( QString::fromStdString( splash_path ));
00280     }
00281     frame_->initialize( QString::fromStdString( display_config ));
00282     if( !fixed_frame.empty() )
00283     {
00284       frame_->getManager()->setFixedFrame( QString::fromStdString( fixed_frame ));
00285     }
00286 
00287     frame_->getManager()->getSelectionManager()->setDebugMode( verbose );
00288 
00289     frame_->show();
00290 
00291     ros::NodeHandle private_nh("~");
00292     reload_shaders_service_ = private_nh.advertiseService("reload_shaders", reloadShaders);
00293 
00294 #if CATCH_EXCEPTIONS
00295   }
00296   catch (std::exception& e)
00297   {
00298     ROS_ERROR("Caught exception while loading: %s", e.what());
00299     return false;
00300   }
00301 #endif
00302   return true;
00303 }
00304 
00305 VisualizerApp::~VisualizerApp()
00306 {
00307   delete continue_timer_;
00308   delete frame_;
00309 }
00310 
00311 void VisualizerApp::startContinueChecker()
00312 {
00313   continue_timer_ = new QTimer( this );
00314   connect( continue_timer_, SIGNAL( timeout() ), this, SLOT( checkContinue() ));
00315   continue_timer_->start( 100 );
00316 }
00317 
00318 void VisualizerApp::checkContinue()
00319 {
00320   if( !ros::ok() )
00321   {
00322     if( frame_ )
00323     {
00324       // Make sure the window doesn't ask if we want to save first.
00325       frame_->setWindowModified( false );
00326     }
00327     QApplication::closeAllWindows();
00328   }
00329 }
00330 
00331 } // namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:16