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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31