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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36