Simbody physics engine. More...
#include <SimbodyPhysics.hh>


| Public Member Functions | |
| SimbodyPhysics (WorldPtr _world) | |
| Constructor.  More... | |
| virtual | ~SimbodyPhysics () | 
| Destructor.  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 ModelPtr | CreateModel (BasePtr _parent) | 
| 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... | |
| SimTK::MultibodySystem * | GetDynamicsWorld () const | 
| Register a joint with the dynamics world.  More... | |
| virtual boost::any | GetParam (const std::string &_key) const | 
| Get an parameter of the physics engine.  More... | |
| virtual std::string | GetType () const | 
| Return the physics engine type (ode|bullet|dart|simbody).  More... | |
| virtual void | Init () | 
| Initialize the physics engine.  More... | |
| virtual void | InitForThread () | 
| Init the engine for threads.  More... | |
| void | InitModel (const physics::ModelPtr _model) | 
| Add a Model to the Simbody system.  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) | 
| Set a parameter of the physics engine.  More... | |
| virtual void | SetSeed (uint32_t _seed) | 
| Set the random number seed for the physics engine.  More... | |
| 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 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 | 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 | 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 | 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... | |
| Static Public Member Functions | |
| static SimTK::Transform | GetPose (sdf::ElementPtr _element) | 
| If the given element contains a <pose> element, return it as a Transform.  More... | |
| static std::string | GetTypeString (unsigned int _type) | 
| Convert Base::GetType() to string, this is needed by the MultibodyGraphMaker.  More... | |
| static std::string | GetTypeString (physics::Base::EntityType _type) | 
| Convert Base::GetType() to string, this is needed by the MultibodyGraphMaker.  More... | |
| static SimTK::Transform | Pose2Transform (const math::Pose &_pose) | 
| Convert the given pose in x,y,z,thetax,thetay,thetaz format to a Simbody Transform.  More... | |
| static SimTK::Quaternion | QuadToQuad (const math::Quaternion &_q) | 
| Convert gazebo::math::Quaternion to SimTK::Quaternion.  More... | |
| static math::Quaternion | QuadToQuad (const SimTK::Quaternion &_q) | 
| Convert SimTK::Quaternion to gazebo::math::Quaternion.  More... | |
| static math::Pose | Transform2Pose (const SimTK::Transform &_xAB) | 
| Convert a Simbody transform to a pose in x,y,z, thetax,thetay,thetaz format.  More... | |
| static math::Vector3 | Vec3ToVector3 (const SimTK::Vec3 &_v) | 
| Convert SimTK::Vec3 to gazebo::math::Vector3.  More... | |
| static SimTK::Vec3 | Vector3ToVec3 (const math::Vector3 &_v) | 
| Convert gazebo::math::Vector3 to SimTK::Vec3.  More... | |
| Public Attributes | |
| SimTK::CompliantContactSubsystem | contact | 
| SimTK::Force::DiscreteForces | discreteForces | 
| SimTK::GeneralForceSubsystem | forces | 
| SimTK::Force::Gravity | gravity | 
| SimTK::Integrator * | integ | 
| SimTK::SimbodyMatterSubsystem | matter | 
| bool | simbodyPhysicsInitialized | 
| true if initialized  More... | |
| bool | simbodyPhysicsStepped | 
| SimTK::MultibodySystem | system | 
| SimTK::ContactTrackerSubsystem | tracker | 
| 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... | |
| 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... | |
Simbody physics engine.
| gazebo::physics::SimbodyPhysics::SimbodyPhysics | ( | WorldPtr | _world | ) | 
Constructor.
| 
 | virtual | 
Destructor.
| 
 | 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.
Create a new model.
| [in] | _base | Boost shared pointer to a new model. | 
Reimplemented from 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.
| SimTK::MultibodySystem* gazebo::physics::SimbodyPhysics::GetDynamicsWorld | ( | ) | const | 
Register a joint with the dynamics world.
| 
 | virtual | 
Get an parameter of the physics engine.
| [in] | _attr | String key | 
Reimplemented from gazebo::physics::PhysicsEngine.
| 
 | static | 
