Revision: 8607
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8607&view=rev
Author:   natepak
Date:     2010-04-10 21:07:58 +0000 (Sat, 10 Apr 2010)

Log Message:
-----------
Cleaned up the deletion of models

Modified Paths:
--------------
    code/gazebo/trunk/CMakeLists.txt
    code/gazebo/trunk/benchmarks/CMakeLists.txt
    code/gazebo/trunk/benchmarks/box_pile_benchmark.cc
    code/gazebo/trunk/benchmarks/camera_benchmark.cc
    code/gazebo/trunk/benchmarks/laser_benchmark.cc
    code/gazebo/trunk/libgazebo/CMakeLists.txt
    code/gazebo/trunk/libgazebo/Iface.cc
    code/gazebo/trunk/libgazebo/Server.cc
    code/gazebo/trunk/libgazebo/SimIface.cc
    code/gazebo/trunk/libgazebo/gz.h
    code/gazebo/trunk/server/Entity.cc
    code/gazebo/trunk/server/Entity.hh
    code/gazebo/trunk/server/GazeboConfig.cc
    code/gazebo/trunk/server/Model.cc
    code/gazebo/trunk/server/Model.hh
    code/gazebo/trunk/server/Simulator.cc
    code/gazebo/trunk/server/World.cc
    code/gazebo/trunk/server/main.cc
    code/gazebo/trunk/server/physics/Body.cc
    code/gazebo/trunk/server/physics/Body.hh
    code/gazebo/trunk/server/physics/Geom.cc
    code/gazebo/trunk/server/physics/Geom.hh
    code/gazebo/trunk/server/physics/RayShape.cc
    code/gazebo/trunk/server/physics/Shape.cc
    code/gazebo/trunk/server/physics/ode/ODEBody.cc
    code/gazebo/trunk/server/physics/ode/ODEMultiRayShape.cc
    code/gazebo/trunk/server/physics/ode/ODERayShape.cc
    code/gazebo/trunk/server/rendering/OgreAdaptor.cc
    code/gazebo/trunk/server/rendering/RTShaderSystem.cc
    code/gazebo/trunk/server/rendering/RTShaderSystem.hh
    code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc

Modified: code/gazebo/trunk/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/CMakeLists.txt    2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/CMakeLists.txt    2010-04-10 21:07:58 UTC (rev 8607)
@@ -16,6 +16,8 @@
 
 message (STATUS "${PROJECT_NAME} version ${GAZEBO_VERSION}")
 
