Revision: 9027
          http://playerstage.svn.sourceforge.net/playerstage/?rev=9027&view=rev
Author:   natepak
Date:     2011-01-18 17:23:26 +0000 (Tue, 18 Jan 2011)

Log Message:
-----------
Fixed show physics

Modified Paths:
--------------
    code/gazebo/branches/dev/server/GraphicsIfaceHandler.cc
    code/gazebo/branches/dev/server/Messages.hh
    code/gazebo/branches/dev/server/World.cc
    code/gazebo/branches/dev/server/physics/Body.cc
    code/gazebo/branches/dev/server/physics/Body.hh
    code/gazebo/branches/dev/server/physics/Geom.cc
    code/gazebo/branches/dev/server/physics/Joint.cc
    code/gazebo/branches/dev/server/physics/MultiRayShape.cc
    code/gazebo/branches/dev/server/physics/RayShape.cc
    code/gazebo/branches/dev/server/rendering/OgreDynamicLines.cc
    code/gazebo/branches/dev/server/rendering/OgreDynamicLines.hh
    code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.cc
    code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.hh
    code/gazebo/branches/dev/server/rendering/RenderTypes.hh
    code/gazebo/branches/dev/server/rendering/Visual.cc
    code/gazebo/branches/dev/server/rendering/Visual.hh
    code/gazebo/branches/dev/server/wx/BoxMaker.cc
    code/gazebo/branches/dev/server/wx/CylinderMaker.cc
    code/gazebo/branches/dev/server/wx/SphereMaker.cc
    code/gazebo/branches/dev/worlds/new/empty.world

