Revision: 8929
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8929&view=rev
Author:   natepak
Date:     2010-10-01 21:57:32 +0000 (Fri, 01 Oct 2010)

Log Message:
-----------
Updates

Modified Paths:
--------------
    code/gazebo/branches/simpar/player/CMakeLists.txt
    code/gazebo/branches/simpar/plugins/ball_drop.cc
    code/gazebo/branches/simpar/plugins/box_push.cc
    code/gazebo/branches/simpar/plugins/pioneer_circle.cc
    code/gazebo/branches/simpar/plugins/pioneer_gripper.cc
    code/gazebo/branches/simpar/plugins/pioneer_line.cc
    code/gazebo/branches/simpar/server/Logger.cc
    code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc
    code/gazebo/branches/simpar/worlds/empty.world
    code/gazebo/branches/simpar/worlds/pioneer2dx.world
    code/gazebo/branches/simpar/worlds/pioneer2dx_ramp.world
    code/gazebo/branches/simpar/worlds/simpleshapes.world

Modified: code/gazebo/branches/simpar/player/CMakeLists.txt
===================================================================
--- code/gazebo/branches/simpar/player/CMakeLists.txt   2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/player/CMakeLists.txt   2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -1,31 +1,30 @@
-
-set (gazeboplugin_sources GazeboDriver.cc
-             GazeboClient.cc
-             GazeboInterface.cc
-             GazeboTime.cc
-             SimulationInterface.cc
-             Position2dInterface.cc
-             Position3dInterface.cc
-             LaserInterface.cc
-             CameraInterface.cc
-             FiducialInterface.cc
-             PTZInterface.cc
-             OpaqueInterface.cc
-             ActarrayInterface.cc
-             GripperInterface.cc
-             BumperInterface.cc
-             IRInterface.cc
-)
-
-include_directories( 
-  ${PLAYER_INCLUDE_DIRS} 
-  ${CMAKE_SOURCE_DIR}/libgazebo 
-  ${boost_include_dirs}
-)
-
-link_directories( ${PLAYER_LINK_DIRS} ${boost_library_dirs} gazeboshm)
-
-add_library(gazeboplugin SHARED ${gazeboplugin_sources})
-target_link_libraries(gazeboplugin ${PLAYER_LINK_LIBS} gazeboshm )
-
-install(TARGETS gazeboplugin DESTINATION ${CMAKE_INSTALL_PREFIX}/lib )
+#set (gazeboplugin_sources GazeboDriver.cc
+#             GazeboClient.cc
+#             GazeboInterface.cc
+#             GazeboTime.cc
+#             SimulationInterface.cc
+#             Position2dInterface.cc
+#             Position3dInterface.cc
+#             LaserInterface.cc
+#             CameraInterface.cc
+#             FiducialInterface.cc
+#             PTZInterface.cc
+#             OpaqueInterface.cc
+#             ActarrayInterface.cc
+#             GripperInterface.cc
+#             BumperInterface.cc
+#             IRInterface.cc
+#)
+#
+#include_directories( 
+#  ${PLAYER_INCLUDE_DIRS} 
+#  ${CMAKE_SOURCE_DIR}/libgazebo 
+#  ${boost_include_dirs}
+#)
+#
+#link_directories( ${PLAYER_LINK_DIRS} ${boost_library_dirs} gazeboshm)
+#
+#add_library(gazeboplugin SHARED ${gazeboplugin_sources})
+#target_link_libraries(gazeboplugin ${PLAYER_LINK_LIBS} gazeboshm )
+#
+#install(TARGETS gazeboplugin DESTINATION ${CMAKE_INSTALL_PREFIX}/lib )

