Revision: 9016
          http://playerstage.svn.sourceforge.net/playerstage/?rev=9016&view=rev
Author:   natepak
Date:     2011-01-10 23:52:19 +0000 (Mon, 10 Jan 2011)

Log Message:
-----------
Fixed setting the pose of bodies and geoms

Modified Paths:
--------------
    code/gazebo/branches/dev/server/Common.cc
    code/gazebo/branches/dev/server/Common.hh
    code/gazebo/branches/dev/server/Entity.cc
    code/gazebo/branches/dev/server/Entity.hh
    code/gazebo/branches/dev/server/Messages.cc
    code/gazebo/branches/dev/server/Messages.hh
    code/gazebo/branches/dev/server/Model.cc
    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/PlaneShape.cc
    code/gazebo/branches/dev/server/physics/ode/ODEBody.cc
    code/gazebo/branches/dev/server/physics/ode/ODEPhysics.cc
    code/gazebo/branches/dev/server/rendering/Grid.cc
    code/gazebo/branches/dev/server/rendering/Scene.cc
    code/gazebo/branches/dev/server/rendering/Scene.hh
    code/gazebo/branches/dev/server/rendering/Visual.cc

Modified: code/gazebo/branches/dev/server/Common.cc
===================================================================
--- code/gazebo/branches/dev/server/Common.cc   2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Common.cc   2011-01-10 23:52:19 UTC (rev 
9016)
@@ -88,6 +88,13 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Load 
+void Common::Load(XMLConfigNode *node)
+{
+  this->nameP->Load(node);
+}
+
+////////////////////////////////////////////////////////////////////////////////
 /// Set the name of the entity
 void Common::SetName(const std::string &name)
 {

Modified: code/gazebo/branches/dev/server/Common.hh
===================================================================
--- code/gazebo/branches/dev/server/Common.hh   2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Common.hh   2011-01-10 23:52:19 UTC (rev 
9016)
@@ -47,6 +47,9 @@
     /// \brief Destructor
     public: virtual ~Common();
 
+    /// \brief Load 
+    public: virtual void Load(XMLConfigNode *node);
+
     /// \brief Set the name of the entity
     /// \param name Body name
     public: virtual void SetName(const std::string &name);

Modified: code/gazebo/branches/dev/server/Entity.cc
===================================================================
--- code/gazebo/branches/dev/server/Entity.cc   2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Entity.cc   2011-01-10 23:52:19 UTC (rev 
9016)
@@ -50,36 +50,42 @@
   this->staticP->Callback( &Entity::SetStatic, this );
   Param::End();
  
-  std::ostringstream visname;
-  visname << "Entity_" << this->GetId() << "_VISUAL";
-
   this->visualMsg = new VisualMsg();
-  this->visualMsg->id = visname.str();
+  //this->visualMsg->id = this->GetName();
 
   if (this->parent && this->parent->HasType(ENTITY))
   {
     Entity *ep = (Entity*)(this->parent);
-    this->visualMsg->parentId = ep->GetName();
     this->SetStatic(ep->IsStatic());
   }
-  else
+  /*else
   {
     this->visualMsg = new VisualMsg();
   }
 
   Simulator::Instance()->SendMessage( *this->visualMsg );
+  */
 
   // NATY: put functionality back in
   //this->visualNode->SetOwner(this);
 }
 
+////////////////////////////////////////////////////////////////////////////////
+/// Load
+void Entity::Load(XMLConfigNode *node)
+{
+  Common::Load(node);
+  this->RegisterVisual();
+}
+ 
+
 void Entity::SetName(const std::string &name)
 {
+  // TODO: if an entitie's name is changed, then the old visual is never
+  // removed. Should add in functionality to modify/update the visual
   Common::SetName(name);
-  std::ostringstream visname;
-  visname << name << "_VISUAL";
-  this->visualMsg->id = visname.str();
-  Simulator::Instance()->SendMessage( *this->visualMsg );
+  //this->visualMsg->id = this->GetCompleteScopedName();
+  //Simulator::Instance()->SendMessage( *this->visualMsg );
 }
 
 
