All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::physics::Model Class Reference

A model is a collection of links, joints, and plugins. More...

#include <physics/physics.hh>

Inheritance diagram for gazebo::physics::Model:
Inheritance graph
[legend]

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 FillMsg (msgs::Model &_msg)
 Fill a model message.
 
virtual void Fini ()
 Finalize the model.
 
bool GetAutoDisable () const
 Return the value of the SDF <allow_auto_disable> element.
 
virtual math::Box GetBoundingBox () const
 Get the size of the bounding box.
 
JointPtr GetJoint (const std::string &name)
 Get a joint.
 
JointControllerPtr GetJointController ()
 Get a handle to the Controller for the joints in this model.
 
unsigned int GetJointCount () const
 Get the number of joints.
 
const Joint_VGetJoints () const
 Get the joints.
 
LinkPtr GetLink (const std::string &_name="canonical") const
 Get a link by name.
 
LinkPtr GetLinkById (unsigned int _id) const
 This is an internal function
 
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 LoadJoints ()
 Load all the joints.
 
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::PoseGetDirtyPose () const
 Returns Entity::dirtyPose.
 
math::Pose GetInitialRelativePose () const
 Get the initial relative pose.
 
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::PoseGetWorldPose () 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
 This is an internal function.
 
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 WorldPtrGetWorld () 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< ModelPtrattachedModels
 used by Model::AttachStaticModel
 
std::vector< math::PoseattachedModelsOffset
 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::ConnectionPtrconnections
 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 container.
 
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...
 

Detailed Description

A model is a collection of links, joints, and plugins.

Constructor & Destructor Documentation

gazebo::physics::Model::Model ( BasePtr  _parent)
explicit

Constructor.

Parameters
[in]_parentParent object.
virtual gazebo::physics::Model::~Model ( )
virtual

Destructor.

Member Function Documentation

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.

Parameters
[in]_modelPointer to the static model.
[in]_offsetOffset, relative to this Model, to place _model.
void gazebo::physics::Model::DetachStaticModel ( const std::string &  _model)

Detach a static model from this model.

Parameters
[in]_modelName of an attached static model to remove.
See Also
Model::AttachStaticModel.
void gazebo::physics::Model::FillMsg ( msgs::Model &  _msg)

Fill a model message.

Parameters
[in]_msgMessage to fill using this model's data.
virtual void gazebo::physics::Model::Fini ( )
virtual

Finalize the model.

Reimplemented from gazebo::physics::Entity.

Reimplemented in gazebo::physics::Actor.

bool gazebo::physics::Model::GetAutoDisable ( ) const

Return the value of the SDF <allow_auto_disable> element.

Returns
True if auto disable is allowed for this model.
virtual math::Box gazebo::physics::Model::GetBoundingBox ( ) const
virtual

Get the size of the bounding box.

Returns
The bounding box.

Reimplemented from gazebo::physics::Entity.

JointPtr gazebo::physics::Model::GetJoint ( const std::string &  name)

Get a joint.

Parameters
nameThe name of the joint, specified in the world file
Returns
Pointer to the joint
JointControllerPtr gazebo::physics::Model::GetJointController ( )
inline

Get a handle to the Controller for the joints in this model.

Returns
A handle to the Controller for the joints in this model.
unsigned int gazebo::physics::Model::GetJointCount ( ) const

Get the number of joints.

Returns
Get the number of joints.
const Joint_V& gazebo::physics::Model::GetJoints ( ) const

Get the joints.

Returns
Vector of joints.
LinkPtr gazebo::physics::Model::GetLink ( const std::string &  _name = "canonical") const

Get a link by name.

Parameters
[in]_nameName of the link to get.
Returns
Pointer to the link, NULL if the name is invalid.
LinkPtr gazebo::physics::Model::GetLinkById ( unsigned int  _id) const

This is an internal function

Get a link by id.

Returns
Pointer to the link, NULL if the id is invalid.
Link_V gazebo::physics::Model::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.

Returns
a vector of Link's in this model
unsigned int gazebo::physics::Model::GetPluginCount ( ) const

Get the number of plugins this model has.

Returns
Number of plugins associated with this model.
virtual math::Vector3 gazebo::physics::Model::GetRelativeAngularAccel ( ) const
virtual

Get the angular acceleration of the entity.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetRelativeAngularVel ( ) const
virtual

Get the angular velocity of the entity.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetRelativeLinearAccel ( ) const
virtual

Get the linear acceleration of the entity.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetRelativeLinearVel ( ) const
virtual

Get the linear velocity of the entity.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual const sdf::ElementPtr gazebo::physics::Model::GetSDF ( )
virtual

Get the SDF values for the model.

Returns
The SDF value for this 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.

Returns
Number of sensors.
virtual math::Vector3 gazebo::physics::Model::GetWorldAngularAccel ( ) const
virtual

Get the angular acceleration of the entity in the world frame.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetWorldAngularVel ( ) const
virtual

Get the angular velocity of the entity in the world frame.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetWorldLinearAccel ( ) const
virtual

Get the linear acceleration of the entity in the world frame.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual math::Vector3 gazebo::physics::Model::GetWorldLinearVel ( ) const
virtual

Get the linear velocity of the entity in the world frame.

Returns
math::Vector3, set to 0, 0, 0 if the model has no body.

Reimplemented from gazebo::physics::Entity.

virtual void gazebo::physics::Model::Init ( )
virtual

Initialize the model.

Reimplemented from gazebo::physics::Base.

Reimplemented in gazebo::physics::Actor.

void gazebo::physics::Model::Load ( sdf::ElementPtr  _sdf)
virtual

Load the model.

Parameters
[in]_sdfSDF parameters to load from.

Reimplemented from gazebo::physics::Entity.

void gazebo::physics::Model::LoadJoints ( )

Load all the joints.

void gazebo::physics::Model::LoadPlugins ( )

Load all plugins.

Load all plugins specified in the SDF for the model.

virtual void gazebo::physics::Model::OnPoseChange ( )
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.

Parameters
[in]_msgMessage to process.
virtual void gazebo::physics::Model::RemoveChild ( EntityPtr  _child)
virtual

Remove a child.

Parameters
[in]_childRemove a child entity.
void gazebo::physics::Model::Reset ( )
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.

Parameters
[in]_velThe new angular acceleration
void gazebo::physics::Model::SetAngularVel ( const math::Vector3 _vel)

Set the angular velocity of the model, and all its links.

Parameters
[in]_velThe new angular velocity.
void gazebo::physics::Model::SetAutoDisable ( bool  _disable)

Allow the model the auto disable.

This is ignored if the model has joints.

Parameters
[in]_disableIf 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.

Parameters
[in]_modeThe collision mode
void gazebo::physics::Model::SetEnabled ( bool  _enabled)

Enable all the links in all the models.

Parameters
[in]_enabledTrue to enable all the links.
void gazebo::physics::Model::SetGravityMode ( const bool &  _value)

Set the gravity mode of the model.

Parameters
[in]_valueFalse 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.

Parameters
[in]_animMap of joint names to their position animation.
[in]_onCompleteCallback 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.

See Also
JointController::SetJointPosition
Parameters
[in]_jointNameName of the joint to set.
[in]_positionPosition 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.

See Also
JointController::SetJointPositions.
Parameters
[in]_jointPositionsMap of joint names to their positions.
void gazebo::physics::Model::SetLaserRetro ( const float  _retro)

Set the laser retro reflectiveness of the model.

Parameters
[in]_retroRetro reflectance value.
void gazebo::physics::Model::SetLinearAccel ( const math::Vector3 _vel)

Set the linear acceleration of the model, and all its links.

Parameters
[in]_velThe new linear acceleration.
void gazebo::physics::Model::SetLinearVel ( const math::Vector3 _vel)

Set the linear velocity of the model, and all its links.

Parameters
[in]_velThe new linear velocity.
void gazebo::physics::Model::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.

Doing so, keeps the configuration of the Model unchanged, i.e. all Joint angles are unchanged.

Parameters
[in]_posePose to set the link to.
[in]_linkNameName of the link to set.
void gazebo::physics::Model::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.

Doing so, keeps the configuration of the Model unchanged, i.e. all Joint angles are unchanged.

Parameters
[in]_posePose to set the link to.
[in]_linkPointer to the link to set.
void gazebo::physics::Model::SetState ( const ModelState _state)

Set the current model state.

Parameters
[in]_stateState to set the model to.
virtual void gazebo::physics::Model::StopAnimation ( )
virtual

Stop the current animations.

Reimplemented from gazebo::physics::Entity.

void gazebo::physics::Model::Update ( )
virtual

Update the model.

Reimplemented from gazebo::physics::Base.

virtual void gazebo::physics::Model::UpdateParameters ( sdf::ElementPtr  _sdf)
virtual

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from gazebo::physics::Entity.

Reimplemented in gazebo::physics::Actor.

Member Data Documentation

std::vector<ModelPtr> gazebo::physics::Model::attachedModels
protected
std::vector<math::Pose> gazebo::physics::Model::attachedModelsOffset
protected

The documentation for this class was generated from the following file: