render_system.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, 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 // This is required for QT_MAC_USE_COCOA to be set
00031 #include <QtCore/qglobal.h>
00032 
00033 #ifndef Q_OS_MAC
00034 #include <X11/Xlib.h>
00035 #include <X11/Xutil.h>
00036 #include <GL/glx.h>
00037 #endif
00038 
00039 // X.h #defines CursorShape to be "0".  Qt uses CursorShape in normal
00040 // C++ way.  This wasn't an issue until ogre_logging.h (below)
00041 // introduced a #include of <QString>.
00042 #ifdef CursorShape
00043 #undef CursorShape
00044 #endif
00045 
00046 #include <ros/package.h> // This dependency should be moved out of here, it is just used for a search path.
00047 #include <ros/console.h>
00048 
00049 #include <OgreRenderWindow.h>
00050 #include <OgreSceneManager.h>
00051 #if ((OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 9) || OGRE_VERSION_MAJOR >= 2 )
00052 #include <OgreOverlaySystem.h>
00053 #endif
00054 
00055 #include "rviz/env_config.h"
00056 #include "rviz/ogre_helpers/ogre_logging.h"
00057 
00058 #include "rviz/ogre_helpers/render_system.h"
00059 
00060 #include <QMessageBox>
00061 
00062 namespace rviz
00063 {
00064 
00065 RenderSystem* RenderSystem::instance_ = 0;
00066 int RenderSystem::force_gl_version_ = 0;
00067 bool RenderSystem::force_no_stereo_ = false;
00068 
00069 RenderSystem* RenderSystem::get()
00070 {
00071   if( instance_ == 0 )
00072   {
00073     instance_ = new RenderSystem();
00074   }
00075   return instance_;
00076 }
00077 
00078 void RenderSystem::forceGlVersion( int version )
00079 {
00080   force_gl_version_ = version;
00081   ROS_INFO_STREAM( "Forcing OpenGl version " << (float)version / 100.0 << "." );
00082 }
00083 
00084 void RenderSystem::forceNoStereo()
00085 {
00086   force_no_stereo_ = true;
00087   ROS_INFO("Forcing Stereo OFF");
00088 }
00089 
00090 RenderSystem::RenderSystem()
00091 : ogre_overlay_system_(NULL)
00092 , stereo_supported_(false)
00093 {
00094   OgreLogging::configureLogging();
00095 
00096   std::string rviz_path = ros::package::getPath(ROS_PACKAGE_NAME);
00097 
00098   setupDummyWindowId();
00099   ogre_root_ = new Ogre::Root( rviz_path+"/ogre_media/plugins.cfg" );
00100 #if ((OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 9) || OGRE_VERSION_MAJOR >= 2 )
00101   ogre_overlay_system_ = new Ogre::OverlaySystem();
00102 #endif
00103   loadOgrePlugins();
00104   setupRenderSystem();
00105   ogre_root_->initialise(false);
00106   makeRenderWindow( dummy_window_id_, 1, 1 );
00107   detectGlVersion();
00108   setupResources();
00109   Ogre::ResourceGroupManager::getSingleton().initialiseAllResourceGroups();
00110 }
00111 
00112 void RenderSystem::prepareOverlays(Ogre::SceneManager* scene_manager)
00113 {
00114 #if ((OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 9) || OGRE_VERSION_MAJOR >= 2 )
00115   if (ogre_overlay_system_)
00116     scene_manager->addRenderQueueListener(ogre_overlay_system_);
00117 #endif
00118 }
00119 
00120 void RenderSystem::setupDummyWindowId()
00121 {
00122 #ifdef Q_OS_MAC
00123   dummy_window_id_ = 0;
00124 #else
00125   Display *display = XOpenDisplay(0);
00126   assert( display );
00127 
00128   int screen = DefaultScreen( display );
00129 
00130   int attribList[] = { GLX_RGBA, GLX_DOUBLEBUFFER, GLX_DEPTH_SIZE, 16, 
00131                        GLX_STENCIL_SIZE, 8, None };
00132 
00133   XVisualInfo *visual = glXChooseVisual( display, screen, (int*)attribList );
00134 
00135   dummy_window_id_ = XCreateSimpleWindow( display,
00136                                           RootWindow( display, screen ),
00137                                           0, 0, 1, 1, 0, 0, 0 );
00138 
00139   GLXContext context = glXCreateContext( display, visual, NULL, 1 );
00140 
00141   glXMakeCurrent( display, dummy_window_id_, context );
00142 #endif
00143 }
00144 
00145 void RenderSystem::loadOgrePlugins()
00146 {
00147   std::string plugin_prefix = get_ogre_plugin_path() + "/";
00148 #ifdef Q_OS_MAC
00149   plugin_prefix += "lib";
00150 #endif
00151   ogre_root_->loadPlugin( plugin_prefix + "RenderSystem_GL" );
00152   ogre_root_->loadPlugin( plugin_prefix + "Plugin_OctreeSceneManager" );
00153   ogre_root_->loadPlugin( plugin_prefix + "Plugin_ParticleFX" );
00154 }
00155 
00156 void RenderSystem::detectGlVersion()
00157 {
00158   if ( force_gl_version_ )
00159   {
00160     gl_version_ = force_gl_version_;
00161   }
00162   else
00163   {
00164     Ogre::RenderSystem *renderSys = ogre_root_->getRenderSystem();
00165     renderSys->createRenderSystemCapabilities();
00166     const Ogre::RenderSystemCapabilities* caps = renderSys->getCapabilities();
00167     int major = caps->getDriverVersion().major;
00168     int minor = caps->getDriverVersion().minor;
00169     gl_version_ = major * 100 + minor*10;
00170   }
00171 
00172   switch ( gl_version_ )
00173   {
00174     case 200:
00175       glsl_version_ = 110;
00176       break;
00177     case 210:
00178       glsl_version_ = 120;
00179       break;
00180     case 300:
00181       glsl_version_ = 130;
00182       break;
00183     case 310:
00184       glsl_version_ = 140;
00185       break;
00186     case 320:
00187       glsl_version_ = 150;
00188       break;
00189     default:
00190       if ( gl_version_ > 320 )
00191       {
00192         glsl_version_  = gl_version_;
00193       }
00194       else
00195       {
00196         glsl_version_ = 0;
00197       }
00198       break;
00199   }
00200   ROS_INFO_STREAM( "OpenGl version: " << (float)gl_version_ / 100.0 << " (GLSL " << (float)glsl_version_ / 100.0 << ")." );
00201 }
00202 
00203 void RenderSystem::setupRenderSystem()
00204 {
00205   Ogre::RenderSystem *renderSys;
00206   const Ogre::RenderSystemList *rsList;
00207 
00208   // Get the list of available renderers.
00209 #if OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR == 6
00210   rsList = ogre_root_->getAvailableRenderers();
00211 #else
00212   rsList = &(ogre_root_->getAvailableRenderers());
00213 #endif
00214    
00215   // Look for the OpenGL one, which we require.
00216   renderSys = NULL;
00217   for( unsigned int i = 0; i < rsList->size(); i++ )
00218   {
00219     renderSys = rsList->at( i );
00220     if( renderSys->getName().compare("OpenGL Rendering Subsystem")== 0 )
00221     {
00222       break;
00223     }
00224   }
00225 
00226   if( renderSys == NULL )
00227   {
00228     throw std::runtime_error( "Could not find the opengl rendering subsystem!\n" );
00229   }
00230 
00231   // We operate in windowed mode
00232   renderSys->setConfigOption("Full Screen","No");
00233 
00239   //  renderSys->setConfigOption("RTT Preferred Mode", "FBO");
00240 
00241   // Set the Full Screen Anti-Aliasing factor.
00242   renderSys->setConfigOption("FSAA", "2");
00243 
00244   ogre_root_->setRenderSystem(renderSys);
00245 }
00246 
00247 void RenderSystem::setupResources()
00248 {
00249   std::string rviz_path = ros::package::getPath(ROS_PACKAGE_NAME);
00250   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media", "FileSystem", ROS_PACKAGE_NAME );
00251   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/textures", "FileSystem", ROS_PACKAGE_NAME );
00252   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/fonts", "FileSystem", ROS_PACKAGE_NAME );
00253   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/models", "FileSystem", ROS_PACKAGE_NAME );
00254   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials", "FileSystem", ROS_PACKAGE_NAME );
00255   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts", "FileSystem", ROS_PACKAGE_NAME );
00256   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl120", "FileSystem", ROS_PACKAGE_NAME );
00257   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl120/nogp", "FileSystem", ROS_PACKAGE_NAME );
00258   // Add resources that depend on a specific glsl version.
00259   // Unfortunately, Ogre doesn't have a notion of glsl versions so we can't go
00260   // the 'official' way of defining multiple schemes per material and let Ogre decide which one to use.
00261   if ( getGlslVersion() >= 150  )
00262   {
00263     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl150", "FileSystem", ROS_PACKAGE_NAME );
00264     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts150", "FileSystem", ROS_PACKAGE_NAME );
00265   }
00266   else if ( getGlslVersion() >= 120  )
00267   {
00268     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts120", "FileSystem", ROS_PACKAGE_NAME );
00269   }
00270   else
00271   {
00272     std::string s = "Your graphics driver does not support OpenGL 2.1. Please enable software rendering before running RViz (e.g. type 'export LIBGL_ALWAYS_SOFTWARE=1').";
00273     QMessageBox msgBox;
00274     msgBox.setText(s.c_str());
00275     msgBox.exec();
00276     throw std::runtime_error( s );
00277   }
00278 
00279   // Add paths exported to the "media_export" package.
00280   std::vector<std::string> media_paths;
00281   ros::package::getPlugins( "media_export", "ogre_media_path", media_paths );
00282   std::string delim(":");
00283   for( std::vector<std::string>::iterator iter = media_paths.begin(); iter != media_paths.end(); iter++ )
00284   {
00285     if( !iter->empty() )
00286     {
00287       std::string path;
00288       int pos1 = 0;
00289       int pos2 = iter->find(delim);
00290       while( pos2 != (int)std::string::npos )
00291       {
00292         path = iter->substr( pos1, pos2 - pos1 );
00293         ROS_DEBUG("adding resource location: '%s'\n", path.c_str());
00294         Ogre::ResourceGroupManager::getSingleton().addResourceLocation( path, "FileSystem", ROS_PACKAGE_NAME );
00295         pos1 = pos2 + 1;
00296         pos2 = iter->find( delim, pos2 + 1 );
00297       }
00298       path = iter->substr( pos1, iter->size() - pos1 );
00299       ROS_DEBUG("adding resource location: '%s'\n", path.c_str());
00300       Ogre::ResourceGroupManager::getSingleton().addResourceLocation( path, "FileSystem", ROS_PACKAGE_NAME );
00301     }
00302   }
00303 }
00304 
00305 // On Intel graphics chips under X11, there sometimes comes a
00306 // BadDrawable error during Ogre render window creation.  It is not
00307 // consistent, happens sometimes but not always.  Underlying problem
00308 // seems to be a driver bug.  My workaround here is to notice when
00309 // that specific BadDrawable error happens on request 136 minor 3
00310 // (which is what the problem looks like when it happens) and just try
00311 // over and over again until it works (or until 100 failures, which
00312 // makes it seem like it is a different bug).
00313 static bool x_baddrawable_error = false;
00314 #ifdef Q_WS_X11
00315 static int (*old_error_handler)( Display*, XErrorEvent* );
00316 int checkBadDrawable( Display* display, XErrorEvent* error )
00317 {
00318   if( error->error_code == BadDrawable &&
00319       error->request_code == 136 &&
00320       error->minor_code == 3 )
00321   {
00322     x_baddrawable_error = true;
00323     return 0;
00324   }
00325   else
00326   {
00327     // If the error does not exactly match the one from the driver bug,
00328     // handle it the normal way so we see it.
00329     return old_error_handler( display, error );
00330   }
00331 }
00332 #endif // Q_WS_X11
00333 
00334 Ogre::RenderWindow* RenderSystem::makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height )
00335 {
00336   static int windowCounter = 0; // Every RenderWindow needs a unique name, oy.
00337 
00338   Ogre::NameValuePairList params;
00339   Ogre::RenderWindow *window = NULL;
00340 
00341   std::stringstream window_handle_stream;
00342   window_handle_stream << window_id;
00343 
00344 #ifdef Q_OS_MAC
00345   params["externalWindowHandle"] = window_handle_stream.str();
00346 #else
00347   params["parentWindowHandle"] = window_handle_stream.str();
00348 #endif
00349 
00350   params["externalGLControl"] = true;
00351 
00352 // Set the macAPI for Ogre based on the Qt implementation
00353 #ifdef QT_MAC_USE_COCOA
00354   params["macAPI"] = "cocoa";
00355   params["macAPICocoaUseNSView"] = "true";
00356 #else
00357   params["macAPI"] = "carbon";
00358 #endif
00359 
00360   std::ostringstream stream;
00361   stream << "OgreWindow(" << windowCounter++ << ")";
00362 
00363 
00364   // don't bother trying stereo if Ogre does not support it.
00365 #if !OGRE_STEREO_ENABLE
00366   force_no_stereo_ = true;
00367 #endif
00368 
00369   // attempt to create a stereo window
00370   bool is_stereo = false;
00371   if (!force_no_stereo_)
00372   {
00373     params["stereoMode"] = "Frame Sequential";
00374     window = tryMakeRenderWindow( stream.str(), width, height, &params, 100);
00375     params.erase("stereoMode");
00376 
00377     if (window)
00378     {
00379 #if OGRE_STEREO_ENABLE
00380       is_stereo = window->isStereoEnabled();
00381 #endif
00382       if (!is_stereo)
00383       {
00384         // Created a non-stereo window.  Discard it and try again (below)
00385         // without the stereo parameter.
00386         ogre_root_->detachRenderTarget(window);
00387         window->destroy();
00388         window = NULL;
00389         stream << "x";
00390         is_stereo = false;
00391       }
00392     }
00393   }
00394 
00395   if ( window == NULL )
00396   {
00397     window = tryMakeRenderWindow( stream.str(), width, height, &params, 100);
00398   }
00399 
00400   if( window == NULL )
00401   {
00402     ROS_ERROR( "Unable to create the rendering window after 100 tries." );
00403     assert(false);
00404   }
00405 
00406   if (window)
00407   {
00408     window->setActive(true);
00409     //window->setVisible(true);
00410     window->setAutoUpdated(false);
00411   }
00412 
00413   stereo_supported_ = is_stereo;
00414 
00415   ROS_INFO_ONCE("Stereo is %s", stereo_supported_ ? "SUPPORTED" : "NOT SUPPORTED");
00416 
00417   return window;
00418 }
00419 
00420 Ogre::RenderWindow* RenderSystem::tryMakeRenderWindow(
00421       const std::string& name,
00422       unsigned int width,
00423       unsigned int height,
00424       const Ogre::NameValuePairList* params,
00425       int max_attempts )
00426 {
00427   Ogre::RenderWindow *window = NULL;
00428   int attempts = 0;
00429 
00430 #ifdef Q_WS_X11
00431   old_error_handler = XSetErrorHandler( &checkBadDrawable );
00432 #endif
00433 
00434   while (window == NULL && (attempts++) < max_attempts)
00435   {
00436     try
00437     {
00438       window = ogre_root_->createRenderWindow( name, width, height, false, params );
00439 
00440       // If the driver bug happened, tell Ogre we are done with that
00441       // window and then try again.
00442       if( x_baddrawable_error )
00443       {
00444         ogre_root_->detachRenderTarget( window );
00445         window = NULL;
00446         x_baddrawable_error = false;
00447       }
00448     }
00449     catch( std::exception ex )
00450     {
00451       std::cerr << "rviz::RenderSystem: error creating render window: "
00452                 << ex.what() << std::endl;
00453       window = NULL;
00454     }
00455   }
00456 
00457 #ifdef Q_WS_X11
00458   XSetErrorHandler( old_error_handler );
00459 #endif
00460 
00461   if( window && attempts > 1 )
00462   {
00463     ROS_INFO( "Created render window after %d attempts.", attempts );
00464   }
00465 
00466   return window;
00467 }
00468 
00469 
00470 } // end namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:28