Revision: 8986
          http://playerstage.svn.sourceforge.net/playerstage/?rev=8986&view=rev
Author:   natepak
Date:     2010-11-29 22:49:26 +0000 (Mon, 29 Nov 2010)

Log Message:
-----------
More bug fixes

Modified Paths:
--------------
    code/gazebo/branches/dev/Media/materials/scripts/Gazebo.material
    code/gazebo/branches/dev/server/CMakeLists.txt
    code/gazebo/branches/dev/server/Quatern.hh
    code/gazebo/branches/dev/server/Simulator.cc
    code/gazebo/branches/dev/server/Simulator.hh
    code/gazebo/branches/dev/server/World.cc
    code/gazebo/branches/dev/server/World.hh
    code/gazebo/branches/dev/server/physics/Body.cc
    code/gazebo/branches/dev/server/physics/Geom.cc
    code/gazebo/branches/dev/server/physics/Geom.hh
    code/gazebo/branches/dev/server/rendering/Visual.cc
    code/gazebo/branches/dev/server/rendering/Visual.hh
    code/gazebo/branches/dev/server/rendering/WindowManager.cc
    code/gazebo/branches/dev/server/wx/BoxMaker.cc
    code/gazebo/branches/dev/server/wx/RenderControl.cc

Modified: code/gazebo/branches/dev/Media/materials/scripts/Gazebo.material
===================================================================
--- code/gazebo/branches/dev/Media/materials/scripts/Gazebo.material    
2010-11-29 05:34:15 UTC (rev 8985)
+++ code/gazebo/branches/dev/Media/materials/scripts/Gazebo.material    
2010-11-29 22:49:26 UTC (rev 8986)
@@ -271,6 +271,25 @@
        }
 }
 
+material Gazebo/TurquoiseGlowOutline : Gazebo/Turquoise
+{
+       technique
+       {
+    pass ambient
+    {
+      ambient 0 1 1
+      polygon_mode wireframe
+    }
+
+               pass light
+               {
+                       emissive 0 1 1
+      diffuse 0 1 1
+      polygon_mode wireframe
+               }
+       }
+}
+
 material Gazebo/RedTransparent
 {
        technique

Modified: code/gazebo/branches/dev/server/CMakeLists.txt
===================================================================
--- code/gazebo/branches/dev/server/CMakeLists.txt      2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/CMakeLists.txt      2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -132,6 +132,7 @@
              STLLoader.hh
              Events.hh
              Plugin.hh
+             Messages.hh
 )
 
 APPEND_TO_SERVER_HEADERS(${headers})

Modified: code/gazebo/branches/dev/server/Quatern.hh
===================================================================
--- code/gazebo/branches/dev/server/Quatern.hh  2010-11-29 05:34:15 UTC (rev 
8985)
+++ code/gazebo/branches/dev/server/Quatern.hh  2010-11-29 22:49:26 UTC (rev 
8986)
@@ -100,7 +100,7 @@
   public: static Quatern EulerToQuatern( const Vector3 &vec );
 
   /// \brief Convert euler angles to quatern.
-  public: Quatern EulerToQuatern( double x, double y, double z);
+  public: static Quatern EulerToQuatern( double x, double y, double z);
 
   /// \brief Get the Euler roll angle in radians
   public: double GetRoll();

Modified: code/gazebo/branches/dev/server/Simulator.cc
===================================================================
--- code/gazebo/branches/dev/server/Simulator.cc        2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/Simulator.cc        2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -30,6 +30,7 @@
 #include <boost/bind.hpp>
 #include <boost/thread/recursive_mutex.hpp>
 
+#include "Messages.hh"
 #include "RenderState.hh"
 #include "PhysicsFactory.hh"
 #include "gazebo_config.h"
@@ -634,3 +635,11 @@
     }
   }
 }
+
+////////////////////////////////////////////////////////////////////////////////
+/// Send a message
+void Simulator::SendMessage( const Message &message )
+{
+  for (unsigned int i=0; i < this->worlds.size(); i++)
+    this->worlds[i]->ReceiveMessage( message );
+}

Modified: code/gazebo/branches/dev/server/Simulator.hh
===================================================================
--- code/gazebo/branches/dev/server/Simulator.hh        2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/Simulator.hh        2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -56,6 +56,7 @@
   class Model;
   class World;
   class Plugin;
