Bullet physics engine. More...
#include <BulletPhysics.hh>

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... | |
| 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 bool | GetParam (const std::string &_key, boost::any &_value) const |
| Documentation inherited. More... | |
| virtual std::string | GetType () const |
| Return the physics engine type (ode|bullet|dart|simbody). 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 | SetGravity (const gazebo::math::Vector3 &_gravity) |
| Set the gravity 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) |
| virtual void | UpdateCollision () |
| Update the physics engine collision. More... | |
| virtual void | UpdatePhysics () |
| Update the physics engine. More... | |
Public Member Functions inherited from gazebo::physics::PhysicsEngine | |
| 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 math::Vector3 | GetGravity () const |
| Return the gravity vector. 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... | |
| 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... | |
| double | GetUpdatePeriod () |
| Get the simulation update period. More... | |
| virtual ignition::math::Vector3d | MagneticField () const |
| Return the magnetic field vector. More... | |
| virtual void | SetAutoDisableFlag (bool _autoDisable) |
| : 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... | |
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... | |
Additional Inherited Members | |
Protected Attributes inherited from gazebo::physics::PhysicsEngine | |
| ContactManager * | contactManager |
| 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... | |
Bullet physics engine.
Bullet physics parameter types.
| gazebo::physics::BulletPhysics::BulletPhysics | ( | WorldPtr | _world | ) |
Constructor.
|
virtual |
Destructor.
|
virtual |
Convert a bullet mass to a gazebo Mass.
|
virtual |
Convert a gazebo Mass to a bullet Mass.
|
virtual |
Create a collision.
| [in] | _shapeType | Type of collision to create. |
| [in] | _link | Parent link. |
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Create a new joint.
| [in] | _type | Type of joint to create. |
| [in] | _parent | Model parent. |
Implements gazebo::physics::PhysicsEngine.
Create a new body.
| [in] | _parent | Parent model for the link. |
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Create a physics::Shape object.
| [in] | _shapeType | Type of shape to create. |
| [in] | _collision | Collision parent. |
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Debug print out of the physic engine state.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Finilize the physics engine.
Reimplemented from gazebo::physics::PhysicsEngine.
|
inline |
Register a joint with the dynamics world.
|
virtual |
Documentation inherited.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Documentation inherited.
Reimplemented from gazebo::physics::PhysicsEngine.
|
inlinevirtual |
Return the physics engine type (ode|bullet|dart|simbody).
Implements gazebo::physics::PhysicsEngine.
|
virtual |
|
virtual |
Initialize the physics engine.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Init the engine for threads.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Load the physics engine.
| [in] | _sdf | Pointer to the SDF parameters. |
Reimplemented from gazebo::physics::PhysicsEngine.
|
protectedvirtual |
virtual callback for gztopic "~/physics".
| [in] | _msg | Physics message. |
Reimplemented from gazebo::physics::PhysicsEngine.
|
protectedvirtual |
Create a physics based ray sensor.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Rest the physics engine.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Set the gravity vector.
| [in] | _gravity | New gravity vector. |
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Documentation inherited.
Reimplemented from gazebo::physics::PhysicsEngine.
|
virtual |
Set the random number seed for the physics engine.
| [in] | _seed | The random number seed. |
Implements gazebo::physics::PhysicsEngine.
|
virtual |
|
virtual |
|
virtual |
Update the physics engine collision.
Implements gazebo::physics::PhysicsEngine.
|
virtual |
Update the physics engine.
Reimplemented from gazebo::physics::PhysicsEngine.