Revision: 6986
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6986&view=rev
Author:   natepak
Date:     2008-08-28 15:49:20 +0000 (Thu, 28 Aug 2008)

Log Message:
-----------
Updates to the bandit model

Modified Paths:
--------------
    code/gazebo/trunk/examples/libgazebo/position/position.cc
    code/gazebo/trunk/server/controllers/Controller.cc
    code/gazebo/trunk/server/controllers/Controller.hh
    code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc
    code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.hh
    code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc
    code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.hh
    code/gazebo/trunk/server/physics/Body.cc
    code/gazebo/trunk/server/physics/Body.hh
    code/gazebo/trunk/server/physics/Joint.cc
    code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
    code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
    code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
    code/gazebo/trunk/worlds/bandit.world
    code/gazebo/trunk/worlds/models/bandit.model
    code/gazebo/trunk/worlds/simpleshapes.world

Added Paths:
-----------
    code/gazebo/trunk/Media/models/bandit/left_eyebrow.mesh
    code/gazebo/trunk/Media/models/bandit/lowerlip.mesh
    code/gazebo/trunk/Media/models/bandit/right_eyebrow.mesh
    code/gazebo/trunk/Media/models/bandit/upperlip.mesh
    code/gazebo/trunk/examples/libgazebo/bandit/
    code/gazebo/trunk/examples/libgazebo/bandit/SConstruct
    code/gazebo/trunk/examples/libgazebo/bandit/bandit.cc


Property changes on: code/gazebo/trunk/Media/models/bandit/left_eyebrow.mesh
___________________________________________________________________
Added: svn:mime-type
   + application/octet-stream


Property changes on: code/gazebo/trunk/Media/models/bandit/lowerlip.mesh
___________________________________________________________________
Added: svn:mime-type
   + application/octet-stream


Property changes on: code/gazebo/trunk/Media/models/bandit/right_eyebrow.mesh
___________________________________________________________________
Added: svn:mime-type
   + application/octet-stream


Property changes on: code/gazebo/trunk/Media/models/bandit/upperlip.mesh
___________________________________________________________________
Added: svn:mime-type
   + application/octet-stream

Added: code/gazebo/trunk/examples/libgazebo/bandit/SConstruct
===================================================================
--- code/gazebo/trunk/examples/libgazebo/bandit/SConstruct                      
        (rev 0)
+++ code/gazebo/trunk/examples/libgazebo/bandit/SConstruct      2008-08-28 
15:49:20 UTC (rev 6986)
@@ -0,0 +1,16 @@
+
+# 3rd party packages
+parseConfigs=['pkg-config --cflags --libs libgazebo',
+              'pkg-config --cflags --libs libgazeboServer']
+
+
+env = Environment (
+  CC = 'g++',
+  CCFLAGS = Split ('-pthread -pipe  -W -Wall -O2'),
+)
+
+# Parse all the package configurations
+for cfg in parseConfigs:
+  env.ParseConfig(cfg)
+
+env.Program('bandit','bandit.cc')

Added: code/gazebo/trunk/examples/libgazebo/bandit/bandit.cc
===================================================================
--- code/gazebo/trunk/examples/libgazebo/bandit/bandit.cc                       
        (rev 0)
+++ code/gazebo/trunk/examples/libgazebo/bandit/bandit.cc       2008-08-28 
15:49:20 UTC (rev 6986)
@@ -0,0 +1,59 @@
+#include <gazebo/gazebo.h>
+#include <gazebo/GazeboError.hh>
+
+int main()
+{
+  gazebo::Client *client = new gazebo::Client();
+  gazebo::SimulationIface *simIface = new gazebo::SimulationIface();
+  gazebo::ActarrayIface *actarrayIface = new gazebo::ActarrayIface();
+
+  int serverId = 0;
+
+  /// Connect to the libgazebo server
+  try
+  {
+    client->ConnectWait(serverId, GZ_CLIENT_ID_USER_FIRST);
+  }
+  catch (gazebo::GazeboError e)
+  {
+    std::cout << "Gazebo error: Unable to connect\n" << e << "\n";
+    return -1;
+  }
+
+  /// Open the Simulation Interface
+  try
+  {
+    simIface->Open(client, "default");
+  }
+  catch (gazebo::GazeboError e)
+  {
+    std::cout << "Gazebo error: Unable to connect to the sim interface\n" << e 
<< "\n";
+    return -1;
+  }
+
+  /// Open the Actuator Array interface
+  try
+  {
+    actarrayIface->Open(client, "bandit_actarray_iface");
+  }
+  catch (std::string e)
+  {
+    std::cout << "Gazebo error: Unable to connect to the actarray interface\n"
+    << e << "\n";
+    return -1;
+  }
+
+  while (true)
+  {
+    actarrayIface->Lock(1);
+    actarrayIface->data->cmd_pos[16] = 0.3;
+    actarrayIface->data->cmd_pos[17] = -0.3;
+    actarrayIface->data->cmd_pos[18] = 0.3;
+    actarrayIface->data->cmd_pos[19] = -0.3;
+    actarrayIface->Unlock();
+
+    usleep(100000);
+  }
+  return 0;
+}
+

Modified: code/gazebo/trunk/examples/libgazebo/position/position.cc
===================================================================
--- code/gazebo/trunk/examples/libgazebo/position/position.cc   2008-08-28 
01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/examples/libgazebo/position/position.cc   2008-08-28 
15:49:20 UTC (rev 6986)
@@ -51,7 +51,7 @@
   while (true)
   {
     posIface->Lock(1);
-    posIface->data->cmdVelocity.pos.x += 10;
+    posIface->data->cmdVelocity.pos.x = 0.2;
     posIface->Unlock();
 
     usleep(100000);

Modified: code/gazebo/trunk/server/controllers/Controller.cc
===================================================================
--- code/gazebo/trunk/server/controllers/Controller.cc  2008-08-28 01:30:51 UTC 
(rev 6985)
+++ code/gazebo/trunk/server/controllers/Controller.cc  2008-08-28 15:49:20 UTC 
(rev 6986)
@@ -176,10 +176,13 @@
 /// Update the controller. Called every cycle.
 void Controller::Update()
 {
-  if (lastUpdate + updatePeriod <= Simulator::Instance()->GetSimTime())
+  if (this->IsConnected())
   {
-    this->UpdateChild();
-    lastUpdate = Simulator::Instance()->GetSimTime();
+    if (lastUpdate + updatePeriod <= Simulator::Instance()->GetSimTime())
+    {
+      this->UpdateChild();
+      lastUpdate = Simulator::Instance()->GetSimTime();
+    }
   }
 }
 
@@ -200,6 +203,21 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Return true if an interface is open 
+bool Controller::IsConnected() const
+{
+  std::vector<Iface*>::const_iterator iter;
+
+  for (iter=this->ifaces.begin(); iter!=this->ifaces.end(); iter++)
+  {
+    if ((*iter)->GetOpenCount() > 0)
+      return true;
+  }
+
+  return false;
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Get the name of the controller
 std::string Controller::GetName() const
 {

Modified: code/gazebo/trunk/server/controllers/Controller.hh
===================================================================
--- code/gazebo/trunk/server/controllers/Controller.hh  2008-08-28 01:30:51 UTC 
(rev 6985)
+++ code/gazebo/trunk/server/controllers/Controller.hh  2008-08-28 15:49:20 UTC 
(rev 6986)
@@ -74,6 +74,9 @@
   /// \brief Finialize the controller. Called once on completion.
   public: void Fini();
 
+  /// \brief Return true if an interface is open 
+  public: bool IsConnected() const;
+
   /// \brief Load function for the child class
   protected: virtual void LoadChild(XMLConfigNode * /*node*/) {return;}
 

Modified: 
code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc
===================================================================
--- code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc     
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.cc     
2008-08-28 15:49:20 UTC (rev 6986)
@@ -55,7 +55,7 @@
 // Destructor
 Bandit_Actarray::~Bandit_Actarray()
 {
-  for (int i=0; i<16; i++)
+  for (int i=0; i<JOINTCNT; i++)
   {
     GZ_DELETE(this->jointNamesP[i]);
     GZ_DELETE(this->forcesP[i]);
@@ -96,7 +96,7 @@
 /// Save the controller.
 void Bandit_Actarray::SaveChild(std::string &prefix, std::ostream &stream)
 {
-  for (int i=0; i<16; i++)
+  for (int i=0; i<JOINTCNT; i++)
   {
     stream << prefix << "<joint name=\"" << this->jointNamesP[i]->GetValue() 
<< "\">\n";
     stream << prefix << "  " << *(this->forcesP[i]) << "\n";
@@ -109,7 +109,7 @@
 // Initialize the controller
 void Bandit_Actarray::InitChild()
 {
-  for (int i=0; i<16; i++)
+  for (int i=0; i<JOINTCNT; i++)
   {
     this->joints[i]->SetParam( dParamVel, 0.0);
     this->joints[i]->SetParam( dParamFMax, **(this->forcesP[i]) );
@@ -126,9 +126,9 @@
   this->myIface->Lock(1);
   this->myIface->data->head.time = Simulator::Instance()->GetSimTime();
 
-  this->myIface->data->actuators_count = 16;
+  this->myIface->data->actuators_count = JOINTCNT;
 
-  for (unsigned int i=0; i<16; i++)
+  for (unsigned int i=0; i<JOINTCNT; i++)
   {
     double cmdAngle = this->myIface->data->cmd_pos[i];
     double cmdSpeed = this->myIface->data->cmd_speed[i];
@@ -153,6 +153,7 @@
         joint->SetParam( dParamVel, **(this->gainsP[i]) * angle);
         joint->SetParam( dParamFMax, **(this->forcesP[i]) );
       }
+
     }
     else if (this->myIface->data->joint_mode[i] == 
GAZEBO_ACTARRAY_JOINT_SPEED_MODE)
     {

Modified: 
code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.hh
===================================================================
--- code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.hh     
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/controllers/actarray/bandit/Bandit_Actarray.hh     
2008-08-28 15:49:20 UTC (rev 6986)
@@ -31,6 +31,8 @@
 #include "Controller.hh"
 #include "Entity.hh"
 
+#define JOINTCNT 20
+
 namespace gazebo
 {
   class HingeJoint;
@@ -90,10 +92,10 @@
   /// The parent Model
   private: Model *myParent;
 
-  private: Param<std::string> *jointNamesP[16];
-  private: HingeJoint *joints[16];
-  private: Param<float> *forcesP[16];
-  private: Param<float> *gainsP[16];
+  private: Param<std::string> *jointNamesP[JOINTCNT];
+  private: HingeJoint *joints[JOINTCNT];
+  private: Param<float> *forcesP[JOINTCNT];
+  private: Param<float> *gainsP[JOINTCNT];
 
 };
 

Modified: code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc
===================================================================
--- code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.cc 
2008-08-28 15:49:20 UTC (rev 6986)
@@ -103,6 +103,16 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// True if a stereo iface is connected
+bool Stereo_Camera::StereoIfaceConnected() const
+{
+  if (this->stereoIface)
+    return this->stereoIface->GetOpenCount() > 0;
+  else
+    return false;
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Update the controller
 void Stereo_Camera::UpdateChild()
 {

Modified: code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.hh
===================================================================
--- code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.hh 
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/controllers/camera/stereo/Stereo_Camera.hh 
2008-08-28 15:49:20 UTC (rev 6986)
@@ -30,6 +30,7 @@
 
 #include <map>
 
+#include "Stereo_Camera.hh"
 #include "Param.hh"
 #include "Controller.hh"
 
@@ -75,6 +76,9 @@
   /// \brief Destructor
   public: virtual ~Stereo_Camera();
 
+  /// \brief True if a stereo iface is connected
+  public: bool StereoIfaceConnected() const;
+
   /// \brief Load the controller
   /// \param node XML config node
   /// \return 0 on success

Modified: code/gazebo/trunk/server/physics/Body.cc
===================================================================
--- code/gazebo/trunk/server/physics/Body.cc    2008-08-28 01:30:51 UTC (rev 
6985)
+++ code/gazebo/trunk/server/physics/Body.cc    2008-08-28 15:49:20 UTC (rev 
6986)
@@ -213,12 +213,12 @@
   std::vector< Sensor* >::iterator sensorIter;
   std::vector< Geom* >::iterator geomIter;
 
+  this->UpdatePose();
+
   if (!this->IsStatic())
   {
-    Pose3d pose = this->GetPose();
-
     // Set the pose of the scene node
-    this->visualNode->SetPose(pose);
+    this->visualNode->SetPose(this->pose);
   }
 
   for (geomIter=this->geoms.begin();
@@ -256,8 +256,9 @@
 // Set the pose of the body
 void Body::SetPose(const Pose3d &pose)
 {
-  Pose3d localPose;
 
+  this->pose = pose;
+
   if (this->IsStatic())
   {
     Pose3d oldPose = this->staticPose;
@@ -279,8 +280,10 @@
   }
   else
   {
+    Pose3d localPose;
+
     // Compute pose of CoM
-    localPose = this->comPose + pose;
+    localPose = this->comPose + this->pose;
 
     this->SetPosition(localPose.pos);
     this->SetRotation(localPose.rot);
@@ -291,21 +294,20 @@
 // Return the pose of the body
 Pose3d Body::GetPose() const
 {
-  Pose3d pose;
-
   if (this->IsStatic())
-  {
-    pose = this->staticPose;
-  }
+    return this->staticPose;
   else
-  {
-    pose.pos = this->GetPosition();
-    pose.rot = this->GetRotation();
+    return this->pose;
+}
 
-    pose = this->comPose.CoordPoseSolve(pose);
-  }
+////////////////////////////////////////////////////////////////////////////////
+// Update the pose of the body
+void Body::UpdatePose()
+{
+  this->pose.pos = this->GetPosition();
+  this->pose.rot = this->GetRotation();
 
-  return pose;
+  this->pose = this->comPose.CoordPoseSolve(pose);
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/trunk/server/physics/Body.hh
===================================================================
--- code/gazebo/trunk/server/physics/Body.hh    2008-08-28 01:30:51 UTC (rev 
6985)
+++ code/gazebo/trunk/server/physics/Body.hh    2008-08-28 15:49:20 UTC (rev 
6986)
@@ -150,7 +150,10 @@
   
     /// \brief Load a renderable
     private: void LoadVisual(XMLConfigNode *node);
-  
+
+    /// \brief Update the pose of the body
+    private: void UpdatePose();
+ 
     /// List of geometries attached to this body
     private: std::vector< Geom* > geoms;
   
@@ -167,6 +170,7 @@
   
     private: Pose3d comPose;
     private: Pose3d staticPose;
+    private: Pose3d pose;
   
     private: Param<Vector3> *xyzP;
     private: Param<Quatern> *rpyP;

Modified: code/gazebo/trunk/server/physics/Joint.cc
===================================================================
--- code/gazebo/trunk/server/physics/Joint.cc   2008-08-28 01:30:51 UTC (rev 
6985)
+++ code/gazebo/trunk/server/physics/Joint.cc   2008-08-28 15:49:20 UTC (rev 
6986)
@@ -42,7 +42,7 @@
 
   this->nameP = new Param<std::string>("name","",1);
   this->erpP = new Param<double>("erp",0.4,0);
-  this->cfmP = new Param<double>("cfm",0.8,0);
+  this->cfmP = new Param<double>("cfm",10e-3,0);
   this->suspensionCfmP = new Param<double>("suspensionCfm",0.0,0);
   this->body1NameP = new Param<std::string>("body1",std::string(),1);
   this->body2NameP = new Param<std::string>("body2",std::string(),1);

Modified: code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-08-28 
01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/sensors/camera/MonoCameraSensor.cc 2008-08-28 
15:49:20 UTC (rev 6986)
@@ -131,6 +131,12 @@
 // Update the drawing
 void MonoCameraSensor::UpdateChild()
 {
+  // Only continue if the controller has an active interface. Or frames need
+  // to be saved
+  if ( (this->controller && !this->controller->IsConnected()) &&
+       !this->saveFramesP->GetValue())
+    return;
+
   this->UpdateCam();
 
   this->renderTarget->update();

Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.cc       
2008-08-28 15:49:20 UTC (rev 6986)
@@ -140,6 +140,7 @@
   this->renderTarget = this->renderTargets[D_LEFT];
 
   this->InitCam();
+
   // Hack to make the camera use the right render target too.
   for (i=0; i<4; i++)
   {
@@ -206,6 +207,12 @@
   Ogre::SceneNode *gridNode = NULL;
   int i;
 
+  // Only continue if the controller has an active interface. Or frames need
+  // to be saved
+  if ( (this->controller && !this->controller->IsConnected()) &&
+       !this->saveFramesP->GetValue())
+    return;
+
   this->UpdateCam();
 
   try
@@ -236,7 +243,6 @@
     // we have to set the distance every time.
     this->GetOgreCamera()->setFarClipDistance( this->farClipP->GetValue() );
 
-
     Ogre::AutoParamDataSource autoParamDataSource;
 
     vp = this->renderTargets[i]->getViewport(0);

Modified: code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh
===================================================================
--- code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh       
2008-08-28 01:30:51 UTC (rev 6985)
+++ code/gazebo/trunk/server/sensors/camera/StereoCameraSensor.hh       
2008-08-28 15:49:20 UTC (rev 6986)
@@ -120,7 +120,7 @@
     private: double baseline;
   
     private: Ogre::Camera *depthCamera;
-  
+
     /*private: 
              class StereoCameraListener : public Ogre::RenderTargetListener
              {

Modified: code/gazebo/trunk/worlds/bandit.world
===================================================================
--- code/gazebo/trunk/worlds/bandit.world       2008-08-28 01:30:51 UTC (rev 
6985)
+++ code/gazebo/trunk/worlds/bandit.world       2008-08-28 15:49:20 UTC (rev 
6986)
@@ -19,17 +19,25 @@
     <stepTime>0.3</stepTime>
     <gravity>0 0 -9.8</gravity>
     <cfm>10e-5</cfm>
-    <erp>0.3</erp>
+    <erp>0.1</erp>
   </physics:ode>
 
   <rendering:gui>
     <type>fltk</type>
     <size>800 600</size>
     <pos>0 0</pos>
+    <frames>
+      <row height="100%">
+        <camera width="100%">
+          <xyz>2.16 0.0 0.86</xyz>
+          <rpy>0 16.5 179.50</rpy>
+        </camera>
+      </row>
+    </frames>
   </rendering:gui>
 
   <rendering:ogre>
-    <ambient>1.0 1.0 1.0 1.0</ambient>
+    <ambient>0.8 0.8 0.8 1.0</ambient>
     <sky>
       <material>Gazebo/CloudySky</material>
     </sky>
@@ -58,7 +66,6 @@
       <xi:include href="models/pioneer2dx.model" />
     </include>
 
-
     <model:physical name="box_model">
       <xyz>0.15 0 0.125</xyz>
       <static>false</static>
@@ -82,6 +89,7 @@
 
       <model:physical name="bandit">
         <xyz>0.02 0 0.49</xyz>
+        <static>false</static>
 
         <attach>
           <parentBody>box_body</parentBody>
@@ -135,11 +143,11 @@
   <model:renderable name="directional_white">
     <light>
       <type>directional</type>
-      <direction>0 -0.5 -0.5</direction>
-      <diffuseColor>0.4 0.4 0.4</diffuseColor>
+      <direction>-1 1.0 -0.5</direction>
+      <diffuseColor>0.2 0.2 0.2</diffuseColor>
       <specularColor>0.0 0.0 0.0</specularColor>
       <attenuation>100 0.0 1.0 0.4</attenuation>
     </light>
   </model:renderable>
-  
+
 </gazebo:world>

Modified: code/gazebo/trunk/worlds/models/bandit.model
===================================================================
--- code/gazebo/trunk/worlds/models/bandit.model        2008-08-28 01:30:51 UTC 
(rev 6985)
+++ code/gazebo/trunk/worlds/models/bandit.model        2008-08-28 15:49:20 UTC 
(rev 6986)
@@ -484,9 +484,117 @@
     <highStop>20</highStop>
   </joint:hinge>
 
+  <body name="left_eyebrow_body">
+    <xyz>0.035 0.041 0.034</xyz>
+    <rpy>85 0 -70</rpy>
+
+    <geom:box name="left_eyebrow_geom">
+      <size>0.045 0.02 0.002</size>
+      <mass>0</mass>
+
+      <visual>
+        <size>0.045 0.02 0.002</size>
+        <mesh>bandit/right_eyebrow.mesh</mesh>
+        <material>Gazebo/Black</material>
+      </visual>
+    </geom:box>
+  </body>
+
+  <joint:hinge name="left_eyebrow_hinge">
+    <body1>head_body</body1>
+    <body2>left_eyebrow_body</body2>
+    <anchor>left_eyebrow_body</anchor>
+    <anchorOffset>-0.01 0.01 0</anchorOffset>
+    <axis>1 0 0</axis>
+    <lowStop>-70</lowStop>
+    <highStop>70</highStop>
+  </joint:hinge>
+
+  <body name="right_eyebrow_body">
+    <xyz>0.035 -0.041 0.034</xyz>
+    <rpy>95 16 -110</rpy>
+
+    <geom:box name="right_eyebrow_geom">
+      <size>0.045 0.02 0.002</size>
+      <mass>0</mass>
+      <visual>
+        <size>0.045 0.02 0.002</size>
+        <mesh>bandit/right_eyebrow.mesh</mesh>
+        <material>Gazebo/Black</material>
+      </visual>
+    </geom:box>
+  </body>
+
+  <joint:hinge name="right_eyebrow_hinge">
+    <body1>head_body</body1>
+    <body2>right_eyebrow_body</body2>
+    <anchor>right_eyebrow_body</anchor>
+    <anchorOffset>-0.01 -0.01 0</anchorOffset>
+    <axis>1 0 0</axis>
+    <lowStop>-70</lowStop>
+    <highStop>70</highStop>
+  </joint:hinge>
+
+  <body name="upperlip_body">
+    <xyz>0.044 -0.001 -0.05</xyz>
+    <rpy>0 0 0</rpy>
+
+    <geom:box name="upperlip_geom">
+      <size>0.02 0.08 0.014</size>
+      <mass>0</mass>
+      <visual>
+        <rpy>0 0 -91</rpy>
+        <xyz>0.006 -0.0015 0</xyz>
+        <scale>0.05 0.05 0.05</scale>
+        <mesh>bandit/upperlip.mesh</mesh>
+        <material>Gazebo/Red</material>
+      </visual>
+    </geom:box>
+  </body>
+
+  <joint:hinge name="upperlip_hinge">
+    <body1>head_body</body1>
+    <body2>upperlip_body</body2>
+    <anchor>upperlip_body</anchor>
+    <anchorOffset>0 -0.042 0.0</anchorOffset>
+    <axis>0 1 0</axis>
+    <lowStop>-20</lowStop>
+    <highStop>20</highStop>
+  </joint:hinge>
+
+  <body name="lowerlip_body">
+    <xyz>0.044 0.0 -0.06</xyz>
+    <rpy>0 0 0</rpy>
+
+    <geom:box name="lowerlip_geom">
+      <size>0.02 0.08 0.014</size>
+      <mass>0</mass>
+
+      <visual>
+        <rpy>90 0 90</rpy>
+        <xyz>0.01 0 -0.015</xyz>
+        <scale>0.09 0.1 0.1</scale>
+        <mesh>bandit/lowerlip.mesh</mesh>
+        <material>Gazebo/Red</material>
+      </visual>
+    </geom:box>
+  </body>
+
+  <joint:hinge name="lowerlip_hinge">
+    <body1>head_body</body1>
+    <body2>lowerlip_body</body2>
+    <anchor>lowerlip_body</anchor>
+    <anchorOffset>0.0 -0.042 0</anchorOffset>
+    <axis>0 1 0</axis>
+    <lowStop>-20</lowStop>
+    <highStop>20</highStop>
+  </joint:hinge>
+
+
+
   <controller:bandit_actarray name="bandit_controller">
     <joint name="head_neck_hinge">
-      <force>2</force>
+      <force>1</force>
       <gain>2</gain>
     </joint>
 
@@ -565,6 +673,26 @@
       <gain>2</gain>
     </joint>
 
+    <joint name="left_eyebrow_hinge">
+      <force>1</force>
+      <gain>2</gain>
+    </joint>
+
+    <joint name="right_eyebrow_hinge">
+      <force>1</force>
+      <gain>2</gain>
+    </joint>
+
+    <joint name="lowerlip_hinge">
+      <force>1</force>
+      <gain>2</gain>
+    </joint>
+
+    <joint name="upperlip_hinge">
+      <force>1</force>
+      <gain>2</gain>
+    </joint>
+
     <interface:actarray name="bandit_actarray_iface"/>
 
   </controller:bandit_actarray>

Modified: code/gazebo/trunk/worlds/simpleshapes.world
===================================================================
--- code/gazebo/trunk/worlds/simpleshapes.world 2008-08-28 01:30:51 UTC (rev 
6985)
+++ code/gazebo/trunk/worlds/simpleshapes.world 2008-08-28 15:49:20 UTC (rev 
6986)
@@ -38,16 +38,17 @@
   <model:physical name="sphere1_model">
     <xyz>1 0 0.5</xyz>
     <rpy>0.0 0.0 0.0</rpy>
-    <static>true</static>
+    <static>false</static>
 
     <body:sphere name="sphere1_body">
       <geom:sphere name="sphere1_geom">
-        <size>0.5</size>
+        <size>0.25</size>
         <mass>0.0</mass>
 
         <mu1>109999.0</mu1>
 
         <visual>
+          <size>0.5 0.5 0.5</size>
           <mesh>unit_sphere</mesh>
           <material>Gazebo/Rocky</material>
         </visual>
@@ -74,7 +75,6 @@
     </body:box>
   </model:physical>
 
-  <!--
   <model:physical name="cylinder1_model">
     <xyz>1 -1.5 0.5</xyz>
     <rpy>0.0 0.0 0.0</rpy>
@@ -92,7 +92,6 @@
       </geom:cylinder>
     </body:cylinder>
   </model:physical>
-  -->
 
    <!-- Ground Plane -->
    <model:physical name="plane1_model">


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

-------------------------------------------------------------------------
This SF.Net email is sponsored by the Moblin Your Move Developer's challenge
Build the coolest Linux based applications with Moblin SDK & win great prizes
Grand prize is a trip for two to an Open Source event anywhere in the world
http://moblin-contest.org/redirect.php?banner_id=100&url=/
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to