All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
gazebo::physics::ODEPhysics Class Reference

ODE physics engine. More...

#include <ODEPhysics.hh>

Inheritance diagram for gazebo::physics::ODEPhysics:
Inheritance graph
[legend]
Collaboration diagram for gazebo::physics::ODEPhysics:
Collaboration graph
[legend]

Public Types

enum  ODEParam {
  SOLVER_TYPE, GLOBAL_CFM, GLOBAL_ERP, SOR_PRECON_ITERS,
  PGS_ITERS, SOR, CONTACT_MAX_CORRECTING_VEL, CONTACT_SURFACE_LAYER,
  MAX_CONTACTS, MIN_STEP_SIZE
}
 ODE Physics parameter types. More...
 

Public Member Functions

 ODEPhysics (WorldPtr _world)
 Constructor. More...
 
virtual ~ODEPhysics ()
 Destructor. More...
 
void Collide (ODECollision *_collision1, ODECollision *_collision2, dContactGeom *_contactCollisions)
 Collide two collision objects. More...
 
virtual CollisionPtr CreateCollision (const std::string &_shapeType, LinkPtr _parent)
 Create a collision. More...
 
virtual JointPtr CreateJoint (const std::string &_type, ModelPtr _parent)
 Create a new joint. More...
 
virtual LinkPtr CreateLink (ModelPtr _parent)
 Create a new body. More...
 
virtual ShapePtr CreateShape (const std::string &_shapeType, CollisionPtr _collision)
 Create a physics::Shape object. More...
 
virtual void DebugPrint () const
 Debug print out of the physic engine state. More...
 
virtual void Fini ()
 Finilize the physics engine. More...
 
virtual double GetContactMaxCorrectingVel ()
 : Remove this function, and replace it with a more generic property map. More...
 
virtual double GetContactSurfaceLayer ()
 : Remove this function, and replace it with a more generic property map. More...
 
virtual unsigned int GetMaxContacts ()
 : Remove this function, and replace it with a more generic property map. More...
 
virtual boost::any GetParam (const std::string &_key) const
 Documentation inherited. More...
 
virtual int GetSORPGSIters ()
 
virtual int GetSORPGSPreconIters ()
 
virtual double GetSORPGSW ()
 
dSpaceID GetSpaceId () const
 Return the world space id. More...
 
virtual std::string GetStepType () const
 Get the step type (quick, world). More...
 
virtual std::string GetType () const
 Return the physics engine type (ode|bullet|dart|simbody). More...
 
virtual double GetWorldCFM ()
 : Remove this function, and replace it with a more generic property map More...
 
virtual double GetWorldERP ()
 : Remove this function, and replace it with a more generic property map More...
 
dWorldID GetWorldId ()
 Get the world id. More...
 
virtual void Init ()
 Initialize the physics engine. More...
 
virtual void InitForThread ()
 Init the engine for threads. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the physics engine. More...
 
void ProcessJointFeedback (ODEJointFeedback *_feedback)
 process joint feedbacks. More...
 
virtual void Reset ()
 Rest the physics engine. More...
 
virtual void SetContactMaxCorrectingVel (double vel)
 : Remove this function, and replace it with a more generic property map More...
 
virtual void SetContactSurfaceLayer (double layer_depth)
 : Remove this function, and replace it with a more generic property map More...
 
virtual void SetGravity (const gazebo::math::Vector3 &_gravity)
 Set the gavity vector. More...
 
virtual void SetMaxContacts (unsigned int max_contacts)
 : Remove this function, and replace it with a more generic property map More...
 
virtual bool SetParam (const std::string &_key, const boost::any &_value)
 Documentation inherited. More...
 
virtual void SetSeed (uint32_t _seed)
 Set the random number seed for the physics engine. More...
 
virtual void SetSORPGSIters (unsigned int iters)
 
virtual void SetSORPGSPreconIters (unsigned int iters)
 
virtual void SetSORPGSW (double w)
 
