Revision: 8429 http://playerstage.svn.sourceforge.net/playerstage/?rev=8429&view=rev Author: natepak Date: 2009-11-21 21:26:54 +0000 (Sat, 21 Nov 2009)
Log Message: ----------- Fixed up the contact sensor Modified Paths: -------------- code/gazebo/trunk/server/controllers/bumper/generic/Generic_Bumper.cc code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.cc code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.hh code/gazebo/trunk/server/physics/CMakeLists.txt code/gazebo/trunk/server/physics/Geom.cc code/gazebo/trunk/server/physics/Geom.hh code/gazebo/trunk/server/physics/bullet/BulletGeom.cc code/gazebo/trunk/server/physics/bullet/BulletPhysics.cc code/gazebo/trunk/server/physics/ode/ODEGeom.cc code/gazebo/trunk/server/physics/ode/ODEPhysics.cc code/gazebo/trunk/server/physics/ode/ODEPhysics.hh code/gazebo/trunk/server/sensors/contact/ContactSensor.cc code/gazebo/trunk/server/sensors/contact/ContactSensor.hh Added Paths: ----------- code/gazebo/trunk/server/physics/Contact.cc code/gazebo/trunk/server/physics/Contact.hh code/gazebo/trunk/server/physics/JointFeedback.hh code/gazebo/trunk/server/physics/SurfaceParams.cc code/gazebo/trunk/server/physics/SurfaceParams.hh Removed Paths: ------------- code/gazebo/trunk/server/physics/ContactParams.cc code/gazebo/trunk/server/physics/ContactParams.hh Modified: code/gazebo/trunk/server/controllers/bumper/generic/Generic_Bumper.cc =================================================================== --- code/gazebo/trunk/server/controllers/bumper/generic/Generic_Bumper.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/controllers/bumper/generic/Generic_Bumper.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -74,17 +74,16 @@ { this->myIface->Lock(1); - this->myIface->data->bumper_count = this->myParent->GetContactCount(); + this->myIface->data->bumper_count = this->myParent->GetGeomCount(); this->myIface->data->head.time = Simulator::Instance()->GetRealTime(); - for (unsigned int i=0; i < this->myParent->GetContactCount(); i++) + for (unsigned int i=0; i < this->myParent->GetGeomCount(); i++) { - this->myIface->data->bumpers[i] = this->myParent->GetContactState(i); + this->myIface->data->bumpers[i] = + this->myParent->GetGeomContactCount(i) > 0 ? 1 : 0; } - this->myParent->ResetContactStates(); - this->myIface->Unlock(); } Modified: code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.cc =================================================================== --- code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -29,7 +29,6 @@ #include "PhysicsEngine.hh" #include "Geom.hh" -#include "ContactParams.hh" #include "Simulator.hh" #include "RaySensor.hh" #include "Global.hh" @@ -193,8 +192,8 @@ this->holdJoint = World::Instance()->GetPhysicsEngine()->CreateJoint(Joint::SLIDER); this->holdJoint->SetName(this->GetName() + "_Hold_Joint"); - this->paddles[LEFT]->contact->Callback(&Pioneer2_Gripper::LeftPaddleCB, this); - this->paddles[RIGHT]->contact->Callback(&Pioneer2_Gripper::RightPaddleCB, this); + this->paddles[LEFT]->ContactCallback(&Pioneer2_Gripper::LeftPaddleCB, this); + this->paddles[RIGHT]->ContactCallback(&Pioneer2_Gripper::RightPaddleCB, this); } //////////////////////////////////////////////////////////////////////////////// @@ -366,20 +365,20 @@ //////////////////////////////////////////////////////////////////////////////// // Left paddle contact callback -void Pioneer2_Gripper::LeftPaddleCB(Geom *g1, Geom *g2) +void Pioneer2_Gripper::LeftPaddleCB(const Contact &contact) { - if (g1->GetName() != this->paddles[LEFT]->GetName()) - this->contactGeoms[LEFT] = g1; + if (contact.geom1->GetName() != this->paddles[LEFT]->GetName()) + this->contactGeoms[LEFT] = contact.geom1; else - this->contactGeoms[LEFT] = g2; + this->contactGeoms[LEFT] = contact.geom2; } //////////////////////////////////////////////////////////////////////////////// // Right paddle contact callback -void Pioneer2_Gripper::RightPaddleCB(Geom *g1, Geom *g2) +void Pioneer2_Gripper::RightPaddleCB(const Contact &contact) { - if (g1->GetName() != this->paddles[RIGHT]->GetName()) - this->contactGeoms[RIGHT] = g1; + if (contact.geom1->GetName() != this->paddles[RIGHT]->GetName()) + this->contactGeoms[RIGHT] = contact.geom1; else - this->contactGeoms[RIGHT] = g2; + this->contactGeoms[RIGHT] = contact.geom2; } Modified: code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.hh =================================================================== --- code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.hh 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/controllers/gripper/pioneer2/Pioneer2_Gripper.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -68,10 +68,10 @@ public: virtual ~Pioneer2_Gripper(); /// \brief Left paddle contact callback - public: void LeftPaddleCB(Geom *g1, Geom *g2); + public: void LeftPaddleCB(const Contact &contact); /// \brief Right paddle contact callback - public: void RightPaddleCB(Geom *g1, Geom *g2); + public: void RightPaddleCB(const Contact &contact); /// \brief Load the controller /// \param node XML config node Modified: code/gazebo/trunk/server/physics/CMakeLists.txt =================================================================== --- code/gazebo/trunk/server/physics/CMakeLists.txt 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/CMakeLists.txt 2009-11-21 21:26:54 UTC (rev 8429) @@ -11,7 +11,7 @@ set (sources Body.cc PhysicsFactory.cc PhysicsEngine.cc - ContactParams.cc + SurfaceParams.cc Mass.cc Joint.cc Geom.cc @@ -25,12 +25,13 @@ TrimeshShape.cc MapShape.cc HeightmapShape.cc + Contact.cc ) set (headers BallJoint.hh Body.hh PhysicsFactory.hh - ContactParams.hh + SurfaceParams.hh Hinge2Joint.hh HingeJoint.hh Joint.hh @@ -49,6 +50,8 @@ SphereShape.hh TrimeshShape.hh HeightmapShape.hh + Contact.hh + ) add_library(gazebo_physics SHARED ${sources}) Added: code/gazebo/trunk/server/physics/Contact.cc =================================================================== --- code/gazebo/trunk/server/physics/Contact.cc (rev 0) +++ code/gazebo/trunk/server/physics/Contact.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -0,0 +1,71 @@ +/* + * Gazebo - Outdoor Multi-Robot Simulator + * Copyright (C) 2003 + * Nate Koenig & Andrew Howard + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/* Desc: Specification of a contact + * Author: Nate Koenig + * Date: 10 Nov 2009 + * SVN: $Id$ + */ + +#include "Contact.hh" + +using namespace gazebo; + +//////////////////////////////////////////////////////////////////////////////// +/// Constructor +Contact::Contact() +{ + this->geom1 = NULL; + this->geom2 = NULL; +} + +//////////////////////////////////////////////////////////////////////////////// +/// Copy constructor +Contact::Contact(const Contact &c) +{ + *this = c; +} + +//////////////////////////////////////////////////////////////////////////////// +/// Destructor +Contact::~Contact() +{ +} + +//////////////////////////////////////////////////////////////////////////////// +// Clone the contact +Contact Contact::Clone() const +{ + Contact c = *this; + return c; +} + +//////////////////////////////////////////////////////////////////////////////// +// Operator = +const Contact &Contact::operator=(const Contact &contact) +{ + this->geom1 = contact.geom1; + this->geom2 = contact.geom2; + this->forces = contact.forces; + this->pos = contact.pos; + this->normal = contact.normal; + this->depth = contact.depth; + return *this; +} Added: code/gazebo/trunk/server/physics/Contact.hh =================================================================== --- code/gazebo/trunk/server/physics/Contact.hh (rev 0) +++ code/gazebo/trunk/server/physics/Contact.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -0,0 +1,66 @@ +/* + * Gazebo - Outdoor Multi-Robot Simulator + * Copyright (C) 2003 + * Nate Koenig & Andrew Howard + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/* Desc: Specification of a contact + * Author: Nate Koenig + * Date: 10 Nov 2009 + * SVN: $Id$ + */ + +#ifndef CONTACT_HH +#define CONTACT_HH + +#include "Vector3.hh" +#include "JointFeedback.hh" + +namespace gazebo +{ + class Geom; + + class Contact + { + /// \brief Constructor + public: Contact(); + + /// \brief Copy constructor + public: Contact(const Contact &c); + + /// \brief Destructor + public: virtual ~Contact(); + + /// \brief Clone the contact + public: Contact Clone() const; + + /// \brief Operator = + public: const Contact &operator=(const Contact &contact); + + public: Geom *geom1; + public: Geom *geom2; + + public: JointFeedback forces; + + public: Vector3 pos; + public: Vector3 normal; + + public: double depth; + }; +} + +#endif Deleted: code/gazebo/trunk/server/physics/ContactParams.cc =================================================================== --- code/gazebo/trunk/server/physics/ContactParams.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/ContactParams.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -1,73 +0,0 @@ -/* - * Gazebo - Outdoor Multi-Robot Simulator - * Copyright (C) 2003 - * Nate Koenig & Andrew Howard - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program; if not, write to the Free Software - * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - * - */ -/* Desc: Parameters for contact joints - * Author: Nate Koenig - * Date: 30 July 2003 - * CVS: $Id$ - */ - -#include <float.h> -#include "XMLConfig.hh" -#include "ContactParams.hh" - -using namespace gazebo; - -////////////////////////////////////////////////////////////////////////////// -// Default constructor -ContactParams::ContactParams() -{ - this->kp = 100000000.0; - - // Damping constraint - this->kd = 1.0; - - // Bounce param - this->bounce = 0.0; - - // Minumum velocity before bouce is applied - this->bounceVel = 10.0; - - this->softCfm = 0.01; - - this->mu1 = FLT_MAX; - this->mu2 = FLT_MAX; - this->slip1 = 0.01; - this->slip2 = 0.01; - - this->enableFriction = true; -} - -////////////////////////////////////////////////////////////////////////////// -/// Load the contact params -void ContactParams::Load(XMLConfigNode *node) -{ - this->kp = node->GetDouble("kp",this->kp); - this->kd = node->GetDouble("kd",this->kd); - this->bounce = node->GetDouble("bounce",this->bounce); - this->bounceVel = node->GetDouble("bounceVel",this->bounceVel); - - this->mu1 = node->GetDouble("mu1",this->mu1); - this->mu2 = node->GetDouble("mu2",this->mu2); - this->slip1 = node->GetDouble("slip1",this->slip1); - this->slip2 = node->GetDouble("slip2",this->slip2); - - this->softCfm = node->GetDouble("softCFM",this->softCfm); -} Deleted: code/gazebo/trunk/server/physics/ContactParams.hh =================================================================== --- code/gazebo/trunk/server/physics/ContactParams.hh 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/ContactParams.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -1,93 +0,0 @@ -/* - * Gazebo - Outdoor Multi-Robot Simulator - * Copyright (C) 2003 - * Nate Koenig & Andrew Howard - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program; if not, write to the Free Software - * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - * - */ -/* Desc: Parameters for contact joints - * Author: Nate Koenig - * Date: 30 July 2003 - * SVN: $Id$ - */ - -#ifndef CONTACTPARAMS_HH -#define CONTACTPARAMS_HH - -#include <boost/signal.hpp> -#include <boost/bind.hpp> - -namespace gazebo -{ - - class Geom; - - class XMLConfigNode; - - /// \brief Contact params - class ContactParams - { - /// Constructor - public: ContactParams(); - - /// \brief Load the contact params - public: void Load(XMLConfigNode *node); - - public: template< typename C> - void Callback( void (C::*func)(Geom *, Geom*), C *c ) - { - contactSignal.connect( boost::bind( func, c, _1, _2 ) ); - } - - /// Spring constant - public: double kp; - - /// Damping constant - public: double kd; - - /// 0..1, 0=no bounciness - public: double bounce; - - /// first coefficient of friction - public: double mu1; - - /// second coefficient of friction - public: double mu2; - - /// Force-dependent-slip direction 1 - public: double slip1; - - /// Force-dependent-slip direction 2 - public: double slip2; - - /// \brief bounce vel - public: double bounceVel; - - /// \brief soft constraint force mixing - public: double softCfm; - - public: bool enableFriction; - - public: Vector3 body1Force; - public: Vector3 body1Torque; - public: Vector3 body2Force; - public: Vector3 body2Torque; - - public: boost::signal< void (Geom*, Geom*)> contactSignal; - }; -} - -#endif Modified: code/gazebo/trunk/server/physics/Geom.cc =================================================================== --- code/gazebo/trunk/server/physics/Geom.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/Geom.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -33,7 +33,7 @@ #include "OgreCreator.hh" #include "Global.hh" #include "GazeboMessage.hh" -#include "ContactParams.hh" +#include "SurfaceParams.hh" #include "World.hh" #include "Body.hh" #include "Geom.hh" @@ -53,7 +53,7 @@ this->body = body; // Create the contact parameters - this->contact = new ContactParams(); + this->surface = new SurfaceParams(); this->bbVisual = NULL; @@ -112,7 +112,7 @@ this->mass.SetMass( **this->massP ); - this->contact->Load(node); + this->surface->Load(node); this->shape->Load(node); @@ -240,6 +240,7 @@ // Update void Geom::Update() { + this->ClearContacts(); } //////////////////////////////////////////////////////////////////////////////// @@ -250,43 +251,6 @@ } //////////////////////////////////////////////////////////////////////////////// -/// Get the mass of the geom -/*const dMass *Geom::GetBodyMassMatrix() -{ - - Pose3d pose; - dQuaternion q; - dMatrix3 r; - - if (!this->placeable) - return NULL; - - this->physicsEngine->LockMutex(); - pose = this->GetPose(); // get pose of the geometry - - q[0] = pose.rot.u; - q[1] = pose.rot.x; - q[2] = pose.rot.y; - q[3] = pose.rot.z; - - dQtoR(q,r); // turn quaternion into rotation matrix - - // this->mass was init to zero at start, - // read user specified mass into this->dblMass and dMassAdd in this->mass - this->bodyMass = this->mass; - - - if (dMassCheck(&this->bodyMass)) - { - dMassRotate(&this->bodyMass, r); - dMassTranslate( &this->bodyMass, pose.pos.x, pose.pos.y, pose.pos.z); - } - this->physicsEngine->UnlockMutex(); - - return &this->bodyMass; -}*/ - -//////////////////////////////////////////////////////////////////////////////// /// Set the laser fiducial integer id void Geom::SetLaserFiducialId(int id) { @@ -425,7 +389,7 @@ /// Set the friction mode of the geom void Geom::SetFrictionMode( const bool &v ) { - this->contact->enableFriction = v; + this->surface->enableFriction = v; } @@ -457,5 +421,36 @@ return this->shape; } +//////////////////////////////////////////////////////////////////////////////// +/// Add an occurance of a contact to this geom +void Geom::AddContact(const Contact &contact) +{ + this->contacts.push_back( contact.Clone() ); + this->contactSignal( contact ); +} +//////////////////////////////////////////////////////////////////////////////// +/// Clear all contact info +void Geom::ClearContacts() +{ + this->contacts.clear(); +} +//////////////////////////////////////////////////////////////////////////////// +/// Get the number of contacts +unsigned int Geom::GetContactCount() const +{ + return this->contacts.size(); +} + +//////////////////////////////////////////////////////////////////////////////// +/// Get a specific contact +Contact Geom::GetContact(unsigned int i) const +{ + if (i < this->contacts.size()) + return this->contacts[i]; + else + gzerr(0) << "Invalid contact index\n"; + + return Contact(); +} Modified: code/gazebo/trunk/server/physics/Geom.hh =================================================================== --- code/gazebo/trunk/server/physics/Geom.hh 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/Geom.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -27,6 +27,10 @@ #ifndef GEOM_HH #define GEOM_HH +#include <boost/signal.hpp> +#include <boost/bind.hpp> + +#include "Contact.hh" #include "Shape.hh" #include "Param.hh" #include "Entity.hh" @@ -38,7 +42,7 @@ { class Model; class Body; - class ContactParams; + class SurfaceParams; class XMLConfigNode; class OgreVisual; class PhysicsEngine; @@ -143,11 +147,31 @@ /// \brief Get the attached shape public: Shape *GetShape() const; + /// \brief Add an occurance of a contact to this geom + public: void AddContact(const Contact &contact); + + /// \brief Clear all contact info + public: void ClearContacts(); + + /// \brief Get the number of contacts + public: unsigned int GetContactCount() const; + + /// \brief Get a specific contact + public: Contact GetContact(unsigned int i) const; + + public: template< typename C> + void ContactCallback( void (C::*func)(const Contact&), C *c ) + { + contactSignal.connect( boost::bind(func, c, _1) ); + } + /// \brief Create the bounding box for the geom private: void CreateBoundingBox(); /// Contact parameters - public: ContactParams *contact; + public: SurfaceParams *surface; + + public: std::vector<Contact> contacts; /// The body this geom belongs to protected: Body *body; @@ -181,6 +205,8 @@ protected: PhysicsEngine *physicsEngine; protected: Shape *shape; + + public: boost::signal< void (const Contact &)> contactSignal; }; /// \} Added: code/gazebo/trunk/server/physics/JointFeedback.hh =================================================================== --- code/gazebo/trunk/server/physics/JointFeedback.hh (rev 0) +++ code/gazebo/trunk/server/physics/JointFeedback.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -0,0 +1,55 @@ +/* + * Gazebo - Outdoor Multi-Robot Simulator + * Copyright (C) 2003 + * Nate Koenig & Andrew Howard + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/* Desc: Specification of a contact + * Author: Nate Koenig + * Date: 10 Nov 2009 + * SVN: $Id$ + */ + +#ifndef JOINTFEEDBACK_HH +#define JOINTFEEDBACK_HH + +#include "Vector3.hh" + +namespace gazebo +{ + class JointFeedback + { + /// \brief Operator = + public: const JointFeedback &operator=(const JointFeedback &f) + { + this->body1Force = f.body1Force; + this->body2Force = f.body2Force; + + this->body1Torque = f.body1Torque; + this->body2Torque = f.body2Torque; + return *this; + } + + public: Vector3 body1Force; + public: Vector3 body2Force; + + public: Vector3 body1Torque; + public: Vector3 body2Torque; + }; +} + +#endif Copied: code/gazebo/trunk/server/physics/SurfaceParams.cc (from rev 8427, code/gazebo/trunk/server/physics/ContactParams.cc) =================================================================== --- code/gazebo/trunk/server/physics/SurfaceParams.cc (rev 0) +++ code/gazebo/trunk/server/physics/SurfaceParams.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -0,0 +1,73 @@ +/* + * Gazebo - Outdoor Multi-Robot Simulator + * Copyright (C) 2003 + * Nate Koenig & Andrew Howard + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/* Desc: Parameters for contact joints + * Author: Nate Koenig + * Date: 30 July 2003 + * CVS: $Id$ + */ + +#include <float.h> +#include "XMLConfig.hh" +#include "SurfaceParams.hh" + +using namespace gazebo; + +////////////////////////////////////////////////////////////////////////////// +// Default constructor +SurfaceParams::SurfaceParams() +{ + this->kp = 100000000.0; + + // Damping constraint + this->kd = 1.0; + + // Bounce param + this->bounce = 0.0; + + // Minumum velocity before bouce is applied + this->bounceVel = 10.0; + + this->softCfm = 0.01; + + this->mu1 = FLT_MAX; + this->mu2 = FLT_MAX; + this->slip1 = 0.01; + this->slip2 = 0.01; + + this->enableFriction = true; +} + +////////////////////////////////////////////////////////////////////////////// +/// Load the contact params +void SurfaceParams::Load(XMLConfigNode *node) +{ + this->kp = node->GetDouble("kp",this->kp); + this->kd = node->GetDouble("kd",this->kd); + this->bounce = node->GetDouble("bounce",this->bounce); + this->bounceVel = node->GetDouble("bounceVel",this->bounceVel); + + this->mu1 = node->GetDouble("mu1",this->mu1); + this->mu2 = node->GetDouble("mu2",this->mu2); + this->slip1 = node->GetDouble("slip1",this->slip1); + this->slip2 = node->GetDouble("slip2",this->slip2); + + this->softCfm = node->GetDouble("softCFM",this->softCfm); +} Property changes on: code/gazebo/trunk/server/physics/SurfaceParams.cc ___________________________________________________________________ Added: svn:keywords + Id Revision Added: svn:mergeinfo + /code/branches/federation/gazebo/server/physics/ContactParams.cc:7371-7550 /code/gazebo/branches/bullet2/server/physics/ContactParams.cc:8281-8355 /code/gazebo/branches/ogre-1.4.9/server/physics/ContactParams.cc:7137-7636 Copied: code/gazebo/trunk/server/physics/SurfaceParams.hh (from rev 8427, code/gazebo/trunk/server/physics/ContactParams.hh) =================================================================== --- code/gazebo/trunk/server/physics/SurfaceParams.hh (rev 0) +++ code/gazebo/trunk/server/physics/SurfaceParams.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -0,0 +1,77 @@ +/* + * Gazebo - Outdoor Multi-Robot Simulator + * Copyright (C) 2003 + * Nate Koenig & Andrew Howard + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/* Desc: Parameters for contact joints + * Author: Nate Koenig + * Date: 30 July 2003 + * SVN: $Id$ + */ + +#ifndef CONTACTPARAMS_HH +#define CONTACTPARAMS_HH + +namespace gazebo +{ + class Geom; + + class XMLConfigNode; + + /// \brief Surface params + class SurfaceParams + { + /// Constructor + public: SurfaceParams(); + + /// \brief Load the contact params + public: void Load(XMLConfigNode *node); + + /// Spring constant + public: double kp; + + /// Damping constant + public: double kd; + + /// 0..1, 0=no bounciness + public: double bounce; + + /// first coefficient of friction + public: double mu1; + + /// second coefficient of friction + public: double mu2; + + /// Force-dependent-slip direction 1 + public: double slip1; + + /// Force-dependent-slip direction 2 + public: double slip2; + + /// \brief bounce vel + public: double bounceVel; + + /// \brief soft constraint force mixing + public: double softCfm; + + public: bool enableFriction; + + }; +} + +#endif Property changes on: code/gazebo/trunk/server/physics/SurfaceParams.hh ___________________________________________________________________ Added: svn:keywords + Id Revision Added: svn:mergeinfo + /code/branches/federation/gazebo/server/physics/ContactParams.hh:7371-7550 /code/gazebo/branches/bullet2/server/physics/ContactParams.hh:8281-8355 /code/gazebo/branches/ogre-1.4.9/server/physics/ContactParams.hh:7137-7636 Modified: code/gazebo/trunk/server/physics/bullet/BulletGeom.cc =================================================================== --- code/gazebo/trunk/server/physics/bullet/BulletGeom.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/bullet/BulletGeom.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -33,7 +33,6 @@ #include "OgreCreator.hh" #include "Global.hh" #include "GazeboMessage.hh" -#include "ContactParams.hh" #include "World.hh" #include "BulletBody.hh" #include "Simulator.hh" Modified: code/gazebo/trunk/server/physics/bullet/BulletPhysics.cc =================================================================== --- code/gazebo/trunk/server/physics/bullet/BulletPhysics.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/bullet/BulletPhysics.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -45,7 +45,6 @@ #include "GazeboError.hh" #include "World.hh" #include "Vector3.hh" -#include "ContactParams.hh" #include "Entity.hh" #include "XMLConfig.hh" Modified: code/gazebo/trunk/server/physics/ode/ODEGeom.cc =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEGeom.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/ode/ODEGeom.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -33,7 +33,7 @@ #include "OgreCreator.hh" #include "Global.hh" #include "GazeboMessage.hh" -#include "ContactParams.hh" +#include "SurfaceParams.hh" #include "World.hh" #include "ODEBody.hh" #include "Simulator.hh" Modified: code/gazebo/trunk/server/physics/ode/ODEPhysics.cc =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/ode/ODEPhysics.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -34,9 +34,9 @@ #include "Vector3.hh" #include "ODEGeom.hh" #include "ODEBody.hh" -#include "ContactParams.hh" #include "Entity.hh" #include "XMLConfig.hh" +#include "SurfaceParams.hh" #include "ODEHingeJoint.hh" #include "ODEHinge2Joint.hh" @@ -211,25 +211,24 @@ iter != this->contactFeedbackIter; iter++) { - if ((*iter).geom1 == NULL) - printf("Geom1 is null\n"); + if ((*iter).contact.geom1 == NULL) + gzerr(0) << "collision update Geom1 is null\n"; - if ((*iter).geom2 == NULL) - printf("Geom2 is null\n"); + if ((*iter).contact.geom2 == NULL) + gzerr(0) << "Collision update Geom2 is null\n"; - (*iter).geom1->contact->body1Force.Set( - (*iter).feedback.f1[0], (*iter).feedback.f1[1], (*iter).feedback.f1[2]); - (*iter).geom2->contact->body2Force.Set( - (*iter).feedback.f2[0], (*iter).feedback.f2[1], (*iter).feedback.f2[2]); + (*iter).contact.forces.body1Force.Set( (*iter).feedback.f1[0], + (*iter).feedback.f1[1], (*iter).feedback.f1[2]); + (*iter).contact.forces.body2Force.Set( (*iter).feedback.f2[0], + (*iter).feedback.f2[1], (*iter).feedback.f2[2]); + (*iter).contact.forces.body1Torque.Set((*iter).feedback.t1[0], + (*iter).feedback.t1[1], (*iter).feedback.t1[2]); + (*iter).contact.forces.body2Torque.Set((*iter).feedback.t2[0], + (*iter).feedback.t2[1], (*iter).feedback.t2[2]); - (*iter).geom1->contact->body1Torque.Set( - (*iter).feedback.t1[0], (*iter).feedback.t1[1], (*iter).feedback.t1[2]); - (*iter).geom1->contact->body2Torque.Set( - (*iter).feedback.t2[0], (*iter).feedback.t2[1], (*iter).feedback.t2[2]); - - // Call the geom's contact callbacks - (*iter).geom1->contact->contactSignal( (*iter).geom1, (*iter).geom2 ); - (*iter).geom2->contact->contactSignal( (*iter).geom2, (*iter).geom1 ); + // Add the contact to each geom + (*iter).contact.geom1->AddContact( (*iter).contact ); + (*iter).contact.geom2->AddContact( (*iter).contact ); } // Reset the contact pointer @@ -423,6 +422,8 @@ return this->spaceId; } +//////////////////////////////////////////////////////////////////////////////// +// Handle a collision void ODEPhysics::CollisionCallback( void *data, dGeomID o1, dGeomID o2) { ODEPhysics *self; @@ -449,7 +450,6 @@ } else { - // We should never test two geoms in the same space assert(dGeomGetSpace(o1) != dGeomGetSpace(o2)); @@ -491,21 +491,21 @@ // Compute the CFM and ERP by assuming the two bodies form a // spring-damper system. h = self->stepTimeP->GetValue(); - kp = 1.0 / (1.0 / geom1->contact->kp + 1.0 / geom2->contact->kp); - kd = geom1->contact->kd + geom2->contact->kd; + kp = 1.0 / (1.0 / geom1->surface->kp + 1.0 / geom2->surface->kp); + kd = geom1->surface->kd + geom2->surface->kd; contact.surface.soft_erp = h * kp / (h * kp + kd); contact.surface.soft_cfm = 1.0 / (h * kp + kd); - if (geom1->contact->enableFriction && geom2->contact->enableFriction) + if (geom1->surface->enableFriction && geom2->surface->enableFriction) { - contact.surface.mu = std::min(geom1->contact->mu1, - geom2->contact->mu1); - contact.surface.mu2 = std::min(geom1->contact->mu2, - geom2->contact->mu2); - contact.surface.slip1 = std::min(geom1->contact->slip1, - geom2->contact->slip1); - contact.surface.slip2 = std::min(geom1->contact->slip2, - geom2->contact->slip2); + contact.surface.mu = std::min(geom1->surface->mu1, + geom2->surface->mu1); + contact.surface.mu2 = std::min(geom1->surface->mu2, + geom2->surface->mu2); + contact.surface.slip1 = std::min(geom1->surface->slip1, + geom2->surface->slip1); + contact.surface.slip2 = std::min(geom1->surface->slip2, + geom2->surface->slip2); } else { @@ -515,10 +515,10 @@ contact.surface.slip2 = 0.1; } - contact.surface.bounce = std::min(geom1->contact->bounce, - geom2->contact->bounce); - contact.surface.bounce_vel = std::min(geom1->contact->bounceVel, - geom2->contact->bounceVel); + contact.surface.bounce = std::min(geom1->surface->bounce, + geom2->surface->bounce); + contact.surface.bounce_vel = std::min(geom1->surface->bounceVel, + geom2->surface->bounceVel); dJointID c = dJointCreateContact (self->worldId, self->contactGroup, &contact); @@ -526,9 +526,17 @@ { self->contactFeedbacks.resize( self->contactFeedbacks.size() + 500); } - - (*self->contactFeedbackIter).geom1 = geom1; - (*self->contactFeedbackIter).geom2 = geom2; + + // Store the contact info + (*self->contactFeedbackIter).contact.geom1 = geom1; + (*self->contactFeedbackIter).contact.geom2 = geom2; + (*self->contactFeedbackIter).contact.depth = contact.geom.depth; + (*self->contactFeedbackIter).contact.pos.x = contact.geom.pos[0]; + (*self->contactFeedbackIter).contact.pos.y = contact.geom.pos[1]; + (*self->contactFeedbackIter).contact.pos.z = contact.geom.pos[2]; + (*self->contactFeedbackIter).contact.normal.x = contact.geom.normal[0]; + (*self->contactFeedbackIter).contact.normal.y = contact.geom.normal[1]; + (*self->contactFeedbackIter).contact.normal.z = contact.geom.normal[2]; dJointSetFeedback(c, &(*self->contactFeedbackIter).feedback); self->contactFeedbackIter++; Modified: code/gazebo/trunk/server/physics/ode/ODEPhysics.hh =================================================================== --- code/gazebo/trunk/server/physics/ode/ODEPhysics.hh 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/physics/ode/ODEPhysics.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -163,8 +163,7 @@ private: class ContactFeedback { public: dJointFeedback feedback; - public: Geom *geom1; - public: Geom *geom2; + public: Contact contact; }; private: std::vector<ContactFeedback> contactFeedbacks; Modified: code/gazebo/trunk/server/sensors/contact/ContactSensor.cc =================================================================== --- code/gazebo/trunk/server/sensors/contact/ContactSensor.cc 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/sensors/contact/ContactSensor.cc 2009-11-21 21:26:54 UTC (rev 8429) @@ -35,7 +35,6 @@ #include "Simulator.hh" #include "SensorFactory.hh" #include "Geom.hh" -#include "ContactParams.hh" #include "ContactSensor.hh" #include "Vector3.hh" @@ -59,96 +58,16 @@ ContactSensor::~ContactSensor() { std::vector< ParamT<std::string> *>::iterator iter; - std::vector<ContactState>::iterator citer; + std::vector<Contact>::iterator citer; for (iter = this->geomNamesP.begin(); iter != this->geomNamesP.end(); iter++) delete *iter; this->geomNamesP.clear(); - this->contacts.clear(); + this->geoms.clear(); } ////////////////////////////////////////////////////////////////////////////// -/// Get the contact time -double ContactSensor::GetContactTime(unsigned int index) const -{ - if (index < this->contacts.size()) - return this->contacts[index].time; - - return 0; -} - -////////////////////////////////////////////////////////////////////////////// -/// Return the number of contacts -unsigned int ContactSensor::GetContactCount() const -{ - return this->contacts.size(); -} - -////////////////////////////////////////////////////////////////////////////// -/// Return the contact states -uint8_t ContactSensor::GetContactState(unsigned int index) const -{ - if (index < this->contacts.size()) - return this->contacts[index].state; - - return 0; -} - -////////////////////////////////////////////////////////////////////////////// -/// Return the contact geom name -std::string ContactSensor::GetContactGeomName(unsigned int index) const -{ - if (index < this->contacts.size()) - return this->contacts[index].name; - - return std::string(""); -} - -////////////////////////////////////////////////////////////////////////////// -/// Return contact force on the first body -Vector3 ContactSensor::GetContactBody1Force(unsigned int index) const -{ - Vector3 result; - - if (index < this->contacts.size()) - result = this->contacts[index].body1Force; - - return result; -} - -////////////////////////////////////////////////////////////////////////////// -/// Return contact force on the second body -Vector3 ContactSensor::GetContactBody2Force(unsigned int index) const -{ - Vector3 result; - - if (index < this->contacts.size()) - result = this->contacts[index].body2Force; - - return result; -} - -////////////////////////////////////////////////////////////////////////////// -/// Return the self geom name -std::string ContactSensor::GetGeomName(unsigned int index) const -{ - if (index < this->contacts.size()) - return this->contacts[index].name; - - return std::string(""); -} - -////////////////////////////////////////////////////////////////////////////// -/// Reset the contact states -void ContactSensor::ResetContactStates() -{ - std::vector<ContactState>::iterator iter; - for (iter = this->contacts.begin(); iter != this->contacts.end(); iter++) - (*iter).state = 0; -} - -////////////////////////////////////////////////////////////////////////////// /// Load the ray using parameter from an XMLConfig node void ContactSensor::LoadChild(XMLConfigNode *node) { @@ -159,6 +78,7 @@ Param::Begin(&this->parameters); geomNode = node->GetChild("geom"); + while (geomNode) { ParamT<std::string> *geomName = new ParamT<std::string>("geom","",1); @@ -170,32 +90,34 @@ } ////////////////////////////////////////////////////////////////////////////// -/// Save the sensor info in XML format -void ContactSensor::SaveChild(std::string &prefix, std::ostream &stream) +// Init the contact +void ContactSensor::InitChild() { std::vector< ParamT<std::string> *>::iterator iter; for (iter = this->geomNamesP.begin(); iter != this->geomNamesP.end(); iter++) - stream << prefix << " " << *(iter) << "\n"; + { + // Get the geom from the body + Geom *geom = this->body->GetGeom( **(*iter) ); + this->geoms.push_back(geom); + } } ////////////////////////////////////////////////////////////////////////////// -// Init the contact -void ContactSensor::InitChild() +/// Save the sensor info in XML format +void ContactSensor::SaveChild(std::string &prefix, std::ostream &stream) { std::vector< ParamT<std::string> *>::iterator iter; for (iter = this->geomNamesP.begin(); iter != this->geomNamesP.end(); iter++) - { - // Get the geom from the body - Geom *geom = this->body->GetGeom( **(*iter) ); + stream << prefix << " " << *(iter) << "\n"; +} - // Set the callback - if (geom) - geom->contact->Callback( &ContactSensor::ContactCallback, this ); - else - gzthrow("Unable to find geom[" + **(*iter) + "]"); - } +////////////////////////////////////////////////////////////////////////////// +// Update the sensor information +void ContactSensor::UpdateChild() +{ + //this->contacts.clear(); } ////////////////////////////////////////////////////////////////////////////// @@ -205,38 +127,28 @@ } ////////////////////////////////////////////////////////////////////////////// -// Update the sensor information -void ContactSensor::UpdateChild() +/// Get the number of geoms that the sensor is observing +unsigned int ContactSensor::GetGeomCount() const { + return this->geoms.size(); } ////////////////////////////////////////////////////////////////////////////// -/// Contact callback -void ContactSensor::ContactCallback(Geom *g1, Geom *g2) +/// Return the number of contacts for an observed geom +unsigned int ContactSensor::GetGeomContactCount(unsigned int geomIndex) const { - // somehow here, extract contact information when user requests it - // - std::vector< ParamT<std::string> *>::iterator iter; - unsigned int i = 0; + if (geomIndex < this->geoms.size()) + return this->geoms[geomIndex]->GetContactCount(); - for (iter = this->geomNamesP.begin(); iter != this->geomNamesP.end(); iter++) - { - if ( **(*iter) == g1->GetName() || **(*iter) == g2->GetName() ) - { - if (i >= this->contacts.size()) - this->contacts.resize( this->contacts.size() + 10); - - this->contacts[i].state = 1; - this->contacts[i].time = Simulator::Instance()->GetRealTime(); - this->contacts[i].name = **(*iter)==g1->GetName()? g2->GetName() : g1->GetName(); - this->contacts[i].body1Force = g1->contact->body1Force; - this->contacts[i].body2Force = g1->contact->body2Force; - this->contacts[i].body1Torque = g1->contact->body1Torque; - this->contacts[i].body2Torque = g1->contact->body2Torque; - i++; - } - } - + return 0; } +////////////////////////////////////////////////////////////////////////////// +/// Get a contact for a geom by index +Contact ContactSensor::GetContact(unsigned int geom, unsigned int index) const +{ + if (geom < this->geoms.size()) + return this->geoms[geom]->GetContact( index ); + return Contact(); +} Modified: code/gazebo/trunk/server/sensors/contact/ContactSensor.hh =================================================================== --- code/gazebo/trunk/server/sensors/contact/ContactSensor.hh 2009-11-21 00:13:10 UTC (rev 8428) +++ code/gazebo/trunk/server/sensors/contact/ContactSensor.hh 2009-11-21 21:26:54 UTC (rev 8429) @@ -34,12 +34,12 @@ #include "Angle.hh" #include "Sensor.hh" #include "Body.hh" +#include "Contact.hh" namespace gazebo { class XMLConfigNode; - class ContactParams; /// \addtogroup gazebo_sensor /// \brief Contact sensor. @@ -61,64 +61,35 @@ /// \brief Destructor public: virtual ~ContactSensor(); - /// \brief Return the number of contacts - public: unsigned int GetContactCount() const; - - /// \brief Get a contact time - public: double GetContactTime(unsigned int index) const; - - /// \brief Return a contact state - public: uint8_t GetContactState(unsigned int index) const; - - /// \brief Return contact geometry name - public: std::string GetContactGeomName(unsigned int index) const; - - /// \brief Return contact force on the first body - public: Vector3 GetContactBody1Force(unsigned int index) const; - - /// \brief Return contact force on the second body - public: Vector3 GetContactBody2Force(unsigned int index) const; - - /// \brief Return geometry name - public: std::string GetGeomName(unsigned int index) const; - - /// \brief Reset the contact states - public: void ResetContactStates(); - /// Load the contact sensor using parameter from an XMLConfig node /// \param node The XMLConfig node protected: virtual void LoadChild(XMLConfigNode *node); - /// \brief Save the sensor info in XML format - protected: virtual void SaveChild(std::string &prefix,std::ostream &stream); - /// Initialize the sensor protected: virtual void InitChild(); /// Update sensed values protected: virtual void UpdateChild(); - + + /// \brief Save the sensor info in XML format + protected: virtual void SaveChild(std::string &prefix,std::ostream &stream); + /// Finalize the sensor protected: virtual void FiniChild(); - /// \brief Contact callback - private: void ContactCallback(Geom *g1, Geom *g2); + /// \brief Get the number of geoms that the sensor is observing + public: unsigned int GetGeomCount() const; + /// \brief Return the number of contacts for an observed geom + public: unsigned int GetGeomContactCount(unsigned int geomIndex) const; + + /// \brief Get a contact for a geom by index + public: Contact GetContact(unsigned int geom, unsigned int index) const; + /// Geom name parameter private: std::vector< ParamT<std::string> *> geomNamesP; - private: class ContactState - { - public: std::string name; - public: Vector3 body1Force; - public: Vector3 body2Force; - public: Vector3 body1Torque; - public: Vector3 body2Torque; - public: double time; - public: uint8_t state; - }; - - private: std::vector<ContactState> contacts; + private: std::vector<Geom *> geoms; }; /// \} /// \} This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------------ Let Crystal Reports handle the reporting - Free Crystal Reports 2008 30-Day trial. Simplify your report design, integration and deployment - and focus on what you do best, core application coding. Discover what's new with Crystal Reports now. http://p.sf.net/sfu/bobj-july _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit