PhysicsEngine Class Referenceabstract

Base class for a physics engine. More...

#include <physics/physics.hh>

Inherited by BulletPhysics, DARTPhysics, ODEPhysics, and SimbodyPhysics.

Public Member Functions

 PhysicsEngine (WorldPtr _world)
 Default constructor. More...
 
virtual ~PhysicsEngine ()
 Destructor. More...
 
virtual CollisionPtr CreateCollision (const std::string &_shapeType, LinkPtr _link)=0
 Create a collision. More...
 
CollisionPtr CreateCollision (const std::string &_shapeType, const std::string &_linkName)
 Create a collision. More...
 
virtual JointPtr CreateJoint (const std::string &_type, ModelPtr _parent=ModelPtr())=0
 Create a new joint. More...
 
virtual LinkPtr CreateLink (ModelPtr _parent)=0
 Create a new body. More...
 
virtual ModelPtr CreateModel (BasePtr _base)
 Create a new model. More...
 
virtual ShapePtr CreateShape (const std::string &_shapeType, CollisionPtr _collision)=0
 Create a physics::Shape object. More...
 
virtual void DebugPrint () const =0
 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 math::Vector3 GetGravity () const
 Return the gravity vector. More...
 
double GetMaxStepSize () const
 Get max step size. More...
 
virtual boost::any GetParam (const std::string &_key) const
 Get an parameter of the physics engine. More...
 
virtual bool GetParam (const std::string &_key, boost::any &_value) const
 Get a parameter from the physics engine with a boolean to indicate success or failure. 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...
 
double GetTargetRealTimeFactor () const
 Get target real time factor. More...
 
virtual std::string GetType () const =0
 Return the physics engine type (ode|bullet|dart|simbody). More...
 
double GetUpdatePeriod ()
 Get the simulation update period. More...
 
virtual void Init ()=0
 Initialize the physics engine. More...
 
virtual void InitForThread ()=0
 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...
 
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 SetGravity (const gazebo::math::Vector3 &_gravity)=0
 Set the gravity vector. More...
 
virtual void SetMaxContacts (unsigned int _maxContacts)
 : 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)
 Set a parameter of the physics engine. More...
 
void SetRealTimeUpdateRate (double _rate)
 Set real time update rate. More...
 
virtual void SetSeed (uint32_t _seed)=0
 Set the random number seed for the physics engine. More...
 
void SetTargetRealTimeFactor (double _factor)
 Set target real time factor. More...
 
virtual void UpdateCollision ()=0
 Update the physics engine collision. More...
 
virtual void UpdatePhysics ()
 Update the physics engine. 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

Base class for a physics engine.

Constructor & Destructor Documentation

§ PhysicsEngine()

PhysicsEngine ( WorldPtr  _world)
explicit

Default constructor.

Parameters
[in]_worldPointer to the world.

§ ~PhysicsEngine()

virtual ~PhysicsEngine ( )
virtual

Destructor.

Member Function Documentation

§ CreateCollision() [1/2]

virtual CollisionPtr CreateCollision ( const std::string &  _shapeType,
LinkPtr  _link 
)
pure virtual

Create a collision.

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

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ CreateCollision() [2/2]

CollisionPtr CreateCollision ( const std::string &  _shapeType,
const std::string &  _linkName 
)

Create a collision.

Parameters
[in]_shapeTypeType of collision to create.
[in]_linkNameName of the parent link.

§ CreateJoint()

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

Create a new joint.

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

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ CreateLink()

virtual LinkPtr CreateLink ( ModelPtr  _parent)
pure virtual

Create a new body.

Parameters
[in]_parentParent model for the link.

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ CreateModel()

virtual ModelPtr CreateModel ( BasePtr  _base)
virtual

Create a new model.

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

Reimplemented in DARTPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ CreateShape()

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

Create a physics::Shape object.

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

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ DebugPrint()

virtual void DebugPrint ( ) const
pure virtual

Debug print out of the physic engine state.

Implemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::GetAutoDisableFlag().

§ Fini()

virtual void Fini ( )
virtual

Finilize the physics engine.

Reimplemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

§ GetAutoDisableFlag()

