ODEPhysics Class Reference

ODE physics engine. More...

#include <ODEPhysics.hh>

Inherits PhysicsEngine.

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, INERTIA_RATIO_REDUCTION, FRICTION_MODEL,
  WORLD_SOLVER_TYPE
}
 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...
 
CollisionPtr CreateCollision (const std::string &_shapeType, const std::string &_linkName)
 Create a collision. 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 ModelPtr CreateModel (BasePtr _base)
 Create a new model. 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 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 double GetContactMaxCorrectingVel ()
 
virtual double GetContactSurfaceLayer ()
 
virtual std::string GetFrictionModel () const
 Get friction model. More...
 
virtual math::Vector3 GetGravity () const
 Return the gravity vector. More...
 
virtual unsigned int GetMaxContacts ()
 
double GetMaxStepSize () const
 Get max step size. More...
 
virtual boost::any GetParam (const std::string &_key) const
 Documentation inherited. More...
 
virtual bool GetParam (const std::string &_key, boost::any &_value) const
 Documentation inherited. More...
 
boost::recursive_mutex * GetPhysicsUpdateMutex () const
 returns a pointer to the PhysicsEngine::physicsUpdateMutex. More...
 
double GetRealTimeUpdateRate () const
 Get real time update rate. More...
 
sdf::ElementPtr GetSDF () const
 Get a pointer to the SDF element for this physics engine. 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...
 
double GetTargetRealTimeFactor () const
 Get target real time factor. More...
 
virtual std::string GetType () const
 Return the physics engine type (ode|bullet|dart|simbody). More...
 
double GetUpdatePeriod ()
 Get the simulation update period. More...
 
virtual double GetWorldCFM ()
 
virtual double GetWorldERP ()
 
dWorldID GetWorldId ()
 Get the world id. More...
 
virtual std::string GetWorldStepSolverType () const
 Get solver type for world step. 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...
 
virtual ignition::math::Vector3d MagneticField () const
 Return the magnetic field vector. More...
 
void ProcessJointFeedback (ODEJointFeedback *_feedback)
 process joint feedbacks. More...
 
virtual void Reset ()
 Rest the physics engine. More...
 
virtual void SetAutoDisableFlag (bool _autoDisable)
 : Remove this function, and replace it with a more generic property map More...
 
virtual void SetContactMaxCorrectingVel (double vel)
 
virtual void SetContactSurfaceLayer (double layer_depth)
 
virtual void SetFrictionModel (const std::string &_fricModel)
 Set friction model type. More...
 
virtual void SetGravity (const gazebo::math::Vector3 &_gravity)
 Set the gravity vector. More...
 
virtual void SetMaxContacts (unsigned int max_contacts)
 : Remove this function, and replace it with a more generic property map More...
 
void SetMaxStepSize (double _stepSize)
 Set max step size. More...
 
virtual bool SetParam (const std::string &_key, const boost::any &_value)
 Documentation inherited. More...
 
void SetRealTimeUpdateRate (double _rate)
 Set real time update rate. 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...
 
void SetTargetRealTimeFactor (double _factor)
 Set target real time factor. More...
 
virtual void SetWorldCFM (double cfm)
 
virtual void SetWorldERP (double erp)
 
virtual void SetWorldStepSolverType (const std::string &_worldSolverType)
 Set world step solver type. More...
 
virtual void UpdateCollision ()
 Update the physics engine collision. More...
 
virtual void UpdatePhysics ()
 Update the physics engine. More...
 
WorldPtr World () const
 Get a pointer to the world. More...
 

Static Public Member Functions

static Friction_Model ConvertFrictionModel (const std::string &_fricModel)
 Convert a string to a Friction_Model enum. More...
 
static std::string ConvertFrictionModel (const Friction_Model _fricModel)
 Convert a Friction_Model enum to a string. More...
 
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...
 
static std::string ConvertWorldStepSolverType (const World_Solver_Type _solverType)
 Convert a World_Solver_Type enum to a string. More...
 
static World_Solver_Type ConvertWorldStepSolverType (const std::string &_solverType)
 Convert a string to a World_Solver_Type enum. 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...
 

Protected Attributes

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

enum ODEParam

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.

INERTIA_RATIO_REDUCTION 

Limit ratios of inertias of adjacent links (note that the corresponding SDF tag is "use_dynamic_moi_rescaling")

FRICTION_MODEL 

friction model

WORLD_SOLVER_TYPE 

LCP Solver.

Constructor & Destructor Documentation

ODEPhysics ( WorldPtr  _world)

Constructor.

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

Destructor.

Member Function Documentation

