| 
|   | 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...
  | 
|   | 
| 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 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...
  | 
|   | 
| btDynamicsWorld *  | GetDynamicsWorld () const  | 
|   | Register a joint with the dynamics world.  More...
  | 
|   | 
| virtual boost::any  | GetParam (const std::string &_key) const  | 
|   | Documentation inherited.  More...
  | 
|   | 
| virtual std::string  | GetType () const  | 
|   | Return the physics engine type (ode|bullet|dart|simbody).  More...
  | 
|   | 
| virtual double  | GetWorldCFM () | 
|   | : Remove this function, and replace it with a more generic property map  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 void  | Reset () | 
|   | Rest the physics engine.  More...
  | 
|   | 
| virtual void  | SetGravity (const gazebo::math::Vector3 &_gravity) | 
|   | Set the gavity vector.  More...
  | 
|   | 
| virtual bool  | SetParam (const std::string &_key, const boost::any &_value) | 
|   | Documentation inherited.  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  | SetWorldCFM (double _cfm) | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   | 
| virtual void  | UpdateCollision () | 
|   | Update the physics engine collision.  More...
  | 
|   | 
| virtual void  | UpdatePhysics () | 
|   | Update the physics engine.  More...
  | 
|   | 
|   | PhysicsEngine (WorldPtr _world) | 
|   | Default constructor.  More...
  | 
|   | 
| virtual  | ~PhysicsEngine () | 
|   | Destructor.  More...
  | 
|   | 
| CollisionPtr  | CreateCollision (const std::string &_shapeType, const std::string &_linkName) | 
|   | Create a collision.  More...
  | 
|   | 
| virtual ModelPtr  | CreateModel (BasePtr _base) | 
|   | Create a new model.  More...
  | 
|   | 
| virtual bool  | GetAutoDisableFlag () | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   | 
| ContactManager *  | GetContactManager () const  | 
|   | Get a pointer to the contact manger.  More...
  | 
|   | 
| virtual double  | GetContactMaxCorrectingVel () | 
|   | : Remove this function, and replace it with a more generic property map.  More...
  | 
|   | 
| virtual double  | GetContactSurfaceLayer () | 
|   | : Remove this function, and replace it with a more generic property map.  More...
  | 
|   | 
| virtual math::Vector3  | GetGravity () const  | 
|   | Return the gavity vector.  More...
  | 
|   | 
| virtual unsigned int  | GetMaxContacts () | 
|   | : Remove this function, and replace it with a more generic property map.  More...
  | 
|   | 
| double  | GetMaxStepSize () const  | 
|   | Get max step size.  More...
  | 
|   | 
| boost::recursive_mutex *  | GetPhysicsUpdateMutex () const  | 
|   | returns a pointer to the PhysicsEngine::physicsUpdateMutex.  More...
  | 
|   | 
| double  | GetRealTimeUpdateRate () const  | 
|   | Get real time update rate.  More...
  | 
|   | 
| double  | GetTargetRealTimeFactor () const  | 
|   | Get target real time factor.  More...
  | 
|   | 
| double  | GetUpdatePeriod () | 
|   | Get the simulation update period.  More...
  | 
|   | 
| virtual double  | GetWorldERP () | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   | 
| virtual void  | SetAutoDisableFlag (bool _autoDisable) | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   | 
| virtual void  | SetContactMaxCorrectingVel (double _vel) | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   | 
| virtual void  | SetContactSurfaceLayer (double _layerDepth) | 
|   | : Remove this function, and replace it with a more generic property map  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...
  | 
|   | 
| void  | SetRealTimeUpdateRate (double _rate) | 
|   | Set real time update rate.  More...
  | 
|   | 
| void  | SetTargetRealTimeFactor (double _factor) | 
|   | Set target real time factor.  More...
  | 
|   | 
| virtual void  | SetWorldERP (double _erp) | 
|   | : Remove this function, and replace it with a more generic property map  More...
  | 
|   |