+set (CMAKE_INCLUDE_DIRECTORIES_PROJECT_BEFORE ON)
+
 set (BUILD_GAZEBO ON CACHE INTERNAL "Build Gazebo" FORCE)
 
 set (gazeboserver_sources_desc "List of server sources" 
@@ -104,6 +106,7 @@
   message (STATUS "Cmake C Flags:${CMAKE_C_FLAGS}")
   
   if (BUILD_GAZEBO)
+    include (libgazebo)
 
     if (use_internal_assimp)
       add_subdirectory(3rd_party)
@@ -112,6 +115,7 @@
     add_subdirectory(libgazebo)
     add_subdirectory(server)
     add_subdirectory(worlds)
+    add_subdirectory(tools)
     add_subdirectory(Media)
     
     if (INCLUDE_PLAYER)

Modified: code/gazebo/trunk/benchmarks/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/benchmarks/CMakeLists.txt 2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/benchmarks/CMakeLists.txt 2010-04-10 21:07:58 UTC (rev 
8607)
@@ -1,4 +1,4 @@
-project(factory)
+project(benchmarks)
 
 cmake_minimum_required( VERSION 2.4 FATAL_ERROR )
 
@@ -21,7 +21,11 @@
 
 include_directories(.)
 
-set (sources laser_benchmark.cc box_grid_benchmark.cc box_pile_benchmark.cc 
joint_chain_benchmark.cc)
+set (sources laser_benchmark.cc 
+             box_grid_benchmark.cc 
+             box_pile_benchmark.cc 
+             joint_chain_benchmark.cc
+             camera_benchmark.cc)
 
 set_source_files_properties(${sources} PROPERTIES COMPILE_FLAGS "-ggdb -g2 
-Wall")
 
@@ -29,8 +33,10 @@
 add_executable(box_pile_benchmark box_pile_benchmark.cc)
 add_executable(box_grid_benchmark box_grid_benchmark.cc)
 add_executable(joint_chain_benchmark joint_chain_benchmark.cc)
+add_executable(camera_benchmark camera_benchmark.cc)
 
 target_link_libraries(laser_benchmark ${LINK_LIBS} )
 target_link_libraries(box_grid_benchmark ${LINK_LIBS} )
 target_link_libraries(box_pile_benchmark ${LINK_LIBS} )
 target_link_libraries(joint_chain_benchmark ${LINK_LIBS} )
+target_link_libraries(camera_benchmark ${LINK_LIBS} )

Modified: code/gazebo/trunk/benchmarks/box_pile_benchmark.cc
===================================================================
--- code/gazebo/trunk/benchmarks/box_pile_benchmark.cc  2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/benchmarks/box_pile_benchmark.cc  2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -9,7 +9,7 @@
 gazebo::FactoryIface *factoryIface = NULL;
 int laser_count = 0;
 
-std::string test_name="Boxes Benchmark";
+std::string test_name="Box Pile Benchmark";
 std::string xlabel = "Box Count";
 std::string ylabel = "Simtime / Realtime";
 std::string data_filename = "/tmp/" + test_name + ".data";
@@ -106,7 +106,7 @@
     double simTime = 0;
     double realTime = 0;
 
-    for (unsigned int i=0; i < 50; i++)
+    for (unsigned int i=0; i < 30; i++)
     {
       simTime += simIface->data->simTime;
       realTime += simIface->data->realTime;

Modified: code/gazebo/trunk/benchmarks/camera_benchmark.cc
===================================================================
--- code/gazebo/trunk/benchmarks/camera_benchmark.cc    2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/benchmarks/camera_benchmark.cc    2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -31,13 +31,13 @@
     std::cerr << "Error\n";
 }
 
-void spawn_box(double x, double y, double z=10)
+void spawn_camera(double x, double y, double z=1)
 {
   std::ostringstream model;
 
   model << "<model:physical name='camera" << camera_count++ << "'>";
   model << "  <xyz>" << x << " " << y << " " << z << "</xyz>";
-  model << "  <rpy>30 40 0</rpy>";
+  model << "  <static>true</static>";
   model << "  <body:box name='body'>";
 
   model << "    <geom:box name='geom'>";
@@ -50,9 +50,13 @@
   model << "      </visual>";
   model << "    </geom:box>";
 
-  model << "   <sensor:camera name='camera'>";
+  model << "   <sensor:camera name='camera" << camera_count << "'>";
+  model << "     <alwaysActive>true</alwaysActive>";
   model << "     <imageSize>640 480</imageSize>";
-  model << "     
+  model << "     <hfov>60</hfov>";
+  model << "     <nearClip>0.1</nearClip>";
+  model << "     <farClip>50</farClip>";
+  model << "   </sensor:camera>";
 
   model << "  </body:box>";
   model << "</model:physical>";
@@ -103,24 +107,28 @@
 
   FILE *out = fopen(data_filename.c_str(), "w");
 
-  for (unsigned int j=0; j < 100; j++)
+  for (int y=-10; y < 10; y++)
   {
-    spawn_box(j+1, 0);
+    for ( int x=-10; x < 10; x++)
+    {
+      spawn_camera(x, y);
 
-    double simTime = 0;
-    double realTime = 0;
+      double simTime = 0;
+      double realTime = 0;
 
-    for (unsigned int i=0; i < 50; i++)
-    {
-      simTime += simIface->data->simTime;
-      realTime += simIface->data->realTime;
+      for (unsigned int i=0; i < 50; i++)
+      {
+        simTime += simIface->data->simTime;
+        realTime += simIface->data->realTime;
 
-      /// Wait .1 seconds 
-      usleep(100000);
+        /// Wait .1 seconds 
+        usleep(100000);
+      }
+
+      double percent = simTime / realTime;
+      fprintf(out,"%f\n",percent);
+
     }
-
-    double percent = simTime / realTime;
-    fprintf(out,"%f\n",percent);
   }
   fclose(out);
 

Modified: code/gazebo/trunk/benchmarks/laser_benchmark.cc
===================================================================
--- code/gazebo/trunk/benchmarks/laser_benchmark.cc     2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/benchmarks/laser_benchmark.cc     2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -114,9 +114,9 @@
   if (!out)
     std::cerr << "Unable to open log file";
 
-  for (int y = -5; y < 5; y++)
+  for (int y = -10; y < 10; y++)
   {
-    for (int x = -5; x < 5; x++)
+    for (int x = -10; x < 10; x++)
     {
       spawn_laser(x,y);
 

Modified: code/gazebo/trunk/libgazebo/CMakeLists.txt
===================================================================
--- code/gazebo/trunk/libgazebo/CMakeLists.txt  2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/libgazebo/CMakeLists.txt  2010-04-10 21:07:58 UTC (rev 
8607)
@@ -1,31 +1,30 @@
-SET (sources Server.cc 
+set (sources Server.cc 
              Client.cc 
              Iface.cc 
              IfaceFactory.cc 
+             FactoryIface.cc 
              SimIface.cc 
              Graphics3dIface.cc
 )
 
-SET (headers gz.h IfaceFactory.hh)
+set (headers gz.h IfaceFactory.hh)
 
-INCLUDE_DIRECTORIES(
-  ${boost_include_dirs}
-)
+include_directories(${boost_include_dirs})
 
-IF (${ENABLE_BINDINGS})
-  ADD_SUBDIRECTORY(bindings)
-ENDIF (${ENABLE_BINDINGS})
+if (${ENABLE_BINDINGS})
+  add_subdirectory(bindings)
+endif (${ENABLE_BINDINGS})
 
-LINK_DIRECTORIES(${boost_library_dirs})
+link_directories(${boost_library_dirs})
 
-ADD_LIBRARY(gazeboshm SHARED ${sources})
-SET_TARGET_PROPERTIES(gazeboshm PROPERTIES OUTPUT_NAME "gazebo" VERSION 
${GAZEBO_VERSION})
+add_library(gazeboshm SHARED ${sources})
+set_target_properties(gazeboshm PROPERTIES OUTPUT_NAME "gazebo" VERSION 
${GAZEBO_VERSION})
 
-TARGET_LINK_LIBRARIES( gazeboshm ${boost_libraries})
+target_link_libraries( gazeboshm ${boost_libraries})
 
-INSTALL (TARGETS gazeboshm DESTINATION ${CMAKE_INSTALL_PREFIX}/lib)
-INSTALL (FILES ${headers} DESTINATION ${CMAKE_INSTALL_PREFIX}/include/gazebo)
+install (TARGETS gazeboshm DESTINATION ${CMAKE_INSTALL_PREFIX}/lib)
+install (FILES ${headers} DESTINATION ${CMAKE_INSTALL_PREFIX}/include/gazebo)
 
-CONFIGURE_FILE(${CMAKE_SOURCE_DIR}/cmake/libgazebo_pkgconfig.cmake 
${CMAKE_CURRENT_BINARY_DIR}/libgazebo.pc @ONLY)
+configure_file(${CMAKE_SOURCE_DIR}/cmake/libgazebo_pkgconfig.cmake 
${CMAKE_CURRENT_BINARY_DIR}/libgazebo.pc @ONLY)
 
-INSTALL(FILES ${CMAKE_CURRENT_BINARY_DIR}/libgazebo.pc DESTINATION 
${CMAKE_INSTALL_PREFIX}/lib/pkgconfig COMPONENT pkgconfig)
+install(FILES ${CMAKE_CURRENT_BINARY_DIR}/libgazebo.pc DESTINATION 
${CMAKE_INSTALL_PREFIX}/lib/pkgconfig COMPONENT pkgconfig)

Modified: code/gazebo/trunk/libgazebo/Iface.cc
===================================================================
--- code/gazebo/trunk/libgazebo/Iface.cc        2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/libgazebo/Iface.cc        2010-04-10 21:07:58 UTC (rev 
8607)
@@ -240,7 +240,7 @@
   this->mmapFd = 0;
 
   // Delete the file
-  std::cout <<  "deleting "<< this->filename << "\n";
+  //std::cout <<  "deleting "<< this->filename << "\n";
 
   if (unlink(this->filename.c_str()) < 0)
   {
@@ -310,7 +310,7 @@
     throw(stream.str());
   }
 
-  std::ios_base::fmtflags origFlags = std::cout.flags();
+  /*std::ios_base::fmtflags origFlags = std::cout.flags();
 
   // Print the name, version info
   std::cout << "opening " << this->filename.c_str() << " "
@@ -320,6 +320,7 @@
   << ((GazeboData*) this->mMap)->size << "\n";
 
   std::cout.setf(origFlags);
+  */
 
   this->Lock(1);
   ((GazeboData*)this->mMap)->openCount++;

Modified: code/gazebo/trunk/libgazebo/Server.cc
===================================================================
--- code/gazebo/trunk/libgazebo/Server.cc       2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/libgazebo/Server.cc       2010-04-10 21:07:58 UTC (rev 
8607)
@@ -174,7 +174,7 @@
 {
   char cmd[1024];
 
-  std::cout << "deleting " << this->filename << "\n";
+  //std::cout << "deleting " << this->filename << "\n";
 
   // unlink the pid file
   std::string pidfn = this->filename + "/gazebo.pid";

Modified: code/gazebo/trunk/libgazebo/SimIface.cc
===================================================================
--- code/gazebo/trunk/libgazebo/SimIface.cc     2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/libgazebo/SimIface.cc     2010-04-10 21:07:58 UTC (rev 
8607)
@@ -169,14 +169,14 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the 3d pose of a model
-bool SimulationIface::GetPose3d(const char *modelName, Pose &pose)
+bool SimulationIface::GetPose3d(const std::string &modelName, Pose &pose)
 {
   this->Lock(1);
   this->data->responseCount = 0;
   SimulationRequestData *request = 
&(this->data->requests[this->data->requestCount++]);
   request->type = SimulationRequestData::GET_POSE3D;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
   this->Unlock();
 
@@ -192,14 +192,14 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the 2d pose of a model
-bool SimulationIface::GetPose2d(const char *modelName, Pose &pose)
+bool SimulationIface::GetPose2d(const std::string &modelName, Pose &pose)
 {
   this->Lock(1);
   this->data->responseCount = 0;
   SimulationRequestData *request = 
&(this->data->requests[this->data->requestCount++]);
   request->type = SimulationRequestData::GET_POSE2D;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -216,7 +216,8 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Set the 3d pose of a model
-void SimulationIface::SetPose3d(const char *modelName, const Pose &modelPose)
+void SimulationIface::SetPose3d(const std::string &modelName, 
+                                const Pose &modelPose)
 {
   this->Lock(1);
   this->data->responseCount = 0;
@@ -226,7 +227,7 @@
   request->modelPose = modelPose;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -234,7 +235,8 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Set the 2d pose of a model
-void SimulationIface::SetPose2d(const char *modelName, float x, float y, float 
yaw)
+void SimulationIface::SetPose2d(const std::string &modelName, 
+                                float x, float y, float yaw)
 {
   this->Lock(1);
   this->data->responseCount = 0;
@@ -243,7 +245,7 @@
   request->type = gazebo::SimulationRequestData::SET_POSE2D;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   request->modelPose.pos.x = x;
@@ -255,7 +257,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Set the complete state of a model
-void SimulationIface::SetState(const char *modelName, Pose &modelPose, 
+void SimulationIface::SetState(const std::string &modelName, Pose &modelPose, 
     Vec3 &linearVel, Vec3 &angularVel, Vec3 &linearAccel, 
     Vec3 &angularAccel )
 {
@@ -265,7 +267,7 @@
 
   request->type = gazebo::SimulationRequestData::SET_STATE;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   if (isnan(linearVel.x)) linearVel.x = 0.0;
@@ -293,7 +295,7 @@
 }
 
//////////////////////////////////////////////////////////////////////////////////
 /// Get then children of a model
-void SimulationIface::GetChildInterfaces(const char *modelName)
+void SimulationIface::GetChildInterfaces(const std::string &modelName)
 {
 
   this->Lock(1);
@@ -302,7 +304,7 @@
   request->type = gazebo::SimulationRequestData::GET_MODEL_INTERFACES;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -310,7 +312,7 @@
 }
 
///////////////////////////////////////////////////////////////////////////////////
 /// \brief Get the Type of a model e.g. "laser" "model" "fiducial"
-void SimulationIface::GetInterfaceType(const char *modelName)
+void SimulationIface::GetInterfaceType(const std::string &modelName)
 {
   this->Lock(1);
   SimulationRequestData *request = 
&(this->data->requests[this->data->requestCount++]);
@@ -318,14 +320,14 @@
   request->type = gazebo::SimulationRequestData::GET_INTERFACE_TYPE;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
 }
 ///////////////////////////////////////////////////////////////////////////////
 /// Get the complete state of a model
-bool SimulationIface::GetState(const char *modelName, Pose &modelPose, 
+bool SimulationIface::GetState(const std::string &modelName, Pose &modelPose, 
               Vec3 &linearVel, Vec3 &angularVel, 
               Vec3 &linearAccel, Vec3 &angularAccel )
 {
@@ -335,7 +337,7 @@
 
   request->type = gazebo::SimulationRequestData::GET_STATE;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -385,7 +387,8 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the type of this model
-bool SimulationIface::GetModelType(const char *modelName, std::string &type)
+bool SimulationIface::GetModelType(const std::string &modelName, 
+                                   std::string &type)
 {
   this->Lock(1);
   this->data->responseCount = 0;
@@ -395,7 +398,7 @@
   request = &(this->data->requests[this->data->requestCount++]);
   request->type = SimulationRequestData::GET_MODEL_TYPE;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -435,7 +438,8 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the number of children a model has
-bool SimulationIface::GetNumChildren(const char *modelName, unsigned int &num)
+bool SimulationIface::GetNumChildren(const std::string &modelName, 
+                                     unsigned int &num)
 {
   this->Lock(1);
   this->data->responseCount = 0;
@@ -445,7 +449,7 @@
   request = &(this->data->requests[this->data->requestCount++]);
   request->type = SimulationRequestData::GET_NUM_CHILDREN;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();
@@ -485,7 +489,8 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the name of a child
-bool SimulationIface::GetChildName(const char *modelName, unsigned int child,
+bool SimulationIface::GetChildName(const std::string &modelName, 
+                                   unsigned int child,
                                    std::string &childName)
 {
   this->Lock(1);
@@ -497,7 +502,7 @@
   request = &(this->data->requests[this->data->requestCount++]);
   request->type = SimulationRequestData::GET_CHILD_NAME;
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
   request->uintValue = child;
   this->Unlock();
@@ -514,7 +519,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the extents of a model
-bool SimulationIface::GetModelExtent(const char *modelName, Vec3 &ext)
+bool SimulationIface::GetModelExtent(const std::string &modelName, Vec3 &ext)
 {
   this->Lock(1);
   this->data->responseCount = 0;
@@ -522,7 +527,7 @@
   request->type = SimulationRequestData::GET_MODEL_EXTENT;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
   this->Unlock();
 
@@ -536,7 +541,8 @@
 }
 
////////////////////////////////////////////////////////////////////////////////
 /// Get the Fiducial ID of this model 
-bool SimulationIface::GetModelFiducialID(const char *modelName, unsigned int 
&id)
+bool SimulationIface::GetModelFiducialID(const std::string &modelName, 
+                                         unsigned int &id)
 {
   this->Lock(1);
 
@@ -547,7 +553,7 @@
   request->type = SimulationRequestData::GET_MODEL_FIDUCIAL_ID;
 
   memset(request->modelName, 0, 512);
-  strncpy(request->modelName, modelName, 512);
+  strncpy(request->modelName, modelName.c_str(), 512);
   request->modelName[511] = '\0';
 
   this->Unlock();

Modified: code/gazebo/trunk/libgazebo/gz.h
===================================================================
--- code/gazebo/trunk/libgazebo/gz.h    2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/libgazebo/gz.h    2010-04-10 21:07:58 UTC (rev 8607)
@@ -544,54 +544,56 @@
   public: void Run(double simTime);
 
   /// \brief Get the 3d pose of a model
-  public: bool GetPose3d(const char *modelName, Pose &pose);
+  public: bool GetPose3d(const std::string &modelName, Pose &pose);
 
   /// \brief Get the 2d pose of a model
-  public: bool GetPose2d(const char *modelName, Pose &pose);
+  public: bool GetPose2d(const std::string &modelName, Pose &pose);
 
   /// \brief Set the 3d pose of a model
-  public: void SetPose3d(const char *modelName, const Pose &modelPose);
+  public: void SetPose3d(const std::string &modelName, const Pose &modelPose);
 
   /// \brief Set the 2d pose of a model
-  public: void SetPose2d(const char *modelName, float x, float y, float yaw);
+  public: void SetPose2d(const std::string &modelName, float x, float y, 
+                         float yaw);
 
   /// \brief Set the complete state of a model
-  public: void SetState(const char *modelName, Pose &modelPose, 
+  public: void SetState(const std::string &modelName, Pose &modelPose, 
               Vec3 &linearVel, Vec3 &angularVel, 
               Vec3 &linearAccel, Vec3 &angularAccel );
 
   /// \brief Get the complete state of a model
-  public: bool GetState(const char *modelName, Pose &modelPose, 
+  public: bool GetState(const std::string &modelName, Pose &modelPose, 
               Vec3 &linearVel, Vec3 &angularVel, 
               Vec3 &linearAccel, Vec3 &angularAccel );
 
   /// \brief Get the child interfaces of a model
-  public: void GetChildInterfaces(const char *modelName);
+  public: void GetChildInterfaces(const std::string &modelName);
 
   /// \brief Get the Type of an interface e.g. "laser" "model" "fiducial"
-  public: void GetInterfaceType(const char *modelName);
+  public: void GetInterfaceType(const std::string &modelName);
 
   /// \brief Get the type of this model
-  public: bool GetModelType(const char *modelName, std::string &type);
+  public: bool GetModelType(const std::string &modelName, std::string &type);
 
   /// \brief Get the number of models 
   public: bool GetNumModels(unsigned int &num);
 
   /// \brief Get the number of children a model has
-  public: bool GetNumChildren(const char *modelName, unsigned int &num);
+  public: bool GetNumChildren(const std::string &modelName, unsigned int &num);
 
   /// \brief Get the name of a model
-  public: bool GetModelName(unsigned int child, std::string &name);
+  public: bool GetModelName(unsigned int model, std::string &name);
 
   /// \brief Get the name of a child
-  public: bool GetChildName(const char *modelName, unsigned int child, 
+  public: bool GetChildName(const std::string &modelName, unsigned int child, 
                             std::string &name);
 
   /// \brief Get the extents of a model
-  public: bool GetModelExtent(const char *modelName, Vec3 &ext);
+  public: bool GetModelExtent(const std::string &modelName, Vec3 &ext);
 
   /// \brief Get the model Fiducial ID (if one global ID was set)
-  public: bool GetModelFiducialID(const char *modelName, unsigned int &id);
+  public: bool GetModelFiducialID(const std::string &modelName, 
+                                  unsigned int &id);
 
   public: void GoAckWait();
   public: void GoAckPost();
@@ -1209,6 +1211,9 @@
             this->data = (FactoryData*)this->mMap; 
           }
 
+  /// \brief Delete a model by name
+  public: bool DeleteModel(const std::string &model_name);
+
   /// Pointer to the factory data
   public: FactoryData *data;
 };

Modified: code/gazebo/trunk/server/Entity.cc
===================================================================
--- code/gazebo/trunk/server/Entity.cc  2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/Entity.cc  2010-04-10 21:07:58 UTC (rev 8607)
@@ -80,10 +80,33 @@
 // Destructor
 Entity::~Entity()
 {
+  if (this->parent)
+    this->parent->RemoveChild(this);
+
   delete this->staticP;
 
+  std::vector<Entity*>::iterator iter;
+
   World::Instance()->GetPhysicsEngine()->RemoveEntity(this);
 
+  for (iter = this->children.begin(); iter != this->children.end(); iter++)
+  {
+    if (*iter)
+    {
+      (*iter)->SetParent(NULL);
+
+      World::Instance()->GetPhysicsEngine()->RemoveEntity(*iter);
+
+      Model *m = dynamic_cast<Model*>(*iter);
+      if (m)
+      {
+        m->Detach();
+      }
+
+      //delete *iter;
+    }
+  }
+
   if (Simulator::Instance()->GetRenderEngineEnabled())
   {
     if (this->visualNode)
@@ -92,6 +115,7 @@
     }
   }
   this->visualNode = NULL;
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -127,6 +151,21 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Remove a child from this entity
+void Entity::RemoveChild(Entity *child)
+{
+  std::vector<Entity*>::iterator iter;
+  for (iter = this->children.begin(); iter != this->children.end(); iter++)
+  {
+    if ((*iter)->GetName() == child->GetName())
+    {
+      this->children.erase(iter);
+      break;
+    }
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Get all children
 std::vector< Entity* > &Entity::GetChildren() 
 {

Modified: code/gazebo/trunk/server/Entity.hh
===================================================================
--- code/gazebo/trunk/server/Entity.hh  2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/Entity.hh  2010-04-10 21:07:58 UTC (rev 8607)
@@ -74,6 +74,10 @@
     /// \brief Add a child to this entity
     /// \param child Child entity
     public: void AddChild(Entity *child);
+
+    /// \brief Remove a child from this entity
+    /// \param child Child to remove
+    public: void RemoveChild(Entity *child);
   
     /// \brief Get all children
     /// \return Vector of children entities

Modified: code/gazebo/trunk/server/GazeboConfig.cc
===================================================================
--- code/gazebo/trunk/server/GazeboConfig.cc    2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/GazeboConfig.cc    2010-04-10 21:07:58 UTC (rev 
8607)
@@ -100,7 +100,7 @@
       node = rc.GetRootNode()->GetChild("gazeboPath");
       while (node)
       {
-        gzmsg(2) << "Gazebo Path[" << node->GetValue() << "]\n";
+        gzmsg(5) << "Gazebo Path[" << node->GetValue() << "]\n";
         this->gazeboPaths.push_back(node->GetValue());
         node = node->GetNext("gazeboPath");
       }
@@ -112,7 +112,7 @@
       node = rc.GetRootNode()->GetChild("ogrePath");
       while (node)
       {
-        gzmsg(2) << "Ogre Path[" << node->GetValue() << "]\n";
+        gzmsg(5) << "Ogre Path[" << node->GetValue() << "]\n";
         this->ogrePaths.push_back( node->GetValue() );
         node = node->GetNext("ogrePath");
       }

Modified: code/gazebo/trunk/server/Model.cc
===================================================================
--- code/gazebo/trunk/server/Model.cc   2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/Model.cc   2010-04-10 21:07:58 UTC (rev 8607)
@@ -113,13 +113,10 @@
     this->graphicsHandler = NULL;
   }
 
-  for (biter=this->bodies.begin(); biter != this->bodies.end(); biter++)
+  for (biter = this->bodies.begin(); biter != this->bodies.end(); biter++)
   {
     if (biter->second)
-    {
-      delete biter->second;
-      biter->second = NULL;
-    }
+      delete (biter->second);
   }
   this->bodies.clear();
 
@@ -547,6 +544,17 @@
     this->graphicsHandler = NULL;
   }
 
+  std::vector< Entity* >::iterator iter;
+  for (iter = this->children.begin(); iter != this->children.end(); iter++)
+  {
+    if (*iter)
+    {
+      Model *m = dynamic_cast<Model*>(*iter);
+      if (m)
+        m->Fini();
+    }
+  }
+
   this->FiniChild();
 }
 
@@ -939,7 +947,17 @@
   return NULL;
 }
 
+
 
////////////////////////////////////////////////////////////////////////////////
+// Detach from parent model
+void Model::Detach()
+{
+  if (this->joint)
+    delete this->joint;
+  this->joint = NULL;
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Attach this model to its parent
 void Model::Attach(XMLConfigNode *node)
 {

Modified: code/gazebo/trunk/server/Model.hh
===================================================================
--- code/gazebo/trunk/server/Model.hh   2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/Model.hh   2010-04-10 21:07:58 UTC (rev 8607)
@@ -174,7 +174,10 @@
 
     /// \brief Get a geom by name
     public: Geom *GetGeom(const std::string &name) const;
-  
+
+    /// \brief Detach from parent model
+    public: void Detach();
+
     /// \brief Attach this model to its parent
     public: void Attach(XMLConfigNode *node);
   

Modified: code/gazebo/trunk/server/Simulator.cc
===================================================================
--- code/gazebo/trunk/server/Simulator.cc       2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/Simulator.cc       2010-04-10 21:07:58 UTC (rev 
8607)
@@ -108,12 +108,6 @@
     this->model_delete_mutex = NULL;
   }
 
-  if (this->gui)
-  {
-    delete this->gui;
-    this->gui = NULL;
-  }
-
   if (this->physicsThread)
   {
     delete this->physicsThread;
@@ -129,7 +123,15 @@
   if (!this->loaded)
     return;
 
+  if (this->gui)
+  {
+    delete this->gui;
+    this->gui = NULL;
+  }
+
+
   gazebo::World::Instance()->Close();
+
   if (this->renderEngineEnabled)
     gazebo::OgreAdaptor::Instance()->Close();
 }

Modified: code/gazebo/trunk/server/World.cc
===================================================================
--- code/gazebo/trunk/server/World.cc   2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/World.cc   2010-04-10 21:07:58 UTC (rev 8607)
@@ -96,6 +96,7 @@
   {
     if (*miter)
     {
+      (*miter)->Fini();
       delete (*miter);
       (*miter) = NULL;
     }
@@ -530,10 +531,7 @@
     for (miter=this->toDeleteModels.begin();
         miter!=this->toDeleteModels.end(); miter++)
     {
-      //std::cerr << "ProcessEngitiesToDelete " <<  (*miter)->GetName() << 
std::endl;
       (*miter)->Fini();
-      this->models.erase(
-          std::remove(this->models.begin(), this->models.end(), *miter) );
       delete (*miter);
     }
 
@@ -551,10 +549,10 @@
   // Update all the models
   for (miter=this->models.begin(); miter!=this->models.end(); miter++)
   {
-    if ((*miter)->GetName() == name)
+    if ((*miter)->GetCompleteScopedName() == name)
     {
-      (*miter)->Fini();
       this->toDeleteModels.push_back(*miter);
+      this->models.erase( std::remove(this->models.begin(), 
this->models.end(), *miter));
     }
   }
 }
@@ -574,9 +572,6 @@
   // Set the model's pose (relative to parent)
   //this->SetModelPose(model, model->GetInitPose());
 
-  // Add the model to our list
-  this->models.push_back(model);
-
   // If calling LoadEntity()->LoadModel()from Simulator::Load()->World::Load()
   // GetWorldInitialized() is false, in this case, model->Init() is
   // called later directly from main.cc through Simulator::Init()
@@ -588,6 +583,9 @@
 
   if (parent != NULL)
     model->Attach(node->GetChild("attach"));
+  else
+    // Add the model to our list
+    this->models.push_back(model);
 
   return model;
 }
@@ -645,7 +643,7 @@
 
   for (iter = models.begin(); iter != models.end(); iter++)
   {
-    if ((*iter)->GetName() == modelName)
+    if ((*iter)->GetCompleteScopedName() == modelName)
       return (*iter);
   }
 
@@ -962,7 +960,7 @@
             Model *model = this->models[index];
             memset(response->modelName, 0, 512);
 
-            strncpy(response->modelName, model->GetName().c_str(), 512);
+            strncpy(response->modelName, 
model->GetCompleteScopedName().c_str(), 512);
             response->strValue[511] = '\0';
 
             response++;
@@ -990,7 +988,7 @@
             if (ent)
             {
               memset(response->strValue, 0, 512);
-              strncpy(response->modelName, ent->GetName().c_str(), 512);
+              strncpy(response->modelName, 
ent->GetCompleteScopedName().c_str(), 512);
               response->strValue[511] = '\0';
 
               response++;
@@ -1389,21 +1387,7 @@
 
   this->simIface->Unlock();
 
-  // lock so models is not used
-  boost::recursive_mutex::scoped_lock 
lock(*Simulator::Instance()->GetMDMutex());
-
-  // Remove and delete all models that are marked for deletion
-  std::vector< Model* >::iterator miter;
-  for (miter=this->toDeleteModels.begin();
-      miter!=this->toDeleteModels.end(); miter++)
-  {
-//    (*miter)->Fini();
-    this->models.erase(
-        std::remove(this->models.begin(), this->models.end(), *miter) );
-    delete *miter;
-  }
-
-  this->toDeleteModels.clear();
+  //this->ProcessEntitiesToDelete();
 }
 
 void World::GetInterfaceNames(Entity* en, std::vector<std::string>& list)

Modified: code/gazebo/trunk/server/main.cc
===================================================================
--- code/gazebo/trunk/server/main.cc    2010-04-02 15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/main.cc    2010-04-10 21:07:58 UTC (rev 8607)
@@ -327,6 +327,6 @@
     return -1;
   }
 
-  printf("Done.\n");
+  printf("Gazebo done.\n");
   return 0;
 }

Modified: code/gazebo/trunk/server/physics/Body.cc
===================================================================
--- code/gazebo/trunk/server/physics/Body.cc    2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/physics/Body.cc    2010-04-10 21:07:58 UTC (rev 
8607)
@@ -56,6 +56,7 @@
     : Entity(parent)
 {
   this->comEntity = new Entity(this);
+  this->comEntity->SetName("COM Entity");
 
   this->physicsEngine = World::Instance()->GetPhysicsEngine();
 
@@ -101,26 +102,35 @@
 Body::~Body()
 {
   std::map< std::string, Geom* >::iterator giter;
+  std::vector<Entity*>::iterator iter;
   std::vector< Sensor* >::iterator siter;
 
+  if (this->cgVisual)
+  {
+    OgreCreator::Instance()->DeleteVisual( this->cgVisual );
+    this->cgVisual = NULL;
+  }
+
+  /*if (this->comEntity)
+    delete this->comEntity;
+  this->comEntity = NULL;
+  */
+
+  /*for (iter = this->children.begin(); iter != this->children.end(); iter++)
+    if (*iter)
+    {
+      std::cout << "Deleting[" << *iter << "]\n";
+      delete *iter;
+    }
+    */
   for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
-  {
     if (giter->second)
       delete giter->second;
-    giter->second = NULL;
-  }
   this->geoms.clear();
 
   for (siter = this->sensors.begin(); siter != this->sensors.end(); siter++)
     SensorManager::Instance()->RemoveSensor(*siter);
 
-
-  if (this->cgVisual)
-  {
-    OgreCreator::Instance()->DeleteVisual( this->cgVisual );
-    this->cgVisual = NULL;
-  }
-
   delete this->xyzP;
   delete this->rpyP;
   delete this->dampingFactorP;
@@ -139,9 +149,6 @@
   delete this->ixzP;
   delete this->iyzP;
 
-  if (this->comEntity)
-    delete this->comEntity;
-  this->comEntity = NULL;
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -262,8 +269,13 @@
 void Body::Fini()
 {
   std::vector< Sensor* >::iterator siter;
+  std::map< std::string, Geom* >::iterator giter;
+
   for (siter = this->sensors.begin(); siter != this->sensors.end(); siter++)
     (*siter)->Fini();
+
+  for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
+    giter->second->Fini();
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -399,7 +411,7 @@
     }
   }
 
-
+  this->enabled = true;
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -418,7 +430,13 @@
   // Apply our angular accel
   this->SetTorque(this->angularAccel);
 
+  if (this->GetEnabled() != this->enabled)
   {
+    this->enabled = this->GetEnabled();
+    this->enabledSignal(this->enabled);
+  }
+
+  {
     //DiagnosticTimer timer("Body[" + this->GetName() +"] Update Geoms");
 
     for (geomIter=this->geoms.begin();

Modified: code/gazebo/trunk/server/physics/Body.hh
===================================================================
--- code/gazebo/trunk/server/physics/Body.hh    2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/physics/Body.hh    2010-04-10 21:07:58 UTC (rev 
8607)
@@ -211,6 +211,15 @@
 
     public: Entity *GetCoMEntity() { return this->comEntity; }
 
+    /// \brief Connect a boost::slot the the add entity signal
+    public: template<typename T>
+            boost::signals::connection ConnectEnabledSignal( T subscriber )
+            { return enabledSignal.connect(subscriber); }
+
+    public: template<typename T>
+            void DisconnectEnabledSignal( T subscriber )
+            { enabledSignal.disconnect(subscriber); }
+
     /// List of geometries attached to this body
     protected: std::map< std::string, Geom* > geoms;
 
@@ -262,12 +271,17 @@
     protected: ParamT<double> *iyzP;
     protected: Mass customMass;
 
+
     /// \brief if this is the canonical :ody of a model, point back
     protected: Model* canonicalModel;
 
     /// \brief this is how you set canonical body from the model
     public: void SetCanonicalModel(Model* model);
 
+    private: boost::signal<void (bool)> enabledSignal;
+
+    /// This flag is used to trigger the enabledSignal
+    private: bool enabled;
   };
 
   /// \}

Modified: code/gazebo/trunk/server/physics/Geom.cc
===================================================================
--- code/gazebo/trunk/server/physics/Geom.cc    2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/physics/Geom.cc    2010-04-10 21:07:58 UTC (rev 
8607)
@@ -80,17 +80,16 @@
   World::Instance()->ConnectShowPhysicsSignal( boost::bind(&Geom::ShowPhysics, 
this, _1) );
   World::Instance()->ConnectShowJointsSignal( boost::bind(&Geom::ShowJoints, 
this, _1) );
   World::Instance()->ConnectShowBoundingBoxesSignal( 
boost::bind(&Geom::ShowBoundingBox, this, _1) );
+
+  this->body->ConnectEnabledSignal( boost::bind(&Geom::EnabledCB, this, _1) );
 }
 
 
////////////////////////////////////////////////////////////////////////////////
 // Destructor
 Geom::~Geom()
 {
-  World::Instance()->DisconnectShowPhysicsSignal( 
boost::bind(&Geom::ShowPhysics, this, _1) );
-  World::Instance()->DisconnectShowJointsSignal( 
boost::bind(&Geom::ShowJoints, this, _1) );
-  World::Instance()->DisconnectShowBoundingBoxesSignal( 
boost::bind(&Geom::ShowBoundingBox, this, _1) );
-
-  for (std::vector<OgreVisual*>::iterator iter = this->visuals.begin(); iter 
!= this->visuals.end(); iter++)
+  for (std::vector<OgreVisual*>::iterator iter = this->visuals.begin(); 
+       iter != this->visuals.end(); iter++)
   {
     if (*iter)
     {
@@ -111,10 +110,29 @@
   delete this->laserFiducialIdP;
   delete this->laserRetroP;
 
-  delete this->shape;
+  if (this->shape)
+    delete this->shape;
+  this->shape = NULL;
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Finalize the geom
+void Geom::Fini()
+{
+  this->body->DisconnectEnabledSignal(boost::bind(&Geom::EnabledCB, this, _1));
+
+  World::Instance()->DisconnectShowPhysicsSignal( 
+      boost::bind(&Geom::ShowPhysics, this, _1) );
+
+  World::Instance()->DisconnectShowJointsSignal( 
+      boost::bind(&Geom::ShowJoints, this, _1) );
+
+  World::Instance()->DisconnectShowBoundingBoxesSignal( 
+      boost::bind(&Geom::ShowBoundingBox, this, _1) );
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // First step in the loading process
 void Geom::Load(XMLConfigNode *node)
 {
@@ -265,14 +283,6 @@
 // Update
 void Geom::Update()
 {
-  if (this->body && this->bbVisual)
-  {
-    if (this->body->GetEnabled())
-      this->bbVisual->SetBoundingBoxMaterial("Gazebo/GreenTransparent");
-    else
-      this->bbVisual->SetBoundingBoxMaterial("Gazebo/RedTransparent");
-  }
-
   this->ClearContacts();
 }
 
@@ -507,3 +517,16 @@
 
   return Contact();
 }
+
+////////////////////////////////////////////////////////////////////////////////
+/// Enable callback: Called when the body changes
+void Geom::EnabledCB(bool enabled)
+{
+  if (this->bbVisual)
+  {
+    if (enabled)
+      this->bbVisual->SetBoundingBoxMaterial("Gazebo/GreenTransparent");
+    else
+      this->bbVisual->SetBoundingBoxMaterial("Gazebo/RedTransparent");
+  }
+}

Modified: code/gazebo/trunk/server/physics/Geom.hh
===================================================================
--- code/gazebo/trunk/server/physics/Geom.hh    2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/physics/Geom.hh    2010-04-10 21:07:58 UTC (rev 
8607)
@@ -61,6 +61,9 @@
     /// \brief Destructor
     public: virtual ~Geom();
 
+    /// \brief Finalize the geom
+    public: void Fini();
+
     /// \brief Load the geom
     public: virtual void Load(XMLConfigNode *node);
 
@@ -170,7 +173,10 @@
             {
               contactSignal.connect( boost::bind(func, c, _1) );
             }
- 
+
+    /// \brief Enable callback: Called when the body changes
+    private: void EnabledCB(bool enabled);
+
     /// \brief Create the bounding box for the geom
     private: void CreateBoundingBox();
 

Modified: code/gazebo/trunk/server/physics/RayShape.cc
===================================================================
--- code/gazebo/trunk/server/physics/RayShape.cc        2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/server/physics/RayShape.cc        2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -134,8 +134,6 @@
 
   this->relativeEndPos = dir * len + this->relativeStartPos;
 
-  //std::cout << "Len[" << len << "] St[" << this->relativeStartPos << "] 
End[" << this->relativeEndPos << "] dir[" << dir << "]\n";
-
   if (this->line)
   {
     this->line->SetPoint(1,  this->relativeEndPos);

Modified: code/gazebo/trunk/server/physics/Shape.cc
===================================================================
--- code/gazebo/trunk/server/physics/Shape.cc   2010-04-02 15:07:45 UTC (rev 
8606)
+++ code/gazebo/trunk/server/physics/Shape.cc   2010-04-10 21:07:58 UTC (rev 
8607)
@@ -19,6 +19,8 @@
 // Destructor
 Shape::~Shape()
 {
+  if (this->parent)
+    this->parent->SetShape(NULL);
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/physics/ode/ODEBody.cc
===================================================================
--- code/gazebo/trunk/server/physics/ode/ODEBody.cc     2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/server/physics/ode/ODEBody.cc     2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -98,6 +98,7 @@
 // Move callback. Use this to move the visuals
 void ODEBody::MoveCallback(dBodyID id)
 {
+
   Pose3d pose;
   const dReal *p;
   const dReal *r;

Modified: code/gazebo/trunk/server/physics/ode/ODEMultiRayShape.cc
===================================================================
--- code/gazebo/trunk/server/physics/ode/ODEMultiRayShape.cc    2010-04-02 
15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/physics/ode/ODEMultiRayShape.cc    2010-04-10 
21:07:58 UTC (rev 8607)
@@ -12,6 +12,8 @@
 ODEMultiRayShape::ODEMultiRayShape(Geom *parent)
   : MultiRayShape(parent)
 {
+  this->SetName("ODE Multiray Shape");
+
   // Create a space to contain the ray space
   this->superSpaceId = dSimpleSpaceCreate( 0 );
 
@@ -141,8 +143,10 @@
 void ODEMultiRayShape::AddRay(const Vector3 &start, const Vector3 &end )
 {
   MultiRayShape::AddRay(start,end);
+  ODEGeom *odeGeom = new ODEGeom(parent->GetBody());
+  odeGeom->SetName("ODE Ray Geom");
 
-  ODERayShape *ray = new ODERayShape( new ODEGeom(parent->GetBody()), 
**this->displayTypeP == "lines");
+  ODERayShape *ray = new ODERayShape(odeGeom, **this->displayTypeP == "lines" 
);
 
   ray->SetPoints(start,end);
   this->rays.push_back(ray);

Modified: code/gazebo/trunk/server/physics/ode/ODERayShape.cc
===================================================================
--- code/gazebo/trunk/server/physics/ode/ODERayShape.cc 2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/server/physics/ode/ODERayShape.cc 2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -38,6 +38,8 @@
 ODERayShape::ODERayShape( Geom *parent, bool displayRays )
     : RayShape(parent, displayRays)
 {
+  this->SetName("ODE Ray Shape");
+
   ODEGeom *geom = (ODEGeom*)this->parent;
 
   // Create default ray with unit length

Modified: code/gazebo/trunk/server/rendering/OgreAdaptor.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreAdaptor.cc   2010-04-02 15:07:45 UTC 
(rev 8606)
+++ code/gazebo/trunk/server/rendering/OgreAdaptor.cc   2010-04-10 21:07:58 UTC 
(rev 8607)
@@ -104,6 +104,7 @@
   delete this->drawGridP;
   delete this->skyMaterialP;
 
+  RTShaderSystem::Instance()->Fini();
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/rendering/RTShaderSystem.cc
===================================================================
--- code/gazebo/trunk/server/rendering/RTShaderSystem.cc        2010-04-02 
15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/rendering/RTShaderSystem.cc        2010-04-10 
21:07:58 UTC (rev 8607)
@@ -154,6 +154,29 @@
 #endif
 }
 
+void RTShaderSystem::Fini()
+{
+#if OGRE_VERSION_MAJOR >= 1 && OGRE_VERSION_MINOR >= MINOR_VERSION
+  // Restore default scheme.
+  
Ogre::MaterialManager::getSingleton().setActiveScheme(Ogre::MaterialManager::DEFAULT_SCHEME_NAME);
+
+  // Unregister the material manager listener.
+  if (this->materialMgrListener != NULL)
+  {
+    Ogre::MaterialManager::getSingleton().removeListener(
+        this->materialMgrListener);
+    this->materialMgrListener = NULL;
+  }
+
+  // Finalize RTShader system.
+  if (this->shaderGenerator != NULL)
+  {
+    Ogre::RTShader::ShaderGenerator::finalize();
+    this->shaderGenerator = NULL;
+  }
+#endif
+}
+
 
////////////////////////////////////////////////////////////////////////////////
 // Set an Ogre::Entity to use RT shaders
 void RTShaderSystem::AttachEntity(OgreVisual *vis)

Modified: code/gazebo/trunk/server/rendering/RTShaderSystem.hh
===================================================================
--- code/gazebo/trunk/server/rendering/RTShaderSystem.hh        2010-04-02 
15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/rendering/RTShaderSystem.hh        2010-04-10 
21:07:58 UTC (rev 8607)
@@ -61,6 +61,9 @@
     /// \brief Init the run time shader system
     public: void Init();
 
+    /// \brief Finalize the shader system
+    public: void Fini();
+
     /// \brief Update the shaders
     public: void UpdateShaders();
 

Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2010-04-02 
15:07:45 UTC (rev 8606)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2010-04-10 
21:07:58 UTC (rev 8607)
@@ -156,15 +156,20 @@
   if (!Simulator::Instance()->GetRenderEngineEnabled())
     return;
 
+  if (this->active || **this->alwaysActiveP || **this->saveFramesP)
+    this->UpdateCam();
+
+
   // Only continue if the controller has an active interface. Or frames need
   // to be saved
-  if ( (this->controller && !this->controller->IsConnected()) &&
+  /*if ( (this->controller && !this->controller->IsConnected()) &&
        !this->saveFramesP->GetValue())
     return;
 
   // Or skip if user sets camera to inactive
   if (this->active)
     this->UpdateCam();
+    */
 }
 
 
////////////////////////////////////////////////////////////////////////////////


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

------------------------------------------------------------------------------
Download Intel&#174; Parallel Studio Eval
Try the new software tools for yourself. Speed compiling, find bugs
proactively, and fine-tune applications for parallel performance.
See why Intel Parallel Studio got high marks during beta.
http://p.sf.net/sfu/intel-sw-dev
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to