virtual bool GetAutoDisableFlag ( )
inlinevirtual

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

access functions to set ODE parameters..

Returns
Auto disable flag.

References PhysicsEngine::DebugPrint(), PhysicsEngine::GetContactManager(), PhysicsEngine::GetParam(), and PhysicsEngine::SetParam().

§ GetContactManager()

ContactManager* GetContactManager ( ) const

Get a pointer to the contact manger.

Returns
Pointer to the contact manager.

Referenced by PhysicsEngine::GetAutoDisableFlag().

§ GetGravity()

virtual math::Vector3 GetGravity ( ) const
virtual

Return the gravity vector.

Returns
The gravity vector.

Referenced by PhysicsEngine::UpdatePhysics().

§ GetMaxStepSize()

double GetMaxStepSize ( ) const

Get max step size.

Returns
Max step size.

Referenced by PhysicsEngine::Reset().

§ GetParam() [1/2]

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

Get an parameter of the physics engine.

Parameters
[in]_attrString key
See also
SetParam
Returns
The value of the parameter

Reimplemented in ODEPhysics, SimbodyPhysics, BulletPhysics, and DARTPhysics.

Referenced by PhysicsEngine::GetAutoDisableFlag().

§ GetParam() [2/2]

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

Get a parameter from the physics engine with a boolean to indicate success or failure.

Parameters
[in]_keyKey of the accessed param
[out]_valueValue of the accessed param
Returns
True if the parameter was successfully retrieved

Reimplemented in ODEPhysics, SimbodyPhysics, BulletPhysics, and DARTPhysics.

§ GetPhysicsUpdateMutex()

boost::recursive_mutex* GetPhysicsUpdateMutex ( ) const
inline

§ GetRealTimeUpdateRate()

double GetRealTimeUpdateRate ( ) const

Get real time update rate.

Returns
Update rate

Referenced by PhysicsEngine::Reset().

§ GetSDF()

sdf::ElementPtr GetSDF ( ) const

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

Returns
Pointer to the physics SDF element.

Referenced by PhysicsEngine::GetPhysicsUpdateMutex().

§ GetTargetRealTimeFactor()

double GetTargetRealTimeFactor ( ) const

Get target real time factor.

Returns
Target real time factor

Referenced by PhysicsEngine::Reset().

§ GetType()

virtual std::string GetType ( ) const
pure virtual

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

Returns
Type of the physics engine.

Implemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::Reset().

§ GetUpdatePeriod()

double GetUpdatePeriod ( )

Get the simulation update period.

Returns
Simulation update period.

Referenced by PhysicsEngine::Reset().

§ Init()

virtual void Init ( )
pure virtual

Initialize the physics engine.

Implemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

§ InitForThread()

virtual void InitForThread ( )
pure virtual

Init the engine for threads.

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::Reset().

§ Load()

virtual void Load ( sdf::ElementPtr  _sdf)
virtual

Load the physics engine.

Parameters
[in]_sdfPointer to the SDF parameters.

Reimplemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

§ MagneticField()

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

Return the magnetic field vector.

Returns
The magnetic field vector.

Referenced by PhysicsEngine::UpdatePhysics().

§ OnPhysicsMsg()

