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 <OGRE/OgreRenderWindow.h>
00050 
00051 #include "rviz/env_config.h"
00052 #include "rviz/ogre_helpers/ogre_logging.h"
00053 
00054 #include "rviz/ogre_helpers/render_system.h"
00055 
00056 #include <QMessageBox>
00057 
00058 namespace rviz
00059 {
00060 
00061 RenderSystem* RenderSystem::instance_ = 0;
00062 int RenderSystem::force_gl_version_ = 0;
00063 
00064 RenderSystem* RenderSystem::get()
00065 {
00066   if( instance_ == 0 )
00067   {
00068     instance_ = new RenderSystem();
00069   }
00070   return instance_;
00071 }
00072 
00073 void RenderSystem::forceGlVersion( int version )
00074 {
00075   force_gl_version_ = version;
00076   ROS_INFO_STREAM( "Forcing OpenGl version " << (float)version / 100.0 << "." );
00077 }
00078 
00079 RenderSystem::RenderSystem()
00080 {
00081   OgreLogging::configureLogging();
00082 
00083   std::string rviz_path = ros::package::getPath(ROS_PACKAGE_NAME);
00084 
00085   setupDummyWindowId();
00086   ogre_root_ = new Ogre::Root( rviz_path+"/ogre_media/plugins.cfg" );
00087   loadOgrePlugins();
00088   setupRenderSystem();
00089   ogre_root_->initialise(false);
00090   makeRenderWindow( dummy_window_id_, 1, 1 );
00091   detectGlVersion();
00092   setupResources();
00093   Ogre::ResourceGroupManager::getSingleton().initialiseAllResourceGroups();
00094  }
00095 
00096 void RenderSystem::setupDummyWindowId()
00097 {
00098 #ifdef Q_OS_MAC
00099   dummy_window_id_ = 0;
00100 #else
00101   Display *display = XOpenDisplay(0);
00102   assert( display );
00103 
00104   int screen = DefaultScreen( display );
00105 
00106   int attribList[] = { GLX_RGBA, GLX_DOUBLEBUFFER, GLX_DEPTH_SIZE, 16, 
00107                        GLX_STENCIL_SIZE, 8, None };
00108 
00109   XVisualInfo *visual = glXChooseVisual( display, screen, (int*)attribList );
00110 
00111   dummy_window_id_ = XCreateSimpleWindow( display,
00112                                           RootWindow( display, screen ),
00113                                           0, 0, 1, 1, 0, 0, 0 );
00114 
00115   GLXContext context = glXCreateContext( display, visual, NULL, 1 );
00116 
00117   glXMakeCurrent( display, dummy_window_id_, context );
00118 #endif
00119 }
00120 
00121 void RenderSystem::loadOgrePlugins()
00122 {
00123   std::string plugin_prefix = get_ogre_plugin_path() + "/";
00124 #ifdef Q_OS_MAC
00125   plugin_prefix += "lib";
00126 #endif
00127   ogre_root_->loadPlugin( plugin_prefix + "RenderSystem_GL" );
00128   ogre_root_->loadPlugin( plugin_prefix + "Plugin_OctreeSceneManager" );
00129   ogre_root_->loadPlugin( plugin_prefix + "Plugin_ParticleFX" );
00130 }
00131 
00132 void RenderSystem::detectGlVersion()
00133 {
00134   if ( force_gl_version_ )
00135   {
00136     gl_version_ = force_gl_version_;
00137   }
00138   else
00139   {
00140     Ogre::RenderSystem *renderSys = ogre_root_->getRenderSystem();
00141     renderSys->createRenderSystemCapabilities();
00142     const Ogre::RenderSystemCapabilities* caps = renderSys->getCapabilities();
00143     int major = caps->getDriverVersion().major;
00144     int minor = caps->getDriverVersion().minor;
00145     gl_version_ = major * 100 + minor*10;
00146   }
00147 
00148   switch ( gl_version_ )
00149   {
00150     case 200:
00151       glsl_version_ = 110;
00152       break;
00153     case 210:
00154       glsl_version_ = 120;
00155       break;
00156     case 300:
00157       glsl_version_ = 130;
00158       break;
00159     case 310:
00160       glsl_version_ = 140;
00161       break;
00162     case 320:
00163       glsl_version_ = 150;
00164       break;
00165     default:
00166       if ( gl_version_ > 320 )
00167       {
00168         glsl_version_  = gl_version_;
00169       }
00170       else
00171       {
00172         glsl_version_ = 0;
00173       }
00174       break;
00175   }
00176   ROS_INFO_STREAM( "OpenGl version: " << (float)gl_version_ / 100.0 << " (GLSL " << (float)glsl_version_ / 100.0 << ")." );
00177 }
00178 
00179 void RenderSystem::setupRenderSystem()
00180 {
00181   Ogre::RenderSystem *renderSys;
00182   const Ogre::RenderSystemList *rsList;
00183 
00184   // Get the list of available renderers.
00185 #if OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR == 6
00186   rsList = ogre_root_->getAvailableRenderers();
00187 #else
00188   rsList = &(ogre_root_->getAvailableRenderers());
00189 #endif
00190    
00191   // Look for the OpenGL one, which we require.
00192   renderSys = NULL;
00193   for( unsigned int i = 0; i < rsList->size(); i++ )
00194   {
00195     renderSys = rsList->at( i );
00196     if( renderSys->getName().compare("OpenGL Rendering Subsystem")== 0 )
00197     {
00198       break;
00199     }
00200   }
00201 
00202   if( renderSys == NULL )
00203   {
00204     throw std::runtime_error( "Could not find the opengl rendering subsystem!\n" );
00205   }
00206 
00207   // We operate in windowed mode
00208   renderSys->setConfigOption("Full Screen","No");
00209 
00215   //  renderSys->setConfigOption("RTT Preferred Mode", "FBO");
00216 
00217   // Set the Full Screen Anti-Aliasing factor.
00218   renderSys->setConfigOption("FSAA", "2");
00219 
00220   ogre_root_->setRenderSystem(renderSys);
00221 }
00222 
00223 void RenderSystem::setupResources()
00224 {
00225   std::string rviz_path = ros::package::getPath(ROS_PACKAGE_NAME);
00226   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media", "FileSystem", ROS_PACKAGE_NAME );
00227   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/textures", "FileSystem", ROS_PACKAGE_NAME );
00228   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/fonts", "FileSystem", ROS_PACKAGE_NAME );
00229   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/models", "FileSystem", ROS_PACKAGE_NAME );
00230   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials", "FileSystem", ROS_PACKAGE_NAME );
00231   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts", "FileSystem", ROS_PACKAGE_NAME );
00232   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl120", "FileSystem", ROS_PACKAGE_NAME );
00233   Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl120/nogp", "FileSystem", ROS_PACKAGE_NAME );
00234   // Add resources that depend on a specific glsl version.
00235   // Unfortunately, Ogre doesn't have a notion of glsl versions so we can't go
00236   // the 'official' way of defining multiple schemes per material and let Ogre decide which one to use.
00237   if ( getGlslVersion() >= 150  )
00238   {
00239     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/glsl150", "FileSystem", ROS_PACKAGE_NAME );
00240     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts150", "FileSystem", ROS_PACKAGE_NAME );
00241   }
00242   else if ( getGlslVersion() >= 120  )
00243   {
00244     Ogre::ResourceGroupManager::getSingleton().addResourceLocation( rviz_path + "/ogre_media/materials/scripts120", "FileSystem", ROS_PACKAGE_NAME );
00245   }
00246   else
00247   {
00248     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').";
00249     QMessageBox msgBox;
00250     msgBox.setText(s.c_str());
00251     msgBox.exec();
00252     throw std::runtime_error( s );
00253   }
00254 }
00255 
00256 // On Intel graphics chips under X11, there sometimes comes a
00257 // BadDrawable error during Ogre render window creation.  It is not
00258 // consistent, happens sometimes but not always.  Underlying problem
00259 // seems to be a driver bug.  My workaround here is to notice when
00260 // that specific BadDrawable error happens on request 136 minor 3
00261 // (which is what the problem looks like when it happens) and just try
00262 // over and over again until it works (or until 100 failures, which
00263 // makes it seem like it is a different bug).
00264 static bool x_baddrawable_error = false;
00265 #ifdef Q_WS_X11
00266 static int (*old_error_handler)( Display*, XErrorEvent* );
00267 int checkBadDrawable( Display* display, XErrorEvent* error )
00268 {
00269   if( error->error_code == BadDrawable &&
00270       error->request_code == 136 &&
00271       error->minor_code == 3 )
00272   {
00273     x_baddrawable_error = true;
00274     return 0;
00275   }
00276   else
00277   {
00278     // If the error does not exactly match the one from the driver bug,
00279     // handle it the normal way so we see it.
00280     return old_error_handler( display, error );
00281   }
00282 }
00283 #endif // Q_WS_X11
00284 
00285 Ogre::RenderWindow* RenderSystem::makeRenderWindow( intptr_t window_id, unsigned int width, unsigned int height )
00286 {
00287   static int windowCounter = 0; // Every RenderWindow needs a unique name, oy.
00288 
00289   Ogre::NameValuePairList params;
00290   Ogre::RenderWindow *window = NULL;
00291 
00292   std::stringstream window_handle_stream;
00293   window_handle_stream << window_id;
00294 
00295 #ifdef Q_OS_MAC
00296   params["externalWindowHandle"] = window_handle_stream.str();
00297 #else
00298   params["parentWindowHandle"] = window_handle_stream.str();
00299 #endif
00300 
00301   params["externalGLControl"] = true;
00302 
00303 // Set the macAPI for Ogre based on the Qt implementation
00304 #ifdef QT_MAC_USE_COCOA
00305   params["macAPI"] = "cocoa";
00306   params["macAPICocoaUseNSView"] = "true";
00307 #else
00308   params["macAPI"] = "carbon";
00309 #endif
00310 
00311   std::ostringstream stream;
00312   stream << "OgreWindow(" << windowCounter++ << ")";
00313 
00314 #ifdef Q_WS_X11
00315   old_error_handler = XSetErrorHandler( &checkBadDrawable );
00316 #endif
00317 
00318   int attempts = 0;
00319   while (window == NULL && (attempts++) < 100)
00320   {
00321     try
00322     {
00323       window = ogre_root_->createRenderWindow( stream.str(), width, height, false, &params );
00324 
00325       // If the driver bug happened, tell Ogre we are done with that
00326       // window and then try again.
00327       if( x_baddrawable_error )
00328       {
00329         ogre_root_->detachRenderTarget( window );
00330         window = NULL;
00331         x_baddrawable_error = false;
00332       }
00333     }
00334     catch( std::exception ex )
00335     {
00336       std::cerr << "rviz::RenderSystem: error creating render window: "
00337                 << ex.what() << std::endl;
00338       window = NULL;
00339     }
00340   }
00341 
00342 #ifdef Q_WS_X11
00343   XSetErrorHandler( old_error_handler );
00344 #endif
00345 
00346   if( window == NULL )
00347   {
00348     ROS_ERROR( "Unable to create the rendering window after 100 tries." );
00349     assert(false);
00350   }
00351 
00352   if( attempts > 1 )
00353   {
00354     ROS_INFO( "Created render window after %d attempts.", attempts );
00355   }
00356 
00357   if (window)
00358   {
00359     window->setActive(true);
00360     //window->setVisible(true);
00361     window->setAutoUpdated(false);
00362   }
00363 
00364   return window;
00365 }
00366 
00367 } // end namespace rviz


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