virtual void SetStepType (const std::string &_type)
 Set the step type (quick, world). More...
 
virtual void SetWorldCFM (double cfm)
 : Remove this function, and replace it with a more generic property map More...
 
virtual void SetWorldERP (double erp)
 : Remove this function, and replace it with a more generic property map More...
 
virtual void UpdateCollision ()
 Update the physics engine collision. More...
 
virtual void UpdatePhysics ()
 Update the physics engine. More...
 
- Public Member Functions inherited from gazebo::physics::PhysicsEngine
 PhysicsEngine (WorldPtr _world)
 Default constructor. More...
 
virtual ~PhysicsEngine ()
 Destructor. More...
 
CollisionPtr CreateCollision (const std::string &_shapeType, const std::string &_linkName)
 Create a collision. More...
 
virtual ModelPtr CreateModel (BasePtr _base)
 Create a new model. More...
 
virtual bool GetAutoDisableFlag ()
 : Remove this function, and replace it with a more generic property map More...
 
ContactManagerGetContactManager () const
 Get a pointer to the contact manger. More...
 
virtual math::Vector3 GetGravity () const
 Return the gavity vector. More...
 
double GetMaxStepSize () const
 Get max step size. More...
 
boost::recursive_mutex * GetPhysicsUpdateMutex () const
 returns a pointer to the PhysicsEngine::physicsUpdateMutex. More...
 
double GetRealTimeUpdateRate () const
 Get real time update rate. More...
 
double GetTargetRealTimeFactor () const
 Get target real time factor. More...
 
double GetUpdatePeriod ()
 Get the simulation update period. More...
 
virtual void SetAutoDisableFlag (bool _autoDisable)
 : Remove this function, and replace it with a more generic property map More...
 
void SetMaxStepSize (double _stepSize)
 Set max step size. More...
 
void SetRealTimeUpdateRate (double _rate)
 Set real time update rate. More...
 
void SetTargetRealTimeFactor (double _factor)
 Set target real time factor. More...
 

Static Public Member Functions

static void ConvertMass (InertialPtr _interial, void *_odeMass)
 Convert an ODE mass to Inertial. More...
 
static void ConvertMass (void *_odeMass, InertialPtr _inertial)
 Convert an Inertial to ODE mass. More...
 

Protected Member Functions

virtual void OnPhysicsMsg (ConstPhysicsPtr &_msg)
 virtual callback for gztopic "~/physics". More...
 
virtual void OnRequest (ConstRequestPtr &_msg)
 virtual callback for gztopic "~/request". More...
 

Additional Inherited Members

- Protected Attributes inherited from gazebo::physics::PhysicsEngine
ContactManagercontactManager
 Class that handles all contacts generated by the physics engine. More...
 
double maxStepSize
 Real time update rate. More...
 
transport::NodePtr node
 Node for communication. More...
 
transport::SubscriberPtr physicsSub
 Subscribe to the physics topic. More...
 
boost::recursive_mutex * physicsUpdateMutex
 Mutex to protect the update cycle. More...
 
double realTimeUpdateRate
 Real time update rate. More...
 
transport::SubscriberPtr requestSub
 Subscribe to the request topic. More...
 
transport::PublisherPtr responsePub
 Response publisher. More...
 
sdf::ElementPtr sdf
 Our SDF values. More...
 
double targetRealTimeFactor
 Target real time factor. More...
 
WorldPtr world
 Pointer to the world. More...
 

Detailed Description

ODE physics engine.

Member Enumeration Documentation

ODE Physics parameter types.

Enumerator
SOLVER_TYPE 

Solve type.

GLOBAL_CFM 

Constraint force mixing.

GLOBAL_ERP 

Error reduction parameter.

SOR_PRECON_ITERS 

Number of iterations.

PGS_ITERS 

Number of iterations.

SOR 

SOR over-relaxation parameter.

CONTACT_MAX_CORRECTING_VEL 

Max correcting velocity.

CONTACT_SURFACE_LAYER 

Surface layer depth.

MAX_CONTACTS 

Maximum number of contacts.

MIN_STEP_SIZE 

Minimum step size.

Constructor & Destructor Documentation

gazebo::physics::ODEPhysics::ODEPhysics ( WorldPtr  _world)

Constructor.

Parameters
[in]_worldThe World that uses this physics engine.
virtual gazebo::physics::ODEPhysics::~ODEPhysics ( )
virtual

Destructor.

Member Function Documentation

void gazebo::physics::ODEPhysics::Collide ( ODECollision _collision1,
ODECollision _collision2,
dContactGeom *  _contactCollisions 
)

Collide two collision objects.

Parameters
[in]_collision1First collision object.
[in]_collision2Second collision object.
[in,out]_contactCollisionArray of contacts.
static void gazebo::physics::ODEPhysics::ConvertMass ( InertialPtr  _interial,
void *  _odeMass 
)
static

Convert an ODE mass to Inertial.

Parameters
[out]_intertialPointer to an Inertial object.
[in]_odeMassPointer to an ODE mass that will be converted.
static void gazebo::physics::ODEPhysics::ConvertMass ( void *  _odeMass,
InertialPtr  _inertial 
)
static

Convert an Inertial to ODE mass.

Parameters
[out]_odeMassPointer to an ODE mass.
[in]_intertialPointer to an Inertial object that will be converted.
virtual CollisionPtr gazebo::physics::ODEPhysics::CreateCollision ( const std::string &  _shapeType,
LinkPtr  _link 
)
virtual

Create a collision.

Parameters
[in]_shapeTypeType of collision to create.
[in]_linkParent link.

Implements gazebo::physics::PhysicsEngine.

virtual JointPtr gazebo::physics::ODEPhysics::CreateJoint ( const std::string &  _type,
ModelPtr  _parent 
)
virtual

Create a new joint.

Parameters
[in]_typeType of joint to create.
[in]_parentModel parent.

Implements gazebo::physics::PhysicsEngine.

virtual LinkPtr gazebo::physics::ODEPhysics::CreateLink ( ModelPtr  _parent)
virtual

Create a new body.

Parameters
[in]_parentParent model for the link.

Implements gazebo::physics::PhysicsEngine.

virtual ShapePtr gazebo::physics::ODEPhysics::CreateShape ( const std::string &  _shapeType,
CollisionPtr  _collision 
)
virtual

Create a physics::Shape object.

Parameters
[in]_shapeTypeType of shape to create.
[in]_collisionCollision parent.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::DebugPrint ( ) const
virtual

Debug print out of the physic engine state.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::Fini ( )
virtual

Finilize the physics engine.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual double gazebo::physics::ODEPhysics::GetContactMaxCorrectingVel ( )
virtual

: Remove this function, and replace it with a more generic property map.

access functions to set ODE parameters.

Returns
Max correcting velocity.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual double gazebo::physics::ODEPhysics::GetContactSurfaceLayer ( )
virtual

: Remove this function, and replace it with a more generic property map.

access functions to set ODE parameters.

Returns
Contact suerface layer depth.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual unsigned int gazebo::physics::ODEPhysics::GetMaxContacts ( )
virtual

: Remove this function, and replace it with a more generic property map.

access functions to set ODE parameters.

Returns
Maximum number of allows contacts.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual boost::any gazebo::physics::ODEPhysics::GetParam ( const std::string &  _key) const
virtual

Documentation inherited.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual int gazebo::physics::ODEPhysics::GetSORPGSIters ( )
virtual
virtual int gazebo::physics::ODEPhysics::GetSORPGSPreconIters ( )
virtual
virtual double gazebo::physics::ODEPhysics::GetSORPGSW ( )
virtual
dSpaceID gazebo::physics::ODEPhysics::GetSpaceId ( ) const

Return the world space id.

Returns
The space id for the world.
virtual std::string gazebo::physics::ODEPhysics::GetStepType ( ) const
virtual

