Revision: 8715
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8715&view=rev
Author:   natepak
Date:     2010-05-27 18:01:12 +0000 (Thu, 27 May 2010)

Log Message:
-----------
More updates for logging data

Modified Paths:
--------------
    code/gazebo/branches/simpar/benchmarks/CMakeLists.txt
    code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
    code/gazebo/branches/simpar/libgazebo/SimIface.cc
    code/gazebo/branches/simpar/libgazebo/gz.h
    code/gazebo/branches/simpar/server/CMakeLists.txt
    code/gazebo/branches/simpar/server/World.cc
    code/gazebo/branches/simpar/server/World.hh
    code/gazebo/branches/simpar/server/physics/PhysicsEngine.cc
    code/gazebo/branches/simpar/server/physics/PhysicsEngine.hh
    code/gazebo/branches/simpar/server/physics/ode/CMakeLists.txt
    code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc
    code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.hh
    code/gazebo/branches/simpar/worlds/empty.world

Added Paths:
-----------
    code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
    code/gazebo/branches/simpar/benchmarks/table_benchmark.cc
    code/gazebo/branches/simpar/server/Logger.cc
    code/gazebo/branches/simpar/server/Logger.hh
    code/gazebo/branches/simpar/worlds/table.world

Modified: code/gazebo/branches/simpar/benchmarks/CMakeLists.txt
===================================================================
--- code/gazebo/branches/simpar/benchmarks/CMakeLists.txt       2010-05-26 
01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/benchmarks/CMakeLists.txt       2010-05-27 
18:01:12 UTC (rev 8715)
@@ -21,52 +21,23 @@
 
 include_directories(.)
 
-set (sources laser_benchmark.cc 
-             box_grid_benchmark.cc 
-             box_pile_benchmark.cc 
-             joint_chain_benchmark.cc
-             camera_benchmark.cc
-             spinningbox_benchmark.cc
-             pendulum_benchmark.cc
-             box_drop_benchmark.cc
-             )
+set (benchmarks laser 
+                box_grid 
+                box_pile 
+                joint_chain 
+                camera 
+                spinningbox 
+                pendulum 
+                box_drop 
+                table
+                pioneer_circle
+                )
 
-set_source_files_properties(${sources} PROPERTIES COMPILE_FLAGS "-ggdb -g2 
-Wall")
-
-add_executable(laser_benchmark laser_benchmark.cc)
-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)
-add_executable(spinningbox_benchmark spinningbox_benchmark.cc)
-add_executable(pendulum_benchmark pendulum_benchmark.cc)
-add_executable(box_drop_benchmark box_drop_benchmark.cc)
-
-target_link_libraries(laser_benchmark       gazebo ${LINK_LIBS} )
-target_link_libraries(box_grid_benchmark    gazebo ${LINK_LIBS} )
-target_link_libraries(box_pile_benchmark    gazebo ${LINK_LIBS} )
-target_link_libraries(joint_chain_benchmark gazebo ${LINK_LIBS} )
-target_link_libraries(camera_benchmark      gazebo ${LINK_LIBS} )
-target_link_libraries(spinningbox_benchmark gazebo ${LINK_LIBS} )
-target_link_libraries(pendulum_benchmark    gazebo ${LINK_LIBS} )
-target_link_libraries(box_drop_benchmark    gazebo ${LINK_LIBS} )
-
-set_target_properties(laser_benchmark       PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(box_grid_benchmark    PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(box_pile_benchmark    PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(joint_chain_benchmark PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(camera_benchmark      PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(spinningbox_benchmark   PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(pendulum_benchmark      PROPERTIES SKIP_BUILD_RPATH TRUE)
-set_target_properties(box_drop_benchmark      PROPERTIES SKIP_BUILD_RPATH TRUE)
-
-set_target_properties(laser_benchmark       PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(box_grid_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(box_pile_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(joint_chain_benchmark PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(camera_benchmark      PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(spinningbox_benchmark PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(pendulum_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-set_target_properties(box_drop_benchmark    PROPERTIES LINK_FLAGS 
"${LINK_FLAGS} ${gazebo_lflags}")
-
-install (TARGETS laser_benchmark box_grid_benchmark box_pile_benchmark 
joint_chain_benchmark camera_benchmark spinningbox_benchmark pendulum_benchmark 
box_drop_benchmark DESTINATION ${CMAKE_INSTALL_PREFIX}/bin)
+foreach (src ${benchmarks})
+  set_source_files_properties(${src}_benchmark.cc PROPERTIES COMPILE_FLAGS 
"-Wall")
+  add_executable(${src}_benchmark ${src}_benchmark.cc)
+  target_link_libraries(${src}_benchmark  gazebo ${LINK_LIBS} )
+  set_target_properties(${src}_benchmark  PROPERTIES SKIP_BUILD_RPATH TRUE)
+  set_target_properties(${src}_benchmark  PROPERTIES LINK_FLAGS "${LINK_FLAGS} 
${gazebo_lflags}")
+  install (TARGETS ${src}_benchmark DESTINATION ${CMAKE_INSTALL_PREFIX}/bin)
+endforeach (src ${benchmarks})

Modified: code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc        
2010-05-26 01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/benchmarks/box_drop_benchmark.cc        
2010-05-27 18:01:12 UTC (rev 8715)
@@ -3,6 +3,7 @@
 #include <stdlib.h>
 #include <vector>
 #include <libgazebo/gz.h>
+#include <boost/lexical_cast.hpp>
 
 gazebo::Client *client = NULL;
 gazebo::SimulationIface *simIface = NULL;
@@ -45,7 +46,7 @@
   model << "      <kp>100000000.0</kp>";
   model << "      <kd>1.0</kd>";
   model << "      <bounce>0</bounce>";
-  model << "      <bounceVel>0</bounceVel>";
+  model << "      <bounceVel>100000</bounceVel>";
   model << "      <slip1>0.01</slip1>";
   model << "      <slip2>0.01</slip2>";
   model << "      <visual>";
@@ -63,6 +64,32 @@
   factoryIface->Unlock();
 }
 
+void RunSim()
+{
+  simIface->StartLogEntity("box");
+  simIface->Unpause();
+  /*gazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
+  gazebo::Pose modelPose;
+
+  double time = simIface->data->realTime;
+  while ( simIface->data->realTime - time < 10.0 )
+  {
+    //simIface->GetState("box", modelPose, linearVel, angularVel, linearAccel, 
angularAccel); 
+
+    //if ( fabs(prev_z - modelPose.pos.z) >= 1e-5)
+      //time = simIface->data->realTime;
+
+    //prev_z = modelPose.pos.z;
+  }
+  */
+  usleep(10000000);
+
+  simIface->StopLogEntity("box");
+  simIface->Pause();
+  simIface->Reset();
+}
+
+
 int main()
 {
   client = new gazebo::Client();
@@ -101,34 +128,52 @@
               << e << "\n";
     return -1;
   }
-
-  FILE *out = fopen(data_filename.c_str(), "w");
-
   double prev_z = 5;
-
   spawn_box(0, 0, prev_z);
-  simIface->Unpause();
+  usleep(10000);
 
-  gazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
-  gazebo::Pose modelPose;
 
-  double time = simIface->data->realTime;
-  while ( simIface->data->realTime - time < 2.0 )
+  std::vector<std::string > step_types;
+  std::vector<std::string >::iterator iter;
+  //step_types.push_back("robust");
+  step_types.push_back("world");
+  step_types.push_back("quick");
+
+  for (iter = step_types.begin(); iter != step_types.end(); iter++)
   {
-    simIface->GetState("box", modelPose, linearVel, angularVel, linearAccel, 
angularAccel); 
-    fprintf(out,"%f %f %f %f %f %f %f %f\n", simIface->data->simTime, 
simIface->data->realTime, modelPose.pos.x, modelPose.pos.y, modelPose.pos.z, 
modelPose.roll, modelPose.pitch, modelPose.yaw );
+    std::string path = std::string("/home/nate/work/simpar/data/box_drop/") + 
*iter + "/";
 
-    if ( fabs(prev_z - modelPose.pos.z) >= 1e-5)
-      time = simIface->data->realTime;
+    system((std::string("mkdir -p ")+path).c_str());
 
-    prev_z = modelPose.pos.z;
-  }
+    FILE *out = fopen(std::string(path+"index.txt").c_str(), "w");
+    fprintf(out,"# index step_time\n");
 
-  fclose(out);
+    int i = 0;
 
-  //make_plot();
+    simIface->SetStepType(*iter);
+    for (double step=0.1; step > 1e-5; step *= 0.5)
+    {
+      unsigned int iterations = 10;
+      if (*iter == "world")
+        iterations = 199;
+      for (; iterations < 200; iterations +=20, i++)
+      {
+        simIface->SetStepTime(step);
+        simIface->SetStepIterations(iterations);
 
+        fprintf(out,"%d %f %d\n",i,step, iterations);
+        std::cout << "Type[" << *iter << "] Step[" << step << "] Iterations[" 
<< iterations << "]\n";
+        RunSim();
+        std::string mv_cmd = std::string("mv /tmp/box.log ") + path + 
"box_drop_benchmark_" + *iter + "_" + boost::lexical_cast<std::string>(i) + 
".data";
+        system(mv_cmd.c_str());
+      }
+    }
+    fclose(out);
+  }
+
   factoryIface->Close();
   simIface->Close();
   client->Disconnect();
 }
+
+

Added: code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc          
                (rev 0)
+++ code/gazebo/branches/simpar/benchmarks/pioneer_circle_benchmark.cc  
2010-05-27 18:01:12 UTC (rev 8715)
@@ -0,0 +1,75 @@
+#include <iostream>
+#include <stdio.h>
+#include <stdlib.h>
+#include <vector>
+#include <libgazebo/gz.h>
+
+gazebo::Client *client = NULL;
+gazebo::SimulationIface *simIface = NULL;
+gazebo::FactoryIface *factoryIface = NULL;
+
+std::string test_name="Pioneer Circle Benchmark";
+std::string data_filename = "/tmp/pioneer_circle_benchmark.data";
+
+void spawn_robot()
+{
+  std::ostringstream model;
+
+  model << "<model:physical name='pioneer'>";
+  model << "  <xyz>0 0 1.145</xyz>";
+  model << "  <rpy>0.0 0.0 90.0</rpy>";
+  model << "  <include embedded='true'>";
+  model << "    <xi:include 
href='/home/nate/local/share/gazebo/worlds/models/pioneer2dx.model'/>";
+  model << "  </include>";
+  model << "</model:physical>";
+
+  factoryIface->Lock(1);
+  strcpy( (char*)factoryIface->data->newModel, model.str().c_str() );
+  factoryIface->Unlock();
+}
+
+int main()
+{
+  client = new gazebo::Client();
+  simIface = new gazebo::SimulationIface();
+  factoryIface = new gazebo::FactoryIface();
+
+  try
+  {
+    client->ConnectWait(0, GZ_CLIENT_ID_USER_FIRST);
+  }
+  catch(std::string e)
+  {
+    std::cerr << "Gazebo Error: Unable to connect: " << e << "\n";
+    return -1;
+  }
+
+  /// Open the sim iface
+  try
+  {
+    simIface->Open(client, "default");
+  }
+  catch (std::string e)
+  {
+    std::cerr << "Gazebo error: Unable to connect to sim iface:" << e << "\n";
+    return -1;
+  }
+
+  // Open the factory iface
+  try
+  {
+    factoryIface->Open(client, "default");
+  }
+  catch( std::string e)
+  {
+    std::cerr << "Gazebo error: Unable to connect to the factory Iface:" 
+              << e << "\n";
+    return -1;
+  }
+
+  spawn_robot();
+
+  factoryIface->Close();
+  simIface->Close();
+  client->Disconnect();
+}

Added: code/gazebo/branches/simpar/benchmarks/table_benchmark.cc
===================================================================
--- code/gazebo/branches/simpar/benchmarks/table_benchmark.cc                   
        (rev 0)
+++ code/gazebo/branches/simpar/benchmarks/table_benchmark.cc   2010-05-27 
18:01:12 UTC (rev 8715)
@@ -0,0 +1,216 @@
+#include <iostream>
+#include <stdio.h>
+#include <stdlib.h>
+#include <vector>
+#include <libgazebo/gz.h>
+
+gazebo::Client *client = NULL;
+gazebo::SimulationIface *simIface = NULL;
+gazebo::FactoryIface *factoryIface = NULL;
+int laser_count = 0;
+
+std::string test_name="Table Benchmark";
+std::string data_filename = "/tmp/table_benchmark.data";
+
+void spawn_table()
+{
+  std::ostringstream model;
+
+  model << "<model:physical name='table'>";
+  model << "  <xyz>0 0 0.51</xyz>";
+  model << "  <rpy>0 0 0</rpy>";
+  model << "  <static>false</static>";
+  model << "  <body:box name='body'>";
+
+  model << "    <geom:box name='surface'>";
+  model << "      <size>1.02 1.02 0.01</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>1.02 1.02 .01</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+
+  model << "    <geom:box name='leg1'>";
+  model << "      <xyz>-0.5 -0.5 -0.25</xyz>";
+  model << "      <size>.02 .02 0.5</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>0.01 0.01 0.5</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+
+  model << "    <geom:box name='leg2'>";
+  model << "      <xyz>-0.5 0.5 -0.25</xyz>";
+  model << "      <size>.02 .02 0.5</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>0.01 0.01 0.5</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+
+  model << "    <geom:box name='leg3'>";
+  model << "      <xyz>0.5 -0.5 -0.25</xyz>";
+  model << "      <size>.02 .02 0.5</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>0.01 0.01 0.5</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+
+  model << "    <geom:box name='leg4'>";
+  model << "      <xyz>0.5 0.5 -0.25</xyz>";
+  model << "      <size>.02 .02 0.5</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>0.01 0.01 0.5</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+
+  model << "  </body:box>";
+  model << "</model:physical>";
+
+  factoryIface->Lock(1);
+  strcpy( (char*)factoryIface->data->newModel, model.str().c_str() );
+  factoryIface->Unlock();
+}
+
+void spawn_box(double x, double y, double z=1)
+{
+  std::ostringstream model;
+
+  model << "<model:physical name='box'>";
+  model << "  <xyz>" << x << " " << y << " " << z << "</xyz>";
+  model << "  <rpy>0 0 0</rpy>";
+  model << "  <body:box name='body'>";
+  model << "    <geom:box name='geom'>";
+  model << "      <size>0.5 0.5 0.5</size>";
+  model << "      <mass>1</mass>";
+  model << "      <kp>100000000.0</kp>";
+  model << "      <kd>1.0</kd>";
+  model << "      <bounce>0</bounce>";
+  model << "      <bounceVel>0</bounceVel>";
+  model << "      <slip1>0.01</slip1>";
+  model << "      <slip2>0.01</slip2>";
+  model << "      <visual>";
+  model << "        <size>0.5 0.5 0.5</size>";
+  model << "        <mesh>unit_box</mesh>";
+  model << "        <material>Gazebo/Rocky</material>";
+  model << "      </visual>";
+  model << "    </geom:box>";
+  model << "  </body:box>";
+  model << "</model:physical>";
+
+  factoryIface->Lock(1);
+  strcpy( (char*)factoryIface->data->newModel, model.str().c_str() );
+  factoryIface->Unlock();
+}
+
+int main()
+{
+  client = new gazebo::Client();
+  simIface = new gazebo::SimulationIface();
+  factoryIface = new gazebo::FactoryIface();
+
+  try
+  {
+    client->ConnectWait(0, GZ_CLIENT_ID_USER_FIRST);
+  }
+  catch(std::string e)
+  {
+    std::cerr << "Gazebo Error: Unable to connect: " << e << "\n";
+    return -1;
+  }
+
+  /// Open the sim iface
+  try
+  {
+    simIface->Open(client, "default");
+  }
+  catch (std::string e)
+  {
+    std::cerr << "Gazebo error: Unable to connect to sim iface:" << e << "\n";
+    return -1;
+  }
+
+  // Open the factory iface
+  try
+  {
+    factoryIface->Open(client, "default");
+  }
+  catch( std::string e)
+  {
+    std::cerr << "Gazebo error: Unable to connect to the factory Iface:" 
+              << e << "\n";
+    return -1;
+  }
+
+  double prev_z = 5;
+
+  spawn_table();
+  usleep(100000);
+  spawn_box(0, 0, prev_z);
+  usleep(1000000);
+  simIface->StartLogEntity("box");
+  simIface->StartLogEntity("table");
+  simIface->Unpause();
+
+  gazebo::Vec3 linearVel, angularVel, linearAccel, angularAccel;
+  gazebo::Pose modelPose;
+
+  double time = simIface->data->realTime;
+  while ( simIface->data->realTime - time < 2.0 )
+  {
+    simIface->GetState("box", modelPose, linearVel, angularVel, linearAccel, 
angularAccel); 
+
+    if ( fabs(prev_z - modelPose.pos.z) >= 1e-5)
+      time = simIface->data->realTime;
+
+    prev_z = modelPose.pos.z;
+  }
+  simIface->StopLogEntity("box");
+  simIface->StopLogEntity("table");
+
+  factoryIface->Close();
+  simIface->Close();
+  client->Disconnect();
+}

Modified: code/gazebo/branches/simpar/libgazebo/SimIface.cc
===================================================================
--- code/gazebo/branches/simpar/libgazebo/SimIface.cc   2010-05-26 01:00:17 UTC 
(rev 8714)
+++ code/gazebo/branches/simpar/libgazebo/SimIface.cc   2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -851,3 +851,109 @@
 
   return true;
 }
+
+////////////////////////////////////////////////////////////////////////////////
+/// Start logging entity information
+void SimulationIface::StartLogEntity(const std::string &entityName)
+{
+  this->Lock(1);
+
+  this->data->responseCount = 0;
+  SimulationRequestData *request;
+
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::START_LOG;
+
+  memset(request->name, 0, 512);
+  strncpy(request->name, entityName.c_str(), 512);
+  request->name[511] = '\0';
+
+  this->Unlock();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Stop logging entity information
+void SimulationIface::StopLogEntity(const std::string &entityName)
+{
+  this->Lock(1);
+
+  this->data->responseCount = 0;
+  SimulationRequestData *request;
+
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::STOP_LOG;
+
+  memset(request->name, 0, 512);
+  strncpy(request->name, entityName.c_str(), 512);
+  request->name[511] = '\0';
+
+  this->Unlock();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the step time
+void SimulationIface::SetStepTime(double time)
+{
+  this->Lock(1);
+
+  this->data->responseCount = 0;
+  SimulationRequestData *request;
+
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::SET_STEP_TIME;
+  request->dblValue = time;
+  this->Unlock();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the step iteraction
+void SimulationIface::SetStepIterations(unsigned int iters)
+{
+  this->Lock(1);
+
+  this->data->responseCount = 0;
+  SimulationRequestData *request;
+
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::SET_STEP_ITERS;
+  request->uintValue = iters;
+
+  this->Unlock();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the step type
+void SimulationIface::SetStepType(const std::string &type)
+{
+  this->Lock(1);
+
+  this->data->responseCount = 0;
+  SimulationRequestData *request;
+
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::SET_STEP_TYPE;
+  memset(request->strValue, 0, 512);
+  strncpy(request->strValue, type.c_str(), 512);
+  request->strValue[511] = '\0';
+
+  this->Unlock();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get the step type
+std::string SimulationIface::GetStepType()
+{
+  this->Lock(1);
+  this->data->responseCount = 0;
+
+  SimulationRequestData *request;
+  request = &(this->data->requests[this->data->requestCount++]);
+  request->type = SimulationRequestData::GET_STEP_TYPE;
+
+  this->Unlock();
+  if (!this->WaitForResponse())
+    return false;
+
+  assert(this->data->responseCount == 1);
+  return data->responses[0].strValue;
+}

Modified: code/gazebo/branches/simpar/libgazebo/gz.h
===================================================================
--- code/gazebo/branches/simpar/libgazebo/gz.h  2010-05-26 01:00:17 UTC (rev 
8714)
+++ code/gazebo/branches/simpar/libgazebo/gz.h  2010-05-27 18:01:12 UTC (rev 
8715)
@@ -447,6 +447,12 @@
                       GET_MODEL_INTERFACES, // for getting interfaces as well 
as the models which are ancestors of interfaces
                       GET_INTERFACE_TYPE,   // if the model is not an 
interface 'unknown' is returned
                       SET_ENTITY_PARAM_VALUE,
+                      START_LOG,
+                      STOP_LOG,
+                      SET_STEP_TIME,
+                      SET_STEP_ITERS,
+                      SET_STEP_TYPE,
+                      GET_STEP_TYPE
                    };
 
   public: Type type; 
@@ -455,6 +461,7 @@
   public: char strValue1[512];
   public: Vec3 vec3Value;
   public: unsigned int uintValue;
+  public: double dblValue;
 
   public: Pose modelPose;
   public: Vec3 modelLinearVel;
@@ -465,7 +472,6 @@
   public: char childInterfaces[GAZEBO_MAX_NUMBER_OF_CHILDREN][512];
   public: int nChildInterfaces;
   //public: char modelType[512];
-
 };
 
 /// \brief Simulation interface data
@@ -653,6 +659,24 @@
   public: void GoAckWait();
   public: void GoAckPost();
 
+  /// \brief Start logging entity information
+  public: void StartLogEntity(const std::string &entityName);
+
+  /// \brief Stop logging entity information
+  public: void StopLogEntity(const std::string &entityName);
+
+  /// \brief Set the step time
+  public: void SetStepTime(double time);
+
+  /// \brief Set the step iteraction
+  public: void SetStepIterations(unsigned int iters);
+
+  /// \brief Set the step type
+  public: void SetStepType(const std::string &type);
+
+  /// \brief Get the step type
+  public: std::string GetStepType();
+
   private: void BlockThread();
 
   /// \brief Wait for a return message

Modified: code/gazebo/branches/simpar/server/CMakeLists.txt
===================================================================
--- code/gazebo/branches/simpar/server/CMakeLists.txt   2010-05-26 01:00:17 UTC 
(rev 8714)
+++ code/gazebo/branches/simpar/server/CMakeLists.txt   2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -93,6 +93,7 @@
              OgreLoader.cc
              AssimpLoader.cc
              STLLoader.cc
+             Logger.cc
 )
 
 SET (headers Common.hh
@@ -125,6 +126,7 @@
              OgreLoader.hh
              AssimpLoader.hh
              STLLoader.hh
+             Logger.hh
 )
 
 APPEND_TO_SERVER_HEADERS(${headers})

Added: code/gazebo/branches/simpar/server/Logger.cc
===================================================================
--- code/gazebo/branches/simpar/server/Logger.cc                                
(rev 0)
+++ code/gazebo/branches/simpar/server/Logger.cc        2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -0,0 +1,102 @@
+#include <iomanip>
+#include "Time.hh"
+#include "World.hh"
+#include "Entity.hh"
+#include "Simulator.hh"
+#include "Logger.hh"
+
+using namespace gazebo;
+
+////////////////////////////////////////////////////////////////////////////////
+/// Constructor
+Logger::Logger()
+{
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Destructor
+Logger::~Logger()
+{
+  std::vector<LogObj*>::iterator iter;
+
+  for (iter = this->logObjects.begin(); iter != this->logObjects.end(); iter++)
+    delete *iter;
+  this->logObjects.clear();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Add a log
+void Logger::AddLog(const std::string &entity)
+{
+  Logger::LogObj *newLog = new Logger::LogObj(entity + ".log");
+  newLog->entityName = entity;
+  this->logObjects.push_back(newLog);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Remove a log
+void Logger::RemoveLog(const std::string &entity)
+{
+  std::vector<LogObj*>::iterator iter;
+
+  for (iter = this->logObjects.begin(); iter != this->logObjects.end(); iter++)
+  {
+    if ( (*iter)->entityName == entity)
+    {
+      delete *iter;
+      this->logObjects.erase(iter);
+      break;
+    }
+  }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Update the logger
+void Logger::Update()
+{
+  std::vector<LogObj*>::iterator iter;
+
+  for (iter = this->logObjects.begin(); iter != this->logObjects.end(); iter++)
+    (*iter)->Update();
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+////////////////////////////////////////////////////////////////////////////////
+/// Constructor
+Logger::LogObj::LogObj(const std::string &filename)
+{
+  std::string fullname = std::string("/tmp/") + filename;
+  this->logFile.open(fullname.c_str(), std::fstream::out);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Destructor
+Logger::LogObj::~LogObj()
+{
+  this->logFile.close();
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Update the log object
+void Logger::LogObj::Update()
+{
+  Entity *entity = World::Instance()->GetEntityByName(this->entityName);
+  if (entity)
+  {
+    Pose3d pose3d = entity->GetAbsPose();
+    Time simTime = Simulator::Instance()->GetSimTime();
+    Time realTime = Simulator::Instance()->GetRealTime();
+
+    double roll, pitch, yaw;
+
+    roll = pose3d.rot.GetRoll();
+    pitch = pose3d.rot.GetPitch();
+    yaw = pose3d.rot.GetYaw();
+
+    this->logFile << std::setprecision(8) << std::fixed
+      << simTime.Double() << " " << realTime.Double() << " "
+      << pose3d.pos.x << " " << pose3d.pos.y << " " << pose3d.pos.z 
+      << " " << roll << " " << pitch << " " << yaw << "\n";
+  }
+}

Added: code/gazebo/branches/simpar/server/Logger.hh
===================================================================
--- code/gazebo/branches/simpar/server/Logger.hh                                
(rev 0)
+++ code/gazebo/branches/simpar/server/Logger.hh        2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -0,0 +1,40 @@
+#ifndef LOGGER_HH
+#define LOGGER_HH
+
+#include <vector>
+#include <fstream>
+#include <string>
+
+namespace gazebo
+{
+  class Logger
+  {
+    /// \brief Constructor
+    public: Logger();
+
+    /// \brief Destructor
+    public: virtual ~Logger();
+
+    /// \brief Add a log file
+    public: void AddLog(const std::string &model);
+
+    /// \brief Remove a log
+    public: void RemoveLog(const std::string &entity);
+
+    /// \brief Update the log files
+    public: void Update();
+
+    private: class LogObj
+             {
+               public: LogObj(const std::string &filename);
+               public: virtual ~LogObj();
+               public: void Update();
+
+               public: std::string entityName;
+               private: std::fstream logFile;
+             };
+
+    private: std::vector<LogObj*> logObjects;
+  };
+}
+#endif

Modified: code/gazebo/branches/simpar/server/World.cc
===================================================================
--- code/gazebo/branches/simpar/server/World.cc 2010-05-26 01:00:17 UTC (rev 
8714)
+++ code/gazebo/branches/simpar/server/World.cc 2010-05-27 18:01:12 UTC (rev 
8715)
@@ -44,6 +44,7 @@
 #include "Simulator.hh"
 #include "gz.h"
 #include "World.hh"
+#include "Logger.hh"
 
 #include "OpenAL.hh"
 
@@ -79,12 +80,15 @@
   this->saveStateBufferSizeP = new ParamT<unsigned 
int>("saveStateBufferSize",1000,0);
   Param::End();
 
+  this->logger = new Logger();
 }
 
 
////////////////////////////////////////////////////////////////////////////////
 // Private destructor
 World::~World()
 {
+  delete this->logger;
+  this->logger = NULL;
   this->Close();
 }
 
@@ -375,6 +379,8 @@
 
   this->factory->Update();
 
+  this->logger->Update();
+
   this->worldUpdateEndSignal();
 }
 
@@ -1335,14 +1341,7 @@
 
           std::string mname = req->name;               
           unsigned int i=mname.find(".");        
-/*
 
-               unsigned int ind = list[j].find(mname);
-               if(ind==0 && ind!=std::string::npos && list[j].size() > 
mname.size()){
-                       
candids.push_back(list[j].substr(ind+mname.size(),list[j].size()-ind-mname.size()));
-               }
-         }
-*/
           while(i!= std::string::npos)
           {
             mname.erase(i,1);
@@ -1350,7 +1349,6 @@
             i= mname.find(".");
           }
 
-
           std::vector<std::string> candids;
 
           for(unsigned int j=0;j<list.size();j++)
@@ -1403,24 +1401,17 @@
           std::vector<Model*>::iterator mmiter;
 
 
-         for (mmiter=models.begin(); mmiter!=models.end(); mmiter++)
-                 GetInterfaceNames((*mmiter), list);
+          for (mmiter=models.begin(); mmiter!=models.end(); mmiter++)
+            GetInterfaceNames((*mmiter), list);
 
 
-         // removing the ">>type" from the end of each interface names 
-         for(unsigned int jj=0;jj<list.size();jj++){
-               unsigned int index = list[jj].find(">>");
-               if(index !=std::string::npos)
-                       list[jj].replace(index,list[jj].size(),"");
-         }
+          // removing the ">>type" from the end of each interface names 
+          for(unsigned int jj=0;jj<list.size();jj++){
+            unsigned int index = list[jj].find(">>");
+            if(index !=std::string::npos)
+              list[jj].replace(index,list[jj].size(),"");
+          }
          
-         
-         //if(strcmp((char*)req->name,"")==0){
-                 /*
-                    for (miter=models.begin(); miter!=models.end(); miter++)
-            GetInterfaceNames((*miter), list);
-*/
-
           // removing the ">>type" from the end of each interface names 
           for(unsigned int jj=0;jj<list.size();jj++)
           {
@@ -1437,27 +1428,27 @@
 
 
 
-                       std::string str = list[i].substr(0,list[i].find("::"));
-                       std::vector<std::string>::iterator itr;
-                       itr = std::find(chlist.begin(),chlist.end(), str);
+              std::string str = list[i].substr(0,list[i].find("::"));
+              std::vector<std::string>::iterator itr;
+              itr = std::find(chlist.begin(),chlist.end(), str);
 
-                       if(itr!=chlist.end() || str=="")
-                               continue;
+              if(itr!=chlist.end() || str=="")
+                continue;
 
-                       unsigned int ii=str.find("::");        
-                       while(ii!= std::string::npos){
-       
-                               str.erase(ii,2);
-                               str.insert(ii,".");
-                               ii= str.find("::");
-                       }
+              unsigned int ii=str.find("::");        
+              while(ii!= std::string::npos){
 
-                       chlist.push_back(str);
-                       
strcpy(response->childInterfaces[response->nChildInterfaces++],str.c_str());
-                       
response->childInterfaces[response->nChildInterfaces-1][511]='\0';
-               
-           }
-               
+                str.erase(ii,2);
+                str.insert(ii,".");
+                ii= str.find("::");
+              }
+
+              chlist.push_back(str);
+              
strcpy(response->childInterfaces[response->nChildInterfaces++],str.c_str());
+              
response->childInterfaces[response->nChildInterfaces-1][511]='\0';
+
+            }
+
           }
           else
           {
@@ -1499,14 +1490,14 @@
               chlist.push_back(str);
               // Adding the parent name to the child name e.g "parent.child" 
               str=mname+"."+str;
-             
-             unsigned int i=str.find("::");        
-             while(i!=std::string::npos){
-                       str.erase(i,2);
-                       str.insert(i,".");
-                       i= str.find("::");
-             }
 
+              unsigned int i=str.find("::");        
+              while(i!=std::string::npos){
+                str.erase(i,2);
+                str.insert(i,".");
+                i= str.find("::");
+              }
+
               strcpy(response->childInterfaces[response->nChildInterfaces++],
                   str.c_str());
               
response->childInterfaces[response->nChildInterfaces-1][511]='\0';
@@ -1518,10 +1509,50 @@
 
           break;  
         }
-       
 
-      case SimulationRequestData::GO:
+     case SimulationRequestData::START_LOG:
         {
+          this->logger->AddLog(req->name);
+          break;
+        }
+
+     case SimulationRequestData::STOP_LOG:
+        {
+          this->logger->RemoveLog(req->name);
+          break;
+        }
+
+     case SimulationRequestData::SET_STEP_TIME:
+        {
+          this->physicsEngine->SetStepTime(Time(req->dblValue));
+          break;
+        }
+
+     case SimulationRequestData::SET_STEP_ITERS:
+        {
+          this->physicsEngine->SetStepIters(req->uintValue);
+          break;
+        }
+
+     case SimulationRequestData::SET_STEP_TYPE:
+        {
+          this->physicsEngine->SetStepType(req->strValue);
+          break;
+        }
+
+     case SimulationRequestData::GET_STEP_TYPE:
+        {
+          memset(response->strValue, 0, 512);
+          strncpy(response->strValue, 
this->physicsEngine->GetStepType().c_str(), 512);
+          response->strValue[511] = '\0';
+          response++;
+          this->simIface->data->responseCount += 1;
+          break;
+        }
+
+
+     case SimulationRequestData::GO:
+        {
           int sec = req->runTime/1000;
           int nsec = (req->runTime - sec*1000) * 1e6;
 

Modified: code/gazebo/branches/simpar/server/World.hh
===================================================================
--- code/gazebo/branches/simpar/server/World.hh 2010-05-26 01:00:17 UTC (rev 
8714)
+++ code/gazebo/branches/simpar/server/World.hh 2010-05-27 18:01:12 UTC (rev 
8715)
@@ -68,6 +68,7 @@
   class WorldState;
   class Timer;
   class Time;
+  class Logger;
    
 /// \brief The World
 /*
@@ -435,6 +436,8 @@
   private: Timer saveStateTimer;
   private: ParamT<Time> *saveStateTimeoutP;
   private: ParamT<unsigned int> *saveStateBufferSizeP;
+
+  private: Logger *logger;
 };
 
 class WorldState

Modified: code/gazebo/branches/simpar/server/physics/PhysicsEngine.cc
===================================================================
--- code/gazebo/branches/simpar/server/physics/PhysicsEngine.cc 2010-05-26 
01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/server/physics/PhysicsEngine.cc 2010-05-27 
18:01:12 UTC (rev 8715)
@@ -130,6 +130,13 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Set the time between each update cycle
+void PhysicsEngine::SetStepTime(Time time)
+{
+  this->stepTimeP->SetValue(time);
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Lock the physics engine mutex
 void PhysicsEngine::LockMutex()
 {

Modified: code/gazebo/branches/simpar/server/physics/PhysicsEngine.hh
===================================================================
--- code/gazebo/branches/simpar/server/physics/PhysicsEngine.hh 2010-05-26 
01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/server/physics/PhysicsEngine.hh 2010-05-27 
18:01:12 UTC (rev 8715)
@@ -138,6 +138,18 @@
     /// \return step time 
     public: Time GetStepTime() const;
 
+    /// \brief Set the step time
+    public: void SetStepTime(Time time);
+
+    /// \brief Set the step iterations
+    public: virtual void SetStepIters(unsigned int iters) {}
+
+    /// \brief Get the step type
+    public: virtual std::string GetStepType() const {return "unknown";}
+
+    /// \brief Set the step type
+    public: virtual void SetStepType(const std::string type) {}
+
     /// \brief Lock the physics engine mutex
     public: void LockMutex();
 

Modified: code/gazebo/branches/simpar/server/physics/ode/CMakeLists.txt
===================================================================
--- code/gazebo/branches/simpar/server/physics/ode/CMakeLists.txt       
2010-05-26 01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/server/physics/ode/CMakeLists.txt       
2010-05-27 18:01:12 UTC (rev 8715)
@@ -40,7 +40,6 @@
 endif (CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE})
 
 LIST_TO_STRING(MY_ODE_CFLAGS "${ODE_CFLAGS}")
-message (STATUS "ODE CFLAGS ${MY_ODE_CFLAGS}")
 
 set_target_properties(gazebo_physics_ode PROPERTIES COMPILE_FLAGS "-fPIC 
${MY_ODE_CFLAGS}")
 target_link_libraries( gazebo_physics_ode ${ODE_LIBRARIES})

Modified: code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc
===================================================================
--- code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc        
2010-05-26 01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc        
2010-05-27 18:01:12 UTC (rev 8715)
@@ -91,7 +91,7 @@
   this->globalCFMP = new ParamT<double>("cfm", 10e-5, 0);
   this->globalERPP = new ParamT<double>("erp", 0.2, 0);
   this->stepTypeP = new ParamT<std::string>("stepType", "quick", 0);
-  this->stepItersP = new ParamT<int>("stepIters", 20, 0);
+  this->stepItersP = new ParamT<unsigned int>("stepIters", 100, 0);
   this->stepWP = new ParamT<double>("stepW", 1.3, 0);  /// over_relaxation 
value for SOR
   this->contactMaxCorrectingVelP = new 
ParamT<double>("contactMaxCorrectingVel", 10.0, 0);
   this->contactSurfaceLayerP = new ParamT<double>("contactSurfaceLayer", 0.01, 
0);
@@ -279,7 +279,11 @@
   else if (**this->stepTypeP == "world")
     dWorldStep( this->worldId, (**this->stepTimeP).Double() );
   else if (**this->stepTypeP == "robust")
+  {
+    printf("Robust Step\n");
     dWorldRobustStep( this->worldId, (**this->stepTimeP).Double() );
+    printf("Robust Step Done\n");
+  }
   else
     gzthrow(std::string("Invalid step type[") + **this->stepTypeP);
 
@@ -389,6 +393,15 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Set the step iterations
+void ODEPhysics::SetStepIters(unsigned int iters)
+{
+  this->stepItersP->SetValue(iters);
+  dWorldSetQuickStepNumIterations(this->worldId, **this->stepItersP );
+  dWorldSetRobustStepMaxIterations(this->worldId, (int)(**this->stepItersP) );
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Convert an odeMass to Mass
 void ODEPhysics::ConvertMass(void *engineMass, const Mass &mass)
 {
@@ -437,6 +450,20 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Get the step type
+std::string ODEPhysics::GetStepType() const
+{
+  return **this->stepTypeP;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the step type
+void ODEPhysics::SetStepType(const std::string type)
+{
+  this->stepTypeP->SetValue(type);
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Handle a collision
 void ODEPhysics::CollisionCallback( void *data, dGeomID o1, dGeomID o2)
 {
@@ -550,8 +577,10 @@
           contact.surface.slip2 = 0.1;
         }
 
-        contact.surface.bounce = std::min(geom1->surface->bounce, 
+        contact.surface.bounce =  0;
+        /*contact.surface.bounce = std::min(geom1->surface->bounce, 
                                      geom2->surface->bounce);
+                                     */
         contact.surface.bounce_vel = std::min(geom1->surface->bounceVel, 
                                          geom2->surface->bounceVel);
         dJointID c = dJointCreateContact (self->worldId,
@@ -589,3 +618,4 @@
     }
   }
 }
+

Modified: code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.hh
===================================================================
--- code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.hh        
2010-05-26 01:00:17 UTC (rev 8714)
+++ code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.hh        
2010-05-27 18:01:12 UTC (rev 8715)
@@ -137,6 +137,15 @@
   /// \brief Convert an odeMass to Mass
   public: virtual void ConvertMass(void *odeMass, const Mass &mass);
 
+  /// \brief Set the step iterations
+  public: virtual void SetStepIters(unsigned int iters);
+
+  /// \brief Get the step type
+  public: virtual std::string GetStepType() const;
+
+  /// \brief Set the step type
+  public: virtual void SetStepType(const std::string type);
+
   /// \brief Do collision detection
   private: static void CollisionCallback( void *data, dGeomID o1, dGeomID o2);
 
@@ -152,7 +161,7 @@
   private: ParamT<double> *globalCFMP; 
   private: ParamT<double> *globalERPP; 
   private: ParamT<std::string> *stepTypeP; 
-  private: ParamT<int> *stepItersP; 
+  private: ParamT<unsigned int> *stepItersP; 
   private: ParamT<double> *stepWP; 
   private: ParamT<double> *contactMaxCorrectingVelP;
   private: ParamT<double> *contactSurfaceLayerP;

Modified: code/gazebo/branches/simpar/worlds/empty.world
===================================================================
--- code/gazebo/branches/simpar/worlds/empty.world      2010-05-26 01:00:17 UTC 
(rev 8714)
+++ code/gazebo/branches/simpar/worlds/empty.world      2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -15,12 +15,12 @@
   <verbosity>4</verbosity>
 
   <physics:ode>
-    <stepTime>0.00001</stepTime>
+    <stepTime>0.001</stepTime>
     <gravity>0 0 -9.8</gravity>
     <cfm>0.0000000001</cfm>
     <erp>0.2</erp>
 
-    <stepType>robust</stepType>
+    <stepType>quick</stepType>
     <stepIters>10</stepIters>
     <stepW>1.3</stepW>
     <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>

Added: code/gazebo/branches/simpar/worlds/table.world
===================================================================
--- code/gazebo/branches/simpar/worlds/table.world                              
(rev 0)
+++ code/gazebo/branches/simpar/worlds/table.world      2010-05-27 18:01:12 UTC 
(rev 8715)
@@ -0,0 +1,192 @@
+<?xml version="1.0"?>
+
+<gazebo:world 
+  xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"; 
+  xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"; 
+  xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"; 
+  xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"; 
+  xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"; 
+  xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"; 
+  
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface";
 
+  
xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering";
 
+  
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller";
+  xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"; 
>
+
+  <verbosity>4</verbosity>
+
+  <physics:ode>
+    <stepTime>0.001</stepTime>
+    <gravity>0 0 -9.8</gravity>
+    <cfm>0.0000000001</cfm>
+    <erp>0.2</erp>
+
+    <stepType>quick</stepType>
+    <stepIters>10</stepIters>
+    <stepW>1.3</stepW>
+    <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
+    <contactSurfaceLayer>0.001</contactSurfaceLayer>
+  </physics:ode>
+
+  <rendering:gui>
+    <type>fltk</type>
+    <size>800 600</size>
+    <pos>0 0</pos>
+  </rendering:gui>
+
+  <rendering:ogre>
+    <ambient>.2 .2 .2 1</ambient>
+    <shadows>true</shadows>
+    <grid>false</grid>
+  </rendering:ogre>
+
+   <!-- Ground Plane -->
+   <model:physical name="plane1_model">
+    <xyz>0 0 0</xyz>
+    <rpy>0 0 0</rpy>
+    <static>true</static>
+
+    <body:plane name="plane1_body">
+      <geom:plane name="plane1_geom">
+        <normal>0 0 1</normal>
+        <size>100 100</size>
+        <segments>1  1</segments>
+        <uvTile>100 100</uvTile>
+        <mu1>109999.0</mu1>
+        <mu2>1000.0</mu2>
+        <material>Gazebo/GrayGrid</material>
+      </geom:plane>
+    </body:plane>
+  </model:physical>
+
+  <model:physical name="table">
+    <xyz>0 0 0.51</xyz>
+    <rpy>0 0 0</rpy>
+    <static>false</static>
+    <body:box name='body'>
+
+      <geom:box name='surface'>
+        <size>1.02 1.02 0.01</size>
+        <mass>1</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>1.02 1.02 .01</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+
+      <geom:box name='leg1'>
+        <xyz>-0.5 -0.5 -0.25</xyz>
+        <size>.02 .02 0.5</size>
+        <mass>1</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>0.01 0.01 0.5</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+
+      <geom:box name='leg2'>
+        <xyz>-0.5 0.5 -0.25</xyz>
+        <size>.02 .02 0.5</size>
+        <mass>1</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>0.01 0.01 0.5</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+
+      <geom:box name='leg3'>
+        <xyz>0.5 -0.5 -0.25</xyz>
+        <size>.02 .02 0.5</size>
+        <mass>1</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>0.01 0.01 0.5</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+
+      <geom:box name='leg4'>
+        <xyz>0.5 0.5 -0.25</xyz>
+        <size>.02 .02 0.5</size>
+        <mass>1</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>0.01 0.01 0.5</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+
+    </body:box>
+  </model:physical>
+
+  <model:physical name="box">
+    <xyz>0 0.2 2.0</xyz>
+    <rpy>0 0 0</rpy>
+    <static>false</static>
+    <body:box name='body'>
+      <geom:box name='surface'>
+        <size>0.5 0.5 0.5</size>
+        <mass>2</mass>
+        <kp>100000000.0</kp>
+        <kd>1.0</kd>
+        <bounce>0</bounce>
+        <bounceVel>0</bounceVel>
+        <slip1>0.01</slip1>
+        <slip2>0.01</slip2>
+        <visual>
+          <size>0.5 0.5 .5</size>
+          <mesh>unit_box</mesh>
+          <material>Gazebo/Rocky</material>
+        </visual>
+      </geom:box>
+    </body:box>
+  </model:physical>
+
+
+  <!-- White Point light -->
+  <model:renderable name="point_white">
+    <xyz>0.0 5.0 10</xyz>
+    <static>true</static>
+    <light>
+      <type>point</type>
+      <diffuseColor>0.4 0.4 0.4</diffuseColor>
+      <specularColor>.1 .1 .1</specularColor>
+      <attenuation>0.2 0.01 0.001</attenuation>
+      <range>30</range>
+      <castShadows>true</castShadows>
+    </light>
+  </model:renderable>
+
+</gazebo:world>


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

------------------------------------------------------------------------------

_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to