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

Bullet physics engine. More...

#include <BulletPhysics.hh>

Inheritance diagram for gazebo::physics::BulletPhysics:
Inheritance graph
[legend]

Public Member Functions

 BulletPhysics (WorldPtr _world)
 Constructor.
 
virtual ~BulletPhysics ()
 Destructor.
 
virtual void ConvertMass (InertialPtr _inertial, void *_engineMass)
 Create a physics based ray sensor.
 
virtual void ConvertMass (void *_engineMass, InertialPtr _inertial)
 Convert an gazebo Mass to a bullet Mass.
 
virtual CollisionPtr CreateCollision (const std::string &_type, LinkPtr _body)
 Create a new collision.
 
virtual JointPtr CreateJoint (const std::string &_type, ModelPtr _parent)
 Create a new joint.
 
virtual LinkPtr CreateLink (ModelPtr _parent)
 Create a new body.
 
virtual ShapePtr CreateShape (const std::string &_shapeType, CollisionPtr _collision)
 Create a physics::Shape object.
 
virtual void DebugPrint () const
 Debug print out of the physic engine state.
 
virtual void Fini ()
 Finilize the Bullet engine.
 
btDynamicsWorld * GetDynamicsWorld () const
 Register a joint with the dynamics world.
 
virtual double GetStepTime ()
 Get the simulation step time.
 
virtual void Init ()
 Initialize the Bullet engine.
 
virtual void InitForThread ()
 Init the engine for threads.
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the Bullet engine.
 
virtual void SetGravity (const gazebo::math::Vector3 &gravity)
 Set the gavity vector.
 
virtual void SetStepTime (double _value)
 Set the simulation step time.
 
virtual void UpdateCollision ()
 Update the Bullet collision.
 
virtual void UpdatePhysics ()
 Update the Bullet engine.
 
- Public Member Functions inherited from gazebo::physics::PhysicsEngine
 PhysicsEngine (WorldPtr _world)
 Default constructor.
 
virtual ~PhysicsEngine ()
 Destructor.
 
CollisionPtr CreateCollision (const std::string &_shapeType, const std::string &_linkName)
 Create a collision.
 
virtual bool GetAutoDisableFlag ()
 : Remove this function, and replace it with a more generic property map
 
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.
 
math::Vector3 GetGravity () const
 Return the gavity vector.
 
virtual int GetMaxContacts ()
 : Remove this function, and replace it with a more generic property map.
 
boost::recursive_mutex * GetPhysicsUpdateMutex () const
 returns a pointer to the PhysicsEngine::physicsUpdateMutex.
 
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.
 
double GetUpdatePeriod ()
 Get the simulation update period.
 
double GetUpdateRate ()
 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 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 SetMaxContacts (double _maxContacts)
 : Remove this function, and replace it with a more generic property map
 
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
 
void SetUpdateRate (double _value)
 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
 

Static Public Member Functions

static math::Pose ConvertPose (const btTransform &_bt)
 Convert a bullet transform to a gazebo pose.
 
static btTransform ConvertPose (const math::Pose &_pose)
 Convert a gazebo pose to a bullet transform.
 

Additional Inherited Members

- Protected Member Functions inherited from gazebo::physics::PhysicsEngine
virtual void OnPhysicsMsg (ConstPhysicsPtr &_msg)
 virtual callback for gztopic "~/physics".
 
virtual void OnRequest (ConstRequestPtr &_msg)
 virtual callback for gztopic "~/request".
 
- Protected Attributes inherited from gazebo::physics::PhysicsEngine
transport::PublisherPtr contactPub
 Contact publisher.
 
transport::NodePtr node
 Node for communication.
 
transport::SubscriberPtr physicsSub
 Subscribe to the physics topic.
 
boost::recursive_mutex * physicsUpdateMutex
 Mutex to protect the update cycle.
 
transport::SubscriberPtr requestSub
 Subscribe to the request topic.
 
transport::PublisherPtr responsePub
 Response publisher.
 
sdf::ElementPtr sdf
 Our SDF values.
 
WorldPtr world
 Pointer to the world.
 

Detailed Description

Bullet physics engine.

Constructor & Destructor Documentation

gazebo::physics::BulletPhysics::BulletPhysics ( WorldPtr  _world)

Constructor.

virtual gazebo::physics::BulletPhysics::~BulletPhysics ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::physics::BulletPhysics::ConvertMass ( InertialPtr  _inertial,
void *  _engineMass 
)
virtual

Create a physics based ray sensor.

Convert an bullet mass to a gazebo Mass

virtual void gazebo::physics::BulletPhysics::ConvertMass ( void *  _engineMass,
InertialPtr  _inertial 
)
virtual

Convert an gazebo Mass to a bullet Mass.

static math::Pose gazebo::physics::BulletPhysics::ConvertPose ( const btTransform &  _bt)
static

Convert a bullet transform to a gazebo pose.

static btTransform gazebo::physics::BulletPhysics::ConvertPose ( const math::Pose _pose)
static

Convert a gazebo pose to a bullet transform.

virtual CollisionPtr gazebo::physics::BulletPhysics::CreateCollision ( const std::string &  _type,
LinkPtr  _body 
)
virtual

Create a new collision.

Implements gazebo::physics::PhysicsEngine.

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

Create a new joint.

Implements gazebo::physics::PhysicsEngine.

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

Create a new body.

Implements gazebo::physics::PhysicsEngine.

virtual ShapePtr gazebo::physics::BulletPhysics::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::BulletPhysics::DebugPrint ( ) const
virtual

Debug print out of the physic engine state.

Implements gazebo::physics::PhysicsEngine.

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

Finilize the Bullet engine.

Reimplemented from gazebo::physics::PhysicsEngine.

btDynamicsWorld* gazebo::physics::BulletPhysics::GetDynamicsWorld ( ) const
inline

Register a joint with the dynamics world.

virtual double gazebo::physics::BulletPhysics::GetStepTime ( )
virtual

Get the simulation step time.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::BulletPhysics::Init ( )
virtual

Initialize the Bullet engine.

Implements gazebo::physics::PhysicsEngine.

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

Init the engine for threads.

Implements gazebo::physics::PhysicsEngine.

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

Load the Bullet engine.

Reimplemented from gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::BulletPhysics::SetGravity ( const gazebo::math::Vector3 gravity)
virtual

Set the gavity vector.

Implements gazebo::physics::PhysicsEngine.

virtual void gazebo::physics::BulletPhysics::SetStepTime ( double  _value)
virtual

Set the simulation step time.

Implements gazebo::physics::PhysicsEngine.

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

Update the Bullet collision.

Implements gazebo::physics::PhysicsEngine.

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

Update the Bullet engine.

Reimplemented from gazebo::physics::PhysicsEngine.


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