+  class Message;
 
   /// \brief The World
   /*
@@ -155,6 +156,9 @@
   
       /// \brief Remove a plugin
       public: void RemovePlugin(const std::string &plugin);
+
+      /// \brief Send a message
+      public: void SendMessage( const Message &message );
   
       /// \brief Function to run gui. Used by guiThread
       private: void PhysicsLoop();
@@ -199,7 +203,7 @@
       private: unsigned int activeWorldIndex;
   
       private: std::vector<Plugin*> plugins;
-  
+
       //Singleton implementation
       private: friend class DestroyerT<Simulator>;
       private: friend class SingletonT<Simulator>;

Modified: code/gazebo/branches/dev/server/World.cc
===================================================================
--- code/gazebo/branches/dev/server/World.cc    2010-11-29 05:34:15 UTC (rev 
8985)
+++ code/gazebo/branches/dev/server/World.cc    2010-11-29 22:49:26 UTC (rev 
8986)
@@ -324,7 +324,7 @@
   Time diffTime;
   Time currTime;
   Time lastTime = this->GetRealTime();
-  struct timespec req, rem;
+  struct timespec req;//, rem;
 
   this->startTime = Time::GetWallTime();
 
@@ -406,6 +406,9 @@
   // Process all incoming messages from simiface
   this->simIfaceHandler->Update();
 
+  /// Process all internal messages
+  this->ProcessMessages();
+
   // NATY: put back in
   //Logger::Instance()->Update();
 
@@ -532,6 +535,8 @@
 
   if (node)
   {
+    std::cout << "Loading an entity\n";
+
     // Check for model nodes
     if (node->GetName() == "model")
     {
@@ -585,7 +590,7 @@
       }
 
       // last bool is initModel, yes, init model after loading it
-      this->LoadEntities( xmlConfig->GetRootNode(), NULL, true, true); 
+      this->LoadEntities( xmlConfig->GetRootNode(), this->rootElement, true, 
true); 
       delete xmlConfig;
     }
     this->toLoadEntities.clear();
@@ -656,6 +661,49 @@
 }
 
 
////////////////////////////////////////////////////////////////////////////////
+/// Receive a message
+void World::ReceiveMessage( const Message &msg )
+{
+  boost::mutex::scoped_lock lock( this->mutex );
+  this->messages.push_back( msg.Clone() );
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Process all messages
+void World::ProcessMessages()
+{
+  boost::mutex::scoped_lock lock( this->mutex );
+
+  for ( unsigned int i=0; i < this->messages.size(); i++)
+  {
+    Message *msg = this->messages[i];
+
+    if (msg->type == INSERT_MODEL)
+    {
+      // Create the world file
+      XMLConfig *xmlConfig = new XMLConfig();
+
+      // Load the XML tree from the given string
+      try
+      {
+        xmlConfig->LoadString( ((InsertModelMsg*)msg)->xmlStr );
+      }
+      catch (gazebo::GazeboError e)
+      {
+        gzerr(0) << "The world could not load the XML data [" << e << "]\n";
+        continue;
+      }
+
+      // last bool is initModel, yes, init model after loading it
+      this->LoadEntities( xmlConfig->GetRootNode(), this->rootElement, true, 
true); 
+      delete xmlConfig;
+    }
+  }
+
+  this->messages.clear();
+}
+
+////////////////////////////////////////////////////////////////////////////////
 // Load a model
 Model *World::LoadModel(XMLConfigNode *node, Common *parent, 
                         bool removeDuplicate, bool initModel)

Modified: code/gazebo/branches/dev/server/World.hh
===================================================================
--- code/gazebo/branches/dev/server/World.hh    2010-11-29 05:34:15 UTC (rev 
8985)
+++ code/gazebo/branches/dev/server/World.hh    2010-11-29 22:49:26 UTC (rev 
8986)
@@ -37,6 +37,7 @@
 
 #include "Global.hh"
 
+#include "Messages.hh"
 #include "Vector3.hh"
 #include "Pose3d.hh"
 #include "Entity.hh"
@@ -203,6 +204,12 @@
   /// \brief Get an element by name
   public: Common *GetByName(const std::string &name);
 
+  /// \brief Receive a message
+  public: void ReceiveMessage( const Message &msg );
+
+  /// \brief Process all messages
+  private: void ProcessMessages();
+
   /// \brief Save the state of the world
   private: void SaveState();
 
@@ -267,6 +274,9 @@
 
   //private: Timer saveStateTimer;
   
+  private: boost::mutex mutex;
+  private: std::vector<Message*> messages;
+
   private: ParamT<std::string> *nameP;
   private: ParamT<Time> *saveStateTimeoutP;
   private: ParamT<unsigned int> *saveStateBufferSizeP;

Modified: code/gazebo/branches/dev/server/physics/Body.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Body.cc     2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/physics/Body.cc     2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -35,7 +35,6 @@
 #include "GazeboMessage.hh"
 #include "Geom.hh"
 #include "Timer.hh"
-#include "Visual.hh"
 #include "OgreDynamicLines.hh"
 #include "Global.hh"
 #include "Vector2.hh"
@@ -57,14 +56,16 @@
     : Entity(parent)
 {
   this->AddType(BODY);
-  this->GetVisualNode()->SetShowInGui(false);
 
+  // NATY: put back in functionality
+  // this->GetVisualNode()->SetShowInGui(false);
+
   this->comEntity = new Entity(this);
   this->comEntity->SetName("COM_Entity");
   this->comEntity->SetShowInGui(false);
-  this->comEntity->GetVisualNode()->SetShowInGui(false);
 
-  this->cgVisual = NULL;
+  // NATY: put back in functionality
+  //this->comEntity->GetVisualNode()->SetShowInGui(false);
 
   Param::Begin(&this->parameters);
   this->xyzP = new ParamT<Vector3>("xyz", Vector3(), 0);
@@ -110,11 +111,9 @@
   std::vector<Entity*>::iterator iter;
   std::vector< Sensor* >::iterator siter;
 
-  if (this->cgVisual)
-  {
-    delete this->cgVisual;
-    this->cgVisual = NULL;
-  }
+  DeleteVisualMsg msg;
+  msg.id = this->cgVisualId;
+  Simulator::Instance()->SendMessage(msg);
 
   for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
     if (giter->second)
@@ -378,32 +377,35 @@
     std::ostringstream visname;
     visname << this->GetCompleteScopedName() + ":" + this->GetName() << 
"_CGVISUAL" ;
 
-    if (this->cgVisual == NULL)
-    {
-      this->cgVisual = new Visual(visname.str(), this->comEntity);
-    }
-    else
-      this->cgVisual->DetachObjects();
+    this->cgVisualId = visname.str();
 
-    if (this->cgVisual)
+    InsertVisualMsg msg;
+    msg.parentId = this->comEntity->GetName();
+    msg.id = this->cgVisualId;
+    msg.type = MESH_RESOURCE;
+    msg.mesh = "body_cg";
+    msg.material = "Gazebo/Red";
+    msg.castShadows = false;
+    msg.attachAxes = true;
+    msg.visible = false;
+    Simulator::Instance()->SendMessage(msg);
+
+    msg.parentId = this->cgVisualId;
+    msg.type = 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++)
     {
-      this->cgVisual->AttachMesh("body_cg");
-      this->cgVisual->SetMaterial("Gazebo/Red");
-      this->cgVisual->SetCastShadows(false);
-      this->cgVisual->AttachAxes();
+      msg.points.clear();
 
-      std::map< std::string, Geom* >::iterator giter;
+      msg.id = visname.str() + "_lineto_" + giter->first->GetName();
+      msg.points.push_back( Vector3(0,0,0) );
+      msg.points.push_back(giter->second->GetRelativePose().pos);
 
-      // Create a line to each geom
-      for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
-      {
-        OgreDynamicLines *line = 
this->cgVisual->AddDynamicLine(RENDERING_LINE_LIST);
-        line->setMaterial("Gazebo/GreenGlow");
-        line->AddPoint(Vector3(0,0,0));
-        line->AddPoint(giter->second->GetRelativePose().pos);
-      }
-
-      this->cgVisual->SetVisible(false);
+      Simulator::Instance()->SendMessage(msg);
     }
   }
 

Modified: code/gazebo/branches/dev/server/physics/Geom.cc
===================================================================
--- code/gazebo/branches/dev/server/physics/Geom.cc     2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/physics/Geom.cc     2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -32,7 +32,6 @@
 #include "Shape.hh"
 #include "Mass.hh"
 #include "PhysicsEngine.hh"
-#include "Visual.hh"
 #include "Global.hh"
 #include "GazeboMessage.hh"
 #include "SurfaceParams.hh"
@@ -55,8 +54,6 @@
   // Create the contact parameters
   this->surface = new SurfaceParams();
 
-  this->bbVisual = NULL;
-
   this->transparency = 0;
 
   this->shape = NULL;
@@ -168,15 +165,25 @@
   while (childNode)
   {
     std::ostringstream visname;
-    visname << this->GetCompleteScopedName() << "_VISUAL_" << 
this->visuals.size();
-    Visual *visual = new Visual(visname.str(), this->visualNode);
-    visual->Load(childNode);
-    visual->SetIgnorePoseUpdates(true);
-    visual->SetOwner(this);
-    visual->SetCastShadows(true);
+    visname << this->GetCompleteScopedName() << "_VISUAL_" << 
+               this->visuals.size();
 
-    this->visuals.push_back(visual);
 
+    InsertVisualMsg msg;
+    msg.parentId = this->GetName();
+    msg.id = visname.str();
+    msg.Load(childNode);
+    msg.castShadows = false;
+    Simulator::Instance()->SendMessage( msg );
+
+    this->visualNames.push_back(visname.str());
+
+    // NATY: get rid of this
+    //visual->SetOwner(this);
+    //visual->SetCastShadows(true);
+    //this->visuals.push_back(visual);
+    //visual->SetIgnorePoseUpdates(true);
+    
     childNode = childNode->GetNext("visual");
   }
 }
@@ -230,11 +237,12 @@
   stream << prefix << "  " << *(this->laserFiducialIdP) << "\n";
   stream << prefix << "  " << *(this->laserRetroP) << "\n";
 
-  for (iter = this->visuals.begin(); iter != this->visuals.end(); iter++)
+  // NATY: put back in functionality
+  /*for (iter = this->visuals.begin(); iter != this->visuals.end(); iter++)
   {
     if (*iter)
       (*iter)->Save(p, stream);
-  }
+  }*/
 
   stream << prefix << "</geom>\n";
 }

Modified: code/gazebo/branches/dev/server/physics/Geom.hh
===================================================================
--- code/gazebo/branches/dev/server/physics/Geom.hh     2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/physics/Geom.hh     2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -234,7 +234,7 @@
     private: float transparency;
 
     /// All the visual apparence 
-    private: std::vector<Visual*> visuals;
+    private: std::vector<std::string> visualNames;
 
     protected: Shape *shape;
 

Modified: code/gazebo/branches/dev/server/rendering/Visual.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/Visual.cc 2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/rendering/Visual.cc 2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -185,8 +185,9 @@
 /// Destructor
 Visual::~Visual()
 {
+  // NATY
+  //delete this->mutex;
 
-  delete this->mutex;
   delete this->xyzP;
   delete this->rpyP;
   delete this->meshNameP;

Modified: code/gazebo/branches/dev/server/rendering/Visual.hh
===================================================================
--- code/gazebo/branches/dev/server/rendering/Visual.hh 2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/rendering/Visual.hh 2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -257,7 +257,8 @@
     private: ParamT<Vector3> *scaleP;
     private: ParamT<Vector2<double> > *meshTileP;
 
-    private: boost::recursive_mutex *mutex;
+    // NATY
+    //private: boost::recursive_mutex *mutex;
 
     private: bool ignorePoseUpdates;
     private: bool dirty;

Modified: code/gazebo/branches/dev/server/rendering/WindowManager.cc
===================================================================
--- code/gazebo/branches/dev/server/rendering/WindowManager.cc  2010-11-29 
05:34:15 UTC (rev 8985)
+++ code/gazebo/branches/dev/server/rendering/WindowManager.cc  2010-11-29 
22:49:26 UTC (rev 8986)
@@ -111,7 +111,7 @@
 {
   if (id >= this->windows.size())
   {
-    gzerr(0) << "Invalid window id[" << id << "]\n";
+    gzerr(5) << "Invalid window id[" << id << "]\n";
   }
   else
   {
@@ -124,7 +124,7 @@
 {
   for (unsigned int i=0; i < this->windows.size(); i++)
   {
-    this->windows[i]->update();
-    //this->windows[i]->swapBuffers();
+    this->windows[i]->update(false);
+    this->windows[i]->swapBuffers();
   }
 }

Modified: code/gazebo/branches/dev/server/wx/BoxMaker.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/BoxMaker.cc      2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/wx/BoxMaker.cc      2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -1,5 +1,6 @@
 #include <iostream>
 
+#include "Messages.hh"
 #include "Events.hh"
 #include "MouseEvent.hh"
 #include "Simulator.hh"
@@ -31,6 +32,7 @@
   stream << "user_box_" << counter++;
   this->visual = new Visual(stream.str(), scene );
   this->visual->AttachMesh("unit_box_U1V1");
+  this->visual->SetMaterial("Gazebo/TurquoiseGlowOutline");
 
   this->state = 1;
 }
@@ -85,7 +87,8 @@
   p2 = event.camera->GetWorldPointOnPlane(event.pos.x, event.pos.y ,norm, 0);
   p2 = this->GetSnappedPoint( p2 );
 
-  this->visual->SetPosition(p1);
+  if (this->state == 1)
+    this->visual->SetPosition(p1);
 
   Vector3 scale = p1-p2;
   Vector3 p = this->visual->GetPosition();
@@ -110,18 +113,19 @@
 
 void BoxMaker::CreateTheEntity()
 {
+  InsertModelMsg msg;
+
   std::ostringstream newModelStr;
 
   if (!this->visual)
     return;
 
-  newModelStr << "<?xml version='1.0'?> <gazebo:world 
xmlns:xi='http://www.w3.org/2001/XInclude' 
xmlns:gazebo='http://playerstage.sourceforge.net/gazebo/xmlschema/#gz' 
xmlns:model='http://playerstage.sourceforge.net/gazebo/xmlschema/#model' 
xmlns:sensor='http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor' 
xmlns:body='http://playerstage.sourceforge.net/gazebo/xmlschema/#body' 
xmlns:geom='http://playerstage.sourceforge.net/gazebo/xmlschema/#geom' 
xmlns:joint='http://playerstage.sourceforge.net/gazebo/xmlschema/#joint' 
xmlns:interface='http://playerstage.sourceforge.net/gazebo/xmlschema/#interface'
 
xmlns:rendering='http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering'
 
xmlns:renderable='http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable'
 
xmlns:controller='http://playerstage.sourceforge.net/gazebo/xmlschema/#controller'
 xmlns:physics='http://playerstage.sourceforge.net/gazebo/xmlschema/#physics' 
>";
+  newModelStr << "<?xml version='1.0'?>";
 
-
-  newModelStr << "<model:physical name=\"" << this->visual->GetName() << "\">\
+  newModelStr << "<model type='physical' name='" << this->visual->GetName() << 
"'>\
     <xyz>" << this->visual->GetPosition() << "</xyz>\
-    <body:box name=\"body\">\
-    <geom:box name=\"geom\">\
+    <body name='body'>\
+    <geom type='box' name='geom'>\
     <size>" << this->visual->GetScale() << "</size>\
     <mass>0.5</mass>\
     <visual>\
@@ -130,14 +134,15 @@
     <material>Gazebo/Grey</material>\
     <shader>pixel</shader>\
     </visual>\
-    </geom:box>\
-    </body:box>\
-    </model:physical>";
+    </geom>\
+    </body>\
+    </model>";
 
-  newModelStr <<  "</gazebo:world>";
-
   delete this->visual;
   this->visual = NULL;
 
-  Simulator::Instance()->GetActiveWorld()->InsertEntity(newModelStr.str());
+  msg.xmlStr = newModelStr.str();
+  Simulator::Instance()->SendMessage( msg );
+
+  //Simulator::Instance()->GetActiveWorld()->InsertEntity();
 }

Modified: code/gazebo/branches/dev/server/wx/RenderControl.cc
===================================================================
--- code/gazebo/branches/dev/server/wx/RenderControl.cc 2010-11-29 05:34:15 UTC 
(rev 8985)
+++ code/gazebo/branches/dev/server/wx/RenderControl.cc 2010-11-29 22:49:26 UTC 
(rev 8986)
@@ -313,7 +313,7 @@
     this->userCamera = scene->GetUserCamera(0);
 
   this->userCamera->SetWorldPosition( Vector3(0,0,3) );
-  this->userCamera->SetWorldRotation( Quatern::EulerToQuatern(0,0,3) );
+  this->userCamera->SetWorldRotation( Quatern::EulerToQuatern(0, DTOR(15), 0) 
);
 
   WindowManager::Instance()->SetCamera(this->windowId, this->userCamera);
 
@@ -382,20 +382,15 @@
     this->currMaker->Start(this->userCamera->GetScene());
 }
 
+////////////////////////////////////////////////////////////////////////////////
+// On resize event
 void RenderControl::OnSize( wxSizeEvent &evt )
 {
-  int width;
-  int height;
   wxSize size = evt.GetSize ();
-  width = size.GetWidth ();
-  height = size.GetHeight ();
 
-  std::cout << "On Size[" << width << ":" << height << "]\n";
-
-  WindowManager::Instance()->Resize(this->windowId, width, height);
-
-  evt.StopPropagation();
-  //evt.Skip(false);
+  WindowManager::Instance()->Resize(this->windowId, size.GetWidth(), 
+                                    size.GetHeight());
+  evt.Skip();
 }
 
 
////////////////////////////////////////////////////////////////////////////////


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

------------------------------------------------------------------------------
Increase Visibility of Your 3D Game App & Earn a Chance To Win $500!
Tap into the largest installed PC base & get more eyes on your game by
optimizing for Intel(R) Graphics Technology. Get started today with the
Intel(R) Software Partner Program. Five $500 cash prizes are up for grabs.
http://p.sf.net/sfu/intelisp-dev2dev
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to