Modified: code/gazebo/branches/simpar/plugins/ball_drop.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/ball_drop.cc    2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/plugins/ball_drop.cc    2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -12,17 +12,17 @@
     {
       this->sphere = NULL;
       this->model_name = "sphere";
-      //this->SpawnBall(0,0,5);
+      this->SpawnBall(0,0,5);
 
       //for (double i=0.001; i > 1e-5; i*=0.5) 
-      this->stepTimes.push_back(0.1);
+      this->stepTimes.push_back(0.001);
 
       //for (unsigned int i=10; i<=100; i+=10)
-      this->stepIters.push_back(10);
+      this->stepIters.push_back(100);
 
-      //this->stepTypes.push_back("robust");
+      this->stepTypes.push_back("robust");
       this->stepTypes.push_back("world");
-      //this->stepTypes.push_back("quick");
+      this->stepTypes.push_back("quick");
 
       this->stepTypesIter = this->stepTypes.begin();
       this->stepTimesIter = this->stepTimes.begin();
@@ -73,7 +73,7 @@
       model << "  <body:sphere name='body'>";
       model << "    <geom:sphere name='geom'>";
       model << "      <size>0.25</size>";
-      model << "      <mass>10</mass>";
+      model << "      <mass>1</mass>";
       model << "      <kp>100000000.0</kp>";
       model << "      <kd>1.0</kd>";
       model << "      <bounce>0</bounce>";
@@ -137,7 +137,8 @@
         Time realTime = Simulator::Instance()->GetRealTime();
         Pose3d pose = this->sphere->GetWorldPose();
 
-        if ( fabs(prev_z - pose.pos.z) >= 1e-5 )
+        double diff = fabs(prev_z - pose.pos.z);
+        if (  diff >= 1e-4 )
           this->prevTime = realTime;
 
         this->prev_z = pose.pos.z;
@@ -153,7 +154,7 @@
     {
       if (LOG)
       {
-       // Logger::Instance()->RemoveLog("sphere");
+        Logger::Instance()->RemoveLog("sphere");
 
         std::string mv_cmd = std::string("mv /tmp/sphere.log ") + this->path + 
           "ball_drop_" + boost::lexical_cast<std::string>(this->count) + 
@@ -163,7 +164,7 @@
             (*this->stepTypesIter).c_str(), *this->stepTimesIter, 
             *this->stepItersIter);
 
-        //system(mv_cmd.c_str());
+        system(mv_cmd.c_str());
       }
 
       this->stepItersIter++;
@@ -193,12 +194,11 @@
                 << "Iters[" << *this->stepItersIter << "] "
                 << "Count[" << this->count << "]\n";
 
-      //this->sphere->Reset();
+      this->sphere->Reset();
       this->prevTime = Simulator::Instance()->GetRealTime();
 
-      /*if (LOG)
+      if (LOG)
         Logger::Instance()->AddLog("sphere","/tmp/sphere.log");
-        */
     }
 
     private: std::vector<unsigned int> stepIters;

Modified: code/gazebo/branches/simpar/plugins/box_push.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/box_push.cc     2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/plugins/box_push.cc     2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -2,7 +2,7 @@
 
 #include <gazebo/gazeboserver.hh>
 