////////////////////////////////////////////////////////////////////////////////
@@ -289,8 +295,9 @@
 void Entity::PoseChange(bool notify)
 {
   PoseMsg msg;
-  msg->id = this->name;
-  msg->pose = this->GetRelativePose();
+  msg.id = this->GetCompleteScopedName();
+  //std::cout << "Pose[" << msg.id << "]\n";
+  msg.pose = this->GetRelativePose();
   Simulator::Instance()->SendMessage( msg );
 
   if (notify)
@@ -305,3 +312,13 @@
     }
   }
 }
+
+////////////////////////////////////////////////////////////////////////////////
+// Register a visual
+void Entity::RegisterVisual()
+{
+  this->visualMsg->id = this->GetCompleteScopedName();
+  if (this->parent)
+    this->visualMsg->parentId = this->parent->GetCompleteScopedName();
+  Simulator::Instance()->SendMessage( *this->visualMsg );
+}

Modified: code/gazebo/branches/dev/server/Entity.hh
===================================================================
--- code/gazebo/branches/dev/server/Entity.hh   2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Entity.hh   2011-01-10 23:52:19 UTC (rev 
9016)
@@ -55,6 +55,9 @@
   
     /// \brief Destructor
     public: virtual ~Entity();
+
+    /// \brief Load
+    public: virtual void Load(XMLConfigNode *node);
  
     public: void SetName(const std::string &name);
  
@@ -126,6 +129,8 @@
     public: virtual Vector3 GetWorldAngularAccel() const
             {return Vector3();}
 
+    /// Register a visual
+    public: void RegisterVisual();
 
     /// \brief This function is called when the entity's (or one of its 
parents)
     ///        pose of the parent has changed

Modified: code/gazebo/branches/dev/server/Messages.cc
===================================================================
--- code/gazebo/branches/dev/server/Messages.cc 2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Messages.cc 2011-01-10 23:52:19 UTC (rev 
9016)
@@ -3,6 +3,15 @@
 
 using namespace gazebo;
 
+VisualMsg::VisualMsg() : Message(VISUAL_MSG) 
+{
+  this->castShadows = true;
+  this->attachAxes = true;
+  this->visible = true;
+  this->transparency = 0.0;
+  this->size.Set(1,1,1);
+}
+
 VisualMsg::VisualMsg(const VisualMsg &m)
   : Message(m)
 {
@@ -22,6 +31,7 @@
   this->plane = m.plane;
   this->uvTile_x = m.uvTile_x;
   this->uvTile_y = m.uvTile_y;
+  this->size = m.size;
 }
 
 void VisualMsg::Load(XMLConfigNode *node)
@@ -31,6 +41,5 @@
   this->castShadows = node->GetBool("castShadows",true,0);
   this->visible = node->GetBool("visible",true,0);
   this->transparency = node->GetDouble("transparency",0.0,0);
-
-  std::cout << "Loading a Visual Message\n\n";
+  this->size = node->GetVector3("size", Vector3(1,1,1));
 }

Modified: code/gazebo/branches/dev/server/Messages.hh
===================================================================
--- code/gazebo/branches/dev/server/Messages.hh 2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Messages.hh 2011-01-10 23:52:19 UTC (rev 
9016)
@@ -42,7 +42,7 @@
     public: enum ActionType {UPDATE, DELETE};
     public: enum RenderType {MESH_RESOURCE, POINTS, LINE_LIST, LINE_STRIP, 
TRIANGLE_FAN};
 
-    public: VisualMsg() : Message(VISUAL_MSG) {}
+    public: VisualMsg();
     public: VisualMsg(const VisualMsg &m);
     public: virtual Message *Clone() const 
             { VisualMsg *msg = new VisualMsg(*this); return msg; }
@@ -63,6 +63,7 @@
     public: std::vector<Vector3> points;
     public: Pose3d pose;
     public: Plane plane;
+    public: Vector3 size;
     public: float uvTile_x;
     public: float uvTile_y;
   };
@@ -70,13 +71,12 @@
   class PoseMsg : public Message
   {
     public: PoseMsg() : Message(POSE_MSG) {}
-    public: PoseMsg(const PoseMsg &m) : Message(m), 
-            id(m.id), pose(m.pose) {}
+    public: PoseMsg(const PoseMsg &m) : Message(m), pose(m.pose), id(m.id) {}
     public: virtual Message *Clone() const 
-            { UpdatePoseMsg *msg = new UpdatePoseMsg(*this); return msg; }
+            { PoseMsg *msg = new PoseMsg(*this); return msg; }
 
+    public: Pose3d pose;
     public: std::string id;
-    public: Pose3d pose;
   };
 }
 

Modified: code/gazebo/branches/dev/server/Model.cc
===================================================================
--- code/gazebo/branches/dev/server/Model.cc    2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/Model.cc    2011-01-10 23:52:19 UTC (rev 
9016)
@@ -64,12 +64,6 @@
     for (size_t i=r.begin(); i != r.end(); i++)
     {
       (*this->bodies)[i]->Update();
-      /*Common *common = (*this->children)[i];
-      if ( common->HasType(BODY) )
-      {
-        ((Body*)common)->Update();
-      }
-      */
     }
   }
 
@@ -184,12 +178,14 @@
 // Load the model
 void Model::Load(XMLConfigNode *node, bool removeDuplicate)
 {
+  Entity::Load(node);
+
   XMLConfigNode *childNode;
   std::string scopedName;
   Pose3d pose;
   Common* dup;
 
-  this->nameP->Load(node);
+  this->staticP->Load(node);
 
   scopedName = this->GetScopedName();
 
@@ -210,8 +206,6 @@
     }
   }
 
-  this->staticP->Load(node);
-
   this->canonicalBodyNameP->Load(node);
   this->xyzP->Load(node);
   this->rpyP->Load(node);
@@ -1182,6 +1176,8 @@
 {
   XMLConfigNode *childNode = NULL;
 
+  std::cout << "LoadPhysical[" << this->GetName() << "]\n";
+
   // Load the bodies
   if (node->GetChildByNSPrefix("body"))
     childNode = node->GetChildByNSPrefix("body");

Modified: code/gazebo/branches/dev/server/World.cc
===================================================================
--- code/gazebo/branches/dev/server/World.cc    2010-12-30 02:05:37 UTC (rev 
9015)
+++ code/gazebo/branches/dev/server/World.cc    2011-01-10 23:52:19 UTC (rev 
9016)
@@ -88,6 +88,7 @@
   this->stepInc = false;
 
   this->rootElement = new Common(NULL);
+  this->rootElement->SetName("root");
   this->rootElement->SetWorld(this);
 
   this->factoryIfaceHandler = NULL;
@@ -670,8 +671,9 @@
 /// Receive a message
 void World::ReceiveMessage( const Message &msg )
 {
+  //std::cout << "Received message\n";
   boost::mutex::scoped_lock lock( this->mutex );
-  if (msg.type == VISUAL_MSG)
+  if (msg.type == VISUAL_MSG || msg.type == POSE_MSG)
     this->scene->ReceiveMessage(msg);
   else
     this->messages.push_back( msg.Clone() );

Modified: code/gazebo/branches/dev/server/physics/Body.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Body.cc     2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/physics/Body.cc     2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -157,6 +157,9 @@
 // Load the body based on an XMLConfig node
 void Body::Load(XMLConfigNode *node)
 {
+  Entity::Load(node);
+  this->comEntity->RegisterVisual();
+
   // before loading child geometry, we have to figure out of selfCollide is 
true
   // and modify parent class Entity so this body has its own spaceId
   this->selfCollideP->Load(node);
@@ -185,7 +188,6 @@
      
   XMLConfigNode *childNode;
 
-  this->nameP->Load(node);
   this->xyzP->Load(node);
   this->rpyP->Load(node);
   this->dampingFactorP->Load(node);
@@ -355,8 +357,6 @@
 // Initialize the body
 void Body::Init()
 {
-  this->poseDirty = false;
-
   // If no geoms are attached, then don't let gravity affect the body.
   if (this->geoms.size()==0 || **this->turnGravityOffP)
     this->SetGravityMode(false);
@@ -375,15 +375,16 @@
   this->linearAccel.Set(0,0,0);
   this->angularAccel.Set(0,0,0);
 
+  // NATY: put back in
   /// Attach mesh for CG visualization
   /// Add a renderable visual for CG, make visible in Update()
-  if (this->mass.GetAsDouble() > 0.0)
+  /*if (this->mass.GetAsDouble() > 0.0)
   {
     std::ostringstream visname;
     visname << this->GetCompleteScopedName() + ":" + this->GetName() << 
"_CGVISUAL" ;
 
     this->cgVisualMsg = new VisualMsg();
-    this->cgVisualMsg->parentId = this->comEntity->GetName();
+    this->cgVisualMsg->parentId = this->comEntity->GetId();
     this->cgVisualMsg->id = visname.str();
     this->cgVisualMsg->render = VisualMsg::MESH_RESOURCE;
     this->cgVisualMsg->mesh = "body_cg";
@@ -411,7 +412,7 @@
 
       Simulator::Instance()->SendMessage(msg);
     }
-  }
+  }*/
 
   this->enabled = true;
 }
@@ -420,12 +421,6 @@
 // Update the body
 void Body::Update()
 {
-  if (this->poseDirty)
-  {
-    this->poseDirty = false;
-    this->SetWorldPose(this->newPose, false);
-  }
-
   // Apply our linear accel
   this->SetForce(this->linearAccel);
 

Modified: code/gazebo/branches/dev/server/physics/Body.hh
===================================================================
--- code/gazebo/branches/dev/server/physics/Body.hh     2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/physics/Body.hh     2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -296,7 +296,6 @@
     private: bool enabled;
 
     protected: Pose3d newPose;
-    protected: bool poseDirty;
   };
 
   /// \}

Modified: code/gazebo/branches/dev/server/physics/Geom.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Geom.cc     2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/physics/Geom.cc     2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -138,10 +138,11 @@
 // First step in the loading process
 void Geom::Load(XMLConfigNode *node)
 {
+  Entity::Load(node);
+
   XMLConfigNode *childNode = NULL;
 
   this->typeP->Load(node);
-  this->nameP->Load(node);
   this->SetName(this->nameP->GetValue());
   this->massP->Load(node);
   this->xyzP->Load(node);
@@ -168,19 +169,18 @@
   while (childNode)
   {
     std::ostringstream visname;
-    visname << this->GetCompleteScopedName() << "_VISUAL_" << 
+    visname << this->GetCompleteScopedName() << "::VISUAL_" << 
                this->visualMsgs.size();
 
 
     VisualMsg *msg = new VisualMsg();
 
-    msg->parentId = this->GetName();
+    msg->parentId = this->GetCompleteScopedName();
     msg->id = visname.str();
     msg->render = VisualMsg::MESH_RESOURCE;
     msg->Load(childNode);
     msg->castShadows = false;
-    msg->pose = this->GetWorldPose();
-    std::cout << "Geom[" << this->GetName() << "] Create a Visual Message with 
Pose[" << msg->pose << "]\n";
+    msg->pose = this->GetRelativePose();
 
     Simulator::Instance()->SendMessage( *msg );
 
@@ -203,13 +203,13 @@
     this->GetBoundingBox(min,max);
 
     std::ostringstream visname;
-    visname << this->GetCompleteScopedName() << "_BBVISUAL" ;
+    visname << this->GetCompleteScopedName() << "::BBVISUAL" ;
 
     this->bbVisualMsg = new VisualMsg();
 
     this->bbVisualMsg->render = VisualMsg::MESH_RESOURCE;
-    this->bbVisualMsg->parentId = this->GetName();
-    this->bbVisualMsg->id = this->GetName() + "_BBVISUAL";
+    this->bbVisualMsg->parentId = this->GetCompleteScopedName();
+    this->bbVisualMsg->id = this->GetCompleteScopedName() + "_BBVISUAL";
     this->bbVisualMsg->castShadows = false;
     this->bbVisualMsg->visible = RenderState::GetShowBoundingBoxes();
     this->bbVisualMsg->boundingbox.min = min;

Modified: code/gazebo/branches/dev/server/physics/PlaneShape.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/PlaneShape.cc       2010-12-30 
02:05:37 UTC (rev 9015)
+++ code/gazebo/branches/dev/server/physics/PlaneShape.cc       2011-01-10 
23:52:19 UTC (rev 9016)
@@ -116,6 +116,9 @@
   this->visualMsg->uvTile_y = (**(this->uvTileP)).y;
   this->visualMsg->material = **(this->materialP);
   this->visualMsg->castShadows = **(this->castShadowsP);
+  this->visualMsg->size.x = (**(this->sizeP)).x;
+  this->visualMsg->size.y = (**(this->sizeP)).y;
+  this->visualMsg->size.z = 0.0;
 
   Simulator::Instance()->SendMessage( *this->visualMsg );
 }

Modified: code/gazebo/branches/dev/server/physics/ode/ODEBody.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/ode/ODEBody.cc      2010-12-30 
02:05:37 UTC (rev 9015)
+++ code/gazebo/branches/dev/server/physics/ode/ODEBody.cc      2011-01-10 
23:52:19 UTC (rev 9016)
@@ -111,11 +111,9 @@
   pose.pos.Set(p[0], p[1], p[2]);
   pose.rot.Set(r[0], r[1], r[2], r[3] );
 
-  self->newPose = self->comEntity->GetRelativePose().GetInverse() + pose;
-  self->newPose.Correct();
-  self->poseDirty = true;
-
-  //self->SetWorldPose(pp, false);
+  pose = self->comEntity->GetRelativePose().GetInverse() + pose;
+  pose.Correct();
+  self->SetWorldPose(pose);
 }
 
 
////////////////////////////////////////////////////////////////////////////////

Modified: code/gazebo/branches/dev/server/physics/ode/ODEPhysics.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/ode/ODEPhysics.cc   2010-12-30 
02:05:37 UTC (rev 9015)
+++ code/gazebo/branches/dev/server/physics/ode/ODEPhysics.cc   2011-01-10 
23:52:19 UTC (rev 9016)
@@ -148,14 +148,6 @@
 
   this->contactGroup = dJointGroupCreate(0);
 
-  // If auto-disable is active, then user interaction with the joints 
-  // doesn't behave properly
-  dWorldSetAutoDisableFlag(this->worldId, 0);
-  dWorldSetAutoDisableTime(this->worldId, 2.0);
-  dWorldSetAutoDisableLinearThreshold(this->worldId, 0.001);
-  dWorldSetAutoDisableAngularThreshold(this->worldId, 0.001);
-  dWorldSetAutoDisableSteps(this->worldId, 50);
-
   Param::Begin(&this->parameters);
   this->globalCFMP = new ParamT<double>("cfm", 10e-5, 0);
   this->globalERPP = new ParamT<double>("erp", 0.2, 0);
@@ -164,7 +156,7 @@
   this->stepWP = new ParamT<double>("stepW", 1.3, 0);  /// over_relaxation 
value for SOR
   this->contactMaxCorrectingVelP = new 
ParamT<double>("contactMaxCorrectingVel", 10.0, 0);
   this->contactSurfaceLayerP = new ParamT<double>("contactSurfaceLayer", 0.01, 
0);
-  this->autoDisableBodyP = new ParamT<bool>("autoDisableBody", false, 0);
+  this->autoDisableBodyP = new ParamT<bool>("autoDisableBody", true, 0);
   this->contactFeedbacksP = new ParamT<int>("contactFeedbacks", 100, 0); // 
just an initial value, appears to get resized if limit is breached
   this->maxContactsP = new ParamT<int>("maxContacts",1000,0); // enforced for 
trimesh-trimesh contacts
   Param::End();
@@ -226,13 +218,14 @@
   // doesn't behave properly
   // disable autodisable by default
   dWorldSetAutoDisableFlag(this->worldId, **this->autoDisableBodyP);
-  dWorldSetAutoDisableTime(this->worldId, 2.0);
+  dWorldSetAutoDisableTime(this->worldId, 0);
   dWorldSetAutoDisableLinearThreshold(this->worldId, 0.001);
   dWorldSetAutoDisableAngularThreshold(this->worldId, 0.001);
-  dWorldSetAutoDisableSteps(this->worldId, 50);
+  dWorldSetAutoDisableSteps(this->worldId, 0);
 
   this->contactFeedbacks.resize(**this->contactFeedbacksP);
 
+  // NATY: not sure if I can remove this...check
   // Reset the contact pointer
   //this->contactFeedbackIter = this->contactFeedbacks.begin();
 
@@ -315,8 +308,6 @@
 {
   this->UpdateCollision();
 
-  //this->LockMutex(); 
-
   // Update the dynamical model
   if (**this->stepTypeP == "quick")
     dWorldQuickStep(this->worldId, (**this->stepTimeP).Double());
@@ -327,8 +318,6 @@
 
   // Very important to clear out the contact group
   dJointGroupEmpty( this->contactGroup );
-
-  //this->UnlockMutex(); 
 }
 
 
@@ -593,6 +582,7 @@
 // Handle a collision
 void ODEPhysics::CollisionCallback( void *data, dGeomID o1, dGeomID o2)
 {
+
   dBodyID b1 = dGeomGetBody(o1);
   dBodyID b2 = dGeomGetBody(o2);
 

Modified: code/gazebo/branches/dev/server/rendering/Grid.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Grid.cc   2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/rendering/Grid.cc   2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -144,7 +144,7 @@
 
   Ogre::SceneNode *parent_node = this->scene->GetManager()->getRootSceneNode();
 
-  this->sceneNode = parent_node->createChildSceneNode();
+  this->sceneNode = parent_node->createChildSceneNode(this->name);
   this->sceneNode->attachObject( this->manualObject );
 
   std::stringstream ss;

Modified: code/gazebo/branches/dev/server/rendering/Scene.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Scene.cc  2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/rendering/Scene.cc  2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -55,7 +55,7 @@
 /// Destructor
 Scene::~Scene()
 {
-  std::map<std::string, Visual*>::iterator iter;
+  VisualMap::iterator iter;
   for (iter = this->visuals.begin(); iter != this->visuals.end(); iter++)
     delete iter->second;
   this->visuals.clear();
@@ -470,8 +470,27 @@
 /// Print scene graph
 void Scene::PrintSceneGraphHelper(std::string prefix, Ogre::Node *node)
 {
-  std::cout << prefix << node->getName() << std::endl;
+  Ogre::SceneNode *snode = dynamic_cast<Ogre::SceneNode*>(node);
 
+  std::string nodeName = node->getName();
+  int numAttachedObjs = 0;
+  bool isInSceneGraph = false;
+  if (snode)
+  {
+    numAttachedObjs = snode->numAttachedObjects();
+    isInSceneGraph = snode->isInSceneGraph();
+  }
+  int numChildren = node->numChildren();
+  Ogre::Vector3 pos = node->getPosition();
+  Ogre::Vector3 scale = node->getScale();
+
+  std::cout << prefix << nodeName << "\n";
+  std::cout << prefix << "  Num Objs[" << numAttachedObjs << "]\n";
+  std::cout << prefix << "  Num Children[" << numChildren << "]\n";
+  std::cout << prefix << "  IsInGraph[" << isInSceneGraph << "]\n";
+  std::cout << prefix << "  Pos[" << pos.x << " " << pos.y << " " << pos.z << 
"]\n";
+  std::cout << prefix << "  Scale[" << scale.x << " " << scale.y << " " << 
scale.z << "]\n";
+  
   prefix += "  ";
   for (unsigned int i=0; i < node->numChildren(); i++)
   {
@@ -660,7 +679,7 @@
     if (this->messages[i]->type == VISUAL_MSG)
     {
       VisualMsg *msg = (VisualMsg*)this->messages[i];
-      std::map<std::string, Visual*>::iterator iter;
+      VisualMap::iterator iter;
       iter = this->visuals.find(msg->id);
       if (iter != this->visuals.end())
       {
@@ -668,7 +687,14 @@
       }
       else
       {
-        Visual *visual = new Visual(msg->id, this);
+        Visual *visual = NULL;
+        VisualMap::iterator iter;
+        iter = this->visuals.find(msg->parentId);
+
+        if (iter != this->visuals.end())
+          visual = new Visual(msg->id, iter->second);
+        else 
+          visual = new Visual(msg->id, this);
         visual->LoadFromMsg(msg);
         this->visuals[msg->id] = visual;
       }
@@ -676,7 +702,7 @@
     else if (this->messages[i]->type == POSE_MSG)
     {
       PoseMsg *msg = (PoseMsg*)this->messages[i];
-      std::map<std::string, Visual*>::iterator iter;
+      VisualMap::iterator iter;
       iter = this->visuals.find(msg->id);
       if (iter != this->visuals.end())
       {

Modified: code/gazebo/branches/dev/server/rendering/Scene.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/Scene.hh  2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/rendering/Scene.hh  2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -25,6 +25,8 @@
 
   class Scene
   {
+    typedef std::map<std::string, Visual*> VisualMap;
+
     public: enum SceneType {BSP, GENERIC};
 
     /// \brief Constructor
@@ -179,8 +181,7 @@
     private: boost::mutex mutex;
     private: std::vector<Message*> messages;
 
-    private: std::map<std::string, Visual*> visuals;
-
+    private: VisualMap visuals;
   };
 };
 #endif 

Modified: code/gazebo/branches/dev/server/rendering/Visual.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Visual.cc 2010-12-30 02:05:37 UTC 
(rev 9015)
+++ code/gazebo/branches/dev/server/rendering/Visual.cc 2011-01-10 23:52:19 UTC 
(rev 9016)
@@ -61,16 +61,13 @@
   this->AddType(VISUAL);
   this->sceneNode = NULL;
 
-  std::ostringstream stream;
-  stream << this->GetName() << "_VISUAL_" << visualCounter++;
-
   Ogre::SceneNode *pnode = NULL;
   if (parent)
     pnode = parent->GetSceneNode();
   else
     gzerr(0) << "Create a visual, invalid parent!!!\n";
 
-  this->sceneNode = pnode->createChildSceneNode( stream.str() );
+    this->sceneNode = pnode->createChildSceneNode( this->GetName() );
 
   this->Init();
 }
@@ -84,11 +81,8 @@
   this->AddType(VISUAL);
   this->sceneNode = NULL;
 
-  std::ostringstream stream;
-  stream << this->GetName() << "_VISUAL_" << visualCounter++;
+  this->sceneNode = parent->createChildSceneNode( this->GetName() );
 
-  this->sceneNode = parent->createChildSceneNode( stream.str() );
-
   this->Init();
 }
 
@@ -101,11 +95,8 @@
   this->AddType(VISUAL);
   this->sceneNode = NULL;
 
-  std::ostringstream stream;
-  stream << this->GetName() << "_VISUAL_" << visualCounter++;
+  this->sceneNode = 
scene->GetManager()->getRootSceneNode()->createChildSceneNode(this->GetName());
 
-  this->sceneNode = 
scene->GetManager()->getRootSceneNode()->createChildSceneNode(stream.str());
-
   this->Init();
 }
 
@@ -235,6 +226,7 @@
   this->meshTileP->Load(NULL);
   this->materialNameP->SetValue(msg->material);
   this->castShadowsP->SetValue(msg->castShadows);
+  this->sizeP->SetValue(msg->size);
 
   this->Load(NULL);
 }
@@ -246,7 +238,7 @@
   std::ostringstream stream;
   Pose3d pose;
   Vector3 size(0,0,0);
-  Ogre::Vector3 meshSize(0,0,0);
+  Ogre::Vector3 meshSize(1,1,1);
   Ogre::MovableObject *obj = NULL;
 
   if (node)
@@ -294,8 +286,6 @@
         MeshManager::Instance()->Load(meshName);
       }
 
-      std::cout << "Mesh Name[" << meshName << "]\n";
-
       // Add the mesh into OGRE
       this->InsertMesh( MeshManager::Instance()->GetMesh(meshName) );
 
@@ -321,18 +311,22 @@
 
   // Get the size of the mesh
   if (obj)
+  {
     meshSize = obj->getBoundingBox().getSize();
+    //this->sizeP->SetValue( Vector3(meshSize.x, meshSize.y, meshSize.z) );
+  }
 
   // Get the desired size of the mesh
   if (node && node->GetChild("size") != NULL)
   {
     this->sizeP->Load(node);
   }
-  else
+  /*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)
+  /*if (node && node->GetChild("scale") != NULL)
   {
     this->scaleP->Load(node);
     Vector3 scale = this->scaleP->GetValue();
@@ -340,6 +334,7 @@
   }
   else
   {
+  */
     Vector3 scale = this->sizeP->GetValue();
     scale.x /= meshSize.x;
     scale.y /= meshSize.y;
@@ -347,9 +342,9 @@
     scale.Correct();
 
     this->scaleP->SetValue( scale );
-
     this->sceneNode->setScale(scale.x, scale.y, scale.z);
-  }
+  //}
+  
 
   // Set the material of the mesh
   if (**this->materialNameP != "none")
@@ -844,6 +839,7 @@
     //this->staticGeom->setOrigin( Ogre::Vector3(pos.x, pos.y, pos.z) );
   }*/
 
+  //std::cout << "SetPos[" << pos << "][" << this->GetName() << "]\n";
   this->sceneNode->setPosition(pos.x, pos.y, pos.z);
 
   /*if (this->IsStatic())


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

------------------------------------------------------------------------------
Gaining the trust of online customers is vital for the success of any company
that requires sensitive data to be transmitted over the Web.   Learn how to 
best implement a security strategy that keeps consumers' information secure 
and instills the confidence they need to proceed with transactions.
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