void 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 Friction_Model ConvertFrictionModel ( const std::string &  _fricModel)
static

Convert a string to a Friction_Model enum.

Parameters
[in]_fricModelFriction model string.
Returns
A Friction_Model enum. Defaults to pyramid_friction if _fricModel is unrecognized.
static std::string ConvertFrictionModel ( const Friction_Model  _fricModel)
static

Convert a Friction_Model enum to a string.

Parameters
[in]_fricModelFriction_Model enum.
Returns
Friction model string. Returns "unknown" if _fricModel is unrecognized.
static void 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 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.
static std::string ConvertWorldStepSolverType ( const World_Solver_Type  _solverType)
static

Convert a World_Solver_Type enum to a string.

Parameters
[in]_solverTypeWorld_Solver_Type enum.
Returns
World solver type string. Returns "unknown" if _solverType is unrecognized.
static World_Solver_Type ConvertWorldStepSolverType ( const std::string &  _solverType)
static

Convert a string to a World_Solver_Type enum.

Parameters
[in]_solverTypeWorld solver type string.
Returns
A World_Solver_Type enum. Defaults to ODE_DEFAULT if _solverType is unrecognized.
CollisionPtr CreateCollision ( const std::string &  _shapeType,
const std::string &  _linkName 
)
inherited

Create a collision.

Parameters
[in]_shapeTypeType of collision to create.
[in]_linkNameName of the parent link.
virtual CollisionPtr CreateCollision ( const std::string &  _shapeType,
LinkPtr  _link 
)
virtual

Create a collision.

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

Implements PhysicsEngine.

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

Create a new joint.

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

Implements PhysicsEngine.

virtual LinkPtr CreateLink ( ModelPtr  _parent)
virtual

Create a new body.

Parameters
[in]_parentParent model for the link.

Implements PhysicsEngine.

virtual ModelPtr CreateModel ( BasePtr  _base)
virtualinherited

Create a new model.

Parameters
[in]_baseBoost shared pointer to a new model.

Reimplemented in DARTPhysics, and SimbodyPhysics.

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

Create a physics::Shape object.

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

Implements PhysicsEngine.

virtual void DebugPrint ( ) const
virtual

Debug print out of the physic engine state.

Implements PhysicsEngine.

virtual void Fini ( )
virtual

Finilize the physics engine.

Reimplemented from PhysicsEngine.

virtual bool GetAutoDisableFlag ( )
inlinevirtualinherited

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

access functions to set ODE parameters..

Returns
Auto disable flag.
ContactManager* GetContactManager ( ) const
inherited

Get a pointer to the contact manger.

Returns
Pointer to the contact manager.
virtual double GetContactMaxCorrectingVel ( )
virtual
virtual double GetContactSurfaceLayer ( )
virtual
virtual std::string GetFrictionModel ( ) const
virtual

Get friction model.

Returns
Friction model type.
virtual math::Vector3 GetGravity ( ) const
virtualinherited

Return the gravity vector.

Returns
The gravity vector.
virtual unsigned int GetMaxContacts ( )
virtual
double GetMaxStepSize ( ) const
inherited

Get max step size.

Returns
Max step size.
virtual boost::any GetParam ( const std::string &  _key) const
virtual

Documentation inherited.

Reimplemented from PhysicsEngine.

virtual bool GetParam ( const std::string &  _key,
boost::any &  _value 
) const
virtual

Documentation inherited.

Reimplemented from PhysicsEngine.

boost::recursive_mutex* GetPhysicsUpdateMutex ( ) const
inlineinherited

returns a pointer to the PhysicsEngine::physicsUpdateMutex.

Returns
Pointer to the physics mutex.

References PhysicsEngine::physicsUpdateMutex.

double GetRealTimeUpdateRate ( ) const
inherited

Get real time update rate.

Returns
Update rate
sdf::ElementPtr GetSDF ( ) const
inherited

Get a pointer to the SDF element for this physics engine.

Returns
Pointer to the physics SDF element.
virtual int GetSORPGSIters ( )
virtual
virtual int GetSORPGSPreconIters ( )
virtual
virtual double GetSORPGSW ( )
virtual
dSpaceID GetSpaceId ( ) const

Return the world space id.

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

Get the step type (quick, world).

Returns
The step type.
double GetTargetRealTimeFactor ( ) const
inherited

Get target real time factor.

Returns
Target real time factor
virtual std::string GetType ( ) const
inlinevirtual

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

Returns
Type of the physics engine.

Implements PhysicsEngine.

double GetUpdatePeriod ( )
inherited

Get the simulation update period.

