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

Base class for a physics engine. More...

#include <physics/physics.hh>

Public Member Functions

 PhysicsEngine (WorldPtr _world)
 Default constructor.
virtual ~PhysicsEngine ()
 Destructor.
virtual CollisionPtr CreateCollision (const std::string &_shapeType, LinkPtr _link)=0
 Create a collision.
CollisionPtr CreateCollision (const std::string &_shapeType, const std::string &_linkName)
 Create a collision.
virtual JointPtr CreateJoint (const std::string &_type, ModelPtr _parent=ModelPtr())=0
 Create a new joint.
virtual LinkPtr CreateLink (ModelPtr _parent)=0
 Create a new body.
virtual ShapePtr CreateShape (const std::string &_shapeType, CollisionPtr _collision)=0
 Create a physics::Shape object.
virtual void DebugPrint () const =0
 Debug print out of the physic engine state.
virtual void Fini ()
 Finilize the physics engine.
virtual bool GetAutoDisableFlag ()
 : Remove this function, and replace it with a more generic property map
ContactManagerGetContactManager () const
 Get a pointer to the contact manger.
virtual double GetContactMaxCorrectingVel ()
 : Remove this function, and replace it with a more generic property map.
virtual double GetContactSurfaceLayer ()
 : Remove this function, and replace it with a more generic property map.
virtual math::Vector3 GetGravity () const
 Return the gavity vector.
virtual int GetMaxContacts ()
 : Remove this function, and replace it with a more generic property map.
double GetMaxStepSize () const
 Get max step size.
virtual boost::any GetParam (std::string _key) const
 Get an parameter of the physics engine.
boost::recursive_mutex * GetPhysicsUpdateMutex () const
 returns a pointer to the PhysicsEngine::physicsUpdateMutex.
double GetRealTimeUpdateRate () const
 Get real time update rate.
virtual int GetSORPGSIters ()
 : Remove this function, and replace it with a more generic property map
virtual int GetSORPGSPreconIters ()
 : Remove this function, and replace it with a more generic property map
virtual double GetSORPGSW ()
 : Remove this function, and replace it with a more generic property map.
virtual double GetStepTime () GAZEBO_DEPRECATED(1.5)
 Get the simulation step time.
double GetTargetRealTimeFactor () const
 Get target real time factor.
virtual std::string GetType () const =0
 Return the type of the physics engine (ode|bullet).
double GetUpdatePeriod ()
 Get the simulation update period.
double GetUpdateRate () GAZEBO_DEPRECATED(1.5)
 Get the simulation update rate.
virtual double GetWorldCFM ()
 : Remove this function, and replace it with a more generic property map
virtual double GetWorldERP ()
 : Remove this function, and replace it with a more generic property map
virtual void Init ()=0
 Initialize the physics engine.
virtual void InitForThread ()=0
 Init the engine for threads.
virtual void Load (sdf::ElementPtr _sdf)
 Load the physics engine.
virtual void Reset ()
 Rest the physics engine.
virtual void SetAutoDisableFlag (bool _autoDisable)
 : Remove this function, and replace it with a more generic property map
virtual void SetContactMaxCorrectingVel (double _vel)
 : Remove this function, and replace it with a more generic property map
virtual void SetContactSurfaceLayer (double _layerDepth)
 : Remove this function, and replace it with a more generic property map
virtual void SetGravity (const gazebo::math::Vector3 &_gravity)=0
 Set the gavity vector.
virtual void SetMaxContacts (double _maxContacts)
 : Remove this function, and replace it with a more generic property map
void SetMaxStepSize (double _stepSize)
 Set max step size.
virtual void SetParam (std::string _key, const boost::any &_value)
 Set a parameter of the physics engine.
void SetRealTimeUpdateRate (double _rate)
 Set real time update rate.
virtual void SetSeed (uint32_t _seed)=0
 Set the random number seed for the physics engine.
virtual void SetSORPGSIters (unsigned int _iters)
 : Remove this function, and replace it with a more generic property map
virtual void SetSORPGSPreconIters (unsigned int _iters)
 : Remove this function, and replace it with a more generic property map
virtual void SetSORPGSW (double _w)
 : Remove this function, and replace it with a more generic property map
virtual void SetStepTime (double _value) GAZEBO_DEPRECATED(1.5)
 Set the simulation step time.
void SetTargetRealTimeFactor (double _factor)
 Set target real time factor.
void SetUpdateRate (double _value) GAZEBO_DEPRECATED(1.5)
 Set the simulation update rate.
virtual void SetWorldCFM (double _cfm)
 : Remove this function, and replace it with a more generic property map
virtual void SetWorldERP (double _erp)
 : Remove this function, and replace it with a more generic property map
virtual void UpdateCollision ()=0
 Update the physics engine collision.
virtual void UpdatePhysics ()
 Update the physics engine.

Protected Member Functions

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

Protected Attributes

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

Detailed Description

Base class for a physics engine.

Constructor & Destructor Documentation

gazebo::physics::PhysicsEngine::PhysicsEngine ( WorldPtr  _world)
explicit

Default constructor.

Parameters
[in]_worldPointer to the world.
virtual gazebo::physics::PhysicsEngine::~PhysicsEngine ( )
virtual

Destructor.

Member Function Documentation

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

Create a collision.

Parameters
[in]_shapeTypeType of collision to create.
[in]_linkParent link.
CollisionPtr gazebo::physics::PhysicsEngine::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.
virtual JointPtr gazebo::physics::PhysicsEngine::CreateJoint ( const std::string &  _type,
ModelPtr  _parent = ModelPtr() 
)
pure virtual

Create a new joint.

Parameters
[in]_typeType of joint to create.
[in]_parentModel parent.
virtual LinkPtr gazebo::physics::PhysicsEngine::CreateLink ( ModelPtr  _parent)
pure virtual

Create a new body.

Parameters
[in]_parentParent model for the link.
virtual ShapePtr gazebo::physics::PhysicsEngine::CreateShape ( const std::string &  _shapeType,
CollisionPtr  _collision 
)
pure virtual

Create a physics::Shape object.

Parameters
[in]_shapeTypeType of shape to create.
[in]_collisionCollision parent.
virtual void gazebo::physics::PhysicsEngine::DebugPrint ( ) const
pure virtual

Debug print out of the physic engine state.

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

Finilize the physics engine.

virtual bool gazebo::physics::PhysicsEngine::GetAutoDisableFlag ( )
inlinevirtual

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

access functions to set ODE parameters..

Returns
Auto disable flag.
ContactManager* gazebo::physics::PhysicsEngine::GetContactManager ( ) const

Get a pointer to the contact manger.

Returns
Pointer to the contact manager.
virtual double gazebo::physics::PhysicsEngine::GetContactMaxCorrectingVel ( )
inlinevirtual

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

access functions to set ODE parameters.

Returns
Max correcting velocity.
virtual double gazebo::physics::PhysicsEngine::GetContactSurfaceLayer ( )
inlinevirtual

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

access functions to set ODE parameters.

Returns
Contact suerface layer depth.
virtual math::Vector3 gazebo::physics::PhysicsEngine::GetGravity ( ) const
virtual

Return the gavity vector.

Returns
The gavity vector.
virtual int gazebo::physics::PhysicsEngine::GetMaxContacts ( )
inlinevirtual

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

access functions to set ODE parameters.

Returns
Maximum number of allows contacts.
double gazebo::physics::PhysicsEngine::GetMaxStepSize ( ) const

Get max step size.

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

Get an parameter of the physics engine.

Parameters
[in]_attrString key
Returns
The value of the parameter
boost::recursive_mutex* gazebo::physics::PhysicsEngine::GetPhysicsUpdateMutex ( ) const
inline

returns a pointer to the PhysicsEngine::physicsUpdateMutex.

Returns
Pointer to the physics mutex.

References physicsUpdateMutex.

double gazebo::physics::PhysicsEngine::GetRealTimeUpdateRate ( ) const

Get real time update rate.

Returns
Update rate
virtual int gazebo::physics::PhysicsEngine::GetSORPGSIters ( )
inlinevirtual

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

access functions to set ODE parameters.

Returns
SORPGS iterations.
virtual int gazebo::physics::PhysicsEngine::GetSORPGSPreconIters ( )
inlinevirtual

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

access functions to set ODE parameters.

Returns
SORPGS precondition iterations.
virtual double gazebo::physics::PhysicsEngine::GetSORPGSW ( )
inlinevirtual

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

access functions to set ODE parameters

Returns
SORPGSW value.
virtual double gazebo::physics::PhysicsEngine::GetStepTime ( )
virtual

Get the simulation step time.

This funciton is deprecated, use World::GetMaxStepSize.

Returns
Simulation step time.
double gazebo::physics::PhysicsEngine::GetTargetRealTimeFactor ( ) const

Get target real time factor.

Returns
Target real time factor
virtual std::string gazebo::physics::PhysicsEngine::GetType ( ) const
pure virtual

Return the type of the physics engine (ode|bullet).

Returns
Type of the physics engine.
double gazebo::physics::PhysicsEngine::GetUpdatePeriod ( )

Get the simulation update period.

Returns
Simulation update period.
double gazebo::physics::PhysicsEngine::GetUpdateRate ( )

Get the simulation update rate.

This funciton is deprecated, use PhysicsEngine::GetRealTimeUpdateRate.

Returns
Update rate.
virtual double gazebo::physics::PhysicsEngine::GetWorldCFM ( )
inlinevirtual

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

Get World CFM.

Returns
World CFM.
virtual double gazebo::physics::PhysicsEngine::GetWorldERP ( )
inlinevirtual

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

Get World ERP.

Returns
World ERP.
virtual void gazebo::physics::PhysicsEngine::Init ( )
pure virtual

Initialize the physics engine.

virtual void gazebo::physics::PhysicsEngine::InitForThread ( )
pure virtual

Init the engine for threads.

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

Load the physics engine.

Parameters
[in]_sdfPointer to the SDF parameters.
virtual void gazebo::physics::PhysicsEngine::OnPhysicsMsg ( ConstPhysicsPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/physics".

Parameters
[in]_msgPhysics message.
virtual void gazebo::physics::PhysicsEngine::OnRequest ( ConstRequestPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/request".

Parameters
[in]_msgRequest message.
virtual void gazebo::physics::PhysicsEngine::Reset ( )
inlinevirtual

Rest the physics engine.

virtual void gazebo::physics::PhysicsEngine::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.
virtual void gazebo::physics::PhysicsEngine::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.
virtual void gazebo::physics::PhysicsEngine::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
virtual void gazebo::physics::PhysicsEngine::SetGravity ( const gazebo::math::Vector3 _gravity)
pure virtual

Set the gavity vector.

Parameters
[in]_gravityNew gravity vector.
virtual void gazebo::physics::PhysicsEngine::SetMaxContacts ( double  _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.
void gazebo::physics::PhysicsEngine::SetMaxStepSize ( double  _stepSize)

Set max step size.

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

Set a parameter of the physics engine.

Parameters
[in]_keyString key
[in]_valueThe value to set to
void gazebo::physics::PhysicsEngine::SetRealTimeUpdateRate ( double  _rate)

Set real time update rate.

Parameters
[in]_rateUpdate rate
virtual void gazebo::physics::PhysicsEngine::SetSeed ( uint32_t  _seed)
pure virtual

Set the random number seed for the physics engine.

Parameters
[in]_seedThe random number seed.
virtual void gazebo::physics::PhysicsEngine::SetSORPGSIters ( unsigned int  _iters)
virtual

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

Access functions to set ODE parameters.

Parameters
[in]_iterNumber of iterations.
virtual void gazebo::physics::PhysicsEngine::SetSORPGSPreconIters ( unsigned int  _iters)
virtual

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

Access functions to set ODE parameters.

Parameters
[in]_iterNumber of iterations.
virtual void gazebo::physics::PhysicsEngine::SetSORPGSW ( double  _w)
virtual

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

Access functions to set ODE parameters.

Parameters
[in]_wSORPGSW value.
virtual void gazebo::physics::PhysicsEngine::SetStepTime ( double  _value)
virtual

Set the simulation step time.

This funciton is deprecated, use World::SetMaxStepSize.

Parameters
[in]_valueValue of the step time.
void gazebo::physics::PhysicsEngine::SetTargetRealTimeFactor ( double  _factor)

Set target real time factor.

Parameters
[in]_factorTarget real time factor
void gazebo::physics::PhysicsEngine::SetUpdateRate ( double  _value)

Set the simulation update rate.

This funciton is deprecated, use PhysicsEngine::SetRealTimeUpdateRate.

Parameters
[in]_valueValue of the update rate.
virtual void gazebo::physics::PhysicsEngine::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.
virtual void gazebo::physics::PhysicsEngine::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.
virtual void gazebo::physics::PhysicsEngine::UpdateCollision ( )
pure virtual

Update the physics engine collision.

virtual void gazebo::physics::PhysicsEngine::UpdatePhysics ( )
inlinevirtual

Update the physics engine.

Member Data Documentation

ContactManager* gazebo::physics::PhysicsEngine::contactManager
protected

Class that handles all contacts generated by the physics engine.

double gazebo::physics::PhysicsEngine::maxStepSize
protected

Real time update rate.

transport::NodePtr gazebo::physics::PhysicsEngine::node
protected

Node for communication.

transport::SubscriberPtr gazebo::physics::PhysicsEngine::physicsSub
protected

Subscribe to the physics topic.

boost::recursive_mutex* gazebo::physics::PhysicsEngine::physicsUpdateMutex
protected

Mutex to protect the update cycle.

Referenced by GetPhysicsUpdateMutex().

double gazebo::physics::PhysicsEngine::realTimeUpdateRate
protected

Real time update rate.

transport::SubscriberPtr gazebo::physics::PhysicsEngine::requestSub
protected

Subscribe to the request topic.

transport::PublisherPtr gazebo::physics::PhysicsEngine::responsePub
protected

Response publisher.

sdf::ElementPtr gazebo::physics::PhysicsEngine::sdf
protected

Our SDF values.

double gazebo::physics::PhysicsEngine::targetRealTimeFactor
protected

Target real time factor.

WorldPtr gazebo::physics::PhysicsEngine::world
protected

Pointer to the world.


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