Revision: 7380
http://playerstage.svn.sourceforge.net/playerstage/?rev=7380&view=rev
Author: natepak
Date: 2009-03-08 02:57:32 +0000 (Sun, 08 Mar 2009)
Log Message:
-----------
Added flag to disable friction model wide
Modified Paths:
--------------
code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
code/branches/federation/gazebo/server/Model.cc
code/branches/federation/gazebo/server/Model.hh
code/branches/federation/gazebo/server/physics/Body.cc
code/branches/federation/gazebo/server/physics/Body.hh
code/branches/federation/gazebo/server/physics/Geom.cc
code/branches/federation/gazebo/server/physics/Geom.hh
code/branches/federation/gazebo/server/physics/HeightmapGeom.cc
code/branches/federation/gazebo/worlds/pioneer2dx.world
Modified:
code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
===================================================================
--- code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
2009-03-08 02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/examples/libgazebo/simiface/simiface.cc
2009-03-08 02:57:32 UTC (rev 7380)
@@ -40,15 +40,16 @@
{
gazebo::Pose pose;
- pose.pos.z = 1.0;
- gazebo::Vec3 linearVel(0.1, 0, 0);
+ pose.pos.x = i+0.1;
+ pose.pos.z = .145;
+ gazebo::Vec3 linearVel(0.2, 0, 0);
gazebo::Vec3 angularVel(0, 0, 0);
gazebo::Vec3 linearAccel(0, 0, 0);
gazebo::Vec3 angularAccel(0, 0, 0);
simIface->SetState(name, pose, linearVel, angularVel,
linearAccel, angularAccel );
- usleep(9000000);
+ usleep(900000);
}
Modified: code/branches/federation/gazebo/server/Model.cc
===================================================================
--- code/branches/federation/gazebo/server/Model.cc 2009-03-08 02:35:03 UTC
(rev 7379)
+++ code/branches/federation/gazebo/server/Model.cc 2009-03-08 02:57:32 UTC
(rev 7380)
@@ -72,6 +72,9 @@
this->enableGravityP = new ParamT<bool>("enableGravity", true, 0);
this->enableGravityP->Callback( &Model::SetGravityMode, this );
+ this->enableFrictionP = new ParamT<bool>("enableFriction", true, 0);
+ this->enableFrictionP->Callback( &Model::SetFrictionMode, this );
+
Param::End();
this->parentBodyNameP = NULL;
@@ -123,6 +126,7 @@
this->xyzP->Load(node);
this->rpyP->Load(node);
this->enableGravityP->Load(node);
+ this->enableFrictionP->Load(node);
this->xmlNode = node;
this->type=node->GetName();
@@ -180,8 +184,10 @@
// This must be placed after creation of the bodies
// Static variable overrides the gravity
if (**this->staticP == false)
- this->SetGravityMode( **(this->enableGravityP) );
+ this->SetGravityMode( **this->enableGravityP );
+ this->SetFrictionMode( **this->enableFrictionP );
+
return 0;
// Get the name of the python module
@@ -235,6 +241,7 @@
stream << prefix << " " << *(this->xyzP) << "\n";
stream << prefix << " " << *(this->rpyP) << "\n";
stream << prefix << " " << *(this->enableGravityP) << "\n";
+ stream << prefix << " " << *(this->enableFrictionP) << "\n";
if (this->type == "physical")
{
@@ -799,6 +806,22 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Set the gravity mode of the model
+void Model::SetFrictionMode( const bool &v )
+{
+ Body *body;
+
+ std::map<std::string, Body* >::iterator iter;
+
+ for (iter=this->bodies.begin(); iter!=this->bodies.end(); iter++)
+ {
+ body = iter->second;
+
+ body->SetFrictionMode( v );
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Load a renderable model (like a light source).
void Model::LoadRenderable(XMLConfigNode *node)
{
Modified: code/branches/federation/gazebo/server/Model.hh
===================================================================
--- code/branches/federation/gazebo/server/Model.hh 2009-03-08 02:35:03 UTC
(rev 7379)
+++ code/branches/federation/gazebo/server/Model.hh 2009-03-08 02:57:32 UTC
(rev 7380)
@@ -158,6 +158,9 @@
/// \brief Set the gravity mode of the model
public: void SetGravityMode( const bool &v );
+ /// \brief Set the friction mode of the model
+ public: void SetFrictionMode( const bool &v );
+
/// \brief Load a body helper function
/// \param node XML Configuration node
private: void LoadBody(XMLConfigNode *node);
@@ -209,6 +212,7 @@
private: ParamT<std::string> *parentBodyNameP;
private: ParamT<std::string> *myBodyNameP;
private: ParamT<bool> *enableGravityP;
+ private: ParamT<bool> *enableFrictionP;
// Name of a light (if the model is renderable:light)
private: std::string lightName;
Modified: code/branches/federation/gazebo/server/physics/Body.cc
===================================================================
--- code/branches/federation/gazebo/server/physics/Body.cc 2009-03-08
02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/server/physics/Body.cc 2009-03-08
02:57:32 UTC (rev 7380)
@@ -202,6 +202,18 @@
}
////////////////////////////////////////////////////////////////////////////////
+/// Set the friction mode of the body
+void Body::SetFrictionMode( const bool &v )
+{
+ std::map< std::string, Geom* >::iterator giter;
+
+ for (giter = this->geoms.begin(); giter != this->geoms.end(); giter++)
+ {
+ giter->second->SetFrictionMode( v );
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
// Initialize the body
void Body::Init()
{
Modified: code/branches/federation/gazebo/server/physics/Body.hh
===================================================================
--- code/branches/federation/gazebo/server/physics/Body.hh 2009-03-08
02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/server/physics/Body.hh 2009-03-08
02:57:32 UTC (rev 7380)
@@ -117,6 +117,9 @@
/// \brief Set whether gravity affects this body
public: void SetGravityMode(bool mode);
+ /// \brief Set the friction mode of the body
+ public: void SetFrictionMode( const bool &v );
+
/// \brief Set the linear velocity of the body
public: void SetLinearVel(const Vector3 &vel);
Modified: code/branches/federation/gazebo/server/physics/Geom.cc
===================================================================
--- code/branches/federation/gazebo/server/physics/Geom.cc 2009-03-08
02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/server/physics/Geom.cc 2009-03-08
02:57:32 UTC (rev 7380)
@@ -562,3 +562,14 @@
{
return this->body->GetModel();
}
+
+////////////////////////////////////////////////////////////////////////////////
+/// Set the friction mode of the geom
+void Geom::SetFrictionMode( const bool &v )
+{
+ this->contact->mu1 = 0;
+ this->contact->mu2 = 0;
+ this->contact->slip1 = 0;
+ this->contact->slip2 = 0;
+}
+
Modified: code/branches/federation/gazebo/server/physics/Geom.hh
===================================================================
--- code/branches/federation/gazebo/server/physics/Geom.hh 2009-03-08
02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/server/physics/Geom.hh 2009-03-08
02:57:32 UTC (rev 7380)
@@ -159,6 +159,9 @@
/// \brief Get the model this geom belongs to
public: Model *GetModel() const;
+ /// \brief Set the friction mode of the geom
+ public: void SetFrictionMode( const bool &v );
+
/// Contact parameters
public: ContactParams *contact;
Modified: code/branches/federation/gazebo/server/physics/HeightmapGeom.cc
===================================================================
--- code/branches/federation/gazebo/server/physics/HeightmapGeom.cc
2009-03-08 02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/server/physics/HeightmapGeom.cc
2009-03-08 02:57:32 UTC (rev 7380)
@@ -227,9 +227,8 @@
stream << "MaxMipMapLevel=2\n";
// Create a data stream for loading the terrain into Ogre
- char *mstr = new char[1024];//stream.str().size()];
- bzero (mstr, 1024);
- sprintf(mstr, (char*)(stream.str().c_str()));
+ char *mstr = strdup(stream.str().c_str());
+
Ogre::DataStreamPtr dataStream(
new Ogre::MemoryDataStream(mstr,strlen(mstr)) );
@@ -287,7 +286,7 @@
pose.rot = pose.rot * quat;
this->body->SetPose(pose);
- delete [] mstr;
+ free(mstr);
}
////////////////////////////////////////////////////////////////////////////////
Modified: code/branches/federation/gazebo/worlds/pioneer2dx.world
===================================================================
--- code/branches/federation/gazebo/worlds/pioneer2dx.world 2009-03-08
02:35:03 UTC (rev 7379)
+++ code/branches/federation/gazebo/worlds/pioneer2dx.world 2009-03-08
02:57:32 UTC (rev 7380)
@@ -94,9 +94,10 @@
-->
<model:physical name="pioneer2dx_model1">
- <xyz>0 0 1.145</xyz>
+ <xyz>0 0 .145</xyz>
<rpy>0.0 0.0 0.0</rpy>
<enableGravity>false</enableGravity>
+ <enableFriction>false</enableFriction>
<controller:differential_position2d name="controller1">
<leftJoint>left_wheel_hinge</leftJoint>
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
Open Source Business Conference (OSBC), March 24-25, 2009, San Francisco, CA
-OSBC tackles the biggest issue in open source: Open Sourcing the Enterprise
-Strategies to boost innovation and cut costs with open source participation
-Receive a $600 discount off the registration fee with the source code: SFAD
http://p.sf.net/sfu/XcvMzF8H
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit