Revision: 8768
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8768&view=rev
Author:   natepak
Date:     2010-06-20 19:34:02 +0000 (Sun, 20 Jun 2010)

Log Message:
-----------
Updates to the plugins

Modified Paths:
--------------
    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/worlds/pioneer2dx.world
    code/gazebo/branches/simpar/worlds/pioneer2dx_gripper.world

Modified: code/gazebo/branches/simpar/plugins/pioneer_circle.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-06-19 
07:53:59 UTC (rev 8767)
+++ code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-06-20 
19:34:02 UTC (rev 8768)
@@ -2,7 +2,7 @@
 
 #include <gazebo/gazeboserver.hh>
 
-#define LOG true
+#define LOG false
 
 namespace gazebo
 {
@@ -11,15 +11,15 @@
   {
     public: PioneerCircle() : Handler() 
     {
-      for (double i=0.001; i > 1e-5; i*=0.5) 
-        this->stepTimes.push_back(i);
+      //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("world");
       this->stepTypes.push_back("quick");
-      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();
@@ -32,7 +32,7 @@
 
       if (LOG)
       {
-        this->indexFile = fopen(std::string(this->path + "index.txt").c_str(), 
"w");
+        this->indexFile = fopen(std::string(this->path + "index.txt").c_str(), 
"a");
         fprintf(this->indexFile, "# index step_type step_time 
step_iterations\n");
       }
     }
@@ -134,6 +134,7 @@
     {
       if (LOG)
       {
+        printf("HERE. Count[%d]\n", this->count);
         Logger::Instance()->RemoveLog("pioneer");
 
         std::string mv_cmd = std::string("mv /tmp/pioneer.log ") + this->path 
+ 

Modified: code/gazebo/branches/simpar/plugins/pioneer_gripper.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_gripper.cc      2010-06-19 
07:53:59 UTC (rev 8767)
+++ code/gazebo/branches/simpar/plugins/pioneer_gripper.cc      2010-06-20 
19:34:02 UTC (rev 8768)
@@ -2,7 +2,7 @@
 #include <boost/bind.hpp>
 #include <gazebo/gazeboserver.hh>
 
-#define LOG false
+#define LOG true
 
 namespace gazebo
 {
@@ -13,14 +13,15 @@
     {
       //for (double i=0.001; i > 1e-5; i*=0.5) 
         //this->stepTimes.push_back(i);
-      this->stepTimes.push_back(0.00001);
+      this->stepTimes.push_back(0.0001);
 
-      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->stepIters.push_back(10);
 
-      this->stepTypes.push_back("quick");
-      this->stepTypes.push_back("robust");
+      //this->stepTypes.push_back("quick");
       this->stepTypes.push_back("world");
+      //this->stepTypes.push_back("robust");
 
       this->stepTypesIter = this->stepTypes.begin();
       this->stepTimesIter = this->stepTimes.begin();
@@ -29,11 +30,11 @@
       this->path = std::string("/home/nate/work/simpar/data/pioneer_gripper/");
       system( (std::string("mkdir -p ") + this->path).c_str() );
 
-      this->count = 0;
+      this->count = 1;
 
       if (LOG)
       {
-        this->indexFile = fopen(std::string(this->path + "index.txt").c_str(), 
"w");
+        this->indexFile = fopen(std::string(this->path + "index.txt").c_str(), 
"a");
         fprintf(this->indexFile, "# index step_type step_time 
step_iterations\n");
       }
     }
@@ -58,12 +59,15 @@
         }
       }
       this->robot->Reset();
+      this->box->Reset();
     }
 
     public: void Load()
     {
       std::string model_name = "pioneer_gripper";
       this->robot = (Model*)World::Instance()->GetEntityByName(model_name);
+      this->box =  (Model*)World::Instance()->GetEntityByName("custom_box");
+      Simulator::Instance()->SetPaused(false);
 
       if (this->robot)
       {
@@ -85,19 +89,19 @@
           Logger::Instance()->AddLog("custom_box","/tmp/box.log");
         }
 
-        /*this->physics->SetStepTime( *this->stepTimesIter );
+        this->physics->SetStepTime( *this->stepTimesIter );
         this->physics->SetStepType( *this->stepTypesIter );
         this->physics->SetSORPGSIters( *this->stepItersIter );
         std::cout << "Type[" << *this->stepTypesIter << "] " 
           << "Time[" << *this->stepTimesIter << "] "
           << "Iters[" << *this->stepItersIter << "]\n";
-        */
       }
       else
         std::cerr << "Unable to find model[" << model_name << "]\n";
 
       this->spawned = false; this->leftForce = 0;
       this->rightForce = 0;
+      this->resetCounter = 10;
     }
 
     public: void Open()
@@ -143,8 +147,21 @@
       return fabs(diff) < 0.130;
     }
 
+    public: bool IsUp()
+            {
+              return this->liftBody->GetWorldPose().pos.z > 0.08;
+            }
+
     public: void UpdateCB()
     {
+      if (this->resetCounter > 0)
+      {
+        this->resetCounter--;
+        return;
+      }
+      else
+        Simulator::Instance()->SetPaused(false);
+
       Time simTime = Simulator::Instance()->GetSimTime();
 
       this->leftPaddle->SetForce(Vector3(0.0,this->leftForce,0.0));
@@ -158,13 +175,14 @@
         this->Lift();
       }
 
-      if (simTime - this->prevTime > Time(60,0))
+      //if (!this->IsClosed() || !this->IsUp())
+        //this->prevTime = simTime;
+
+      if (simTime - this->prevTime > Time(35,0))
       {
-        Logger::Instance()->RemoveLog("pioneer_gripper::left_paddle_body");
-        Logger::Instance()->RemoveLog("pioneer_gripper::right_paddle_body");
-        Logger::Instance()->RemoveLog("custom_box");
-        printf("Done\n");
-        delete this;
+        std::cout << "Done\n";
+        //delete this;
+        this->UpdateJob();
       }
     }
 
@@ -173,17 +191,24 @@
     {
       if (LOG)
       {
-        Logger::Instance()->RemoveLog("pioneer");
+        Logger::Instance()->RemoveLog("pioneer_gripper::left_paddle_body");
+        Logger::Instance()->RemoveLog("pioneer_gripper::right_paddle_body");
+        Logger::Instance()->RemoveLog("custom_box");
 
-        std::string mv_cmd = std::string("mv /tmp/pioneer.log ") + this->path 
+ 
-          "pioneer_line_" + boost::lexical_cast<std::string>(this->count) + 
-          ".data";
+        std::string mv_cmd;
+        
+        mv_cmd = std::string("mv /tmp/pioneer_left.log ") + this->path + 
"pioneer_gripper_left_" + boost::lexical_cast<std::string>(this->count) + 
".data";
+        system(mv_cmd.c_str());
 
+        mv_cmd = std::string("mv /tmp/pioneer_right.log ") + this->path + 
"pioneer_gripper_right_" + boost::lexical_cast<std::string>(this->count) + 
".data";
+        system(mv_cmd.c_str());
+
+        mv_cmd = std::string("mv /tmp/box.log ") + this->path + "box_" + 
boost::lexical_cast<std::string>(this->count) + ".data";
+        system(mv_cmd.c_str());
+
         fprintf(this->indexFile,"%d %s %f %d\n",this->count, 
             (*this->stepTypesIter).c_str(), *this->stepTimesIter, 
             *this->stepItersIter);
-
-        system(mv_cmd.c_str());
       }
 
       this->stepItersIter++;
@@ -203,7 +228,7 @@
         }
       }
 
-      this->physics->SetStepType( *this->stepTypesIter );
+      /*this->physics->SetStepType( *this->stepTypesIter );
       this->physics->SetStepTime( *this->stepTimesIter );
       this->physics->SetSORPGSIters( *this->stepItersIter );
 
@@ -213,11 +238,17 @@
                 << "Iters[" << *this->stepItersIter << "] "
                 << "Count[" << this->count << "]\n";
 
+      //Simulator::Instance()->SetPaused(true);
       this->robot->Reset();
+      this->box->Reset();
+      this->resetCounter = 10;
       this->prevTime = Simulator::Instance()->GetSimTime();
+      */
+      delete this;
 
-      if (LOG)
+      /*if (LOG)
         Logger::Instance()->AddLog("pioneer","/tmp/pioneer.log");
+        */
     }
 
     private: std::vector<unsigned int> stepIters;
@@ -231,11 +262,12 @@
     private: std::string path;
     private: unsigned int count;
 
-    private: Model *robot;
+    private: Model *robot, *box;
     private: Body *leftPaddle, *rightPaddle, *liftBody;
     private: FILE *indexFile;
     private: Time prevTime;
     private: PhysicsEngine *physics;
+    private: int resetCounter;
 
     private: bool spawned;
 

Modified: code/gazebo/branches/simpar/plugins/pioneer_line.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_line.cc 2010-06-19 07:53:59 UTC 
(rev 8767)
+++ code/gazebo/branches/simpar/plugins/pioneer_line.cc 2010-06-20 19:34:02 UTC 
(rev 8768)
@@ -11,15 +11,15 @@
   {
     public: PioneerLine() : Handler()
     {
-      for (double i=0.001; i > 1e-5; i*=0.5) 
-        this->stepTimes.push_back(i);
+      //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);
 
+      this->stepTypes.push_back("quick");
+      this->stepTypes.push_back("world");
       this->stepTypes.push_back("robust");
-      this->stepTypes.push_back("world");
-      this->stepTypes.push_back("quick");
 
       this->stepTypesIter = this->stepTypes.begin();
       this->stepTimesIter = this->stepTimes.begin();
@@ -99,8 +99,8 @@
 
       if (simTime - prevTime < Time(0,100000000)) 
       {
-        this->leftWheel->SetTorque(Vector3(0.0,0.0,.1));
-        this->rightWheel->SetTorque(Vector3(0.0,0.0,.1));
+        this->leftWheel->SetTorque(Vector3(0.0,0.0,0.1));
+        this->rightWheel->SetTorque(Vector3(0.0,0.0,0.1));
       }
       else if (simTime - prevTime >= Time(20,0)) 
         this->UpdateJob();

Modified: code/gazebo/branches/simpar/worlds/pioneer2dx.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-19 07:53:59 UTC 
(rev 8767)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-20 19:34:02 UTC 
(rev 8768)
@@ -51,8 +51,8 @@
     <body:plane name="plane1_body">
       <geom:plane name="plane1_geom">
         <normal>0 0 1</normal>
-        <mu1>50.0</mu1>
-        <mu2>50.0</mu2>
+        <mu1>100000.0</mu1>
+        <mu2>100000.0</mu2>
         <kp>1000000000.0</kp>
         <kd>1.0</kd>
 

Modified: code/gazebo/branches/simpar/worlds/pioneer2dx_gripper.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx_gripper.world 2010-06-19 
07:53:59 UTC (rev 8767)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx_gripper.world 2010-06-20 
19:34:02 UTC (rev 8768)
@@ -19,15 +19,15 @@
   <verbosity>5</verbosity>
 
   <physics:ode>
-    <stepTime>0.01</stepTime>
+    <stepTime>0.001</stepTime>
     <gravity>0 0 -9.8</gravity>
     <cfm>0.0000000001</cfm>
     <erp>0.2</erp>
 
-    <stepType>robust</stepType>
-    <stepIters>20</stepIters>
-    <stepW>.3</stepW>
-    <contactMaxCorrectingVel>1.0</contactMaxCorrectingVel>
+    <stepType>quick</stepType>
+    <stepIters>100</stepIters>
+    <stepW>1.3</stepW>
+    <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
     <contactSurfaceLayer>0.00</contactSurfaceLayer>
 
   </physics:ode>
@@ -87,13 +87,13 @@
     <rpy>0.0 0.0 0.0</rpy>
   
     <body:box name="gripper_base_body">
-      <xyz>0.0 0 0.115</xyz>
+      <xyz>0.0 0 0.08</xyz>
       <geom:box name="gripper_base_geom">
         <xyz>0 0 0</xyz>
-        <size>0.053 0.123 0.130</size>
+        <size>0.053 0.123 0.16</size>
         <mass>10.1</mass>
         <visual>
-          <size>0.053 0.123 0.130</size>
+          <size>0.053 0.123 0.16</size>
           <mesh>unit_box</mesh>
           <material>Gazebo/Black</material>
         </visual>
@@ -101,7 +101,7 @@
     </body:box>
     
     <body:box name="lift_body">
-       <xyz>0.061 0 0.0315</xyz>
+       <xyz>0.061 0 0.0425</xyz>
       <geom:box name="lift_geom">
         <xyz>0 0 0</xyz>
         <size>0.069 0.313 0.063</size>
@@ -143,7 +143,7 @@
       </geom:box>
     </body:box>
     
-    <joint:hinge name="fixed">
+    <!--<joint:hinge name="fixed">
       <body1>gripper_base_body</body1>
       <body2>world</body2>
       <anchor>gripper_base_body</anchor>
@@ -154,6 +154,7 @@
       <erp>0.4</erp>
       <cfm>0.01</cfm>
     </joint:hinge>
+    -->
     
     <joint:slider name="lift_slider_joint">
       <body1>gripper_base_body</body1>
@@ -161,7 +162,7 @@
       <anchor>gripper_base_body</anchor>
       <axis>0 0 1</axis>
       <lowStop>-0.05</lowStop>
-      <highStop>0.05</highStop>
+      <highStop>0.0</highStop>
       <erp>0.3</erp>
       <cfm>10e-5</cfm>
     </joint:slider>


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

------------------------------------------------------------------------------
ThinkGeek and WIRED's GeekDad team up for the Ultimate 
GeekDad Father's Day Giveaway. ONE MASSIVE PRIZE to the 
lucky parental unit.  See the prize list and enter to win: 
http://p.sf.net/sfu/thinkgeek-promo
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to