virtual void OnPhysicsMsg ( ConstPhysicsPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/physics".

Parameters
[in]_msgPhysics message.

Reimplemented in ODEPhysics, SimbodyPhysics, DARTPhysics, and BulletPhysics.

Referenced by PhysicsEngine::GetPhysicsUpdateMutex().

§ OnRequest()

virtual void OnRequest ( ConstRequestPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/request".

Parameters
[in]_msgRequest message.

Reimplemented in ODEPhysics, SimbodyPhysics, DARTPhysics, and BulletPhysics.

Referenced by PhysicsEngine::GetPhysicsUpdateMutex().

§ Reset()

§ SetAutoDisableFlag()

virtual void SetAutoDisableFlag ( bool  _autoDisable)
virtual

: 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.

Referenced by PhysicsEngine::UpdatePhysics().

§ SetGravity()

virtual void SetGravity ( const gazebo::math::Vector3 _gravity)
pure virtual

Set the gravity vector.

Parameters
[in]_gravityNew gravity vector.

Implemented in BulletPhysics, ODEPhysics, DARTPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ SetMaxContacts()

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 in ODEPhysics.

Referenced by PhysicsEngine::UpdatePhysics().

§ SetMaxStepSize()

void SetMaxStepSize ( double  _stepSize)

Set max step size.

Parameters
[in]_stepSizeMax step size.

Referenced by PhysicsEngine::Reset().

§ SetParam()

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

Set a parameter of the physics engine.

See SetParam documentation for descriptions of duplicate parameters.

Parameters
[in]_keyString key Below is a list of _key parameter definitions:
  1. "solver_type" (string) - returns solver used by engine, e.g. "sequential_impulse' for Bullet, "quick" for ODE "Featherstone and Lemkes" for DART and "Spatial Algebra and Elastic Foundation" for Simbody. -# "cfm" (double) - global CFM (ODE/Bullet) -# "erp" (double) - global ERP (ODE/Bullet) -# "precon_iters" (bool) - precondition iterations (experimental). (ODE)
  2. "iters" (int) - number of LCP PGS iterations. If sor_lcp_tolerance is negative, full iteration count is executed. Otherwise, PGS may stop iteration early if sor_lcp_tolerance is satisfied by the total RMS residual.
  3. "sor" (double) - relaxation parameter for Projected Gauss-Seidel (PGS) updates. (ODE/Bullet)
  4. "contact_max_correcting_vel" (double) - truncates correction impulses from ERP by this value. (ODE)
  5. "contact_surface_layer" (double) - ERP is 0 for interpenetration depths below this value. (ODE/Bullet)
  6. "max_contacts" (int) - max number of contact constraints between any pair of collision bodies.
  7. "min_step_size" (double) - minimum internal step size. (defined but not used in ode).
  8. "max_step_size" (double) - maximum physics step size when physics update step must return.
[in]_valueThe value to set to
Returns
true if SetParam is successful, false if operation fails.

Reimplemented in SimbodyPhysics, ODEPhysics, BulletPhysics, and DARTPhysics.

Referenced by PhysicsEngine::GetAutoDisableFlag().

§ SetRealTimeUpdateRate()

void SetRealTimeUpdateRate ( double  _rate)

Set real time update rate.

Parameters
[in]_rateUpdate rate

Referenced by PhysicsEngine::Reset().

§ SetSeed()

virtual void SetSeed ( uint32_t  _seed)
pure virtual

Set the random number seed for the physics engine.

Parameters
[in]_seedThe random number seed.

Implemented in ODEPhysics, BulletPhysics, DARTPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::Reset().

§ SetTargetRealTimeFactor()

void SetTargetRealTimeFactor ( double  _factor)

Set target real time factor.

Parameters
[in]_factorTarget real time factor

Referenced by PhysicsEngine::Reset().

§ UpdateCollision()

virtual void UpdateCollision ( )
pure virtual

Update the physics engine collision.

Implemented in ODEPhysics, DARTPhysics, BulletPhysics, and SimbodyPhysics.

Referenced by PhysicsEngine::Reset().

§ UpdatePhysics()

Member Data Documentation

§ contactManager

ContactManager* contactManager
protected

Class that handles all contacts generated by the physics engine.

§ maxStepSize

double maxStepSize
protected

Real time update rate.

§ node

transport::NodePtr node
protected

Node for communication.

§ physicsSub

transport::SubscriberPtr physicsSub
protected

Subscribe to the physics topic.

§ physicsUpdateMutex

boost::recursive_mutex* physicsUpdateMutex
protected

Mutex to protect the update cycle.

Referenced by PhysicsEngine::GetPhysicsUpdateMutex().

§ realTimeUpdateRate

double realTimeUpdateRate
protected

Real time update rate.

§ requestSub

transport::SubscriberPtr requestSub
protected

Subscribe to the request topic.

§ responsePub

transport::PublisherPtr responsePub
protected

Response publisher.

§ sdf

sdf::ElementPtr sdf
protected

Our SDF values.

§ targetRealTimeFactor

double targetRealTimeFactor
protected

Target real time factor.

§ world

WorldPtr world
protected

Pointer to the world.


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