Revision: 8345
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8345&view=rev
Author:   natepak
Date:     2009-10-30 16:35:24 +0000 (Fri, 30 Oct 2009)

Log Message:
-----------
Incorporated patches from John Hsu

Modified Paths:
--------------
    code/gazebo/trunk/3rd_party/assimp/code/ColladaParser.cpp
    code/gazebo/trunk/cmake/SearchForStuff.cmake
    code/gazebo/trunk/libgazebo/Client.cc
    code/gazebo/trunk/libgazebo/bindings/ruby/CMakeLists.txt
    code/gazebo/trunk/server/CMakeLists.txt
    code/gazebo/trunk/server/Entity.cc
    code/gazebo/trunk/server/Global.hh
    code/gazebo/trunk/server/Model.cc
    code/gazebo/trunk/server/Simulator.cc
    code/gazebo/trunk/server/World.cc
    code/gazebo/trunk/server/World.hh
    code/gazebo/trunk/server/physics/Body.cc
    code/gazebo/trunk/server/rendering/OgreAdaptor.cc
    code/gazebo/trunk/server/rendering/OgreCamera.cc
    code/gazebo/trunk/server/rendering/OgreCreator.cc
    code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
    code/gazebo/trunk/server/sensors/ray/RaySensor.cc

Modified: code/gazebo/trunk/3rd_party/assimp/code/ColladaParser.cpp
===================================================================
--- code/gazebo/trunk/3rd_party/assimp/code/ColladaParser.cpp   2009-10-30 
15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/3rd_party/assimp/code/ColladaParser.cpp   2009-10-30 
16:35:24 UTC (rev 8345)
@@ -76,7 +76,6 @@
        if( !mReader)
                ThrowException( "Collada: Unable to open file.");
 
-  std::cout << "Read Contents\n";
        // start reading
        ReadContents();
 }

