Revision: 8765
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8765&view=rev
Author:   natepak
Date:     2010-06-15 03:40:50 +0000 (Tue, 15 Jun 2010)

Log Message:
-----------
Fixed searching for assimp, and the pioneer circle plugin

Modified Paths:
--------------
    code/gazebo/branches/simpar/cmake/SearchForStuff.cmake
    code/gazebo/branches/simpar/plugins/pioneer_circle.cc
    code/gazebo/branches/simpar/worlds/pioneer2dx.world

Modified: code/gazebo/branches/simpar/cmake/SearchForStuff.cmake
===================================================================
--- code/gazebo/branches/simpar/cmake/SearchForStuff.cmake      2010-06-14 
15:02:52 UTC (rev 8764)
+++ code/gazebo/branches/simpar/cmake/SearchForStuff.cmake      2010-06-15 
03:40:50 UTC (rev 8765)
@@ -49,7 +49,7 @@
 
   #################################################
   # Find ODE
-  pkg_check_modules(ODE ode>=${ODE_VERSION})
+  pkg_check_modules(ODE ode)
   IF (NOT ODE_FOUND)
     BUILD_ERROR ("ODE and development files not found. See the following 
website: http://www.ode.org";)
     set (INCLUDE_ODE FALSE CACHE BOOL "Include support for ODE")

Modified: code/gazebo/branches/simpar/plugins/pioneer_circle.cc
===================================================================
--- code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-06-14 
15:02:52 UTC (rev 8764)
+++ code/gazebo/branches/simpar/plugins/pioneer_circle.cc       2010-06-15 
03:40:50 UTC (rev 8765)
@@ -17,18 +17,18 @@
       for (unsigned int i=10; i<=100; i+=10)
         this->stepIters.push_back(i);
 
+      this->stepTypes.push_back("quick");
       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();
       this->stepItersIter = this->stepIters.begin();
 
-      this->path = std::string("/home/nate/work/simpar/data/pioneer_circle/");
+      this->path = 
std::string("/home/nkoenig/work/simpar/data/pioneer_circle/");
       system( (std::string("mkdir -p ") + this->path).c_str() );
 
-      this->circleCount = 4;
+      this->circleCount = 1;
 
       if (LOG)
       {
@@ -66,6 +66,7 @@
 
       if (this->robot)
       {
+        this->startPose = this->robot->GetWorldPose();
         this->robot->GetVisualNode()->SetRibbonTrail(true);
         this->leftWheel = (Body*)this->robot->GetChild("left_wheel");
         this->rightWheel = (Body*)this->robot->GetChild("right_wheel");
@@ -73,6 +74,8 @@
         this->physics = World::Instance()->GetPhysicsEngine();
 
         this->prevTime = Simulator::Instance()->GetSimTime();
+        this->startTime = Simulator::Instance()->GetSimTime();
+
         this->count = 0;
         this->circleCount = 0;
 
@@ -82,6 +85,10 @@
         World::Instance()->ConnectWorldUpdateStartSignal(
             boost::bind(&PioneerCircle::UpdateCB, this));
 
+        this->physics->SetStepType( *this->stepTypesIter );
+        this->physics->SetStepTime( *this->stepTimesIter );
+        this->physics->SetSORPGSIters( *this->stepItersIter );
+
         std::cout << "Type[" << *this->stepTypesIter << "] " 
                   << "Time[" << *this->stepTimesIter << "] "
                   << "Iters[" << *this->stepItersIter << "]\n";
@@ -95,22 +102,32 @@
       Time simTime = Simulator::Instance()->GetSimTime();
       Pose3d pose = this->robot->GetWorldPose();
 
+      double dist = pose.pos.Distance(this->startPose.pos);
+
+      if (simTime - this->startTime > 10 && 
+          this->startPose.pos == Vector3(0,0,0))
+        this->startPose = pose;
+
       if (this->circleCount <= 1)
       {
         if (this->leftWheel->GetRelativeAngularVel().z < 2.2) 
-          this->leftWheel->SetTorque(Vector3(0.0, 0.0, 0.2));
+          this->leftWheel->SetTorque(Vector3(0.0, 0.0, 0.01));
 
         if (this->rightWheel->GetRelativeAngularVel().z > 2.1)
-          this->rightWheel->SetTorque(Vector3(0.0, 0.0, -0.2));
+          this->rightWheel->SetTorque(Vector3(0.0, 0.0, -0.01));
 
-        if (simTime - this->prevTime > 10.0 && fabs(pose.pos.x) < 0.1 )
+        if (simTime - this->prevTime > 10.0 && dist < this->prevDist )
         {
+          this->startPose = pose;
+          std::cout << "CIRCLE\n";
           this->prevTime = simTime;
           this->circleCount++;
         }
       }
       else 
         this->UpdateJob();
+
+      this->prevDist = dist;
     }
 
     public: void UpdateJob()
@@ -179,10 +196,13 @@
     private: Body *rightWheel;
 
     private: FILE *indexFile;
-    private: Time prevTime;
+    private: Time prevTime, startTime;
     private: PhysicsEngine *physics;
     private: unsigned int circleCount;
     private: unsigned int count;
+
+    private: double prevDist;
+    private: Pose3d startPose;
   };
 
   GZ_REGISTER_HANDLER("PioneerCircle", PioneerCircle)

Modified: code/gazebo/branches/simpar/worlds/pioneer2dx.world
===================================================================
--- code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-14 15:02:52 UTC 
(rev 8764)
+++ code/gazebo/branches/simpar/worlds/pioneer2dx.world 2010-06-15 03:40:50 UTC 
(rev 8765)
@@ -24,7 +24,7 @@
     <cfm>0.0000000001</cfm>
     <erp>0.2</erp>
 
-    <stepType>robust</stepType>
+    <stepType>quick</stepType>
     <stepIters>100</stepIters>
     <stepW>1.3</stepW>
     <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>


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