Base class for a physics engine. More...
#include <physics/physics.hh>

| Public Member Functions | |
| PhysicsEngine (WorldPtr _world) | |
| Default constructor.  More... | |
| virtual | ~PhysicsEngine () | 
| Destructor.  More... | |
| virtual CollisionPtr | CreateCollision (const std::string &_shapeType, LinkPtr _link)=0 | 
| 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=ModelPtr())=0 | 
| Create a new joint.  More... | |
| virtual LinkPtr | CreateLink (ModelPtr _parent)=0 | 
| Create a new body.  More... | |
| virtual ModelPtr | CreateModel (BasePtr _base) | 
| Create a new model.  More... | |
| virtual ShapePtr | CreateShape (const std::string &_shapeType, CollisionPtr _collision)=0 | 
| Create a physics::Shape object.  More... | |
| virtual void | DebugPrint () const =0 | 
| 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... | |
| 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 int | GetMaxContacts () | 
| : Remove this function, and replace it with a more generic property map.  More... | |
| double | GetMaxStepSize () const | 
| Get max step size.  More... | |
| virtual boost::any | GetParam (std::string _key) const | 
| Get an parameter of the physics engine.  More... | |
| boost::recursive_mutex * | GetPhysicsUpdateMutex () const | 
| returns a pointer to the PhysicsEngine::physicsUpdateMutex.  More... | |
| double | GetRealTimeUpdateRate () const | 
| Get real time update rate.  More... | |
| virtual int | GetSORPGSIters () | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual int | GetSORPGSPreconIters () | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual double | GetSORPGSW () | 
| : Remove this function, and replace it with a more generic property map.  More... | |
| double | GetTargetRealTimeFactor () const | 
| Get target real time factor.  More... | |
| virtual std::string | GetType () const =0 | 
| Return the physics engine type (ode|bullet|dart|simbody).  More... | |
| double | GetUpdatePeriod () | 
| Get the simulation update period.  More... | |
| virtual double | GetWorldCFM () | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual double | GetWorldERP () | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual void | Init ()=0 | 
| Initialize the physics engine.  More... | |
| virtual void | InitForThread ()=0 | 
| 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 | 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 | SetGravity (const gazebo::math::Vector3 &_gravity)=0 | 
| Set the gavity vector.  More... | |
| virtual void | SetMaxContacts (double _maxContacts) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| void | SetMaxStepSize (double _stepSize) | 
| Set max step size.  More... | |
| virtual void | SetParam (std::string _key, const boost::any &_value) | 
| Set a parameter of the physics engine.  More... | |
| void | SetRealTimeUpdateRate (double _rate) | 
| Set real time update rate.  More... | |
| virtual void | SetSeed (uint32_t _seed)=0 | 
| Set the random number seed for the physics engine.  More... | |
| virtual void | SetSORPGSIters (unsigned int _iters) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual void | SetSORPGSPreconIters (unsigned int _iters) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual void | SetSORPGSW (double _w) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| void | SetTargetRealTimeFactor (double _factor) | 
| Set target real time factor.  More... | |
| virtual void | SetWorldCFM (double _cfm) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual void | SetWorldERP (double _erp) | 
| : Remove this function, and replace it with a more generic property map  More... | |
| virtual void | UpdateCollision ()=0 | 
| Update the physics engine collision.  More... | |
| virtual void | UpdatePhysics () | 
| Update the physics engine.  More... | |
| Protected Member Functions | |
| virtual void | OnPhysicsMsg (ConstPhysicsPtr &_msg) | 
| virtual callback for gztopic "~/physics".  More... | |
| virtual void | OnRequest (ConstRequestPtr &_msg) | 
| virtual callback for gztopic "~/request".  More... | |
| Protected Attributes | |
| 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... | |
Base class for a physics engine.
| 
 | explicit | 
Default constructor.
| [in] | _world | Pointer to the world. | 
| 
 | virtual | 
Destructor.
| 
 | pure virtual | 
Create a collision.
| [in] | _shapeType | Type of collision to create. | 
| [in] | _link | Parent link. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| CollisionPtr gazebo::physics::PhysicsEngine::CreateCollision | ( | const std::string & | _shapeType, | 
| const std::string & | _linkName | ||
| ) | 
Create a collision.
| [in] | _shapeType | Type of collision to create. | 
| [in] | _linkName | Name of the parent link. | 
| 
 | pure virtual | 