-#define LOG true
+#define LOG false
 
 namespace gazebo
 {

Modified: code/gazebo/branches/simpar/plugins/pioneer_circle.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-10-01 
21:56:40 UTC (rev 8928)
+++ code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-10-01 
21:57:32 UTC (rev 8929)
@@ -2,7 +2,7 @@
 
 #include <gazebo/gazeboserver.hh>
 
-#define LOG false
+#define LOG true
 
 namespace gazebo
 {
@@ -17,9 +17,9 @@
       //for (unsigned int i=10; i<=100; i+=10)
         this->stepIters.push_back(10);
 
+      this->stepTypes.push_back("robust");
       //this->stepTypes.push_back("world");
-      this->stepTypes.push_back("quick");
-      //this->stepTypes.push_back("robust");
+      //this->stepTypes.push_back("quick");
 
       this->stepTypesIter = this->stepTypes.begin();
       this->stepTimesIter = this->stepTimes.begin();

Modified: code/gazebo/branches/simpar/plugins/pioneer_gripper.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_gripper.cc      2010-10-01 
21:56:40 UTC (rev 8928)
+++ code/gazebo/branches/simpar/plugins/pioneer_gripper.cc      2010-10-01 
21:57:32 UTC (rev 8929)
@@ -2,7 +2,7 @@
 #include <boost/bind.hpp>
 #include <gazebo/gazeboserver.hh>
 
-#define LOG true
+#define LOG false
 
 namespace gazebo
 {
@@ -13,15 +13,15 @@
     {
       //for (double i=0.001; i > 1e-5; i*=0.5) 
         //this->stepTimes.push_back(i);
-      this->stepTimes.push_back(0.0001);
+      this->stepTimes.push_back(0.001);
 
       //for (unsigned int i=10; i<=100; i+=10)
         //this->stepIters.push_back(10);
-      this->stepIters.push_back(10);
+      this->stepIters.push_back(100);
 
       //this->stepTypes.push_back("quick");
-      this->stepTypes.push_back("world");
-      //this->stepTypes.push_back("robust");
+      //this->stepTypes.push_back("world");
+      this->stepTypes.push_back("robust");
 
       this->stepTypesIter = this->stepTypes.begin();
       this->stepTimesIter = this->stepTimes.begin();

Modified: code/gazebo/branches/simpar/plugins/pioneer_line.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_line.cc 2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/plugins/pioneer_line.cc 2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -14,11 +14,11 @@
       //for (double i=0.001; i > 1e-5; i*=0.5) 
       this->stepTimes.push_back(0.001);
 
-      for (unsigned int i=10; i<=100; i+=10)
-        this->stepIters.push_back(i);
+      //for (unsigned int i=10; i<=100; i+=10)
+      this->stepIters.push_back(10);
 
-      this->stepTypes.push_back("quick");
-      this->stepTypes.push_back("world");
+      //this->stepTypes.push_back("quick");
+      //this->stepTypes.push_back("world");
       this->stepTypes.push_back("robust");
 
       this->stepTypesIter = this->stepTypes.begin();

Modified: code/gazebo/branches/simpar/server/Logger.cc
===================================================================
--- code/gazebo/branches/simpar/server/Logger.cc        2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/server/Logger.cc        2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -133,8 +133,6 @@
   }
   else
     this->logFile << "0 ";
-
-  this->logFile << "\n";
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc
===================================================================
--- code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc        
2010-10-01 21:56:40 UTC (rev 8928)
+++ code/gazebo/branches/simpar/server/physics/ode/ODEPhysics.cc        
2010-10-01 21:57:32 UTC (rev 8929)
@@ -224,85 +224,7 @@
   std::vector<ContactFeedback>::iterator iter;
   std::vector<dJointFeedback>::iterator jiter;
 
-  /*ODEBody *leftBody = 
(ODEBody*)World::Instance()->GetEntityByName("pioneer::left_wheel");
-  ODEBody *rightBody = 
(ODEBody*)World::Instance()->GetEntityByName("pioneer::right_wheel");
-  ODEBody *castorBody = 
(ODEBody*)World::Instance()->GetEntityByName("pioneer::castor_body");
-  ODEBody *planeBody = 
(ODEBody*)World::Instance()->GetEntityByName("plane1_model::plane1_body");
 
-  if (leftBody && rightBody && planeBody && castorBody)
-  {
-    ODEGeom *leftGeom = (ODEGeom*)leftBody->GetGeom("left_wheel_geom");
-    ODEGeom *rightGeom = (ODEGeom*)rightBody->GetGeom("right_wheel_geom");
-    ODEGeom *castorGeom = (ODEGeom*)castorBody->GetGeom("castor_geom");
-    ODEGeom *planeGeom = (ODEGeom*)planeBody->GetGeom("plane1_geom");
-
-    dContactGeom geomLeft, geomRight, geomCastor;
-    geomLeft.pos[0] = leftBody->GetWorldPose().pos.x;
-    geomLeft.pos[1] = leftBody->GetWorldPose().pos.y;
-    geomLeft.pos[2] = 0;
-    geomLeft.normal[0] = 0;
-    geomLeft.normal[1] = 0;
-    geomLeft.normal[2] = 1;
-    geomLeft.depth = 0;
-    geomLeft.g1 = leftGeom->GetGeomId();
-    geomLeft.g2 = planeGeom->GetGeomId();
-
-    geomRight.pos[0] = rightBody->GetWorldPose().pos.x;
-    geomRight.pos[1] = rightBody->GetWorldPose().pos.y;
-    geomRight.pos[2] = 0;
-    geomRight.normal[0] = 0;
-    geomRight.normal[1] = 0;
-    geomRight.normal[2] = 1;
-    geomRight.depth = 0;
-    geomRight.g1 = rightGeom->GetGeomId();
-    geomRight.g2 = planeGeom->GetGeomId();
-
-    geomCastor.pos[0] = castorBody->GetWorldPose().pos.x;
-    geomCastor.pos[1] = castorBody->GetWorldPose().pos.y;
-    geomCastor.pos[2] = 0;
-    geomCastor.normal[0] = 0;
-    geomCastor.normal[1] = 0;
-    geomCastor.normal[2] = 1;
-    geomCastor.depth =0;
-    geomCastor.g1 = castorGeom->GetGeomId();
-    geomCastor.g2 = planeGeom->GetGeomId();
-
-    dContact contact;
-    contact.geom = geomLeft;
-    contact.surface.mode = dContactSoftERP | dContactSoftCFM; 
-    contact.surface.mu = 0; 
-    contact.surface.mu2 = 0;
-    contact.surface.slip1 = 0.1;
-    contact.surface.slip2 = 0.1;
-    contact.surface.bounce =  0;
-    dJointID c = dJointCreateContact(this->worldId, this->contactGroup, 
&contact);
-    dJointAttach (c, leftBody->GetODEId(), planeBody->GetODEId());
-
-    dContact contact2;
-    contact2.geom = geomRight;
-    contact2.surface.mode = dContactSoftERP | dContactSoftCFM; 
-    contact2.surface.mu = 0; 
-    contact2.surface.mu2 = 0;
-    contact2.surface.slip1 = 0.1;
-    contact2.surface.slip2 = 0.1;
-    contact2.surface.bounce =  0;
-    dJointID c2 = dJointCreateContact(this->worldId, this->contactGroup, 
&contact2);
-    dJointAttach (c2, rightBody->GetODEId(), planeBody->GetODEId());
-
-    dContact contact3;
-    contact3.geom = geomCastor;
-    contact3.surface.mode = dContactSoftERP | dContactSoftCFM; 
-    contact3.surface.mu = 0; 
-    contact3.surface.mu2 = 0;
-    contact3.surface.slip1 = 0.1;
-    contact3.surface.slip2 = 0.1;
-    contact3.surface.bounce =  0;
-    dJointID c3 = dJointCreateContact(this->worldId, this->contactGroup, 
&contact3);
-    dJointAttach (c3, castorBody->GetODEId(), planeBody->GetODEId());
-  }
-*/
-
-
   // Do collision detection; this will add contacts to the contact group
   this->LockMutex(); 
   {
@@ -726,7 +648,7 @@
           continue;
 
         contact.geom = self->contactGeoms[i];
-        contact.surface.mode = dContactSlip1 | dContactSlip2 | 
+        contact.surface.mode = //dContactSlip1 | dContactSlip2 | 
                                dContactSoftERP | dContactSoftCFM |  
                                dContactBounce | dContactMu2 | dContactApprox1;
         //contact.surface.mode = dContactSoftERP | dContactSoftCFM | 
dContactApprox1 | dContactSlip1 | dContactSlip2;

Modified: code/gazebo/branches/simpar/worlds/empty.world
===================================================================
--- code/gazebo/branches/simpar/worlds/empty.world      2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/worlds/empty.world      2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -15,13 +15,12 @@
   <verbosity>4</verbosity>
 
   <physics:ode>
-    <stepTime>0.1</stepTime>
+    <stepTime>0.001</stepTime>
     <gravity>0 0 -9.8</gravity>
     <cfm>0.0000000001</cfm>
     <erp>0.2</erp>
-
-    <stepType>quick</stepType>
-    <stepIters>10</stepIters>
+    <stepType>robust</stepType>
+    <stepIters>100</stepIters>
     <stepW>1.3</stepW>
     <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
     <contactSurfaceLayer>0.0</contactSurfaceLayer>

Modified: code/gazebo/branches/simpar/worlds/pioneer2dx.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-10-01 21:56:40 UTC 
(rev 8928)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-10-01 21:57:32 UTC 
(rev 8929)
@@ -24,8 +24,8 @@
     <cfm>0.0000000001</cfm>
     <erp>0.2</erp>
 
-    <stepType>quick</stepType>
-    <stepIters>100</stepIters>
+    <stepType>robust</stepType>
+    <stepIters>10</stepIters>
     <stepW>1.3</stepW>
     <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
     <contactSurfaceLayer>0.00</contactSurfaceLayer>
@@ -51,8 +51,8 @@
     <body:plane name="plane1_body">
       <geom:plane name="plane1_geom">
         <normal>0 0 1</normal>
-        <mu1>100000.0</mu1>
-        <mu2>100000.0</mu2>
+        <mu1>109999.0</mu1>
+        <mu2>1000.0</mu2>
         <kp>1000000000.0</kp>
         <kd>1.0</kd>
 
@@ -96,7 +96,7 @@
   -->
 
   <model:physical name="pioneer">
-    <xyz>0 0 0.148</xyz>
+    <xyz>0 0 1.448</xyz>
     <rpy>0.0 0.0 0.0</rpy>
 
     <!--

Modified: code/gazebo/branches/simpar/worlds/pioneer2dx_ramp.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx_ramp.world    2010-10-01 
21:56:40 UTC (rev 8928)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx_ramp.world    2010-10-01 
21:57:32 UTC (rev 8929)
@@ -21,13 +21,26 @@
   <physics:ode>
     <stepTime>0.001</stepTime>
     <gravity>0 0 -9.8</gravity>
+    <cfm>0.0000000001</cfm>
+    <erp>0.2</erp>
+
+    <stepType>robust</stepType>
+    <stepIters>10</stepIters>
+    <stepW>1.3</stepW>
+    <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
+    <contactSurfaceLayer>0.00</contactSurfaceLayer>
+  </physics:ode>
+
+
+  <!--
+  <physics:ode>
+    <stepTime>0.001</stepTime>
+    <gravity>0 0 -9.8</gravity>
     <cfm>10e-5</cfm>
     <erp>0.3</erp>
-    <!-- updateRate: <0 == throttle simTime to match realTime.
-                      0 == No throttling
-                     >0 == Frequency at which to throttle the sim --> 
     <updateRate>0</updateRate>
   </physics:ode>
+  -->
 
   <rendering:gui>
     <type>fltk</type>

Modified: code/gazebo/branches/simpar/worlds/simpleshapes.world
===================================================================
--- code/gazebo/branches/simpar/worlds/simpleshapes.world       2010-10-01 
21:56:40 UTC (rev 8928)
+++ code/gazebo/branches/simpar/worlds/simpleshapes.world       2010-10-01 
21:57:32 UTC (rev 8929)
@@ -47,22 +47,17 @@
   </rendering:ogre>
 
   <model:physical name="sphere1_model">
-    <xyz>0 0 0.2</xyz>
-    <rpy>0 0.0 0.0</rpy>
-    <static>true</static>
-
+    <xyz>0 0 5.0</xyz>
     <body:sphere name="sphere1_body">
       <geom:sphere name="sphere1_geom">
-        <size>0.2</size>
-        <mass>1.0</mass>
+        <size>0.25</size>
+        <mass>10.0</mass>
 
         <mu1>109999.0</mu1>
 
         <visual>
-          <size>0.4 0.4 0.4</size>
-          <mesh>lightsensor.3ds</mesh>
-          <shader>pixel</shader>
-          <!--<material>Gazebo/Rocky</material>-->
+          <size>0.5 0.5 0.5</size>
+          <mesh>unit_sphere</mesh>
         </visual>
       </geom:sphere>
     </body:sphere>
@@ -88,7 +83,7 @@
   </model:physical>
 
   <!-- White Point light -->
-  <model:renderable name="point_white">
+  <!--<model:renderable name="point_white">
     <xyz>-2 2 10</xyz>
     <static>false</static>
 
@@ -101,5 +96,6 @@
       <attenuation>0.1 0.01 0.001</attenuation>
     </light>
   </model:renderable>
+  -->
  
 </gazebo:world>


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

------------------------------------------------------------------------------
Start uncovering the many advantages of virtual appliances
and start using them to simplify application deployment and
accelerate your shift to cloud computing.
http://p.sf.net/sfu/novell-sfdev2dev
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to