Returns
Simulation update period.
virtual double GetWorldCFM ( )
virtual
virtual double GetWorldERP ( )
virtual
dWorldID GetWorldId ( )

Get the world id.

Returns
The world id.
virtual std::string GetWorldStepSolverType ( ) const
virtual

Get solver type for world step.

Returns
Type of solver used by world step.
virtual void Init ( )
virtual

Initialize the physics engine.

Implements PhysicsEngine.

virtual void InitForThread ( )
virtual

Init the engine for threads.

Implements PhysicsEngine.

virtual void Load ( sdf::ElementPtr  _sdf)
virtual

Load the physics engine.

Parameters
[in]_sdfPointer to the SDF parameters.

Reimplemented from PhysicsEngine.

virtual ignition::math::Vector3d MagneticField ( ) const
virtualinherited

Return the magnetic field vector.

Returns
The magnetic field vector.
virtual void OnPhysicsMsg ( ConstPhysicsPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/physics".

Parameters
[in]_msgPhysics message.

Reimplemented from PhysicsEngine.

virtual void OnRequest ( ConstRequestPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/request".

Parameters
[in]_msgRequest message.

Reimplemented from PhysicsEngine.

void ProcessJointFeedback ( ODEJointFeedback *  _feedback)

process joint feedbacks.

Parameters
[in]_feedbackODE Joint Contact feedback information.
virtual void Reset ( )
virtual

Rest the physics engine.

Reimplemented from PhysicsEngine.

virtual void SetAutoDisableFlag ( bool  _autoDisable)
virtualinherited

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

Access functions to set ODE parameters.

Parameters
[in]_autoDisableTrue to enable auto disabling of bodies.
virtual void SetContactMaxCorrectingVel ( double  vel)
virtual
virtual void SetContactSurfaceLayer ( double  layer_depth)
virtual
virtual void SetFrictionModel ( const std::string &  _fricModel)
virtual

Set friction model type.

Parameters
[in]_fricModelType of friction model.
virtual void SetGravity ( const gazebo::math::Vector3 _gravity)
virtual

Set the gravity vector.

Parameters
[in]_gravityNew gravity vector.

Implements PhysicsEngine.

virtual void 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 PhysicsEngine.

void SetMaxStepSize ( double  _stepSize)
inherited

Set max step size.

Parameters
[in]_stepSizeMax step size.
virtual bool SetParam ( const std::string &  _key,
const boost::any &  _value 
)
virtual

Documentation inherited.

Reimplemented from PhysicsEngine.

void SetRealTimeUpdateRate ( double  _rate)
inherited

Set real time update rate.

Parameters
[in]_rateUpdate rate
virtual void SetSeed ( uint32_t  _seed)
virtual

Set the random number seed for the physics engine.

Parameters
[in]_seedThe random number seed.

Implements PhysicsEngine.

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

Set the step type (quick, world).

Parameters
[in]_typeThe step type (quick or world).
void SetTargetRealTimeFactor ( double  _factor)
inherited

Set target real time factor.

Parameters
[in]_factorTarget real time factor
virtual void SetWorldCFM ( double  cfm)
virtual
virtual void SetWorldERP ( double  erp)
virtual
virtual void SetWorldStepSolverType ( const std::string &  _worldSolverType)
virtual

Set world step solver type.

Parameters
[in]_worldSolverTypeType of solver used by world step.
virtual void UpdateCollision ( )
virtual

Update the physics engine collision.

Implements PhysicsEngine.

virtual void UpdatePhysics ( )
virtual

Update the physics engine.

Reimplemented from PhysicsEngine.

WorldPtr World ( ) const
inherited

Get a pointer to the world.

Returns
Pointer to the world.

Member Data Documentation

ContactManager* contactManager
protectedinherited

Class that handles all contacts generated by the physics engine.

double maxStepSize
protectedinherited

Real time update rate.

transport::NodePtr node
protectedinherited

Node for communication.

transport::SubscriberPtr physicsSub
protectedinherited

Subscribe to the physics topic.

boost::recursive_mutex* physicsUpdateMutex
protectedinherited

Mutex to protect the update cycle.

Referenced by PhysicsEngine::GetPhysicsUpdateMutex().

double realTimeUpdateRate
protectedinherited

Real time update rate.

transport::SubscriberPtr requestSub
protectedinherited

Subscribe to the request topic.

transport::PublisherPtr responsePub
protectedinherited

Response publisher.

sdf::ElementPtr sdf
protectedinherited

Our SDF values.

double targetRealTimeFactor
protectedinherited

Target real time factor.

WorldPtr world
protectedinherited

Pointer to the world.


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