Modified: code/gazebo/branches/dev/server/GraphicsIfaceHandler.cc
===================================================================
--- code/gazebo/branches/dev/server/GraphicsIfaceHandler.cc     2011-01-18 
05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/GraphicsIfaceHandler.cc     2011-01-18 
17:23:26 UTC (rev 9027)
@@ -171,7 +171,7 @@
 {
   Vector3 pos;
   bool attached = false;
-  OperationType opType;
+  RenderOpType opType;
   OgreDynamicLines *line;
 
   switch(data->drawMode)

Modified: code/gazebo/branches/dev/server/Messages.hh
===================================================================
--- code/gazebo/branches/dev/server/Messages.hh 2011-01-18 05:31:59 UTC (rev 
9026)
+++ code/gazebo/branches/dev/server/Messages.hh 2011-01-18 17:23:26 UTC (rev 
9027)
@@ -3,6 +3,7 @@
 
 #include <vector>
 
+#include "RenderTypes.hh"
 #include "Color.hh"
 #include "Vector3.hh"
 #include "Time.hh"
@@ -66,7 +67,6 @@
   class VisualMsg : public Message
   {
     public: enum ActionType {UPDATE, DELETE};
-    public: enum RenderType {MESH_RESOURCE, POINTS, LINE_LIST, LINE_STRIP, 
TRIANGLE_FAN};
 
     public: VisualMsg();
     public: VisualMsg(const VisualMsg &m);
@@ -78,7 +78,7 @@
     public: std::string parentId;
     public: std::string id;
     public: ActionType action;
-    public: RenderType render;
+    public: RenderOpType render;
     public: std::string mesh;
     public: std::string material;
     public: bool castShadows;

Modified: code/gazebo/branches/dev/server/World.cc
===================================================================
--- code/gazebo/branches/dev/server/World.cc    2011-01-18 05:31:59 UTC (rev 
9026)
+++ code/gazebo/branches/dev/server/World.cc    2011-01-18 17:23:26 UTC (rev 
9027)
@@ -215,6 +215,7 @@
   this->worldStatesInsertIter = this->worldStates.begin();
   this->worldStatesEndIter = this->worldStates.begin();
   this->worldStatesCurrentIter = this->worldStatesInsertIter;
+
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/branches/dev/server/physics/Body.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Body.cc     2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/physics/Body.cc     2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -59,8 +59,6 @@
   // NATY: put back in functionality
   // this->GetVisualNode()->SetShowInGui(false);
 
-  this->cgVisualMsg = NULL;
-
   this->comEntity = new Entity(this);
   this->comEntity->SetName("COM_Entity");
   this->comEntity->SetShowInGui(false);
@@ -112,12 +110,15 @@
   std::vector<Entity*>::iterator iter;
   std::vector< Sensor* >::iterator siter;
 
-  if (this->cgVisualMsg)
+  if (this->cgVisualMsgs.size() > 0)
   {
-    this->cgVisualMsg->action = VisualMsg::DELETE;
-    Simulator::Instance()->SendMessage(*this->cgVisualMsg);
-    delete this->cgVisualMsg;
-    this->cgVisualMsg = NULL;
+    for (unsigned int i=0; i < this->cgVisualMsgs.size(); i++)
+    {
+      this->cgVisualMsgs[i]->action = VisualMsg::DELETE;
+      Simulator::Instance()->SendMessage(*this->cgVisualMsgs[i]);
+      delete this->cgVisualMsgs[i];
+    }
+    this->cgVisualMsgs.clear();
   }
 
   for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
@@ -382,38 +383,39 @@
     std::ostringstream visname;
     visname << this->GetCompleteScopedName() + ":" + this->GetName() << 
"_CGVISUAL" ;
 
-    this->cgVisualMsg = new VisualMsg();
-    this->cgVisualMsg->parentId = this->comEntity->GetCompleteScopedName();
-    this->cgVisualMsg->id = visname.str();
-    this->cgVisualMsg->render = VisualMsg::MESH_RESOURCE;
-    this->cgVisualMsg->mesh = "body_cg";
-    this->cgVisualMsg->material = "Gazebo/Red";
-    this->cgVisualMsg->castShadows = false;
-    this->cgVisualMsg->attachAxes = true;
-    this->cgVisualMsg->visible = false;
-    this->cgVisualMsg->size.Set(0.1, 0.1, 0.1);
-    Simulator::Instance()->SendMessage(*this->cgVisualMsg);
-    this->cgVisualMsg->size.Set(100, 100, 100);
+    VisualMsg *msg;
+    msg = new VisualMsg();
+    msg->parentId = this->comEntity->GetCompleteScopedName();
+    msg->id = visname.str();
+    msg->render = RENDERING_MESH_RESOURCE;
+    msg->mesh = "unit_box";
+    msg->material = "Gazebo/Red";
+    msg->castShadows = false;
+    msg->attachAxes = true;
+    msg->visible = false;
+    msg->size.Set(0.1, 0.1, 0.1);
+    Simulator::Instance()->SendMessage(*msg);
+    this->cgVisualMsgs.push_back( msg );
 
-    /*VisualMsg msg;
-    msg.parentId = this->cgVisualMsg->id;
-    msg.render = VisualMsg::LINE_LIST;
-    msg.attachAxes = false;
-    msg.material = "Gazebo/GreenGlow";
-
-    // Create a line to each geom
-    for (std::map< std::string, Geom* >::iterator giter = this->geoms.begin(); 
-         giter != this->geoms.end(); giter++)
+    if (this->geoms.size() > 1)
     {
-      msg.points.clear();
+      msg = new VisualMsg();
+      msg->parentId = this->comEntity->GetCompleteScopedName();
+      msg->id = visname.str() + "_connectors";
+      msg->render = RENDERING_LINE_LIST;
+      msg->attachAxes = false;
+      msg->material = "Gazebo/GreenGlow";
+      msg->visible = false;
 
-      msg.id = visname.str() + "_lineto_" + giter->first;
-      msg.points.push_back( Vector3(0,0,0) );
-      msg.points.push_back(giter->second->GetRelativePose().pos);
-
-      Simulator::Instance()->SendMessage(msg);
+      // Create a line to each geom
+      for (std::map< std::string, Geom* >::iterator giter = 
this->geoms.begin(); giter != this->geoms.end(); giter++)
+      {
+        msg->points.push_back( Vector3(0,0,0) );
+        msg->points.push_back(giter->second->GetRelativePose().pos);
+      }
+      Simulator::Instance()->SendMessage(*msg);
+      this->cgVisualMsgs.push_back( msg );
     }
-    */
   }
 
   this->enabled = true;
@@ -703,16 +705,22 @@
 /// Toggle show the physics visualizations
 void Body::ToggleShowPhysics()
 {
-  this->cgVisualMsg->visible = !this->cgVisualMsg->visible;
-  Simulator::Instance()->SendMessage(*this->cgVisualMsg);
+  for (unsigned int i=0; i < this->cgVisualMsgs.size(); i++)
+  {
+    this->cgVisualMsgs[i]->visible = !this->cgVisualMsgs[i]->visible;
+    Simulator::Instance()->SendMessage(*this->cgVisualMsgs[i]);
+  }
 }
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Set to true to show the physics visualizations
 void Body::ShowPhysics(bool show)
 {
-  this->cgVisualMsg->visible = show;
-  Simulator::Instance()->SendMessage(*this->cgVisualMsg);
+  for (unsigned int i=0; i < this->cgVisualMsgs.size(); i++)
+  {
+    this->cgVisualMsgs[i]->visible = show;
+    Simulator::Instance()->SendMessage(*this->cgVisualMsgs[i]);
+  }
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/branches/dev/server/physics/Body.hh
===================================================================
--- code/gazebo/branches/dev/server/physics/Body.hh     2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/physics/Body.hh     2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -270,7 +270,7 @@
     protected: ParamT<bool> *turnGravityOffP;
     protected: ParamT<bool> *selfCollideP;
 
-    protected: VisualMsg *cgVisualMsg;
+    protected: std::vector<VisualMsg *> cgVisualMsgs;
 
     protected: Vector3 linearAccel;
     protected: Vector3 angularAccel;

Modified: code/gazebo/branches/dev/server/physics/Geom.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Geom.cc     2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/physics/Geom.cc     2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -26,6 +26,7 @@
 
 #include <sstream>
 
+#include "RenderTypes.hh"
 #include "RenderState.hh"
 #include "Events.hh"
 #include "Model.hh"
@@ -177,10 +178,9 @@
 
     msg->parentId = this->GetCompleteScopedName();
     msg->id = visname.str();
-    msg->render = VisualMsg::MESH_RESOURCE;
+    msg->render = RENDERING_MESH_RESOURCE;
     msg->Load(childNode);
     msg->castShadows = false;
-    msg->pose = this->GetRelativePose();
 
     Simulator::Instance()->SendMessage( *msg );
 
@@ -207,7 +207,7 @@
 
     this->bbVisualMsg = new VisualMsg();
 
-    this->bbVisualMsg->render = VisualMsg::MESH_RESOURCE;
+    this->bbVisualMsg->render = RENDERING_MESH_RESOURCE;
     this->bbVisualMsg->parentId = this->GetCompleteScopedName();
     this->bbVisualMsg->id = this->GetCompleteScopedName() + "_BBVISUAL";
     this->bbVisualMsg->castShadows = false;

Modified: code/gazebo/branches/dev/server/physics/Joint.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Joint.cc    2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/physics/Joint.cc    2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -162,7 +162,7 @@
   this->visualMsg = new VisualMsg();
   this->visualMsg->parentId = this->GetName();
   this->visualMsg->id = visname.str();
-  this->visualMsg->render = VisualMsg::MESH_RESOURCE;
+  this->visualMsg->render = RENDERING_MESH_RESOURCE;
   this->visualMsg->pose.pos = this->anchorPos;
   this->visualMsg->castShadows = false;
   this->visualMsg->mesh = "joint_anchor";
@@ -172,7 +172,7 @@
   this->line1Msg = new VisualMsg();
   this->line1Msg->parentId = this->visualMsg->id;
   this->line1Msg->id = "line1";
-  this->line1Msg->render = VisualMsg::LINE_LIST;
+  this->line1Msg->render = RENDERING_LINE_LIST;
   this->line1Msg->material = "Gazebo/BlueGlow";
   this->line1Msg->points.push_back(Vector3(0,0,0));
   this->line1Msg->points.push_back(Vector3(0,0,0));
@@ -180,7 +180,7 @@
   this->line2Msg = new VisualMsg();
   this->line2Msg->parentId = this->visualMsg->id;
   this->line2Msg->id = "line2";
-  this->line2Msg->render = VisualMsg::LINE_LIST;
+  this->line2Msg->render = RENDERING_LINE_LIST;
   this->line2Msg->material = "Gazebo/BlueGlow";
   this->line2Msg->points.push_back(Vector3(0,0,0));
   this->line2Msg->points.push_back(Vector3(0,0,0));

Modified: code/gazebo/branches/dev/server/physics/MultiRayShape.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/MultiRayShape.cc    2011-01-18 
05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/physics/MultiRayShape.cc    2011-01-18 
17:23:26 UTC (rev 9027)
@@ -14,13 +14,13 @@
   this->rayFanMsg = new VisualMsg();
   this->rayFanMsg->id = this->GetName()+"_fan";
   this->rayFanMsg->parentId = this->geomParent->GetName();
-  this->rayFanMsg->render = VisualMsg::TRIANGLE_FAN;
+  this->rayFanMsg->render = RENDERING_TRIANGLE_FAN;
   this->rayFanMsg->material = "Gazebo/BlueLaser";
 
   this->rayFanOutlineMsg = new VisualMsg();
   this->rayFanOutlineMsg->id = this->GetName()+"_fanoutline";
   this->rayFanOutlineMsg->parentId = this->geomParent->GetName();
-  this->rayFanOutlineMsg->render = VisualMsg::LINE_STRIP;
+  this->rayFanOutlineMsg->render = RENDERING_LINE_STRIP;
   this->rayFanOutlineMsg->material = "Gazebo/BlueGlow";
 
   Param::Begin(&this->parameters);

Modified: code/gazebo/branches/dev/server/physics/RayShape.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/RayShape.cc 2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/physics/RayShape.cc 2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -42,7 +42,7 @@
     this->lineMsg = new VisualMsg();
     this->lineMsg->id = this->GetName();
     this->lineMsg->parentId = this->geomParent->GetName();
-    this->lineMsg->render = VisualMsg::LINE_LIST;
+    this->lineMsg->render = RENDERING_LINE_LIST;
 
     // Add two points
     this->lineMsg->points.push_back(Vector3(0,0,0));

Modified: code/gazebo/branches/dev/server/rendering/OgreDynamicLines.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/OgreDynamicLines.cc       
2011-01-18 05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/rendering/OgreDynamicLines.cc       
2011-01-18 17:23:26 UTC (rev 9027)
@@ -37,7 +37,7 @@
 
 enum { POSITION_BINDING, TEXCOORD_BINDING };
 
-OgreDynamicLines::OgreDynamicLines(OperationType opType)
+OgreDynamicLines::OgreDynamicLines(RenderOpType opType)
 {
   this->Init(opType, false);
   this->setCastShadows(false);

Modified: code/gazebo/branches/dev/server/rendering/OgreDynamicLines.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/OgreDynamicLines.hh       
2011-01-18 05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/rendering/OgreDynamicLines.hh       
2011-01-18 17:23:26 UTC (rev 9027)
@@ -42,7 +42,7 @@
 class OgreDynamicLines : public OgreDynamicRenderable
 {
   /// Constructor
-  public: OgreDynamicLines(OperationType opType=RENDERING_LINE_STRIP);
+  public: OgreDynamicLines(RenderOpType opType=RENDERING_LINE_STRIP);
 
   /// Destructor
   public: virtual ~OgreDynamicLines();

Modified: code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.cc  
2011-01-18 05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.cc  
2011-01-18 17:23:26 UTC (rev 9027)
@@ -21,7 +21,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 /// Initializes the dynamic renderable.
-void OgreDynamicRenderable::Init(OperationType operationType, bool useIndices)
+void OgreDynamicRenderable::Init(RenderOpType operationType, bool useIndices)
 {
   this->SetOperationType(operationType);
 
@@ -42,7 +42,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Set the render operation type
-void OgreDynamicRenderable::SetOperationType(OperationType opType)
+void OgreDynamicRenderable::SetOperationType(RenderOpType opType)
 {
   switch (opType)
   {
@@ -74,9 +74,9 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Get the render operation type
-OperationType OgreDynamicRenderable::GetOperationType() const
+RenderOpType OgreDynamicRenderable::GetOperationType() const
 {
-  OperationType type;
+  RenderOpType type;
   switch (this->mRenderOp.operationType)
   {
     case Ogre::RenderOperation::OT_LINE_LIST:

Modified: code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.hh  
2011-01-18 05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/rendering/OgreDynamicRenderable.hh  
2011-01-18 17:23:26 UTC (rev 9027)
@@ -27,13 +27,13 @@
   /// \param operationType The type of render operation to perform.
   /// \param useIndices Specifies whether to use indices to determine the
   /// vertices to use as input.
-  public: void Init(OperationType operationType, bool useIndices=false);
+  public: void Init(RenderOpType operationType, bool useIndices=false);
 
   /// \brief Set the render operation type
-  public: void SetOperationType(OperationType opType);
+  public: void SetOperationType(RenderOpType opType);
 
   /// \brief Get the render operation type
-  public: OperationType GetOperationType() const;
+  public: RenderOpType GetOperationType() const;
 
   /// \brief Implementation of Ogre::SimpleRenderable
   public: virtual Ogre::Real getBoundingRadius(void) const;

Modified: code/gazebo/branches/dev/server/rendering/RenderTypes.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/RenderTypes.hh    2011-01-18 
05:31:59 UTC (rev 9026)
+++ code/gazebo/branches/dev/server/rendering/RenderTypes.hh    2011-01-18 
17:23:26 UTC (rev 9027)
@@ -1,7 +1,7 @@
 #ifndef RENDERING_HH
 #define RENDERING_HH
 
-enum OperationType 
+enum RenderOpType 
 {
   /// A list of points, 1 vertex per point
   RENDERING_POINT_LIST = 0,//Ogre::RenderOperation::OT_POINT_LIST,
@@ -20,6 +20,8 @@
 
   /// A fan of triangles, 3 vertices for the first triangle, and 1 per 
triangle after that
   RENDERING_TRIANGLE_FAN = 5,//Ogre::RenderOperation::OT_TRIANGLE_FAN 
+
+  RENDERING_MESH_RESOURCE = 6
 };
 
 #endif

Modified: code/gazebo/branches/dev/server/rendering/Visual.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Visual.cc 2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/rendering/Visual.cc 2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -195,7 +195,7 @@
   this->sizeP->SetValue(msg->size);
 
   this->Load(NULL);
-  this->SetVisible(msg->visible);
+  this->UpdateFromMsg(msg);
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -283,7 +283,6 @@
   if (obj)
   {
     meshSize = obj->getBoundingBox().getSize();
-    //this->sizeP->SetValue( Vector3(meshSize.x, meshSize.y, meshSize.z) );
   }
 
   // Get the desired size of the mesh
@@ -291,30 +290,15 @@
   {
     this->sizeP->Load(node);
   }
-  /*else
-    this->sizeP->SetValue( Vector3(meshSize.x, meshSize.y, meshSize.z) );
-    */
 
-  // Get and set teh desired scale of the mesh
-  /*if (node && node->GetChild("scale") != NULL)
-  {
-    this->scaleP->Load(node);
-    Vector3 scale = this->scaleP->GetValue();
-    this->sceneNode->setScale(scale.x, scale.y, scale.z);
-  }
-  else
-  {
-  */
-    Vector3 scale = this->sizeP->GetValue();
-    scale.x /= meshSize.x;
-    scale.y /= meshSize.y;
-    scale.z /= meshSize.z;
-    scale.Correct();
+  Vector3 scale = this->sizeP->GetValue();
+  scale.x /= meshSize.x;
+  scale.y /= meshSize.y;
+  scale.z /= meshSize.z;
+  scale.Correct();
 
-    this->scaleP->SetValue( scale );
-    this->sceneNode->setScale(scale.x, scale.y, scale.z);
-  //}
-  
+  this->scaleP->SetValue( scale );
+  this->sceneNode->setScale(scale.x, scale.y, scale.z);
 
   // Set the material of the mesh
   if (**this->materialNameP != "none")
@@ -501,12 +485,7 @@
 ///  Set the scale
 void Visual::SetScale(const Vector3 &scale )
 {
-  Ogre::Vector3 vscale;
-  vscale.x=scale.x;
-  vscale.y=scale.y;
-  vscale.z=scale.z;
-
-  this->sceneNode->setScale(vscale);
+  this->sceneNode->setScale(Ogre::Vector3(scale.x, scale.y, scale.z));
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -753,7 +732,6 @@
 /// Set whether the visual is visible
 void Visual::SetVisible(bool visible, bool cascade)
 {
-  std::cout << "VIs[" << this->GetName() << "]=" << visible << "\n";
   this->sceneNode->setVisible( visible, cascade );
   this->visible = visible;
 }
@@ -1142,7 +1120,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Add a line to the visual
-OgreDynamicLines *Visual::AddDynamicLine(OperationType type)
+OgreDynamicLines *Visual::AddDynamicLine(RenderOpType type)
 {
   Events::ConnectPreRenderSignal( boost::bind(&Visual::Update, this) );
 
@@ -1382,9 +1360,14 @@
   this->SetPose(msg->pose);
   this->SetTransparency(msg->transparency);
   this->SetScale(msg->size);
-  std::cout << "Scale[" << msg->size << "]\n";
-  
-  this->SetVisible(msg->visible, 1);
+  this->SetVisible(msg->visible);
+
+  if (msg->points.size() > 0)
+  {
+    OgreDynamicLines *lines = this->AddDynamicLine(RENDERING_LINE_LIST);
+    for (unsigned int i=0; i < msg->points.size(); i++)
+      lines->AddPoint( msg->points[i] );
+  }
 }
 
 

Modified: code/gazebo/branches/dev/server/rendering/Visual.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/Visual.hh 2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/rendering/Visual.hh 2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -225,7 +225,7 @@
     public: bool GetUseRTShader() const;
 
     /// \brief Add a line to the visual
-    public: OgreDynamicLines *AddDynamicLine(OperationType type);
+    public: OgreDynamicLines *AddDynamicLine(RenderOpType type);
 
     /// \brief Delete a dynamic line
     public: void DeleteDynamicLine(OgreDynamicLines *line);

Modified: code/gazebo/branches/dev/server/wx/BoxMaker.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/BoxMaker.cc      2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/wx/BoxMaker.cc      2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -18,7 +18,7 @@
 {
   this->state = 0;
   this->visualMsg = new VisualMsg();
-  this->visualMsg->render = VisualMsg::MESH_RESOURCE;
+  this->visualMsg->render = RENDERING_MESH_RESOURCE;
   this->visualMsg->mesh = "unit_box_U1V1";
   this->visualMsg->material = "Gazebo/TurquoiseGlowOutline";
 }

Modified: code/gazebo/branches/dev/server/wx/CylinderMaker.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/CylinderMaker.cc 2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/wx/CylinderMaker.cc 2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -16,7 +16,7 @@
 {
   this->state = 0;
   this->visualMsg = new VisualMsg();
-  this->visualMsg->render = VisualMsg::MESH_RESOURCE;
+  this->visualMsg->render = RENDERING_MESH_RESOURCE;
   this->visualMsg->mesh = "unit_cylinder";
   this->visualMsg->material = "Gazebo/TurquoiseGlowOutline";
 }

Modified: code/gazebo/branches/dev/server/wx/SphereMaker.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/SphereMaker.cc   2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/server/wx/SphereMaker.cc   2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -18,7 +18,7 @@
 {
   this->state = 0;
   this->visualMsg = new VisualMsg();
-  this->visualMsg->render = VisualMsg::MESH_RESOURCE;
+  this->visualMsg->render = RENDERING_MESH_RESOURCE;
   this->visualMsg->mesh = "unit_sphere";
   this->visualMsg->material = "Gazebo/TurquoiseGlowOutline";
 }

Modified: code/gazebo/branches/dev/worlds/new/empty.world
===================================================================
--- code/gazebo/branches/dev/worlds/new/empty.world     2011-01-18 05:31:59 UTC 
(rev 9026)
+++ code/gazebo/branches/dev/worlds/new/empty.world     2011-01-18 17:23:26 UTC 
(rev 9027)
@@ -49,7 +49,7 @@
     </model>
 
     <model type="physical" name="box_model">
-      <xyz>0 0 1.5</xyz>
+      <xyz>0 0 0.5</xyz>
       <static>false</static>
       <body name="body">
         <geom type="box" name="geom">
@@ -61,18 +61,40 @@
             <material>Gazebo/Red</material>
           </visual>
         </geom>
+        <geom type="box" name="geom1">
+          <xyz>0 1.0 1.0</xyz>
+          <size>.5 .5 .5</size>
+          <mass>1.0</mass>
+          <visual>
+            <size>.5 .5 .5</size>
+            <mesh>unit_box</mesh>
+            <material>Gazebo/Red</material>
+          </visual>
+        </geom>
+
+        <geom type="box" name="geom2">
+          <xyz>0 -1.0 1.0</xyz>
+          <size>.5 .5 .5</size>
+          <mass>1.0</mass>
+          <visual>
+            <size>.5 .5 .5</size>
+            <mesh>unit_box</mesh>
+            <material>Gazebo/Red</material>
+          </visual>
+        </geom>
+
       </body>
     </model>
 
     <model type="physical" name="sphere_model">
-      <xyz>0 1.5 3.5</xyz>
+      <xyz>0 2.0 1.5</xyz>
       <static>false</static>
       <body name="body">
-        <geom type="box" name="geom">
-          <size>0.5</size>
+        <geom type="sphere" name="geom">
+          <size>0.1</size>
           <mass>1.0</mass>
           <visual>
-            <size>1 1 1</size>
+            <size>.1 .1 .1</size>
             <mesh>unit_sphere</mesh>
             <material>Gazebo/Blue</material>
           </visual>
@@ -81,10 +103,10 @@
     </model>
 
     <model type="physical" name="cylinder_model">
-      <xyz>0 -1.5 1.5</xyz>
+      <xyz>0 -2 1.5</xyz>
       <static>false</static>
       <body name="body">
-        <geom type="box" name="geom">
+        <geom type="cylinder" name="geom">
           <size>0.5 1.0</size>
           <mass>1.0</mass>
           <visual>


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

------------------------------------------------------------------------------
Protect Your Site and Customers from Malware Attacks
Learn about various malware tactics and how to avoid them. Understand 
malware threats, the impact they can have on your business, and how you 
can protect your company and customers by using code signing.
http://p.sf.net/sfu/oracle-sfdevnl
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to