Get the step type (quick, world).

Returns
The step type.
virtual std::string gazebo::physics::ODEPhysics::GetType ( ) const
inlinevirtual

Return the physics engine type (ode|bullet|dart|simbody).

Returns
Type of the physics engine.

Implements gazebo::physics::PhysicsEngine.

virtual double gazebo::physics::ODEPhysics::GetWorldCFM ( )
virtual

: Remove this function, and replace it with a more generic property map

Get World CFM.

Returns
World CFM.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual double gazebo::physics::ODEPhysics::GetWorldERP ( )
virtual

: Remove this function, and replace it with a more generic property map

Get World ERP.

Returns
World ERP.

Reimplemented from gazebo::physics::PhysicsEngine.

dWorldID gazebo::physics::ODEPhysics::GetWorldId ( )

Get the world id.

Returns
The world id.
virtual void gazebo::physics::ODEPhysics::Init ( )
virtual

Initialize the physics engine.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::InitForThread ( )
virtual

Init the engine for threads.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::Load ( sdf::ElementPtr  _sdf)
virtual

Load the physics engine.

Parameters
[in]_sdfPointer to the SDF parameters.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::OnPhysicsMsg ( ConstPhysicsPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/physics".

Parameters
[in]_msgPhysics message.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::OnRequest ( ConstRequestPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/request".

Parameters
[in]_msgRequest message.

Reimplemented from gazebo::physics::PhysicsEngine.

void gazebo::physics::ODEPhysics::ProcessJointFeedback ( ODEJointFeedback _feedback)

process joint feedbacks.

Parameters
[in]_feedbackODE Joint Contact feedback information.
virtual void gazebo::physics::ODEPhysics::Reset ( )
virtual

Rest the physics engine.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetContactMaxCorrectingVel ( double  _vel)
virtual

: Remove this function, and replace it with a more generic property map

Access functions to set ODE parameters.

Parameters
[in]_velMax correcting velocity.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetContactSurfaceLayer ( double  _layerDepth)
virtual

: Remove this function, and replace it with a more generic property map

Access functions to set ODE parameters.

Parameters
[in]_layerDepthSurface layer depth

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetGravity ( const gazebo::math::Vector3 _gravity)
virtual

Set the gavity vector.

Parameters
[in]_gravityNew gravity vector.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetMaxContacts ( unsigned int  _maxContacts)
virtual

: Remove this function, and replace it with a more generic property map

access functions to set ODE parameters

Parameters
[in]_maxContactsMaximum number of contacts.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual bool gazebo::physics::ODEPhysics::SetParam ( const std::string &  _key,
const boost::any &  _value 
)
virtual

Documentation inherited.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetSeed ( uint32_t  _seed)
virtual

Set the random number seed for the physics engine.

Parameters
[in]_seedThe random number seed.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetSORPGSIters ( unsigned int  iters)
virtual
virtual void gazebo::physics::ODEPhysics::SetSORPGSPreconIters ( unsigned int  iters)
virtual
virtual void gazebo::physics::ODEPhysics::SetSORPGSW ( double  w)
virtual
virtual void gazebo::physics::ODEPhysics::SetStepType ( const std::string &  _type)
virtual

Set the step type (quick, world).

Parameters
[in]_typeThe step type (quick or world).
virtual void gazebo::physics::ODEPhysics::SetWorldCFM ( double  _cfm)
virtual

: Remove this function, and replace it with a more generic property map

Access functions to set ODE parameters.

Parameters
[in]_cfmConstraint force mixing.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::SetWorldERP ( double  _erp)
virtual

: Remove this function, and replace it with a more generic property map

Access functions to set ODE parameters.

Parameters
[in]_erpError reduction parameter.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::UpdateCollision ( )
virtual

Update the physics engine collision.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::ODEPhysics::UpdatePhysics ( )
virtual

Update the physics engine.

Reimplemented from gazebo::physics::PhysicsEngine.


The documentation for this class was generated from the following file: