Revision: 7006
http://playerstage.svn.sourceforge.net/playerstage/?rev=7006&view=rev
Author: natepak
Date: 2008-09-09 13:05:16 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
Applied patch 2101288
Modified Paths:
--------------
code/gazebo/trunk/server/Entity.cc
code/gazebo/trunk/server/Entity.hh
code/gazebo/trunk/server/Model.cc
code/gazebo/trunk/server/Model.hh
code/gazebo/trunk/server/Param.hh
code/gazebo/trunk/server/XMLConfig.cc
code/gazebo/trunk/server/XMLConfig.hh
code/gazebo/trunk/server/gui/Toolbar.cc
code/gazebo/trunk/server/gui/Toolbar.hh
code/gazebo/trunk/server/physics/Body.cc
code/gazebo/trunk/server/physics/Body.hh
code/gazebo/trunk/server/physics/BoxGeom.cc
code/gazebo/trunk/server/physics/BoxGeom.hh
code/gazebo/trunk/server/physics/CylinderGeom.cc
code/gazebo/trunk/server/physics/CylinderGeom.hh
code/gazebo/trunk/server/physics/Geom.cc
code/gazebo/trunk/server/physics/Geom.hh
code/gazebo/trunk/server/physics/PlaneGeom.cc
code/gazebo/trunk/server/physics/PlaneGeom.hh
code/gazebo/trunk/server/physics/SphereGeom.cc
code/gazebo/trunk/server/physics/SphereGeom.hh
code/gazebo/trunk/server/rendering/CameraManager.hh
code/gazebo/trunk/server/rendering/OgreCreator.cc
code/gazebo/trunk/server/rendering/OgreCreator.hh
Modified: code/gazebo/trunk/server/Entity.cc
===================================================================
--- code/gazebo/trunk/server/Entity.cc 2008-09-09 02:52:01 UTC (rev 7005)
+++ code/gazebo/trunk/server/Entity.cc 2008-09-09 13:05:16 UTC (rev 7006)
@@ -45,6 +45,7 @@
Param::Begin(&this->parameters);
this->nameP = new ParamT<std::string>("name","",1);
this->staticP = new ParamT<bool>("static",false,0);
+ //this->staticP->Callback( &Entity::SetStatic, this);
Param::End();
this->selected = false;
@@ -142,7 +143,7 @@
////////////////////////////////////////////////////////////////////////////////
// Set whether this entity is static: immovable
-void Entity::SetStatic(bool s)
+void Entity::SetStatic(const bool &s)
{
std::vector< Entity *>::iterator iter;
Body *body = NULL;
@@ -200,9 +201,29 @@
////////////////////////////////////////////////////////////////////////////////
/// Get the parameters
-std::vector<Param*> *Entity::GetParameters()
+std::vector<Param*> *Entity::GetParams()
{
return &this->parameters;
}
+////////////////////////////////////////////////////////////////////////////////
+/// Get a parameter by name
+Param *Entity::GetParam(const std::string &key) const
+{
+ std::vector<Param*>::const_iterator iter;
+ Param *result = NULL;
+ for (iter = this->parameters.begin(); iter != this->parameters.end(); iter++)
+ {
+ if ((*iter)->GetKey() == key)
+ {
+ result = *iter;
+ break;
+ }
+ }
+
+ if (result == NULL)
+ gzerr(0) << "Unable to find Param using key[" << key << "]\n";
+
+ return result;
+}
Modified: code/gazebo/trunk/server/Entity.hh
===================================================================
--- code/gazebo/trunk/server/Entity.hh 2008-09-09 02:52:01 UTC (rev 7005)
+++ code/gazebo/trunk/server/Entity.hh 2008-09-09 13:05:16 UTC (rev 7006)
@@ -97,7 +97,7 @@
/// \brief Set whether this entity is static: immovable
/// \param s Bool, true = static
- public: void SetStatic(bool s);
+ public: void SetStatic(const bool &s);
/// \brief Return whether this entity is static
/// \return bool True = static
@@ -114,7 +114,10 @@
public: bool operator==(const Entity &ent) const;
/// \brief Get the parameters
- public: std::vector<Param*> *GetParameters();
+ public: std::vector<Param*> *GetParams();
+
+ /// \brief Get a parameter by name
+ public: Param *GetParam(const std::string &key) const;
/// \brief Parent of this entity
protected: Entity *parent;
Modified: code/gazebo/trunk/server/Model.cc
===================================================================
--- code/gazebo/trunk/server/Model.cc 2008-09-09 02:52:01 UTC (rev 7005)
+++ code/gazebo/trunk/server/Model.cc 2008-09-09 13:05:16 UTC (rev 7006)
@@ -62,8 +62,12 @@
Param::Begin(&this->parameters);
this->canonicalBodyNameP = new ParamT<std::string>("canonicalBody",
std::string(),0);
+
this->xyzP = new ParamT<Vector3>("xyz", Vector3(0,0,0), 0);
+ this->xyzP->Callback(&Model::SetPosition, this);
+
this->rpyP = new ParamT<Quatern>("rpy", Quatern(1,0,0,0), 0);
+ this->rpyP->Callback( &Model::SetRotation, this);
Param::End();
this->parentBodyNameP = NULL;
@@ -466,6 +470,26 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Set the position of the model
+void Model::SetPosition( const Vector3 &pos)
+{
+ Pose3d pose = this->GetPose();
+ pose.pos = pos;
+
+ this->SetPose(pose);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the rotation of the model
+void Model::SetRotation( const Quatern &rot)
+{
+ Pose3d pose = this->GetPose();
+ pose.rot = rot;
+
+ this->SetPose(pose);
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Get the current pose
const Pose3d &Model::GetPose() const
{
@@ -689,6 +713,7 @@
return this->bodies[this->canonicalBodyNameP->GetValue()];
}
+
////////////////////////////////////////////////////////////////////////////////
// Load a renderable model (like a light source).
void Model::LoadRenderable(XMLConfigNode *node)
Modified: code/gazebo/trunk/server/Model.hh
===================================================================
--- code/gazebo/trunk/server/Model.hh 2008-09-09 02:52:01 UTC (rev 7005)
+++ code/gazebo/trunk/server/Model.hh 2008-09-09 13:05:16 UTC (rev 7006)
@@ -101,7 +101,13 @@
/// \brief Set the current pose
public: void SetPose(const Pose3d &pose);
-
+
+ /// \brief Set the position of the model
+ public: void SetPosition( const Vector3 &pos );
+
+ /// \brief Set the rotation of the model
+ public: void SetRotation( const Quatern &rot );
+
/// \brief Get the current pose
public: const Pose3d &GetPose() const;
Modified: code/gazebo/trunk/server/Param.hh
===================================================================
--- code/gazebo/trunk/server/Param.hh 2008-09-09 02:52:01 UTC (rev 7005)
+++ code/gazebo/trunk/server/Param.hh 2008-09-09 13:05:16 UTC (rev 7006)
@@ -31,6 +31,8 @@
#include <vector>
#include <boost/lexical_cast.hpp>
#include <boost/any.hpp>
+#include <boost/bind.hpp>
+#include <boost/signal.hpp>
#include <typeinfo>
#include <string>
@@ -61,6 +63,9 @@
/// \brief Get the type
public: virtual std::string GetAsString() const {return std::string();}
+ /// \brief Set the parameter value from a string
+ public: virtual void SetFromString(std::string &, bool callback=false) {}
+
/// List of created parameters
private: static std::vector<Param*> *params;
@@ -81,8 +86,12 @@
/// \brief Load the param from an XML config file
public: void Load(XMLConfigNode *node);
+ /// \brief Get the parameter value as a string
public: virtual std::string GetAsString() const;
+ /// \brief Set the parameter value from a string
+ public: virtual void SetFromString( std::string &str, bool callback=false
);
+
/// \brief Get the value
public: T GetValue() const;
@@ -97,12 +106,20 @@
return out;
}
-
+
+ public: template< typename C>
+ void Callback( void (C::*func)(const T &), C *c)
+ {
+ changeSignal.connect( boost::bind( func, c, _1) );
+ }
+
+
private: T value;
private: T defaultValue;
private: int required;
+ private: boost::signal<void (T)> changeSignal;
};
@@ -138,28 +155,39 @@
std::string input = node->GetString(this->key, stream.str(),
this->required);
+ this->SetFromString( input );
+ }
+
+
//////////////////////////////////////////////////////////////////////////////
+ // Get value as string
+ template<typename T>
+ std::string ParamT<T>::GetAsString() const
+ {
+ return boost::lexical_cast<std::string>(this->value);
+ }
+
+
//////////////////////////////////////////////////////////////////////////////
+ // Set value from string
+ template<typename T>
+ void ParamT<T>::SetFromString(std::string &str, bool callback)
+ {
// "true" and "false" doesn't work properly
- if (input == "true")
- input = "1";
- else if (input == "false")
- input = "0";
+ if (str == "true")
+ str = "1";
+ else if (str == "false")
+ str = "0";
try
{
- this->value = boost::lexical_cast<T>(input);
+ this->value = boost::lexical_cast<T>(str);
}
catch (boost::bad_lexical_cast &e)
{
std::cerr << "Unable to read value with key[" << this->key << "]\n";
}
- }
-
//////////////////////////////////////////////////////////////////////////////
- // Get value as boost
- template<typename T>
- std::string ParamT<T>::GetAsString() const
- {
- return boost::lexical_cast<std::string>(this->value);
+ if (callback)
+ this->changeSignal(this->value);
}
//////////////////////////////////////////////////////////////////////////////
Modified: code/gazebo/trunk/server/XMLConfig.cc
===================================================================
--- code/gazebo/trunk/server/XMLConfig.cc 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/XMLConfig.cc 2008-09-09 13:05:16 UTC (rev
7006)
@@ -458,7 +458,7 @@
while (value[i] == ' ') i++;
while (value[j] == ' ') j--;
result = xmlStrndup(value+i, j-i+1);
- delete value;
+ xmlFree(value);
}
return result;
Modified: code/gazebo/trunk/server/XMLConfig.hh
===================================================================
--- code/gazebo/trunk/server/XMLConfig.hh 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/XMLConfig.hh 2008-09-09 13:05:16 UTC (rev
7006)
@@ -131,7 +131,8 @@
public: std::string GetValue() const;
/// \brief Get an attribute string value
- public: std::string GetString( const std::string &key, const std::string
&def,
+ public: std::string GetString( const std::string &key,
+ const std::string &def,
int require = 0 ) const;
/// \brief Get a attribute character value
Modified: code/gazebo/trunk/server/gui/Toolbar.cc
===================================================================
--- code/gazebo/trunk/server/gui/Toolbar.cc 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/gui/Toolbar.cc 2008-09-09 13:05:16 UTC (rev
7006)
@@ -57,6 +57,13 @@
this->entityBrowser->column_widths( columnWidths );
this->entityBrowser->callback(&Toolbar::AttributeBrowserCB, this);
+ y = this->entityBrowser->y() + this->entityBrowser->h() + 20;
+ this->attributeInput = new Fl_Input(x+10, y, w-20, 20, "Input:");
+ this->attributeInput->align(FL_ALIGN_TOP);
+ this->attributeInput->labelsize(12);
+ this->attributeInput->when( FL_WHEN_ENTER_KEY | FL_WHEN_RELEASE );
+ this->attributeInput->callback(&Toolbar::AttributeInputCB, this);
+
this->end();
this->resizable(NULL);
@@ -64,6 +71,7 @@
Toolbar::~Toolbar()
{
+ delete this->attributeInput;
}
////////////////////////////////////////////////////////////////////////////////
@@ -83,14 +91,14 @@
if (model)
{
const std::map<std::string, Body *> *bodies = model->GetBodies();
- const std::vector< Geom *> *geoms;;
- std::map<std::string, Body *>::const_iterator iter;
- std::vector<Geom*>::const_iterator giter;
+ const std::map<std::string, Geom *> *geoms;
+ std::map<std::string, Body*>::const_iterator iter;
+ std::map<std::string, Geom*>::const_iterator giter;
std::string value;
for (iter = bodies->begin(); iter != bodies->end(); iter++)
{
- value = "@[EMAIL PROTECTED]@s-Body:";
+ value = "@[EMAIL PROTECTED]@s-Body:[EMAIL PROTECTED]@[EMAIL
PROTECTED]" + iter->second->GetName();
this->AddToBrowser(value);
this->AddEntityToAttributeBrowser( iter->second, " " );
@@ -98,9 +106,9 @@
for (giter = geoms->begin(); giter != geoms->end(); giter++)
{
- value = "@[EMAIL PROTECTED]@s -Geom:";
+ value = "@[EMAIL PROTECTED]@s -Geom:[EMAIL PROTECTED]@[EMAIL
PROTECTED]" + giter->second->GetName();
this->AddToBrowser(value);
- this->AddEntityToAttributeBrowser( (*giter), " " );
+ this->AddEntityToAttributeBrowser( giter->second, " " );
}
}
}
@@ -119,10 +127,106 @@
// Attribute browser callback
void Toolbar::AttributeBrowserCB( Fl_Widget * w, void *data)
{
- printf("Callback\n");
+ Fl_Hold_Browser *browser = (Fl_Hold_Browser*)(w);
+ Toolbar *toolbar = (Toolbar*)(data);
+ int selected = browser->value();
+ std::string lineText = browser->text(selected);
+ std::string lbl;
+ int beginLbl = 0;
+ int endLbl = 0;
+ int beginValue = 0;
+
+ if (lineText.find("-Body") != std::string::npos ||
+ lineText.find("-Geom") != std::string::npos)
+ {
+ toolbar->attributeInput->deactivate();
+ return;
+ }
+ else
+ toolbar->attributeInput->activate();
+
+ endLbl = lineText.find("~");
+ while (lineText[beginLbl] == '@') beginLbl+=2;
+ while (lineText[beginLbl] == ' ') beginLbl++;
+
+ beginValue = endLbl+1;
+ while (lineText[beginValue] == '@') beginValue+=2;
+
+ toolbar->attributeInputLbl = lineText.substr(beginLbl, endLbl-beginLbl);
+
+ toolbar->attributeInput->label(toolbar->attributeInputLbl.c_str());
+
+ toolbar->attributeInput->value( lineText.substr(beginValue, lineText.size()
- beginValue).c_str() );
+
+ toolbar->attributeInput->redraw();
}
////////////////////////////////////////////////////////////////////////////////
+// Attribute modification callback
+void Toolbar::AttributeInputCB( Fl_Widget *w, void *data)
+{
+ Fl_Input *input = (Fl_Input*)(w);
+ Toolbar *toolbar = (Toolbar*)(data);
+ Fl_Hold_Browser *browser = toolbar->entityBrowser;
+ int selected = browser->value();
+ Model *model =
dynamic_cast<Model*>(Simulator::Instance()->GetSelectedEntity());
+ Body *body = NULL;
+ Geom *geom = NULL;
+ std::string geomName, bodyName, value, label;
+
+ // Make sure we have a valid model
+ if (!model)
+ {
+ gzerr(0) << "Somehow you selected something that is not a model.\n";
+ return;
+ }
+
+ value = input->value();
+ label = input->label();
+
+ // Get rid of the ':' at the end
+ label = label.substr(0, label.size()-1);
+
+ // Get the name of the body and geom.
+ while (selected > 0)
+ {
+ std::string lineText = browser->text(selected);
+ int lastAmp = lineText.rfind("@")+2;
+
+ if (lineText.find("-Geom:") != std::string::npos && geomName.empty())
+ geomName = lineText.substr( lastAmp, lineText.size()-lastAmp );
+ else if (lineText.find("-Body:") != std::string::npos && bodyName.empty())
+ bodyName = lineText.substr( lastAmp, lineText.size()-lastAmp );
+
+ selected--;
+ }
+
+ // Get the body
+ if (!bodyName.empty())
+ body = model->GetBody(bodyName);
+
+ // Get the geom
+ if (!geomName.empty() && body)
+ geom = body->GetGeom(geomName);
+
+ // Get the parameter
+ Param *param = NULL;
+ if (geom)
+ param = geom->GetParam(label);
+ else if (body)
+ param = body->GetParam(label);
+ else
+ param = model->GetParam(label);
+
+ if (param)
+ {
+ param->SetFromString( value, true );
+ }
+
+ std::cout << "Label[" << label << "] Value[" << value << "]\n";
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Add entity to browser
void Toolbar::AddEntityToAttributeBrowser(Entity *entity, std::string prefix)
{
@@ -131,7 +235,7 @@
std::string value;
std::string colorStr = "";
- parameters = entity->GetParameters();
+ parameters = entity->GetParams();
// Process all the parameters in the entity
for (iter = parameters->begin(); iter != parameters->end(); iter++)
Modified: code/gazebo/trunk/server/gui/Toolbar.hh
===================================================================
--- code/gazebo/trunk/server/gui/Toolbar.hh 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/gui/Toolbar.hh 2008-09-09 13:05:16 UTC (rev
7006)
@@ -52,6 +52,7 @@
public: void Update();
public: static void AttributeBrowserCB( Fl_Widget * w, void *data);
+ public: static void AttributeInputCB( Fl_Widget * w, void *data);
private: void AddEntityToAttributeBrowser(Entity *ent, std::string prefix);
private: void AddToBrowser(const std::string &line);
@@ -60,6 +61,9 @@
private: int columnWidths[3];
private: int attrCount;
+
+ private: Fl_Input *attributeInput;
+ private: std::string attributeInputLbl;
};
}
Modified: code/gazebo/trunk/server/physics/Body.cc
===================================================================
--- code/gazebo/trunk/server/physics/Body.cc 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/Body.cc 2008-09-09 13:05:16 UTC (rev
7006)
@@ -66,7 +66,10 @@
Param::Begin(&this->parameters);
this->xyzP = new ParamT<Vector3>("xyz", Vector3(), 0);
+ this->xyzP->Callback( &Body::SetPosition, this );
+
this->rpyP = new ParamT<Quatern>("rpy", Quatern(), 0);
+ this->rpyP->Callback( &Body::SetRotation, this );
Param::End();
}
@@ -75,12 +78,12 @@
// Destructor
Body::~Body()
{
- std::vector< Geom* >::iterator giter;
+ std::map< std::string, Geom* >::iterator giter;
std::vector< Sensor* >::iterator siter;
for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
{
- GZ_DELETE (*giter);
+ GZ_DELETE (giter->second);
}
this->geoms.clear();
@@ -143,7 +146,7 @@
// Save the body based on our XMLConfig node
void Body::Save(std::string &prefix, std::ostream &stream)
{
- std::vector< Geom* >::iterator giter;
+ std::map<std::string, Geom* >::iterator giter;
std::vector< Sensor* >::iterator siter;
Model *model = dynamic_cast<Model*>(this->parent);
//Vector3 pose = model->GetPose() - this->GetPose();
@@ -160,7 +163,7 @@
for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
{
stream << "\n";
- (*giter)->Save(p, stream);
+ giter->second->Save(p, stream);
}
for (siter = this->sensors.begin(); siter != this->sensors.end(); siter++)
@@ -213,7 +216,7 @@
void Body::Update()
{
std::vector< Sensor* >::iterator sensorIter;
- std::vector< Geom* >::iterator geomIter;
+ std::map< std::string, Geom* >::iterator geomIter;
this->UpdatePose();
@@ -226,7 +229,7 @@
for (geomIter=this->geoms.begin();
geomIter!=this->geoms.end(); geomIter++)
{
- (*geomIter)->Update();
+ geomIter->second->Update();
}
for (sensorIter=this->sensors.begin();
@@ -251,7 +254,13 @@
}
}
- this->geoms.push_back(geom);
+ std::map<std::string, Geom*>::iterator iter =
this->geoms.find(geom->GetName());
+
+ if (iter == this->geoms.end())
+ this->geoms[geom->GetName()] = geom;
+ else
+ gzerr(0) << "Attempting to add two geoms with the same name[" <<
geom->GetName() << "] to body[" << this->GetName() << "].\n";
+
}
////////////////////////////////////////////////////////////////////////////////
@@ -267,7 +276,7 @@
Pose3d newPose;
this->staticPose = pose;
- std::vector<Geom*>::iterator iter;
+ std::map<std::string, Geom*>::iterator iter;
//this->SetPosition(this->staticPose.pos);
//this->SetRotation(this->staticPose.rot);
@@ -275,9 +284,9 @@
for (iter = this->geoms.begin(); iter != this->geoms.end(); iter++)
{
//newPose = (*iter)->GetPose() - this->staticPose;
- newPose = (*iter)->GetPose() - oldPose;
+ newPose = iter->second->GetPose() - oldPose;
newPose += this->staticPose;
- (*iter)->SetPose(newPose);
+ iter->second->SetPose(newPose);
}
}
else
@@ -498,7 +507,7 @@
{
const dMass *lmass;
Pose3d oldPose, newPose, pose;
- std::vector< Geom* >::iterator giter;
+ std::map< std::string, Geom* >::iterator giter;
if (!this->bodyId)
return;
@@ -508,8 +517,8 @@
for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
{
- lmass = (*giter)->GetBodyMassMatrix();
- if ((*giter)->IsPlaceable() && (*giter)->GetGeomId())
+ lmass = giter->second->GetBodyMassMatrix();
+ if (giter->second->IsPlaceable() && giter->second->GetGeomId())
{
dMassAdd( &this->mass, lmass );
}
@@ -535,12 +544,12 @@
// Fixup the poses of the geoms (they are attached to the CoM)
for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
{
- if ((*giter)->IsPlaceable())
+ if (giter->second->IsPlaceable())
{
this->comPose = oldPose;
- pose = (*giter)->GetPose();
+ pose = giter->second->GetPose();
this->comPose = newPose;
- (*giter)->SetPose(pose, false);
+ giter->second->SetPose(pose, false);
}
}
@@ -682,7 +691,25 @@
////////////////////////////////////////////////////////////////////////////////
/// Get the vector of all geoms
-const std::vector<Geom*> *Body::GetGeoms() const
+const std::map<std::string, Geom*> *Body::GetGeoms() const
{
return &(this->geoms);
}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Get a geom by name
+Geom *Body::GetGeom(const std::string &name) const
+{
+ std::map<std::string, Geom*>::const_iterator iter = this->geoms.find(name);
+
+ if (iter != this->geoms.end())
+ {
+ return iter->second;
+ }
+ else
+ {
+ gzerr(0) << "Unknown geom[" << name << "]\n";
+ return NULL;
+ }
+}
+
Modified: code/gazebo/trunk/server/physics/Body.hh
===================================================================
--- code/gazebo/trunk/server/physics/Body.hh 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/Body.hh 2008-09-09 13:05:16 UTC (rev
7006)
@@ -28,7 +28,7 @@
#define BODY_HH
#include <ode/ode.h>
-#include <list>
+#include <map>
#include <vector>
#include "XMLConfig.hh"
@@ -141,7 +141,10 @@
public: Vector3 GetTorque() const;
/// \brief Get the vector of all geoms
- public: const std::vector<Geom*> *GetGeoms() const;
+ public: const std::map<std::string, Geom*> *GetGeoms() const;
+
+ /// \brief Get a geom by name
+ public: Geom *GetGeom(const std::string &name) const;
/// Load a new geom helper function
/// \param node XMLConfigNode used to load the geom
@@ -158,7 +161,7 @@
private: void UpdatePose();
/// List of geometries attached to this body
- private: std::vector< Geom* > geoms;
+ private: std::map< std::string, Geom* > geoms;
/// List of attached sensors
private: std::vector< Sensor* > sensors;
Modified: code/gazebo/trunk/server/physics/BoxGeom.cc
===================================================================
--- code/gazebo/trunk/server/physics/BoxGeom.cc 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/BoxGeom.cc 2008-09-09 13:05:16 UTC (rev
7006)
@@ -39,6 +39,7 @@
{
Param::Begin(&this->parameters);
this->sizeP = new ParamT<Vector3>("size",Vector3(1,1,1),1);
+ this->sizeP->Callback( &BoxGeom::SetSize, this );
Param::End();
}
@@ -55,24 +56,13 @@
void BoxGeom::LoadChild(XMLConfigNode *node)
{
this->sizeP->Load(node);
-
- // Initialize box mass matrix
- dMassSetBoxTotal(&this->mass, this->massP->GetValue(),
- this->sizeP->GetValue().x,
- this->sizeP->GetValue().y,
- this->sizeP->GetValue().z);
-
- // Create a box geometry with box mass matrix
- this->SetGeom(dCreateBox( 0, this->sizeP->GetValue().x,
- this->sizeP->GetValue().y,
- this->sizeP->GetValue().z), true );
+ this->SetSize( this->sizeP->GetValue() );
}
//////////////////////////////////////////////////////////////////////////////
// Set the size of the box
-void BoxGeom::SetSize( Vector3 size )
+void BoxGeom::SetSize( const Vector3 &size )
{
-
this->sizeP->SetValue( size );
// Initialize box mass matrix
Modified: code/gazebo/trunk/server/physics/BoxGeom.hh
===================================================================
--- code/gazebo/trunk/server/physics/BoxGeom.hh 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/BoxGeom.hh 2008-09-09 13:05:16 UTC (rev
7006)
@@ -85,7 +85,7 @@
protected: void SaveChild(std::string &prefix, std::ostream &stream);
/// \brief Set the size of the box
- public: void SetSize( Vector3 size );
+ public: void SetSize( const Vector3 &size );
private: ParamT<Vector3> *sizeP;
};
Modified: code/gazebo/trunk/server/physics/CylinderGeom.cc
===================================================================
--- code/gazebo/trunk/server/physics/CylinderGeom.cc 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/CylinderGeom.cc 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -37,6 +37,8 @@
{
Param::Begin(&this->parameters);
this->sizeP = new ParamT<Vector2<double> >("size", Vector2<double>(1.0,1.0),
1);
+ this->sizeP->Callback( &CylinderGeom::SetSize, this);
+
Param::End();
}
@@ -52,14 +54,21 @@
void CylinderGeom::LoadChild(XMLConfigNode *node)
{
this->sizeP->Load(node);
+ this->SetSize( this->sizeP->GetValue() );
+}
+//////////////////////////////////////////////////////////////////////////////
+// Set the size of the cylinder
+void CylinderGeom::SetSize( const Vector2<double> &size )
+{
+ this->sizeP->SetValue( size );
+
// Initialize mass matrix
dMassSetCylinderTotal(&this->mass, this->massP->GetValue(), 3,
this->sizeP->GetValue().x, this->sizeP->GetValue().y);
this->SetGeom( dCreateCylinder( 0, this->sizeP->GetValue().x,
this->sizeP->GetValue().y ), true );
-
}
//////////////////////////////////////////////////////////////////////////////
Modified: code/gazebo/trunk/server/physics/CylinderGeom.hh
===================================================================
--- code/gazebo/trunk/server/physics/CylinderGeom.hh 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/CylinderGeom.hh 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -77,6 +77,9 @@
/// \brief Destructor
public: virtual ~CylinderGeom();
+ /// \brief Set the size of the cylinder
+ public: void SetSize( const Vector2<double> &size );
+
/// \brief Load the cylinder
protected: void LoadChild(XMLConfigNode *node);
Modified: code/gazebo/trunk/server/physics/Geom.cc
===================================================================
--- code/gazebo/trunk/server/physics/Geom.cc 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/Geom.cc 2008-09-09 13:05:16 UTC (rev
7006)
@@ -63,8 +63,14 @@
Param::Begin(&this->parameters);
this->massP = new ParamT<double>("mass",0.001,0);
+ this->massP->Callback( &Geom::SetMass, this);
+
this->xyzP = new ParamT<Vector3>("xyz", Vector3(), 0);
+ this->xyzP->Callback( &Geom::SetPosition, this);
+
this->rpyP = new ParamT<Quatern>("rpy", Quatern(), 0);
+ this->rpyP->Callback( &Geom::SetRotation, this);
+
this->laserFiducialIdP = new ParamT<int>("laserFiducialId",-1,0);
this->laserRetroP = new ParamT<float>("laserRetro",-1,0);
Param::End();
@@ -502,3 +508,13 @@
*/
}
}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the mass
+void Geom::SetMass(const double &mass)
+{
+ dMassAdjust(&this->mass, mass);
+ this->body->UpdateCoM();
+}
+
+
Modified: code/gazebo/trunk/server/physics/Geom.hh
===================================================================
--- code/gazebo/trunk/server/physics/Geom.hh 2008-09-09 02:52:01 UTC (rev
7005)
+++ code/gazebo/trunk/server/physics/Geom.hh 2008-09-09 13:05:16 UTC (rev
7006)
@@ -137,9 +137,12 @@
/// \brief Set the visibility of the joints
public: void ShowJoints(bool show);
- /// \brief Set the visibility of the physical entity of this geom
+ /// \brief Set the visibility of the physical entity of this geom
public: void ShowPhysics(bool);
+ /// \brief Set the mass
+ public: void SetMass(const double &mass);
+
/// Contact parameters
public: ContactParams *contact;
Modified: code/gazebo/trunk/server/physics/PlaneGeom.cc
===================================================================
--- code/gazebo/trunk/server/physics/PlaneGeom.cc 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/PlaneGeom.cc 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -42,14 +42,26 @@
{
Param::Begin(&this->parameters);
this->normalP = new ParamT<Vector3>("normal",Vector3(0,0,1),0);
+ this->normalP->Callback( &PlaneGeom::SetNormal, this );
+
this->sizeP = new ParamT<Vector2<double> >("size",
Vector2<double>(1000, 1000), 0);
+ this->sizeP->Callback( &PlaneGeom::SetSize, this );
+
this->segmentsP = new ParamT<Vector2<double> >("segments",
Vector2<double>(10, 10), 0);
+ this->segmentsP->Callback( &PlaneGeom::SetSegments, this );
+
this->uvTileP = new ParamT<Vector2<double> >("uvTile",
Vector2<double>(1, 1), 0);
+ this->uvTileP->Callback( &PlaneGeom::SetUVTile, this );
+
this->materialP = new ParamT<std::string>("material","",1);
+ this->materialP->Callback( &PlaneGeom::SetMaterial, this );
+
this->castShadowsP = new ParamT<bool>("castShadows", false, 0);
+ this->castShadowsP->Callback( &PlaneGeom::SetCastShadows, this );
+
Param::End();
}
@@ -83,19 +95,26 @@
{
Vector3 perp;
- double altitude = 0;
-
this->normalP->Load(node);
this->sizeP->Load(node);
this->segmentsP->Load(node);
this->uvTileP->Load(node);
this->materialP->Load(node);
this->castShadowsP->Load(node);
+ this->CreatePlane();
+}
- OgreCreator::CreatePlane(**(this->normalP), **(this->sizeP),
- **(this->segmentsP), **(this->uvTileP), **(this->materialP),
- **(this->castShadowsP), this->GetVisualNode());
+////////////////////////////////////////////////////////////////////////////////
+// Create the plane
+void PlaneGeom::CreatePlane()
+{
+ double altitude = 0;
+ this->meshName = OgreCreator::CreatePlane(**(this->normalP),
+ **(this->sizeP), **(this->segmentsP), **(this->uvTileP),
+ **(this->materialP), **(this->castShadowsP), this->GetVisualNode(),
+ this->meshName);
+
this->SetGeom(dCreatePlane(this->spaceId, this->normalP->GetValue().x,
this->normalP->GetValue().y, this->normalP->GetValue().z,
altitude),false);
@@ -106,6 +125,61 @@
}
//////////////////////////////////////////////////////////////////////////////
+/// Set the normal
+void PlaneGeom::SetNormal( const Vector3 &norm )
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->normalP->SetValue( norm );
+ this->CreatePlane();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Set the size
+void PlaneGeom::SetSize( const Vector2<double> &size )
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->sizeP->SetValue( size );
+ this->CreatePlane();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Set the number of segments
+void PlaneGeom::SetSegments(const Vector2<double> &seg)
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->segmentsP->SetValue( seg );
+ this->CreatePlane();
+}
+
+
+//////////////////////////////////////////////////////////////////////////////
+// Set the uvtile
+void PlaneGeom::SetUVTile(const Vector2<double> &uv)
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->uvTileP->SetValue( uv );
+ this->CreatePlane();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+// Set the material
+void PlaneGeom::SetMaterial(const std::string &mat)
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->materialP->SetValue( mat );
+ this->CreatePlane();
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/// Set cast shadows
+void PlaneGeom::SetCastShadows(const bool &cast)
+{
+ OgreCreator::RemoveMesh(this->meshName);
+ this->castShadowsP->SetValue( cast );
+ this->CreatePlane();
+}
+
+//////////////////////////////////////////////////////////////////////////////
/// Save child parameters
void PlaneGeom::SaveChild(std::string &prefix, std::ostream &stream)
{
Modified: code/gazebo/trunk/server/physics/PlaneGeom.hh
===================================================================
--- code/gazebo/trunk/server/physics/PlaneGeom.hh 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/PlaneGeom.hh 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -96,6 +96,28 @@
/// \brief Load the plane
public: virtual void LoadChild(XMLConfigNode *node);
+ /// \brief Create the plane
+ public: void CreatePlane();
+
+ /// \brief Set the normal
+ public: void SetNormal( const Vector3 &norm );
+
+ /// \brief Set the size
+ public: void SetSize( const Vector2<double> &size );
+
+ /// \brief Set the number of segments
+ public: void SetSegments(const Vector2<double> &seg);
+
+ /// \brief Set the uvtile
+ public: void SetUVTile(const Vector2<double> &uv);
+
+ /// \brief Set the material
+ public: void SetMaterial(const std::string &mat);
+
+ /// \brief Set cast shadows
+ public: void SetCastShadows(const bool &cast);
+
+
/// \brief Save child parameters
protected: void SaveChild(std::string &prefix, std::ostream &stream);
@@ -105,6 +127,8 @@
private: ParamT<Vector2<double> > *uvTileP;
private: ParamT<std::string> *materialP;
private: ParamT<bool> *castShadowsP;
+
+ private: std::string meshName;
};
/// \}
Modified: code/gazebo/trunk/server/physics/SphereGeom.cc
===================================================================
--- code/gazebo/trunk/server/physics/SphereGeom.cc 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/SphereGeom.cc 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -39,6 +39,7 @@
{
Param::Begin(&this->parameters);
this->radiusP = new ParamT<double>("size",1.0,0);
+ this->radiusP->Callback( &SphereGeom::SetSize, this );
Param::End();
}
@@ -55,15 +56,24 @@
void SphereGeom::LoadChild(XMLConfigNode *node)
{
this->radiusP->Load(node);
+ this->SetSize( this->radiusP->GetValue() );
+}
+////////////////////////////////////////////////////////////////////////////////
+// Set the size
+void SphereGeom::SetSize(const double &radius)
+{
+ this->radiusP->SetValue( radius );
+
// Initialize box mass matrix
- dMassSetSphereTotal(&this->mass, this->massP->GetValue(),
this->radiusP->GetValue());
+ dMassSetSphereTotal(&this->mass, this->massP->GetValue(),
+ this->radiusP->GetValue());
// Create the sphere geometry
this->SetGeom( dCreateSphere(0, this->radiusP->GetValue()), true);
}
-//////////////////////////////////////////////////////////////////////////////
+////////////////////////////////////////////////////////////////////////////////
// Save sphere parameters
void SphereGeom::SaveChild(std::string &prefix, std::ostream &stream)
{
Modified: code/gazebo/trunk/server/physics/SphereGeom.hh
===================================================================
--- code/gazebo/trunk/server/physics/SphereGeom.hh 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/physics/SphereGeom.hh 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -78,6 +78,9 @@
/// \brief Destructor
public: virtual ~SphereGeom();
+ /// \brief Set the size
+ public: void SetSize(const double &radius);
+
/// \brief Load the sphere
protected: void LoadChild(XMLConfigNode *node);
Modified: code/gazebo/trunk/server/rendering/CameraManager.hh
===================================================================
--- code/gazebo/trunk/server/rendering/CameraManager.hh 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/rendering/CameraManager.hh 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -78,7 +78,6 @@
public: void DecActiveCamera();
/// \brief Connect a boost::slot the the AddCamera signal
-
public: template<typename T>
void ConnectAddCameraSignal( T subscriber )
{
Modified: code/gazebo/trunk/server/rendering/OgreCreator.cc
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/rendering/OgreCreator.cc 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -74,9 +74,10 @@
////////////////////////////////////////////////////////////////////////////////
// Create a plane
-void OgreCreator::CreatePlane(const Vector3 &normal, const Vector2<double>
&size, const Vector2<double> &segments, const Vector2<double> &uvTile, const
std::string &material, bool castShadows, OgreVisual *parent)
+std::string OgreCreator::CreatePlane(const Vector3 &normal, const
Vector2<double> &size, const Vector2<double> &segments, const Vector2<double>
&uvTile, const std::string &material, bool castShadows, OgreVisual *parent,
const std::string &name)
{
Vector3 n = normal;
+ std::string resultName;
n.Normalize();
Vector3 perp = n.GetPerpendicular();
@@ -85,7 +86,13 @@
//FIXME: only one plane per parent
//TODO:names and parents
- Ogre::MeshManager::getSingleton().createPlane(parent->GetName() + "_PLANE",
+
+ if (name.empty())
+ resultName = parent->GetName() + "_PLANE";
+ else
+ resultName = name;
+
+ Ogre::MeshManager::getSingleton().createPlane(resultName,
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, plane,
size.x, size.y,
(int)segments.x, (int)segments.y,
@@ -97,6 +104,8 @@
parent->SetMaterial(material);
parent->SetCastShadows(castShadows);
+
+ return resultName;
}
@@ -533,6 +542,14 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Remove a mesh by name
+void OgreCreator::RemoveMesh(const std::string &name)
+{
+ if (!name.empty() && Ogre::MeshManager::getSingleton().resourceExists(name))
+ Ogre::MeshManager::getSingleton().remove(name);
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Create a window for Ogre
Ogre::RenderWindow *OgreCreator::CreateWindow(Fl_Window *flWindow, unsigned
int width, unsigned int height)
{
Modified: code/gazebo/trunk/server/rendering/OgreCreator.hh
===================================================================
--- code/gazebo/trunk/server/rendering/OgreCreator.hh 2008-09-09 02:52:01 UTC
(rev 7005)
+++ code/gazebo/trunk/server/rendering/OgreCreator.hh 2008-09-09 13:05:16 UTC
(rev 7006)
@@ -70,10 +70,10 @@
/// It adds itself to the Visual node parent, it will those change parent
/// properties if needed, to avoid this create a child visual node for the
/// plane
- public: static void CreatePlane(const Vector3 &normal,
+ public: static std::string CreatePlane(const Vector3 &normal,
const Vector2<double> &size, const Vector2<double> &segments,
const Vector2<double> &uvTile, const std::string &material,
- bool castShadows, OgreVisual *parent);
+ bool castShadows, OgreVisual *parent, const std::string &name);
/// \brief Create a light source
/// \return The name of the light source
@@ -113,6 +113,9 @@
/// \brief Draw the uniform grid pattern
public: static void DrawGrid();
+ /// \brief Remove a mesh by name
+ public: static void RemoveMesh(const std::string &name);
+
private: static unsigned int lightCounter;
private: static unsigned int windowCounter;
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
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit