A model is a collection of links, joints, and plugins. More...
#include <physics/physics.hh>

| Public Member Functions | |
| Model (BasePtr _parent) | |
| Constructor. | |
| virtual | ~Model () | 
| Destructor. | |
| void | AttachStaticModel (ModelPtr &_model, math::Pose _offset) | 
| Attach a static model to this model. | |
| void | DetachStaticModel (const std::string &_model) | 
| Detach a static model from this model. | |
| void | FillModelMsg (msgs::Model &_msg) GAZEBO_DEPRECATED | 
| DEPRECATED. | |
| void | FillMsg (msgs::Model &_msg) | 
| Fill a model message. | |
| virtual void | Fini () | 
| Finalize the model. | |
| Link_V | GetAllLinks () const GAZEBO_DEPRECATED | 
| Deprecated. | |
| virtual math::Box | GetBoundingBox () const | 
| Get the size of the bounding box. | |
| JointPtr | GetJoint (unsigned int index) const GAZEBO_DEPRECATED | 
| Get a joint by index. | |
| JointPtr | GetJoint (const std::string &name) | 
| Get a joint. | |
| unsigned int | GetJointCount () const | 
| Get the number of joints. | |
| const Joint_V & | GetJoints () const | 
| Get the joints. | |
| LinkPtr | GetLink (const std::string &_name="canonical") const | 
| Get a link by name. | |
| LinkPtr | GetLink (unsigned int _index) const GAZEBO_DEPRECATED | 
| This function is dangerous. Do not use. | |
| LinkPtr | GetLinkById (unsigned int _id) const | 
| Get a link by id. | |
| Link_V | GetLinks () const | 
| Construct and return a vector of Link's in this model Note this constructs the vector of Link's on the fly, could be costly. | |
| unsigned int | GetPluginCount () const | 
| Get the number of plugins this model has. | |
| virtual math::Vector3 | GetRelativeAngularAccel () const | 
| Get the angular acceleration of the entity. | |
| virtual math::Vector3 | GetRelativeAngularVel () const | 
| Get the angular velocity of the entity. | |
| virtual math::Vector3 | GetRelativeLinearAccel () const | 
| Get the linear acceleration of the entity. | |
| virtual math::Vector3 | GetRelativeLinearVel () const | 
| Get the linear velocity of the entity. | |
| virtual const sdf::ElementPtr | GetSDF () | 
| Get the SDF values for the model. | |
| unsigned int | GetSensorCount () const | 
| Get the number of sensors attached to this model. | |
| virtual math::Vector3 | GetWorldAngularAccel () const | 
| Get the angular acceleration of the entity in the world frame. | |
| virtual math::Vector3 | GetWorldAngularVel () const | 
| Get the angular velocity of the entity in the world frame. | |
| virtual math::Vector3 | GetWorldLinearAccel () const | 
| Get the linear acceleration of the entity in the world frame. | |
| virtual math::Vector3 | GetWorldLinearVel () const | 
| Get the linear velocity of the entity in the world frame. | |
| virtual void | Init () | 
| Initialize the model. | |
| void | Load (sdf::ElementPtr _sdf) | 
| Load the model. | |
| void | LoadPlugins () | 
| Load all plugins. | |
| void | ProcessMsg (const msgs::Model &_msg) | 
| Update parameters from a model message. | |
| virtual void | RemoveChild (EntityPtr _child) | 
| Remove a child. | |
| void | Reset () | 
| Reset the model. | |
| void | SetAngularAccel (const math::Vector3 &_vel) | 
| Set the angular acceleration of the model, and all its links. | |
| void | SetAngularVel (const math::Vector3 &_vel) | 
| Set the angular velocity of the model, and all its links. | |
| void | SetAutoDisable (bool _disable) | 
| Allow the model the auto disable. | |
| void | SetCollideMode (const std::string &_mode) | 
| This is not implemented in Link, which means this function doesn't do anything. | |
| void | SetEnabled (bool _enabled) | 
| Enable all the links in all the models. | |
| void | SetGravityMode (const bool &_value) | 
| Set the gravity mode of the model. | |
| void | SetJointAnimation (const std::map< std::string, common::NumericAnimationPtr > _anim, boost::function< void()> _onComplete=NULL) | 
| Joint Animation. | |
| void | SetJointPosition (const std::string &_jointName, double _position) | 
| Set the positions of a Joint by name. | |
| void | SetJointPositions (const std::map< std::string, double > &_jointPositions) | 
| Set the positions of a set of joints. | |
| void | SetLaserRetro (const float _retro) | 
| Set the laser retro reflectiveness of the model. | |
| void | SetLinearAccel (const math::Vector3 &_vel) | 
| Set the linear acceleration of the model, and all its links. | |
| void | SetLinearVel (const math::Vector3 &_vel) | 
| Set the linear velocity of the model, and all its links. | |
| void | SetLinkWorldPose (const math::Pose &_pose, std::string _linkName) | 
| Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. | |
| void | SetLinkWorldPose (const math::Pose &_pose, const LinkPtr &_link) | 
| Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. | |
| void | SetState (const ModelState &_state) | 
| Set the current model state. | |
| virtual void | StopAnimation () | 
| Stop the current animations. | |
| void | Update () | 
| Update the model. | |
| virtual void | UpdateParameters (sdf::ElementPtr _sdf) | 
| Update the parameters using new sdf values. | |
|  Public Member Functions inherited from gazebo::physics::Entity | |
| Entity (BasePtr _parent) | |
| Constructor. | |
| virtual | ~Entity () | 
| Destructor. | |
| CollisionPtr | GetChildCollision (const std::string &_name) | 
| Get a child collision entity, if one exists. | |
| LinkPtr | GetChildLink (const std::string &_name) | 
| Get a child linke entity, if one exists. | |
| math::Box | GetCollisionBoundingBox () const | 
| Returns collision bounding box. | |
| const math::Pose & | GetDirtyPose () const | 
| Returns Entity::dirtyPose. | |
| void | GetNearestEntityBelow (double &_distBelow, std::string &_entityName) | 
| Get the distance to the nearest entity below (along the Z-axis) this entity. | |
| ModelPtr | GetParentModel () | 
| Get the parent model, if one exists. | |
| math::Pose | GetRelativePose () const | 
| Get the pose of the entity relative to its parent. | |
| const math::Pose & | GetWorldPose () const | 
| Get the absolute pose of the entity. | |
| bool | IsCanonicalLink () const | 
| A helper function that checks if this is a canonical body. | |
| bool | IsStatic () const | 
| Return whether this entity is static. | |
| void | PlaceOnEntity (const std::string &_entityName) | 
| Move this entity to be ontop of another entity by name. | |
| void | PlaceOnNearestEntityBelow () | 
| Move this entity to be ontop of the nearest entity below. | |
| void | SetAnimation (const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete) | 
| Set an animation for this entity. | |
| void | SetAnimation (common::PoseAnimationPtr _anim) | 
| Set an animation for this entity. | |
| void | SetCanonicalLink (bool _value) | 
| Set to true if this entity is a canonical link for a model. | |
| void | SetInitialRelativePose (const math::Pose &_pose) | 
| Set the initial pose. | |
| virtual void | SetName (const std::string &_name) | 
| Set the name of the entity. | |
| void | SetRelativePose (const math::Pose &_pose, bool _notify=true, bool _publish=true) | 
| Set the pose of the entity relative to its parent. | |
| void | SetStatic (const bool &_static) | 
| Set whether this entity is static: immovable. | |
| void | SetWorldPose (const math::Pose &_pose, bool _notify=true, bool _publish=true) | 
| Set the world pose of the entity. | |
| void | SetWorldTwist (const math::Vector3 &_linear, const math::Vector3 &_angular, bool _updateChildren=true) | 
| Set angular and linear rates of an physics::Entity. | |
|  Public Member Functions inherited from gazebo::physics::Base | |
| Base (BasePtr _parent) | |
| Constructor. | |
| virtual | ~Base () | 
| Destructor. | |
| void | AddChild (BasePtr _child) | 
| Add a child to this entity. | |
| void | AddType (EntityType _type) | 
| Add a type specifier. | |
| BasePtr | GetById (unsigned int _id) const | 
| Get a child or self by id. | |
| BasePtr | GetByName (const std::string &_name) | 
| Get by name. | |
| BasePtr | GetChild (unsigned int _i) const | 
| Get a child by index. | |
| BasePtr | GetChild (const std::string &_name) | 
| Get a child by name. | |
| unsigned int | GetChildCount () const | 
| Get the number of children. | |
| unsigned int | GetId () const | 
| Return the ID of this entity. | |
| std::string | GetName () const | 
| Return the name of the entity. | |
| BasePtr | GetParent () const | 
| Get the parent. | |
| int | GetParentId () const | 
| Return the ID of the parent. | |
| bool | GetSaveable () const | 
| Get whether the object should be "saved", when the user selects to save the world to xml. | |
| std::string | GetScopedName () const | 
| Return the name of this entity with the model scope world::model1::...::modelN::entityName. | |
| unsigned int | GetType () const | 
| Get the full type definition. | |
| const WorldPtr & | GetWorld () const | 
| Get the World this object is in. | |
| bool | HasType (const EntityType &_t) const | 
| Returns true if this object's type definition has the given type. | |
| bool | IsSelected () const | 
| True if the entity is selected by the user. | |
| bool | operator== (const Base &_ent) const | 
| Returns true if the entities are the same. | |
| void | Print (const std::string &_prefix) | 
| Print this object to screen via gzmsg. | |
| virtual void | RemoveChild (unsigned int _id) | 
| Remove a child from this entity. | |
| void | RemoveChild (const std::string &_name) | 
| Remove a child by name. | |
| void | RemoveChildren () | 
| Remove all children. | |
| virtual void | Reset (Base::EntityType _resetType) | 
| Calls recursive Reset on one of the Base::EntityType's. | |
| void | SetParent (BasePtr _parent) | 
| Set the parent. | |
| void | SetSaveable (bool _v) | 
| Set whether the object should be "saved", when the user selects to save the world to xml. | |
| virtual bool | SetSelected (bool _show) | 
| Set whether this entity has been selected by the user through the gui. | |
| void | SetWorld (const WorldPtr &_newWorld) | 
| Set the world this object belongs to. | |
| Protected Member Functions | |
| virtual void | OnPoseChange () | 
| Callback when the pose of the model has been changed. | |
| Protected Attributes | |
| std::vector< ModelPtr > | attachedModels | 
| used by Model::AttachStaticModel | |
| std::vector< math::Pose > | attachedModelsOffset | 
| used by Model::AttachStaticModel | |
|  Protected Attributes inherited from gazebo::physics::Entity | |
| common::PoseAnimationPtr | animation | 
| Current pose animation. | |
| event::ConnectionPtr | animationConnection | 
| Connection used to update an animation. | |
| math::Pose | animationStartPose | 
| Start pose of an animation. | |
| std::vector< event::ConnectionPtr > | connections | 
| All our event connections. | |
| math::Pose | dirtyPose | 
| The pose set by a physics engine. | |
| transport::NodePtr | node | 
| Communication node. | |
| EntityPtr | parentEntity | 
| A helper that prevents numerous dynamic_casts. | |
| msgs::Pose * | poseMsg | 
| Pose message containr. | |
| common::Time | prevAnimationTime | 
| Previous time an animation was updated. | |
| transport::PublisherPtr | requestPub | 
| Request publisher. | |
| transport::PublisherPtr | visPub | 
| Visual publisher. | |
| msgs::Visual * | visualMsg | 
| Visual message container. | |
|  Protected Attributes inherited from gazebo::physics::Base | |
| Base_V | children | 
| Children of this entity. | |
| Base_V::iterator | childrenEnd | 
| End of the children vector. | |
| BasePtr | parent | 
| Parent of this entity. | |
| sdf::ElementPtr | sdf | 
| The SDF values for this object. | |
| WorldPtr | world | 
| Pointer to the world. | |
| Additional Inherited Members | |
|  Public Types inherited from gazebo::physics::Base | |
| enum | EntityType { BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004, COLLISION = 0x00000008, ACTOR = 0x00000016, LIGHT = 0x00000010, VISUAL = 0x00000020, JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200, SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, SHAPE = 0x00002000, BOX_SHAPE = 0x00004000, CYLINDER_SHAPE = 0x00008000, HEIGHTMAP_SHAPE = 0x00010000, MAP_SHAPE = 0x00020000, MULTIRAY_SHAPE = 0x00040000, RAY_SHAPE = 0x00080000, PLANE_SHAPE = 0x00100000, SPHERE_SHAPE = 0x00200000, TRIMESH_SHAPE = 0x00400000 } | 
| Unique identifiers for all entity types.  More... | |
A model is a collection of links, joints, and plugins.
| 
 | explicit | 
Constructor.
| [in] | _parent | Parent object. | 
| 
 | virtual | 
Destructor.
| void gazebo::physics::Model::AttachStaticModel | ( | ModelPtr & | _model, | 
| math::Pose | _offset | ||
| ) | 
Attach a static model to this model.
This function takes as input a static Model, which is a Model that has been marked as static (no physics simulation), and attaches it to this Model with a given offset.
This function is useful when you want to simulate a grasp of a static object, or move a static object around using a dynamic model.
If you are in doubt, do not use this function.
| [in] | _model | Pointer to the static model. | 
| [in] | _offset | Offset, relative to this Model, to place _model. | 
| void gazebo::physics::Model::DetachStaticModel | ( | const std::string & | _model | ) | 
Detach a static model from this model.
| [in] | _model | Name of an attached static model to remove. | 
| void gazebo::physics::Model::FillModelMsg | ( | msgs::Model & | _msg | ) | 
DEPRECATED.
| void gazebo::physics::Model::FillMsg | ( | msgs::Model & | _msg | ) | 
Fill a model message.
| [in] | _msg | Message to fill using this model's data. | 
| 
 | virtual | 
Finalize the model.
Reimplemented from gazebo::physics::Entity.
Reimplemented in gazebo::physics::Actor.
| Link_V gazebo::physics::Model::GetAllLinks | ( | ) | const | 
Deprecated.
| 
 | virtual | 
Get the size of the bounding box.
Reimplemented from gazebo::physics::Entity.
| JointPtr gazebo::physics::Model::GetJoint | ( | unsigned int | index | ) | const | 
Get a joint by index.
| index | Index of the joint | 
| JointPtr gazebo::physics::Model::GetJoint | ( | const std::string & | name | ) | 
Get a joint.
| name | The name of the joint, specified in the world file | 
| unsigned int gazebo::physics::Model::GetJointCount | ( | ) | const | 
Get the number of joints.
| const Joint_V& gazebo::physics::Model::GetJoints | ( | ) | const | 
Get the joints.
| LinkPtr gazebo::physics::Model::GetLink | ( | const std::string & | _name = "canonical" | ) | const | 
Get a link by name.
| [in] | _name | Name of the link to get. | 
| LinkPtr gazebo::physics::Model::GetLink | ( | unsigned int | _index | ) | const | 
This function is dangerous. Do not use.
| LinkPtr gazebo::physics::Model::GetLinkById | ( | unsigned int | _id | ) | const | 
Get a link by id.
| Link_V gazebo::physics::Model::GetLinks | ( | ) | const | 
| unsigned int gazebo::physics::Model::GetPluginCount | ( | ) | const | 
Get the number of plugins this model has.
| 
 | virtual | 
Get the angular acceleration of the entity.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the angular velocity of the entity.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the linear acceleration of the entity.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the linear velocity of the entity.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the SDF values for the model.
Reimplemented from gazebo::physics::Base.
Reimplemented in gazebo::physics::Actor.
| unsigned int gazebo::physics::Model::GetSensorCount | ( | ) | const | 
Get the number of sensors attached to this model.
This will count all the sensors attached to all the links.
| 
 | virtual | 
Get the angular acceleration of the entity in the world frame.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the angular velocity of the entity in the world frame.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the linear acceleration of the entity in the world frame.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Get the linear velocity of the entity in the world frame.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Initialize the model.
Reimplemented from gazebo::physics::Base.
Reimplemented in gazebo::physics::Actor.
| 
 | virtual | 
Load the model.
| [in] | _sdf | SDF parameters to load from. | 
Reimplemented from gazebo::physics::Entity.
| void gazebo::physics::Model::LoadPlugins | ( | ) | 
Load all plugins.
Load all plugins specified in the SDF for the model.
| 
 | protectedvirtual | 
Callback when the pose of the model has been changed.
Implements gazebo::physics::Entity.
| void gazebo::physics::Model::ProcessMsg | ( | const msgs::Model & | _msg | ) | 
Update parameters from a model message.
| [in] | _msg | Message to process. | 
| 
 | virtual | 
Remove a child.
| [in] | _child | Remove a child entity. | 
| 
 | virtual | 
Reset the model.
Reimplemented from gazebo::physics::Entity.
| void gazebo::physics::Model::SetAngularAccel | ( | const math::Vector3 & | _vel | ) | 
Set the angular acceleration of the model, and all its links.
| [in] | _vel | The new angular acceleration | 
| void gazebo::physics::Model::SetAngularVel | ( | const math::Vector3 & | _vel | ) | 
Set the angular velocity of the model, and all its links.
| [in] | _vel | The new angular velocity. | 
| void gazebo::physics::Model::SetAutoDisable | ( | bool | _disable | ) | 
Allow the model the auto disable.
This is ignored if the model has joints.
| [in] | _disable | If true, the model is allowed to auto disable. | 
| void gazebo::physics::Model::SetCollideMode | ( | const std::string & | _mode | ) | 
This is not implemented in Link, which means this function doesn't do anything.
Set the collide mode of the model.
| [in] | _mode | The collision mode | 
| void gazebo::physics::Model::SetEnabled | ( | bool | _enabled | ) | 
Enable all the links in all the models.
| [in] | _enabled | True to enable all the links. | 
| void gazebo::physics::Model::SetGravityMode | ( | const bool & | _value | ) | 
Set the gravity mode of the model.
| [in] | _value | False to turn gravity on for the model. | 
| void gazebo::physics::Model::SetJointAnimation | ( | const std::map< std::string, common::NumericAnimationPtr > | _anim, | 
| boost::function< void()> | _onComplete = NULL | ||
| ) | 
Joint Animation.
| [in] | _anim | Map of joint names to their position animation. | 
| [in] | _onComplete | Callback function for when the animation completes. | 
| void gazebo::physics::Model::SetJointPosition | ( | const std::string & | _jointName, | 
| double | _position | ||
| ) | 
Set the positions of a Joint by name.
| [in] | _jointName | Name of the joint to set. | 
| [in] | _position | Position to set the joint to. | 
| void gazebo::physics::Model::SetJointPositions | ( | const std::map< std::string, double > & | _jointPositions | ) | 
Set the positions of a set of joints.
| [in] | _jointPositions | Map of joint names to their positions. | 
| void gazebo::physics::Model::SetLaserRetro | ( | const float | _retro | ) | 
Set the laser retro reflectiveness of the model.
| [in] | _retro | Retro reflectance value. | 
| void gazebo::physics::Model::SetLinearAccel | ( | const math::Vector3 & | _vel | ) | 
Set the linear acceleration of the model, and all its links.
| [in] | _vel | The new linear acceleration. | 
| void gazebo::physics::Model::SetLinearVel | ( | const math::Vector3 & | _vel | ) | 
Set the linear velocity of the model, and all its links.
| [in] | _vel | The new linear velocity. | 
| void gazebo::physics::Model::SetLinkWorldPose | ( | const math::Pose & | _pose, | 
| std::string | _linkName | ||
| ) | 
| void gazebo::physics::Model::SetLinkWorldPose | ( | const math::Pose & | _pose, | 
| const LinkPtr & | _link | ||
| ) | 
| void gazebo::physics::Model::SetState | ( | const ModelState & | _state | ) | 
Set the current model state.
| [in] | _state | State to set the model to. | 
| 
 | virtual | 
Stop the current animations.
Reimplemented from gazebo::physics::Entity.
| 
 | virtual | 
Update the model.
Reimplemented from gazebo::physics::Base.
| 
 | virtual | 
Update the parameters using new sdf values.
| [in] | _sdf | SDF values to update from. | 
Reimplemented from gazebo::physics::Entity.
Reimplemented in gazebo::physics::Actor.
| 
 | protected | 
used by Model::AttachStaticModel
| 
 | protected | 
used by Model::AttachStaticModel