If the given element contains a <pose> element, return it as a Transform.
Otherwise return the identity Transform. If there is more than one <pose> element, only the first one is processed.
| 
 | virtual | 
Return the physics engine type (ode|bullet|dart|simbody).
Implements gazebo::physics::PhysicsEngine.
| 
 | static | 
Convert Base::GetType() to string, this is needed by the MultibodyGraphMaker.
| [in] | _type | Joint type returned by Joint::GetType(). | 
| 
 | static | 
Convert Base::GetType() to string, this is needed by the MultibodyGraphMaker.
| [in] | _type | Joint type returned by Joint::GetType(). | 
| 
 | virtual | 
Initialize the physics engine.
Implements gazebo::physics::PhysicsEngine.
| 
 | virtual | 
Init the engine for threads.
Implements gazebo::physics::PhysicsEngine.
| void gazebo::physics::SimbodyPhysics::InitModel | ( | const physics::ModelPtr | _model | ) | 
Add a Model to the Simbody system.
| [in] | _model | Pointer to the model to add into Simbody. | 
| 
 | 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 | 
virtual callback for gztopic "~/request".
| [in] | _msg | Request message. | 
Reimplemented from gazebo::physics::PhysicsEngine.
| 
 | static | 
Convert the given pose in x,y,z,thetax,thetay,thetaz format to a Simbody Transform.
The rotation angles are interpreted as a body-fixed sequence, meaning we rotation about x, then about the new y, then about the now twice-rotated z.
| [in] | _pose | Gazeb's math::Pose object | 
| 
 | static | 
Convert gazebo::math::Quaternion to SimTK::Quaternion.
| [in] | _q | Gazeb's math::Quaternion object | 
| 
 | static | 
Convert SimTK::Quaternion to gazebo::math::Quaternion.
| [in] | _q | Simbody's SimTK::Quaternion object | 
| 
 | virtual | 
Rest the physics engine.
Reimplemented from gazebo::physics::PhysicsEngine.
| 
 | virtual | 
Set the gavity vector.
| [in] | _gravity | New gravity vector. | 
Implements gazebo::physics::PhysicsEngine.
| 
 | virtual | 
Set a parameter of the physics engine.
See SetParam documentation for descriptions of duplicate parameters.
| [in] | _key | String key Below is a list of _key parameter definitions: 
 | 
| [in] | _value | The value to set to | 
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.
| 
 | static | 
Convert a Simbody transform to a pose in x,y,z, thetax,thetay,thetaz format.
| [in] | _xAB | Simbody's SimTK::Transform object | 
| 
 | virtual | 
Update the physics engine collision.
Implements gazebo::physics::PhysicsEngine.
| 
 | virtual | 
Update the physics engine.
Reimplemented from gazebo::physics::PhysicsEngine.
| 
 | static | 
Convert SimTK::Vec3 to gazebo::math::Vector3.
| [in] | _v | Simbody's SimTK::Vec3 object | 
| 
 | static | 
Convert gazebo::math::Vector3 to SimTK::Vec3.
| [in] | _v | Gazeb's math::Vector3 object | 
| SimTK::CompliantContactSubsystem gazebo::physics::SimbodyPhysics::contact | 
| SimTK::Force::DiscreteForces gazebo::physics::SimbodyPhysics::discreteForces | 
| SimTK::GeneralForceSubsystem gazebo::physics::SimbodyPhysics::forces | 
| SimTK::Force::Gravity gazebo::physics::SimbodyPhysics::gravity | 
| SimTK:: Integrator* gazebo::physics::SimbodyPhysics::integ | 
| SimTK::SimbodyMatterSubsystem gazebo::physics::SimbodyPhysics::matter | 
| bool gazebo::physics::SimbodyPhysics::simbodyPhysicsInitialized | 
true if initialized
| bool gazebo::physics::SimbodyPhysics::simbodyPhysicsStepped | 
| SimTK::MultibodySystem gazebo::physics::SimbodyPhysics::system | 
| SimTK::ContactTrackerSubsystem gazebo::physics::SimbodyPhysics::tracker |