Create a new joint.
| [in] | _type | Type of joint to create. | 
| [in] | _parent | Model parent. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
Create a new body.
| [in] | _parent | Parent model for the link. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
Create a new model.
| [in] | _base | Boost shared pointer to a new model. | 
Reimplemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | pure virtual | 
Create a physics::Shape object.
| [in] | _shapeType | Type of shape to create. | 
| [in] | _collision | Collision parent. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | pure virtual | 
Debug print out of the physic engine state.
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | virtual | 
Finilize the physics engine.
Reimplemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map
access functions to set ODE parameters..
| ContactManager* gazebo::physics::PhysicsEngine::GetContactManager | ( | ) | const | 
Get a pointer to the contact manger.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map.
access functions to set ODE parameters.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map.
access functions to set ODE parameters.
| 
 | virtual | 
Return the gavity vector.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map.
access functions to set ODE parameters.
| double gazebo::physics::PhysicsEngine::GetMaxStepSize | ( | ) | const | 
Get max step size.
| 
 | virtual | 
Get an parameter of the physics engine.
| [in] | _attr | String key | 
| 
 | inline | 
returns a pointer to the PhysicsEngine::physicsUpdateMutex.
References physicsUpdateMutex.
| double gazebo::physics::PhysicsEngine::GetRealTimeUpdateRate | ( | ) | const | 
Get real time update rate.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map
access functions to set ODE parameters.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map
access functions to set ODE parameters.
| 
 | inlinevirtual | 
: Remove this function, and replace it with a more generic property map.
access functions to set ODE parameters
| double gazebo::physics::PhysicsEngine::GetTargetRealTimeFactor | ( | ) | const | 
Get target real time factor.
| 
 | pure virtual | 
Return the physics engine type (ode|bullet|dart|simbody).
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| double gazebo::physics::PhysicsEngine::GetUpdatePeriod | ( | ) | 
Get the simulation update period.
| 
 | inlinevirtual | 
| 
 | inlinevirtual | 
| 
 | pure virtual | 
Initialize the physics engine.
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | pure virtual | 
Init the engine for threads.
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | virtual | 
Load the physics engine.
| [in] | _sdf | Pointer to the SDF parameters. | 
Reimplemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | protectedvirtual | 
virtual callback for gztopic "~/physics".
| [in] | _msg | Physics message. | 
Reimplemented in gazebo::physics::SimbodyPhysics, and gazebo::physics::DARTPhysics.
| 
 | protectedvirtual | 
virtual callback for gztopic "~/request".
| [in] | _msg | Request message. | 
Reimplemented in gazebo::physics::SimbodyPhysics, and gazebo::physics::DARTPhysics.
| 
 | inlinevirtual | 
Rest the physics engine.
Reimplemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _autoDisable | True to enable auto disabling of bodies. | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _vel | Max correcting velocity. | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _layerDepth | Surface layer depth | 
| 
 | pure virtual | 
Set the gavity vector.
| [in] | _gravity | New gravity vector. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
access functions to set ODE parameters
| [in] | _maxContacts | Maximum number of contacts. | 
| void gazebo::physics::PhysicsEngine::SetMaxStepSize | ( | double | _stepSize | ) | 
Set max step size.
| [in] | _stepSize | Max step size. | 
| 
 | virtual | 
Set a parameter of the physics engine.
| [in] | _key | String key | 
| [in] | _value | The value to set to | 
| void gazebo::physics::PhysicsEngine::SetRealTimeUpdateRate | ( | double | _rate | ) | 
Set real time update rate.
| [in] | _rate | Update rate | 
| 
 | pure virtual | 
Set the random number seed for the physics engine.
| [in] | _seed | The random number seed. | 
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _iter | Number of iterations. | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _iter | Number of iterations. | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _w | SORPGSW value. | 
| void gazebo::physics::PhysicsEngine::SetTargetRealTimeFactor | ( | double | _factor | ) | 
Set target real time factor.
| [in] | _factor | Target real time factor | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _cfm | Constraint force mixing. | 
| 
 | virtual | 
: Remove this function, and replace it with a more generic property map
Access functions to set ODE parameters.
| [in] | _erp | Error reduction parameter. | 
| 
 | pure virtual | 
Update the physics engine collision.
Implemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | inlinevirtual | 
Update the physics engine.
Reimplemented in gazebo::physics::DARTPhysics, and gazebo::physics::SimbodyPhysics.
| 
 | protected | 
Class that handles all contacts generated by the physics engine.
| 
 | protected | 
Real time update rate.
| 
 | protected | 
Node for communication.
| 
 | protected | 
Subscribe to the physics topic.
| 
 | protected | 
Mutex to protect the update cycle.
Referenced by GetPhysicsUpdateMutex().
| 
 | protected | 
Real time update rate.
| 
 | protected | 
Subscribe to the request topic.
| 
 | protected | 
Response publisher.
| 
 | protected | 
Our SDF values.
| 
 | protected | 
Target real time factor.
| 
 | protected | 
Pointer to the world.