Modified: code/gazebo/trunk/cmake/SearchForStuff.cmake
===================================================================
--- code/gazebo/trunk/cmake/SearchForStuff.cmake        2009-10-30 15:06:10 UTC 
(rev 8344)
+++ code/gazebo/trunk/cmake/SearchForStuff.cmake        2009-10-30 16:35:24 UTC 
(rev 8345)
@@ -13,6 +13,7 @@
 SET (boost_include_dirs "" CACHE STRING "Boost include paths. Use this to 
override automatic detection.")
 SET (boost_library_dirs "" CACHE STRING "Boost library paths. Use this to 
override automatic detection.")
 SET (boost_libraries "" CACHE STRING "Boost libraries. Use this to override 
automatic detection.")
+SET (threadpool_include_dirs "" CACHE STRING "Threadpool include paths. Use 
this to override automatic detection.")
 
 ########################################
 # Find packages
@@ -210,7 +211,12 @@
 MESSAGE (STATUS "Boost Library Path: ${boost_library_dirs}")
 MESSAGE (STATUS "Boost Libraries: ${boost_libraries}")
 
+
 ########################################
+# For Threadpool
+message (STATUS "Threadpool Include Path: ${threadpool_include_dirs}")
+
+########################################
 # Find avformat and avcodec
 IF (HAVE_FFMPEG)
   SET (libavformat_search_path 

Modified: code/gazebo/trunk/libgazebo/Client.cc
===================================================================
--- code/gazebo/trunk/libgazebo/Client.cc       2009-10-30 15:06:10 UTC (rev 
8344)
+++ code/gazebo/trunk/libgazebo/Client.cc       2009-10-30 16:35:24 UTC (rev 
8345)
@@ -84,6 +84,7 @@
 void Client::ConnectWait(int serverId, int clientId)
 {
   bool simulationIfaceIsValid = false;
+  gazebo::SimulationIface simulationIface;
 
   while (!simulationIfaceIsValid)
   {
@@ -129,13 +130,12 @@
 
     this->filename = stream.str();
 
-    std::cout << "opening " << this->filename << "\n";
+    //std::cout << "opening " << this->filename << "\n";
 
     // Connect to gazebo::SimulationIface and check for changing realTime,
     // if simulationIface->data->realTime is not changing, the server might
     // be stale leftovers from previous gazebo crash,
     // disconnect and reconnect client
-    gazebo::SimulationIface simulationIface;
     try
     {
       simulationIface.Open(this,"default");
@@ -177,6 +177,7 @@
     }
   }
 
+  simulationIface.Close();
 }
 
 

Modified: code/gazebo/trunk/libgazebo/bindings/ruby/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/libgazebo/bindings/ruby/CMakeLists.txt    2009-10-30 
15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/libgazebo/bindings/ruby/CMakeLists.txt    2009-10-30 
16:35:24 UTC (rev 8345)
@@ -2,6 +2,8 @@
 
 if(RUBY_LIBRARY AND RUBY_INCLUDE_PATH)
     SET(RUBY_FOUND TRUE)
+    message(STATUS "Found Ruby libraries: ${RUBY_LIBRARY}")
+    message(STATUS "Found Ruby includes: ${RUBY_INCLUDE_PATH}")
 endif (RUBY_LIBRARY AND RUBY_INCLUDE_PATH)
 
   IF(RUBY_FOUND)

Modified: code/gazebo/trunk/server/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/server/CMakeLists.txt     2009-10-30 15:06:10 UTC (rev 
8344)
+++ code/gazebo/trunk/server/CMakeLists.txt     2009-10-30 16:35:24 UTC (rev 
8345)
@@ -1,5 +1,6 @@
 INCLUDE (${gazebo_cmake_dir}/GazeboUtils.cmake)
 
+STRING (REPLACE " " ";" threadpool_include_dirs_split 
"${threadpool_include_dirs}")
 
 ########################################
 # Include all the search paths for headers
@@ -24,6 +25,7 @@
   ${gazeboserver_include_dirs}
   ${boost_include_dirs}
   ${freeimage_include_dir}
+  ${threadpool_include_dirs_split}
   ${FLTK_INCLUDE_DIR}
 )
 

Modified: code/gazebo/trunk/server/Entity.cc
===================================================================
--- code/gazebo/trunk/server/Entity.cc  2009-10-30 15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/Entity.cc  2009-10-30 16:35:24 UTC (rev 8345)
@@ -59,16 +59,16 @@
   {
     this->parent->AddChild(this);
 
-//    if (Simulator::Instance()->GetRenderEngineEnabled())
+    if (Simulator::Instance()->GetRenderEngineEnabled())
       this->visualNode = OgreCreator::Instance()->CreateVisual(
-            visname.str(), this->parent->GetVisualNode(), this);
+          visname.str(), this->parent->GetVisualNode(), this);
     this->SetStatic(parent->IsStatic());
   }
   else
   {
-    //if (Simulator::Instance()->GetRenderEngineEnabled())
-    this->visualNode = OgreCreator::Instance()->CreateVisual( 
-        visname.str(), NULL, this );
+    if (Simulator::Instance()->GetRenderEngineEnabled())
+      this->visualNode = OgreCreator::Instance()->CreateVisual( 
+          visname.str(), NULL, this );
   }
 
   // Add this to the phyic's engine
@@ -83,8 +83,9 @@
 
   World::Instance()->GetPhysicsEngine()->RemoveEntity(this);
 
-  if (this->visualNode)
-    OgreCreator::Instance()->DeleteVisual(this->visualNode);
+  if (Simulator::Instance()->GetRenderEngineEnabled())
+    if (this->visualNode)
+      OgreCreator::Instance()->DeleteVisual(this->visualNode);
   this->visualNode = NULL;
 }
 

Modified: code/gazebo/trunk/server/Global.hh
===================================================================
--- code/gazebo/trunk/server/Global.hh  2009-10-30 15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/Global.hh  2009-10-30 16:35:24 UTC (rev 8345)
@@ -80,6 +80,7 @@
 
 #define ROUND(x) ( (int)( floor((x)+0.5) ) )
 
-//#define TIMING
+#undef TIMING
+#undef USE_THREADPOOL
 
 #endif

Modified: code/gazebo/trunk/server/Model.cc
===================================================================
--- code/gazebo/trunk/server/Model.cc   2009-10-30 15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/Model.cc   2009-10-30 16:35:24 UTC (rev 8345)
@@ -36,6 +36,7 @@
 #include "GazeboMessage.hh"
 #include "XMLConfig.hh"
 #include "World.hh"
+#include "Simulator.hh"
 #include "OgreCreator.hh"
 #include "Body.hh"
 #include "HingeJoint.hh"
@@ -256,12 +257,10 @@
   if (**this->staticP == false)
     this->SetGravityMode( **this->enableGravityP );
 
-
   //global fiducial and retro id
   this->SetLaserFiducialId(**this->laserFiducialP);
   this->SetLaserRetro(**this->laserRetroP);
 
-
   // Create the graphics iface handler
   this->graphicsHandler = new GraphicsIfaceHandler();
   this->graphicsHandler->Load(this->GetScopedName(), this);
@@ -353,7 +352,8 @@
   {
     if (!this->lightName.empty())
     {
-      OgreCreator::SaveLight(p, this->lightName, stream);
+      if (Simulator::Instance()->GetRenderEngineEnabled())
+        OgreCreator::SaveLight(p, this->lightName, stream);
     }
   }
 
@@ -408,6 +408,10 @@
 // Update the model
 void Model::Update()
 {
+#ifdef USE_THREADPOOL
+  World::Instance()->GetPhysicsEngine()->InitForThread();
+#endif
+
   std::map<std::string, Body* >::iterator bodyIter;
   std::map<std::string, Controller* >::iterator contIter;
   std::map<std::string, Joint* >::iterator jointIter;
@@ -422,7 +426,11 @@
   {
     if (bodyIter->second)
     {
+#ifdef USE_THREADPOOL
+      
World::Instance()->threadPool->schedule(boost::bind(&Body::Update,(bodyIter->second)));
+#else
       bodyIter->second->Update();
+#endif
     }
   }
 
@@ -434,9 +442,14 @@
   for (contIter=this->controllers.begin();
        contIter!=this->controllers.end(); contIter++)
   {
-
     if (contIter->second)
+    {
+#ifdef USE_THREADPOOL
+      
World::Instance()->threadPool->schedule(boost::bind(&Controller::Update,(contIter->second)));
+#else
       contIter->second->Update();
+#endif
+    }
   }
 
 #ifdef TIMING
@@ -446,7 +459,11 @@
 
   for (jointIter = this->joints.begin(); jointIter != this->joints.end(); 
jointIter++)
   {
+#ifdef USE_THREADPOOL
+    
World::Instance()->threadPool->schedule(boost::bind(&Joint::Update,(jointIter->second)));
+#else
     jointIter->second->Update();
+#endif
   }
 
 #ifdef TIMING
@@ -454,8 +471,6 @@
   std::cout << "      ALL Joints/canonical body (" << this->GetName() << ") DT 
(" << tmpT4-tmpT3 << ")" << std::endl;
 #endif
 
-
-
   // Call the model's python update function, if one exists
   /*if (this->pFuncUpdate)
   {
@@ -481,16 +496,15 @@
     this->xyzP->SetValue(this->pose.pos);
     this->rpyP->SetValue(this->pose.rot);
   }
+
+  this->UpdateChild();
   
 #ifdef TIMING
-  this->UpdateChild();
   double tmpT5 = Simulator::Instance()->GetWallTime();
   std::cout << "      ALL child (" << this->GetName() << ") update DT (" 
             << tmpT5-tmpT4 << ")" << std::endl;
   std::cout << "      Models::Update() (" << this->GetName() 
             << ") Total DT (" << tmpT5-tmpT1 << ")" << std::endl;
-#else
-   this->UpdateChild();
 #endif
 
 }
@@ -1121,9 +1135,11 @@
   body->SetPose(Pose3d());
   this->bodies[body->GetName()] = body;
 
-  if ((childNode = node->GetChild("light")))
+  if (Simulator::Instance()->GetRenderEngineEnabled() && 
+      (childNode = node->GetChild("light")))
   {
-    this->lightName = OgreCreator::CreateLight(childNode, 
body->GetVisualNode());
+    this->lightName = OgreCreator::CreateLight(childNode, 
+        body->GetVisualNode());
   }
 
 }

Modified: code/gazebo/trunk/server/Simulator.cc
===================================================================
--- code/gazebo/trunk/server/Simulator.cc       2009-10-30 15:06:10 UTC (rev 
8344)
+++ code/gazebo/trunk/server/Simulator.cc       2009-10-30 16:35:24 UTC (rev 
8345)
@@ -353,8 +353,10 @@
         this->gui->Update();
 
       World::Instance()->ProcessEntitiesToLoad();
-      World::Instance()->GraphicsUpdate();
 
+      if (this->renderEngineEnabled)
+        World::Instance()->GraphicsUpdate();
+
       currTime = this->GetWallTime();
 
       if (currTime - lastTime < 1/freq)
@@ -637,9 +639,18 @@
 
     {
       boost::recursive_mutex::scoped_lock lock(*this->mutex);
+#ifdef TIMING
+      double tmpT2 = Simulator::Instance()->GetWallTime();
+      std::cout << " LOCK DT(" << tmpT2-tmpT1 << ")" << std::endl;
+#endif
       world->Update();
     }
 
+#ifdef TIMING
+    double tmpT2 = Simulator::Instance()->GetWallTime();
+    std::cout << " World::Update() DT(" << tmpT2-tmpT1 << ")" << std::endl;
+#endif
+
     currTime = this->GetRealTime();
 
     // Set a default sleep time
@@ -673,6 +684,11 @@
     // Process all incoming messages from simiface
     world->UpdateSimulationIface();
 
+#ifdef TIMING
+    double tmpT3 = Simulator::Instance()->GetWallTime();
+    std::cout << " World::UpdatSimulationIface() DT(" << tmpT3-tmpT2 << ")" << 
std::endl;
+#endif
+
     if (this->timeout > 0 && this->GetRealTime() > this->timeout)
     {
       this->userQuit = true;
@@ -686,8 +702,8 @@
     }
 
 #ifdef TIMING
-    double tmpT2 = this->GetWallTime();
-    std::cout << " Simulator::PhysicsLoop() DT(" << tmpT2-tmpT1 
+    double tmpT4 = this->GetWallTime();
+    std::cout << " Simulator::PhysicsLoop() DT(" << tmpT4-tmpT1 
       << ")" << std::endl;
 #endif
   }

Modified: code/gazebo/trunk/server/World.cc
===================================================================
--- code/gazebo/trunk/server/World.cc   2009-10-30 15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/World.cc   2009-10-30 16:35:24 UTC (rev 8345)
@@ -64,6 +64,12 @@
   this->graphics = NULL;
   this->openAL = NULL;
   this->factory = NULL;
+
+#ifdef USE_THREADPOOL
+  Param::Begin(&this->parameters);
+  this->threadsP = new ParamT<int>("threads",2,0);
+  Param::End();
+#endif
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -119,6 +125,12 @@
     delete this->factory;
     this->factory = NULL;
   }
+
+#ifdef USE_THREADPOOL
+  delete this->threadsP;
+  delete this->threadPool;
+#endif
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -152,8 +164,11 @@
   this->factory = new Factory();
 
   // Create the graphics iface handler
-  this->graphics = new GraphicsIfaceHandler();
-  this->graphics->Load("default");
+  if (Simulator::Instance()->GetRenderEngineEnabled())
+  {
+    this->graphics = new GraphicsIfaceHandler();
+    this->graphics->Load("default");
+  }
 
   // Load OpenAL audio 
   if (rootNode->GetChild("openal","audio"))
@@ -176,6 +191,11 @@
 
   this->physicsEngine->Load(rootNode);
 
+#ifdef USE_THREADPOOL
+  // start a thread pool with X threads
+  this->threadsP->Load(rootNode);
+  this->threadPool = new boost::threadpool::pool(this->threadsP->GetValue());
+#endif
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -221,7 +241,8 @@
   this->toDeleteModels.clear();
   this->toLoadEntities.clear();
 
-  this->graphics->Init();
+  if (Simulator::Instance()->GetRenderEngineEnabled())
+    this->graphics->Init();
 
   this->factory->Init();
 }
@@ -277,10 +298,19 @@
   {
     if (*miter)
     {
+#ifdef USE_THREADPOOL
+      this->threadPool->schedule(boost::bind(&Model::Update,(*miter)));
+#else
       (*miter)->Update();
+#endif
     }
   }
 
+#ifdef USE_THREADPOOL
+  this->threadPool->wait();
+#endif
+
+
 #ifdef TIMING
   double tmpT2 = Simulator::Instance()->GetWallTime();
   std::cout << " World::Update() ALL Models update DT(" << tmpT2-tmpT1 << ")" 
<< std::endl;
@@ -292,7 +322,6 @@
     this->physicsEngine->UpdatePhysics();
   }
 
-
   this->factory->Update();
 
 #ifdef TIMING
@@ -308,7 +337,7 @@
 {
   std::vector< Model* >::iterator miter;
 
-  if (this->graphics)
+  if (Simulator::Instance()->GetRenderEngineEnabled() && this->graphics)
     delete this->graphics;
 
   // Finalize the models
@@ -401,7 +430,6 @@
 // Add a new entity to the world
 void World::InsertEntity( std::string xmlString)
 {
-  boost::recursive_mutex::scoped_lock 
lock(*Simulator::Instance()->GetMRMutex());
   this->toLoadEntities.push_back( xmlString );
 }
 
@@ -409,31 +437,37 @@
 // Load all the entities that have been queued
 void World::ProcessEntitiesToLoad()
 {
-  boost::recursive_mutex::scoped_lock 
lock(*Simulator::Instance()->GetMRMutex());
-  std::vector< std::string >::iterator iter;
-
-  for (iter = this->toLoadEntities.begin(); 
-       iter != this->toLoadEntities.end(); iter++)
+  if (!this->toLoadEntities.empty())
   {
-    // Create the world file
-    XMLConfig *xmlConfig = new XMLConfig();
+    // maybe try try_lock here instead
+    boost::recursive_mutex::scoped_lock lock(
+        *Simulator::Instance()->GetMRMutex());
 
-    // Load the XML tree from the given string
-    try
+    std::vector< std::string >::iterator iter;
+
+    for (iter = this->toLoadEntities.begin(); 
+        iter != this->toLoadEntities.end(); iter++)
     {
-      xmlConfig->LoadString( *iter );
+      // Create the world file
+      XMLConfig *xmlConfig = new XMLConfig();
+
+      // Load the XML tree from the given string
+      try
+      {
+        xmlConfig->LoadString( *iter );
+      }
+      catch (gazebo::GazeboError e)
+      {
+        gzerr(0) << "The world could not load the XML data [" << e << "]\n";
+        continue;
+      }
+
+      this->LoadEntities( xmlConfig->GetRootNode(), NULL, true); 
+      delete xmlConfig;
     }
-    catch (gazebo::GazeboError e)
-    {
-      gzerr(0) << "The world could not load the XML data [" << e << "]\n";
-      continue;
-    }
 
-    this->LoadEntities( xmlConfig->GetRootNode(), NULL, true); 
-    delete xmlConfig;
+    this->toLoadEntities.clear();
   }
- 
-  this->toLoadEntities.clear(); 
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/World.hh
===================================================================
--- code/gazebo/trunk/server/World.hh   2009-10-30 15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/World.hh   2009-10-30 16:35:24 UTC (rev 8345)
@@ -31,10 +31,16 @@
 #include <vector>
 #include <boost/tuple/tuple.hpp>
 
+#ifdef USE_THREADPOOL
+#include "boost/threadpool.hpp"
+#include "boost/thread/mutex.hpp"
+#endif
+
 #include "SingletonT.hh"
 #include "Vector3.hh"
 #include "Pose3d.hh"
 #include "Entity.hh"
+#include "Global.hh"
 
 namespace gazebo
 {
@@ -234,6 +240,13 @@
 
   private: OpenAL *openAL;
 
+#ifdef USE_THREADPOOL
+  private: ParamT<int>* threadsP;
+  /// List of all the parameters
+  protected: std::vector<Param*> parameters;
+  public: boost::threadpool::pool* threadPool;
+#endif
+
   private: friend class DestroyerT<World>;
   private: friend class SingletonT<World>;
 

Modified: code/gazebo/trunk/server/physics/Body.cc
===================================================================
--- code/gazebo/trunk/server/physics/Body.cc    2009-10-30 15:06:10 UTC (rev 
8344)
+++ code/gazebo/trunk/server/physics/Body.cc    2009-10-30 16:35:24 UTC (rev 
8345)
@@ -432,6 +432,11 @@
 // Update the body
 void Body::Update()
 {
+#ifdef USE_THREADPOOL
+  // If calling Body::Update in threadpool
+  World::Instance()->GetPhysicsEngine()->InitForThread();
+#endif
+
   std::vector< Sensor* >::iterator sensorIter;
   std::map< std::string, Geom* >::iterator geomIter;
   Vector3 vel;
@@ -484,7 +489,11 @@
   for (geomIter=this->geoms.begin();
        geomIter!=this->geoms.end(); geomIter++)
   {
+#ifdef USE_THREADPOOL
+    World::Instance()->threadpool->schedule(boost::bind(&Geom::Update, 
(geomIter->second)));
+#else
     geomIter->second->Update();
+#endif
   }
 
 #ifdef TIMING
@@ -495,7 +504,11 @@
   for (sensorIter=this->sensors.begin();
        sensorIter!=this->sensors.end(); sensorIter++)
   {
+#ifdef USE_THREADPOOL
+    World::Instance()->threadpool->schedule(boost::bind(&Sensor::Update, 
(sensorIter)));
+#else
     (*sensorIter)->Update();
+#endif
   }
 
 #ifdef TIMING

Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreAdaptor.cc   2009-10-30 15:06:10 UTC 
(rev 8344)
+++ code/gazebo/trunk/server/rendering/OgreAdaptor.cc   2009-10-30 16:35:24 UTC 
(rev 8345)
@@ -192,8 +192,8 @@
   {
     this->sceneType= SCENE_EXT;
     //this->sceneMgr = this->root->createSceneManager(Ogre::ST_EXTERIOR_FAR);
-    //this->sceneMgr = this->root->createSceneManager(Ogre::ST_EXTERIOR_CLOSE);
-    this->sceneMgr = this->root->createSceneManager(Ogre::ST_GENERIC);
+    this->sceneMgr = this->root->createSceneManager(Ogre::ST_EXTERIOR_CLOSE);
+    //this->sceneMgr = this->root->createSceneManager(Ogre::ST_GENERIC);
   }
 
   // Load Resources
@@ -233,7 +233,6 @@
   this->sceneMgr->setShadowTextureSize(**(this->shadowTextureSizeP));
   this->sceneMgr->setShadowIndexBufferSize(**(this->shadowIndexSizeP) );
   
-
   // Ambient lighting
   this->sceneMgr->setAmbientLight(ambient);
 
@@ -318,8 +317,8 @@
 
     plugins.push_back(path+"/RenderSystem_GL.so");
     plugins.push_back(path+"/Plugin_ParticleFX.so");
-    //plugins.push_back(path+"/Plugin_BSPSceneManager.so");
-    //plugins.push_back(path+"/Plugin_OctreeSceneManager.so");
+    plugins.push_back(path+"/Plugin_BSPSceneManager.so");
+    plugins.push_back(path+"/Plugin_OctreeSceneManager.so");
 
     for (piter=plugins.begin(); piter!=plugins.end(); piter++)
     {

Modified: code/gazebo/trunk/server/rendering/OgreCamera.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCamera.cc    2009-10-30 15:06:10 UTC 
(rev 8344)
+++ code/gazebo/trunk/server/rendering/OgreCamera.cc    2009-10-30 16:35:24 UTC 
(rev 8345)
@@ -112,7 +112,8 @@
 void OgreCamera::LoadCam( XMLConfigNode *node )
 {
   if (!Simulator::Instance()->GetRenderEngineEnabled())
-    gzthrow("Cameras can not be used when running Gazebo without rendering 
engine");
+    return;
+    //gzthrow("Cameras can not be used when running Gazebo without rendering 
engine");
 
   this->visibilityMask = GZ_ALL_CAMERA; 
 
@@ -185,6 +186,9 @@
 // Initialize the camera
 void OgreCamera::InitCam()
 {
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
   this->camera = OgreCreator::CreateCamera(this->cameraName, 
this->nearClipP->GetValue(), this->farClipP->GetValue(), 
*(this->hfovP->GetValue()), this->renderTarget );
 
   // Create a scene node to control pitch motion
@@ -208,6 +212,9 @@
 // Update the drawing
 void OgreCamera::UpdateCam()
 {
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
   if (this->camera)
   {
     if (World::Instance()->GetWireframe())
@@ -258,6 +265,11 @@
 // Render the camera
 void OgreCamera::Render()
 {
+  // disable rendering if "-r" option is given
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
+  // disable rendering if sensor not set to active
   if (!this->renderingEnabled)
     return;
 
@@ -323,6 +335,9 @@
 /// Set the global pose of the camera
 void OgreCamera::SetWorldPose(const Pose3d &pose)
 {
+  if (!Simulator::Instance()->GetRenderEngineEnabled())
+    return;
+
   this->pose = pose;
   this->sceneNode->setPosition( this->pose.pos.x, this->pose.pos.y, 
this->pose.pos.z);
   this->pitchNode->setOrientation( this->pose.rot.u, this->pose.rot.x, 
this->pose.rot.y, this->pose.rot.z);

Modified: code/gazebo/trunk/server/rendering/OgreCreator.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCreator.cc   2009-10-30 15:06:10 UTC 
(rev 8344)
+++ code/gazebo/trunk/server/rendering/OgreCreator.cc   2009-10-30 16:35:24 UTC 
(rev 8345)
@@ -800,9 +800,9 @@
     (*iter)->Update();
   }
 
+  if (!this->visuals.empty())
   {
     boost::recursive_mutex::scoped_lock 
lock(*Simulator::Instance()->GetMRMutex());
-
     // Update the visuals
     for (viter = this->visuals.begin(); viter != this->visuals.end(); viter++)
     {

Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2009-10-30 
15:06:10 UTC (rev 8344)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2009-10-30 
16:35:24 UTC (rev 8345)
@@ -160,7 +160,9 @@
        !this->saveFramesP->GetValue())
     return;
 
-  this->UpdateCam();
+  // Or skip if user sets camera to inactive
+  if (this->active)
+    this->UpdateCam();
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/sensors/ray/RaySensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/ray/RaySensor.cc   2009-10-30 15:06:10 UTC 
(rev 8344)
+++ code/gazebo/trunk/server/sensors/ray/RaySensor.cc   2009-10-30 16:35:24 UTC 
(rev 8345)
@@ -383,7 +383,7 @@
 // Update the sensor information
 void RaySensor::UpdateChild()
 {
-  //  if (this->active)
+  if (this->active)
   {
     std::vector<RayGeom*>::iterator iter;
     Pose3d poseDelta;


This was sent by the SourceForge.net collaborative development platform, the 
world's largest Open Source development site.

------------------------------------------------------------------------------
Come build with us! The BlackBerry(R) Developer Conference in SF, CA
is the only developer event you need to attend this year. Jumpstart your
developing skills, take BlackBerry mobile applications to market and stay 
ahead of the curve. Join us from November 9 - 12, 2009. Register now!
http://p.sf.net/sfu/devconference
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to