BulletPhysics Class Reference

Bullet physics engine. More...

#include <BulletPhysics.hh>

Inherits PhysicsEngine.

Public Types

enum  BulletParam {
  SOLVER_TYPE, GLOBAL_CFM, GLOBAL_ERP, PGS_ITERS,
  SOR, CONTACT_SURFACE_LAYER, MAX_CONTACTS, MIN_STEP_SIZE
}
 Bullet physics parameter types. More...
 

Public Member Functions

 BulletPhysics (WorldPtr _world)
 Constructor. More...
 
virtual ~BulletPhysics ()
 Destructor. More...
 
virtual void ConvertMass (InertialPtr _inertial, void *_engineMass)
 Convert a bullet mass to a gazebo Mass. More...
 
virtual void ConvertMass (void *_engineMass, InertialPtr _inertial)
 Convert a gazebo Mass to a bullet Mass. More...
 
virtual CollisionPtr CreateCollision (const std::string &_type, LinkPtr _body)
 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)
 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...
 
btDynamicsWorld * GetDynamicsWorld () const
 Register a joint with the dynamics world. More...
 
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...
 
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 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 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 ignition::math::Vector3d &_gravity)
 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)
 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)
 
void SetTargetRealTimeFactor (double _factor)
 Set target real time factor. More...
 
virtual void SetWorldCFM (double _cfm)
 
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...
 

Protected Member Functions

virtual void OnPhysicsMsg (ConstPhysicsPtr &_msg)
 virtual callback for gztopic "~/physics". More...
 
virtual void OnRequest (ConstRequestPtr &_msg)
 Create a physics based ray sensor. 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...
 
ignition::transport::Node nodeIgn
 Ignition 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...
 
ignition::transport::Node::Publisher responsePubIgn
 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

Bullet physics engine.

Member Enumeration Documentation

Bullet physics parameter types.

Enumerator
SOLVER_TYPE 

Solve type.

GLOBAL_CFM 

Constraint force mixing.

GLOBAL_ERP 

Error reduction parameter.

PGS_ITERS 

Number of iterations.

SOR 

SOR over-relaxation parameter.

CONTACT_SURFACE_LAYER 

Surface layer depth.

MAX_CONTACTS 

Maximum number of contacts.

MIN_STEP_SIZE 

Minimum step size.

Constructor & Destructor Documentation

BulletPhysics ( WorldPtr  _world)
explicit

Constructor.

virtual ~BulletPhysics ( )
virtual

Destructor.

Member Function Documentation

virtual void ConvertMass ( InertialPtr  _inertial,
void *  _engineMass 
)
virtual

Convert a bullet mass to a gazebo Mass.

virtual void ConvertMass ( void *  _engineMass,
InertialPtr  _inertial 
)
virtual

Convert a gazebo Mass to a bullet Mass.

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.

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 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.
btDynamicsWorld* GetDynamicsWorld ( ) const
inline

Register a joint with the dynamics world.

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.
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 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 void OnPhysicsMsg ( ConstPhysicsPtr &  _msg)
protectedvirtual

virtual callback for gztopic "~/physics".

Parameters
[in]_msgPhysics message.

Reimplemented from PhysicsEngine.

virtual void OnRequest ( ConstRequestPtr &  _msg)
protectedvirtual

Create a physics based ray sensor.

Reimplemented from PhysicsEngine.

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 SetGravity ( const ignition::math::Vector3d &  _gravity)
virtual

Set the gravity vector.

Parameters
[in]_gravityNew gravity vector.

Implements PhysicsEngine.

virtual void SetMaxContacts ( unsigned int  _maxContacts)
virtualinherited

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

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
void SetTargetRealTimeFactor ( double  _factor)
inherited

Set target real time factor.

Parameters
[in]_factorTarget real time factor
virtual void SetWorldCFM ( double  _cfm)
virtual
virtual void UpdateCollision ( )
virtual

Update the physics engine collision.

This function works in tandem with PhysicsEngine::UpdatePhysics() to update the world. This function will be called even if the physics is disabled (when World::PhysicsEnabled()) returns false). Which updates are done in which of the two functions PhysicsEngine::UpdateCollision() and PhysicsEngine::UpdatePhysics() is to some extent left to the implementing physics engine. The intention is that PhysicsEngine::UpdateCollision() will update the collision states of the world, including contact information, and PhysicsEngine::UpdatePhysics() will update the dynamics of the world, i.e. advance the world and react to the collision state. However for some physics engines, both is done in one step, or providing the contact information separately in UpdateCollision() would mean double work, as it can't be avoided to be done again in PhysicsEngine::UpdatePhysics() - in this case it is better that PhysicsEngine::UpdateCollision does not actually update collision and contact information, and instead leaves it to UpdatePhysics(). There should be one exception however when it still does make this update: If World::PhysicsEnabled() returns false, and therefore PhysicsEngine::UpdatePhysics() will not be called in the update step, then PhysicsEngine::UpdateCollision will need to ensure that collision and contact information will still be updated.

Implements PhysicsEngine.

virtual void UpdatePhysics ( )
virtual

Update the physics engine.

Will only be called if the physics are enabled, which is the case when World::PhysicsEnabled() returns true.

See Also
PhysicsEngine::UpdateCollision()

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.

ignition::transport::Node nodeIgn
protectedinherited

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

ignition::transport::Node::Publisher responsePubIgn
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: