Model Class Reference

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

#include <physics/physics.hh>

Inherits Entity.

Inherited by Actor, DARTModel, and SimbodyModel.

Public Types

enum  EntityType {
  BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004,
  COLLISION = 0x00000008, LIGHT = 0x00000010, VISUAL = 0x00000020, JOINT = 0x00000040,
  BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200, SLIDER_JOINT = 0x00000400,
  SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000, FIXED_JOINT = 0x00004000,
  ACTOR = 0x00008000, SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000,
  HEIGHTMAP_SHAPE = 0x00080000, MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000,
  PLANE_SHAPE = 0x00800000, SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000,
  SENSOR_COLLISION = 0x10000000
}
 Unique identifiers for all entity types. More...
 

Public Member Functions

 Model (BasePtr _parent)
 Constructor. More...
 
virtual ~Model ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
void AttachStaticModel (ModelPtr &_model, ignition::math::Pose3d _offset)
 Attach a static model to this model. More...
 
virtual ignition::math::AxisAlignedBox BoundingBox () const override
 Get the size of the bounding box. More...
 
ignition::math::AxisAlignedBox CollisionBoundingBox () const
 Returns collision bounding box. More...
 
virtual gazebo::physics::JointPtr CreateJoint (const std::string &_name, const std::string &_type, physics::LinkPtr _parent, physics::LinkPtr _child)
 Create a joint for this model. More...
 
virtual gazebo::physics::JointPtr CreateJoint (sdf::ElementPtr _sdf)
 Create a joint for this model. More...
 
LinkPtr CreateLink (const std::string &_name)
 Create a new link for this model. More...
 
void DetachStaticModel (const std::string &_model)
 Detach a static model from this model. More...
 
const ignition::math::Pose3d & DirtyPose () const
 Returns Entity::dirtyPose. More...
 
virtual void FillMsg (msgs::Model &_msg)
 Fill a model message. More...
 
virtual void Fini () override
 Finalize the model. More...
 
bool GetAutoDisable () const
 Return the value of the SDF <allow_auto_disable> element. More...
 
BasePtr GetByName (const std::string &_name)
 Get by name. More...
 
BasePtr GetChild (unsigned int _i) const
 Get a child by index. More...
 
BasePtr GetChild (const std::string &_name)
 Get a child by name. More...
 
CollisionPtr GetChildCollision (const std::string &_name)
 Get a child collision entity, if one exists. More...
 
unsigned int GetChildCount () const
 Get the number of children. More...
 
LinkPtr GetChildLink (const std::string &_name)
 Get a child linke entity, if one exists. More...
 
GripperPtr GetGripper (size_t _index) const
 Get a gripper based on an index. More...
 
size_t GetGripperCount () const
 Get the number of grippers in this model. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
JointPtr GetJoint (const std::string &name)
 Get a joint. More...
 
JointControllerPtr GetJointController ()
 Get a handle to the Controller for the joints in this model. More...
 
unsigned int GetJointCount () const
 Get the number of joints. More...
 
const Joint_VGetJoints () const
 Get the joints. More...
 
LinkPtr GetLink (const std::string &_name="canonical") const
 Get a link by name. More...
 
const Link_VGetLinks () 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. More...
 
std::string GetName () const
 Return the name of the entity. More...
 
void GetNearestEntityBelow (double &_distBelow, std::string &_entityName)
 Get the distance to the nearest entity below (along the Z-axis) this entity. More...
 
BasePtr GetParent () const
 Get the parent. More...
 
int GetParentId () const
 Return the ID of the parent. More...
 
ModelPtr GetParentModel ()
 Get the parent model, if one exists. More...
 
unsigned int GetPluginCount () const
 Get the number of plugins this model has. More...
 
bool GetSaveable () const
 Get whether the object should be "saved", when the user selects to save the world to xml. More...
 
std::string GetScopedName (bool _prependWorldName=false) const
 Return the name of this entity with the model scope model1::...::modelN::entityName. More...
 
virtual const sdf::ElementPtr GetSDF () override
 Get the SDF values for the model. More...
 
const sdf::Model * GetSDFDom () const
 Get the SDF DOM for the model. More...
 
virtual bool GetSelfCollide () const
 If true, all links within the model will collide by default. More...
 
unsigned int GetSensorCount () const
 Get the number of sensors attached to this model. More...
 
unsigned int GetType () const
 Get the full type definition. More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. More...
 
double GetWorldEnergy () const
 Returns this model's total energy, or sum of Model::GetWorldEnergyPotential() and Model::GetWorldEnergyKinetic(). More...
 
double GetWorldEnergyKinetic () const
 Returns sum of the kinetic energies of all links in this model. More...
 
double GetWorldEnergyPotential () const
 Returns the potential energy of all links and joint springs in the model. More...
 
bool HasType (const EntityType &_t) const
 Returns true if this object's type definition has the given type. More...
 
virtual void Init () override
 Initialize the model. More...
 
ignition::math::Pose3d InitialRelativePose () const
 Get the initial relative pose. More...
 
bool IsCanonicalLink () const
 A helper function that checks if this is a canonical body. More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
bool IsStatic () const
 Return whether this entity is static. More...
 
void Load (sdf::ElementPtr _sdf) override
 Load the model. More...
 
void LoadJoints ()
 Load all the joints. More...
 
void LoadPlugins ()
 Load all plugins. More...
 
ModelPtr NestedModel (const std::string &_name) const
 Get a nested model that is a direct child of this model. More...
 
const Model_VNestedModels () const
 Get all the nested models. More...
 
bool operator== (const Base &_ent) const
 Returns true if the entities are the same. More...
 
void PlaceOnEntity (const std::string &_entityName)
 Move this entity to be ontop of another entity by name. More...
 
void PlaceOnNearestEntityBelow ()
 Move this entity to be ontop of the nearest entity below. More...
 
void PluginInfo (const common::URI &_pluginUri, ignition::msgs::Plugin_V &_plugins, bool &_success)
 Get information about plugins in this model or one of its children, according to the given _pluginUri. More...
 
void Print (const std::string &_prefix)
 Print this object to screen via gzmsg. More...
 
void ProcessMsg (const msgs::Model &_msg)
 Update parameters from a model message. More...
 
virtual ignition::math::Vector3d RelativeAngularAccel () const override
 Get the angular acceleration of the entity. More...
 
virtual ignition::math::Vector3d RelativeAngularVel () const override
 Get the angular velocity of the entity. More...
 
virtual ignition::math::Vector3d RelativeLinearAccel () const override
 Get the linear acceleration of the entity. More...
 
virtual ignition::math::Vector3d RelativeLinearVel () const override
 Get the linear velocity of the entity. More...
 
ignition::math::Pose3d RelativePose () const
 Get the pose of the entity relative to its parent. More...
 
virtual void RemoveChild (EntityPtr _child)
 Remove a child. More...
 
virtual void RemoveChild (unsigned int _id)
 Remove a child from this entity. More...
 
void RemoveChild (const std::string &_name)
 Remove a child by name. More...
 
void RemoveChild (physics::BasePtr _child)
 Remove a child by pointer. More...
 
void RemoveChildren ()
 Remove all children. More...
 
virtual bool RemoveJoint (const std::string &_name)
 Remove a joint for this model. More...
 
void Reset () override
 Reset the model. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. More...
 
void ResetPhysicsStates ()
 Reset the velocity, acceleration, force and torque of all child links. More...
 
ignition::math::Vector3d Scale () const
 Get the scale of model. More...
 
ignition::math::Pose3d SDFPoseRelativeToParent () const
 Get the SDF pose of the object according to the sdf 1.6 convention. More...
 
std::optional< sdf::SemanticPose > SDFSemanticPose () const override
 Get the SDF SemanticPose object associated with the pose of this object. More...
 
std::vector< std::string > SensorScopedName (const std::string &_name) const
 Get scoped sensor name(s) in the model that matches sensor name. More...
 
void SetAngularVel (const ignition::math::Vector3d &_vel)
 Set the angular velocity of the model, and all its links. More...
 
void SetAnimation (const common::PoseAnimationPtr &_anim, boost::function< void()> _onComplete)
 Set an animation for this entity. More...
 
void SetAnimation (common::PoseAnimationPtr _anim)
 Set an animation for this entity. More...
 
void SetAutoDisable (bool _disable)
 Allow the model the auto disable. More...
 
void SetCanonicalLink (bool _value)
 Set to true if this entity is a canonical link for a model. More...
 
void SetCollideMode (const std::string &_mode)
 This is not implemented in Link, which means this function doesn't do anything. More...
 
void SetEnabled (bool _enabled)
 Enable all the links in all the models. More...
 
void SetGravityMode (const bool &_value)
 Set the gravity mode of the model. More...
 
void SetInitialRelativePose (const ignition::math::Pose3d &_pose)
 Set the initial pose. More...
 
void SetJointAnimation (const std::map< std::string, common::NumericAnimationPtr > &_anims, boost::function< void()> _onComplete=NULL)
 Joint Animation. More...
 
void SetJointPosition (const std::string &_jointName, double _position, int _index=0)
 Set the positions of a Joint by name. More...
 
void SetJointPositions (const std::map< std::string, double > &_jointPositions)
 Set the positions of a set of joints. More...
 
void SetLaserRetro (const float _retro)
 Set the laser retro reflectiveness of the model. More...
 
void SetLinearVel (const ignition::math::Vector3d &_vel)
 Set the linear velocity of the model, and all its links. More...
 
void SetLinkWorldPose (const ignition::math::Pose3d &_pose, std::string _linkName)
 Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. More...
 
void SetLinkWorldPose (const ignition::math::Pose3d &_pose, const LinkPtr &_link)
 Set the Pose of the entire Model by specifying desired Pose of a Link within the Model. More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
void SetRelativePose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
 Set the pose of the entity relative to its parent. More...
 
void SetSaveable (bool _v)
 Set whether the object should be "saved", when the user selects to save the world to xml. More...
 
void SetScale (const ignition::math::Vector3d &_scale, const bool _publish=false)
 Set the scale of model. More...
 
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui. More...
 
virtual void SetSelfCollide (bool _self_collide)
 Set this model's self_collide property. More...
 
void SetState (const ModelState &_state)
 Set the current model state. More...
 
void SetStatic (const bool &_static)
 Set whether this entity is static: immovable. More...
 
virtual void SetWindMode (const bool _mode)
 Set whether wind affects this body. More...
 
void SetWorld (const WorldPtr &_newWorld)
 Set the world this object belongs to. More...
 
void SetWorldPose (const ignition::math::Pose3d &_pose, const bool _notify=true, const bool _publish=true)
 Set the world pose of the entity. More...
 
void SetWorldTwist (const ignition::math::Vector3d &_linear, const ignition::math::Vector3d &_angular, const bool _updateChildren=true)
 Set angular and linear rates of an physics::Entity. More...
 
boost::shared_ptr< Modelshared_from_this ()
 Allow Model class to share itself as a boost shared_ptr. More...
 
virtual void StopAnimation () override
 Stop the current animations. More...
 
std::string TypeStr () const
 Get the string name for the entity type. More...
 
virtual const sdf::ElementPtr UnscaledSDF ()
 
void Update () override
 Update the model. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf) override
 Update the parameters using new sdf values. More...
 
common::URI URI () const
 Return the common::URI of this entity. More...
 
virtual bool WindMode () const
 Get the wind mode. More...
 
virtual ignition::math::Vector3d WorldAngularAccel () const override
 Get the angular acceleration of the entity in the world frame. More...
 
virtual ignition::math::Vector3d WorldAngularVel () const override
 Get the angular velocity of the entity in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearAccel () const override
 Get the linear acceleration of the entity in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearVel () const override
 Get the linear velocity of the entity in the world frame. More...
 
virtual const ignition::math::Pose3d & WorldPose () const
 Get the absolute pose of the entity. More...
 

Protected Member Functions

void ComputeScopedName ()
 Compute the scoped name of this object based on its parents. More...
 
virtual void OnPoseChange () override
 Callback when the pose of the model has been changed. More...
 
virtual void RegisterIntrospectionItems () override
 Register items in the introspection service. More...
 
virtual void UnregisterIntrospectionItems ()
 Unregister items in the introspection service. More...
 

Protected Attributes

common::PoseAnimationPtr animation
 Current pose animation. More...
 
event::ConnectionPtr animationConnection
 Connection used to update an animation. More...
 
ignition::math::Pose3d animationStartPose
 Start pose of an animation. More...
 
std::vector< ModelPtrattachedModels
 used by Model::AttachStaticModel More...
 
std::vector< ignition::math::Pose3d > attachedModelsOffset
 used by Model::AttachStaticModel More...
 
Base_V children
 Children of this entity. More...
 
std::vector< event::ConnectionPtrconnections
 All our event connections. More...
 
ignition::math::Pose3d dirtyPose
 The pose set by a physics engine. More...
 
std::vector< common::URIintrospectionItems
 All the introspection items regsitered for this. More...
 
transport::PublisherPtr jointPub
 Publisher for joint info. More...
 
transport::NodePtr node
 Communication node. More...
 
ignition::transport::Node nodeIgn
 Ignition communication node. More...
 
BasePtr parent
 Parent of this entity. More...
 
EntityPtr parentEntity
 A helper that prevents numerous dynamic_casts. More...
 
common::Time prevAnimationTime
 Previous time an animation was updated. More...
 
transport::PublisherPtr requestPub
 Request publisher. More...
 
ignition::transport::Node::Publisher requestPubIgn
 Request publisher. More...
 
ignition::math::Vector3d scale
 Scale of the entity. More...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
transport::PublisherPtr visPub
 Visual publisher. More...
 
ignition::transport::Node::Publisher visPubIgn
 Visual publisher. More...
 
msgs::Visual * visualMsg
 Visual message container. More...
 
WorldPtr world
 Pointer to the world. More...
 
ignition::math::Pose3d worldPose
 World pose of the entity. More...
 

Detailed Description

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

Member Enumeration Documentation

◆ EntityType

enum EntityType
inherited

Unique identifiers for all entity types.

Enumerator
BASE 

Base type.

ENTITY 

Entity type.

MODEL 

Model type.

LINK 

Link type.

COLLISION 

Collision type.

LIGHT 

Light type.

VISUAL 

Visual type.

JOINT 

Joint type.

BALL_JOINT 

BallJoint type.

HINGE2_JOINT 

Hing2Joint type.

HINGE_JOINT 

HingeJoint type.

SLIDER_JOINT 

SliderJoint type.

SCREW_JOINT 

ScrewJoint type.

UNIVERSAL_JOINT 

UniversalJoint type.

GEARBOX_JOINT 

GearboxJoint type.

FIXED_JOINT 

FixedJoint type.

ACTOR 

Actor type.

SHAPE 

Shape type.

BOX_SHAPE 

BoxShape type.

CYLINDER_SHAPE 

CylinderShape type.

HEIGHTMAP_SHAPE 

HeightmapShape type.

MAP_SHAPE 

MapShape type.

MULTIRAY_SHAPE 

MultiRayShape type.

RAY_SHAPE 

RayShape type.

PLANE_SHAPE 

PlaneShape type.

SPHERE_SHAPE 

SphereShape type.

MESH_SHAPE 

MeshShape type.

POLYLINE_SHAPE 

PolylineShape type.

SENSOR_COLLISION 

Indicates a collision shape used for sensing.

Constructor & Destructor Documentation

◆ Model()

Model ( BasePtr  _parent)
explicit

Constructor.

Parameters
[in]_parentParent object.

◆ ~Model()

virtual ~Model ( )
virtual

Destructor.

Member Function Documentation

◆ AddChild()

void AddChild ( BasePtr  _child)
inherited

Add a child to this entity.

Parameters
[in]_childChild entity.

Referenced by Base::Update().

◆ AddType()

void AddType ( EntityType  _type)
inherited

Add a type specifier.

Parameters
[in]_typeNew type to append to this objects type definition.

Referenced by Base::Update().

◆ AttachStaticModel()

void AttachStaticModel ( ModelPtr _model,
ignition::math::Pose3d  _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.

◆ BoundingBox()

virtual ignition::math::AxisAlignedBox BoundingBox ( ) const
overridevirtual

Get the size of the bounding box.

Returns
The bounding box.

Reimplemented from Entity.

◆ CollisionBoundingBox()

ignition::math::AxisAlignedBox CollisionBoundingBox ( ) const
inherited

Returns collision bounding box.

Returns
Collsion bounding box.

◆ ComputeScopedName()

void ComputeScopedName ( )
protectedinherited

Compute the scoped name of this object based on its parents.

See also
Base::GetScopedName

Referenced by Base::Update().

◆ CreateJoint() [1/2]

virtual gazebo::physics::JointPtr CreateJoint ( const std::string &  _name,
const std::string &  _type,
physics::LinkPtr  _parent,
physics::LinkPtr  _child 
)
virtual

Create a joint for this model.

Parameters
[in]_namename of joint
[in]_typetype of joint
[in]_parentparent link of joint
[in]_childchild link of joint
Remarks
This loads the joint, but does not initialize it. Joint::Init() must be called on the returned joint to make it affect the simulation.
Returns
a JointPtr to the new joint created, returns NULL JointPtr() if joint by name _name already exists.
Exceptions
common::ExceptionWhen _type is not recognized

Reimplemented in DARTModel.

◆ CreateJoint() [2/2]

virtual gazebo::physics::JointPtr CreateJoint ( sdf::ElementPtr  _sdf)
virtual

Create a joint for this model.

Parameters
[in]_sdfSDF parameters for <joint>
Remarks
This loads the joint, but does not initialize it. Joint::Init() must be called on the returned joint to make it affect the simulation.
Returns
a JointPtr to the new joint created, returns NULL JointPtr() if joint by name _name already exists.
Exceptions
common::ExceptionWhen _type is not recognized

Reimplemented in DARTModel.

◆ CreateLink()

LinkPtr CreateLink ( const std::string &  _name)

Create a new link for this model.

Parameters
[in]_namename of the new link
Returns
a LinkPtr to the new link created, returns NULL if link _name already exists.

◆ DetachStaticModel()

void 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.

◆ DirtyPose()

const ignition::math::Pose3d& DirtyPose ( ) const
inherited

Returns Entity::dirtyPose.

The dirty pose is the pose set by the physics engine before it's value is propagated to the rest of the simulator.

Returns
The dirty pose of the entity.

◆ FillMsg()

virtual void FillMsg ( msgs::Model &  _msg)
virtual

Fill a model message.

Parameters
[in]_msgMessage to fill using this model's data.

◆ Fini()

virtual void Fini ( )
overridevirtual

Finalize the model.

Reimplemented from Entity.

Reimplemented in Actor, and DARTModel.

◆ GetAutoDisable()

bool GetAutoDisable ( ) const

Return the value of the SDF <allow_auto_disable> element.

Returns
True if auto disable is allowed for this model.

◆ GetByName()

BasePtr GetByName ( const std::string &  _name)
inherited

Get by name.

Parameters
[in]_nameGet a child (or self) object by name
Returns
A pointer to the object, NULL if not found

Referenced by Base::Update().

◆ GetChild() [1/2]

BasePtr GetChild ( unsigned int  _i) const
inherited

Get a child by index.

Parameters
[in]_iIndex of the child to retreive.
Returns
A pointer to the object, NULL if the index is invalid.

Referenced by Base::Update().

◆ GetChild() [2/2]

BasePtr GetChild ( const std::string &  _name)
inherited

Get a child by name.

Parameters
[in]_nameName of the child.
Returns
A pointer to the object, NULL if not found

◆ GetChildCollision()

CollisionPtr GetChildCollision ( const std::string &  _name)
inherited

Get a child collision entity, if one exists.

Parameters
[in]_nameName of the child collision object.
Returns
Pointer to the Collision object, or NULL if not found.

◆ GetChildCount()

unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.

Referenced by Base::Update().

◆ GetChildLink()

LinkPtr GetChildLink ( const std::string &  _name)
inherited

Get a child linke entity, if one exists.

Parameters
[in]_nameName of the child Link object.
Returns
Pointer to the Link object, or NULL if not found.

◆ GetGripper()

GripperPtr GetGripper ( size_t  _index) const

Get a gripper based on an index.

Returns
A pointer to a Gripper. Null if the _index is invalid.

◆ GetGripperCount()

size_t GetGripperCount ( ) const

Get the number of grippers in this model.

Returns
Size of this->grippers array.
See also
Model::GetGripper()

◆ GetId()

uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.

Referenced by Base::Update().

◆ GetJoint()

JointPtr GetJoint ( const std::string &  name)

Get a joint.

Parameters
nameThe name of the joint, specified in the world file
Returns
Pointer to the joint

◆ GetJointController()

JointControllerPtr GetJointController ( )

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

Returns
A handle to the Controller for the joints in this model.

◆ GetJointCount()

unsigned int GetJointCount ( ) const

Get the number of joints.

Returns
Get the number of joints.

◆ GetJoints()

const Joint_V& GetJoints ( ) const

Get the joints.

Returns
Vector of joints.

◆ GetLink()

LinkPtr 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.

◆ GetLinks()

const 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.

Returns
a vector of Link's in this model

◆ GetName()

std::string GetName ( ) const
inherited

Return the name of the entity.

Returns
Name of the entity.

Referenced by Base::Update().

◆ GetNearestEntityBelow()

void GetNearestEntityBelow ( double &  _distBelow,
std::string &  _entityName 
)
inherited

Get the distance to the nearest entity below (along the Z-axis) this entity.

Parameters
[out]_distBelowThe distance to the nearest entity below.
[out]_entityNameThe name of the nearest entity below.

◆ GetParent()

BasePtr GetParent ( ) const
inherited

Get the parent.

Returns
Pointer to the parent entity.

Referenced by Base::Update().

◆ GetParentId()

int GetParentId ( ) const
inherited

Return the ID of the parent.

Returns
Integer ID.

Referenced by Base::Update().

◆ GetParentModel()

ModelPtr GetParentModel ( )
inherited

Get the parent model, if one exists.

Returns
Pointer to a model, or NULL if no parent model exists.

◆ GetPluginCount()

unsigned int GetPluginCount ( ) const

Get the number of plugins this model has.

Returns
Number of plugins associated with this model.

◆ GetSaveable()

bool GetSaveable ( ) const
inherited

Get whether the object should be "saved", when the user selects to save the world to xml.

Returns
True if the object is saveable.

Referenced by Base::Update().

◆ GetScopedName()

std::string GetScopedName ( bool  _prependWorldName = false) const
inherited

Return the name of this entity with the model scope model1::...::modelN::entityName.

Parameters
[in]_prependWorldNameTrue to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName.
Returns
The scoped name.

Referenced by Base::Update().

◆ GetSDF()

virtual const sdf::ElementPtr GetSDF ( )
overridevirtual

Get the SDF values for the model.

Returns
The SDF value for this model.

Reimplemented from Base.

Reimplemented in Actor.

◆ GetSDFDom()

const sdf::Model* GetSDFDom ( ) const

Get the SDF DOM for the model.

Returns
The SDF DOM for this model.

◆ GetSelfCollide()

virtual bool GetSelfCollide ( ) const
virtual

If true, all links within the model will collide by default.

Two links within the same model will not collide if both have link.self_collide == false. link 1 and link2 collide = link1.self_collide || link2.self_collide Bodies connected by a joint are exempt from this, and will never collide.

Returns
True if self-collide enabled for this model, false otherwise.

Reimplemented in Actor.

◆ GetSensorCount()

unsigned int 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.

◆ GetType()

unsigned int GetType ( ) const
inherited

Get the full type definition.

Returns
The full type definition.

Referenced by Base::Update().

◆ GetWorld()

const WorldPtr& GetWorld ( ) const
inherited

Get the World this object is in.

Returns
The World this object is part of.

Referenced by Base::Update().

◆ GetWorldEnergy()

double GetWorldEnergy ( ) const

Returns this model's total energy, or sum of Model::GetWorldEnergyPotential() and Model::GetWorldEnergyKinetic().

Returns
this link's total energy

◆ GetWorldEnergyKinetic()

double GetWorldEnergyKinetic ( ) const

Returns sum of the kinetic energies of all links in this model.

Computed using link's CoG velocity in the inertial (world) frame.

Returns
this link's kinetic energy

◆ GetWorldEnergyPotential()

double GetWorldEnergyPotential ( ) const

Returns the potential energy of all links and joint springs in the model.

Returns
this link's potential energy,

◆ HasType()

bool HasType ( const EntityType _t) const
inherited

Returns true if this object's type definition has the given type.

Parameters
[in]_tType to check.
Returns
True if this object's type definition has the.

Referenced by Base::Update().

◆ Init()

virtual void Init ( )
overridevirtual

Initialize the model.

Reimplemented from Base.

Reimplemented in Actor, DARTModel, and SimbodyModel.

◆ InitialRelativePose()

ignition::math::Pose3d InitialRelativePose ( ) const
inherited

Get the initial relative pose.

Returns
The initial relative pose.

◆ IsCanonicalLink()

bool IsCanonicalLink ( ) const
inlineinherited

A helper function that checks if this is a canonical body.

Returns
True if the link is canonical.

◆ IsSelected()

bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.

Referenced by Base::Update().

◆ IsStatic()

bool IsStatic ( ) const
inherited

Return whether this entity is static.

Returns
True if static.

◆ Load()

void Load ( sdf::ElementPtr  _sdf)
overridevirtual

Load the model.

Parameters
[in]_sdfSDF parameters to load from.

Reimplemented from Entity.

Reimplemented in SimbodyModel.

◆ LoadJoints()

void LoadJoints ( )

Load all the joints.

◆ LoadPlugins()

void LoadPlugins ( )

Load all plugins.

Load all plugins specified in the SDF for the model.

◆ NestedModel()

ModelPtr NestedModel ( const std::string &  _name) const

Get a nested model that is a direct child of this model.

Parameters
[in]_nameName of the child model to get.
Returns
Pointer to the model, NULL if the name is invalid.

◆ NestedModels()

const Model_V& NestedModels ( ) const

Get all the nested models.

Returns
a vector of Model's in this model

◆ OnPoseChange()

virtual void OnPoseChange ( )
overrideprotectedvirtual

Callback when the pose of the model has been changed.

Implements Entity.

◆ operator==()

bool operator== ( const Base _ent) const
inherited

Returns true if the entities are the same.

Checks only the name.

Parameters
[in]_entBase object to compare with.
Returns
True if the entities are the same.

Referenced by Base::Update().

◆ PlaceOnEntity()

void PlaceOnEntity ( const std::string &  _entityName)
inherited

Move this entity to be ontop of another entity by name.

Parameters
[in]_entityNameName of the Entity this Entity should be ontop of.

◆ PlaceOnNearestEntityBelow()

void PlaceOnNearestEntityBelow ( )
inherited

Move this entity to be ontop of the nearest entity below.

◆ PluginInfo()

void PluginInfo ( const common::URI _pluginUri,
ignition::msgs::Plugin_V &  _plugins,
bool &  _success 
)

Get information about plugins in this model or one of its children, according to the given _pluginUri.

Some accepted URI patterns:

  • Info about a specific model plugin in this model: data://world/<world_name>/model/<this_name>/plugin/<plugin_name>
  • Info about all model plugins in this model (empty plugin name): data://world/<world_name>/model/<this_name>/plugin
  • Info about a model plugin in a nested model: data://world/<world_name>/model/<this_name>/model/ <nested_model_name>/plugin/<plugin_name>
Parameters
[in]_pluginUriURI for the desired plugin(s).
[out]_pluginsMessage containing vector of plugins.
[out]_successTrue if the info was successfully obtained.

◆ Print()

void Print ( const std::string &  _prefix)
inherited

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.

Referenced by Base::Update().

◆ ProcessMsg()

void ProcessMsg ( const msgs::Model &  _msg)

Update parameters from a model message.

Parameters
[in]_msgMessage to process.

◆ RegisterIntrospectionItems()

virtual void RegisterIntrospectionItems ( )
overrideprotectedvirtual

Register items in the introspection service.

Reimplemented from Base.

◆ RelativeAngularAccel()

virtual ignition::math::Vector3d RelativeAngularAccel ( ) const
overridevirtual

Get the angular acceleration of the entity.

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

Reimplemented from Entity.

◆ RelativeAngularVel()

virtual ignition::math::Vector3d RelativeAngularVel ( ) const
overridevirtual

Get the angular velocity of the entity.

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

Reimplemented from Entity.

◆ RelativeLinearAccel()

virtual ignition::math::Vector3d RelativeLinearAccel ( ) const
overridevirtual

Get the linear acceleration of the entity.

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

Reimplemented from Entity.

◆ RelativeLinearVel()

virtual ignition::math::Vector3d RelativeLinearVel ( ) const
overridevirtual

Get the linear velocity of the entity.

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

Reimplemented from Entity.

◆ RelativePose()

ignition::math::Pose3d RelativePose ( ) const
inherited

Get the pose of the entity relative to its parent.

Returns
The pose of the entity relative to its parent.

◆ RemoveChild() [1/4]

virtual void RemoveChild ( EntityPtr  _child)
virtual

Remove a child.

Parameters
[in]_childRemove a child entity.

◆ RemoveChild() [2/4]

virtual void RemoveChild ( unsigned int  _id)
virtualinherited

Remove a child from this entity.

Parameters
[in]_idID of the child to remove.

Referenced by Link::GetKinematic(), and Base::Update().

◆ RemoveChild() [3/4]

void RemoveChild ( const std::string &  _name)
inherited

Remove a child by name.

Parameters
[in]_nameName of the child.

◆ RemoveChild() [4/4]

void RemoveChild ( physics::BasePtr  _child)
inherited

Remove a child by pointer.

Parameters
[in]_childPointer to the child.

◆ RemoveChildren()

void RemoveChildren ( )
inherited

Remove all children.

Referenced by Base::Update().

◆ RemoveJoint()

virtual bool RemoveJoint ( const std::string &  _name)
virtual

Remove a joint for this model.

Parameters
[in]_namename of joint
Returns
true if successful, false if not.

Reimplemented in DARTModel.

◆ Reset() [1/2]

void Reset ( )
overridevirtual

Reset the model.

Reimplemented from Entity.

◆ Reset() [2/2]

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

Calls recursive Reset on one of the Base::EntityType's.

Parameters
[in]_resetTypeThe type of reset operation

◆ ResetPhysicsStates()

void ResetPhysicsStates ( )

Reset the velocity, acceleration, force and torque of all child links.

◆ Scale()

ignition::math::Vector3d Scale ( ) const

Get the scale of model.

Returns
Scale of the model.
See also
void SetScale(const ignition::math::Vector3d &_scale, const bool _publish = false)

◆ SDFPoseRelativeToParent()

ignition::math::Pose3d SDFPoseRelativeToParent ( ) const
inherited

Get the SDF pose of the object according to the sdf 1.6 convention.

This convention is that the pose of an element is relative to its parent XML element, except for joints, whose pose is relative to the child link.

Returns
The pose of the object resolved according to the sdf 1.6 convention

Referenced by Base::Update().

◆ SDFSemanticPose()

std::optional<sdf::SemanticPose> SDFSemanticPose ( ) const
overridevirtual

Get the SDF SemanticPose object associated with the pose of this object.

Objects that support frame semantics need to override this function and provide this function.

Reimplemented from Base.

◆ SensorScopedName()

std::vector<std::string> SensorScopedName ( const std::string &  _name) const

Get scoped sensor name(s) in the model that matches sensor name.

Get the names of sensors in the model where sensor name matches the user provided argument.

Note
A Model does not manage or maintain a pointer to a sensors::Sensor. Access to a Sensor object is accomplished through the sensors::SensorManager. This was done to separate the physics engine from the sensor engine.
Parameters
[in]_nameUnscoped sensor name.
Returns
The scoped name of the sensor(s), or empty list if not found.

◆ SetAngularVel()

void SetAngularVel ( const ignition::math::Vector3d &  _vel)

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

Parameters
[in]_velThe new angular velocity.

◆ SetAnimation() [1/2]

void SetAnimation ( const common::PoseAnimationPtr _anim,
boost::function< void()>  _onComplete 
)
inherited

Set an animation for this entity.

Parameters
[in]_animPose animation.
[in]_onCompleteCallback for when the animation completes.

◆ SetAnimation() [2/2]

void SetAnimation ( common::PoseAnimationPtr  _anim)
inherited

Set an animation for this entity.

Parameters
[in]_animPose animation.

◆ SetAutoDisable()

void 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.

◆ SetCanonicalLink()

void SetCanonicalLink ( bool  _value)
inherited

Set to true if this entity is a canonical link for a model.

Parameters
[in]_valueTrue if the link is canonical.

◆ SetCollideMode()

void 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

◆ SetEnabled()

void SetEnabled ( bool  _enabled)

Enable all the links in all the models.

Parameters
[in]_enabledTrue to enable all the links.

◆ SetGravityMode()

void SetGravityMode ( const bool &  _value)

Set the gravity mode of the model.

Parameters
[in]_valueTrue to enable gravity.

◆ SetInitialRelativePose()

void SetInitialRelativePose ( const ignition::math::Pose3d &  _pose)
inherited

Set the initial pose.

Parameters
[in]_poseThe initial pose.

◆ SetJointAnimation()

void SetJointAnimation ( const std::map< std::string, common::NumericAnimationPtr > &  _anims,
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.

◆ SetJointPosition()

void SetJointPosition ( const std::string &  _jointName,
double  _position,
int  _index = 0 
)

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.

◆ SetJointPositions()

void 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.

◆ SetLaserRetro()

void SetLaserRetro ( const float  _retro)

Set the laser retro reflectiveness of the model.

Parameters
[in]_retroRetro reflectance value.

◆ SetLinearVel()

void SetLinearVel ( const ignition::math::Vector3d &  _vel)

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

Parameters
[in]_velThe new linear velocity.

◆ SetLinkWorldPose() [1/2]

void SetLinkWorldPose ( const ignition::math::Pose3d &  _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.

◆ SetLinkWorldPose() [2/2]

void SetLinkWorldPose ( const ignition::math::Pose3d &  _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.

◆ SetName()

virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameThe new name.

Reimplemented from Base.

◆ SetParent()

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.

Referenced by Base::Update().

◆ SetRelativePose()

void SetRelativePose ( const ignition::math::Pose3d &  _pose,
const bool  _notify = true,
const bool  _publish = true 
)
inherited

Set the pose of the entity relative to its parent.

Parameters
[in]_poseThe new pose.
[in]_notifyTrue = tell children of the pose change.
[in]_publishTrue to publish the pose.

◆ SetSaveable()

void SetSaveable ( bool  _v)
inherited

Set whether the object should be "saved", when the user selects to save the world to xml.

Parameters
[in]_vSet to True if the object should be saved.

Referenced by Base::Update().

◆ SetScale()

void SetScale ( const ignition::math::Vector3d &  _scale,
const bool  _publish = false 
)

Set the scale of model.

Parameters
[in]_scaleScale to set the model to.
[in]_publishTrue to publish a message for the client with the new scale.
See also
ignition::math::Vector3d Scale() const

◆ SetSelected()

virtual bool SetSelected ( bool  _show)
virtualinherited

Set whether this entity has been selected by the user through the gui.

Parameters
[in]_showTrue to set this entity as selected.

Reimplemented in Link.

Referenced by Base::Update().

◆ SetSelfCollide()

virtual void SetSelfCollide ( bool  _self_collide)
virtual

Set this model's self_collide property.

See also
GetSelfCollide
Parameters
[in]_self_collideTrue if self-collisions enabled by default.

Reimplemented in Actor.

◆ SetState()

void SetState ( const ModelState _state)

Set the current model state.

Parameters
[in]_stateState to set the model to.

◆ SetStatic()

void SetStatic ( const bool &  _static)
inherited

Set whether this entity is static: immovable.

Parameters
[in]_staticTrue = static.

Referenced by Link::UpdateSurface().

◆ SetWindMode()

virtual void SetWindMode ( const bool  _mode)
virtual

Set whether wind affects this body.

Parameters
[in]_modeTrue to enable wind.

Reimplemented in Actor.

◆ SetWorld()

void SetWorld ( const WorldPtr _newWorld)
inherited

Set the world this object belongs to.

This will also set the world for all children.

Parameters
[in]_newWorldThe new World this object is part of.

Referenced by Base::Update().

◆ SetWorldPose()

void SetWorldPose ( const ignition::math::Pose3d &  _pose,
const bool  _notify = true,
const bool  _publish = true 
)
inherited

Set the world pose of the entity.

Parameters
[in]_poseThe new world pose.
[in]_notifyTrue = tell children of the pose change.
[in]_publishTrue to publish the pose.

◆ SetWorldTwist()

void SetWorldTwist ( const ignition::math::Vector3d &  _linear,
const ignition::math::Vector3d &  _angular,
const bool  _updateChildren = true 
)
inherited

Set angular and linear rates of an physics::Entity.

Parameters
[in]_linearLinear twist.
[in]_angularAngular twist.
[in]_updateChildrenTrue to pass this update to child entities.

◆ shared_from_this()

boost::shared_ptr<Model> shared_from_this ( )

Allow Model class to share itself as a boost shared_ptr.

Returns
a shared pointer to itself

◆ StopAnimation()

virtual void StopAnimation ( )
overridevirtual

Stop the current animations.

Reimplemented from Entity.

◆ TypeStr()

std::string TypeStr ( ) const
inherited

Get the string name for the entity type.

Returns
The string name for this entity.

Referenced by Base::Update().

◆ UnregisterIntrospectionItems()

virtual void UnregisterIntrospectionItems ( )
protectedvirtualinherited

Unregister items in the introspection service.

Referenced by Base::Update().

◆ UnscaledSDF()

virtual const sdf::ElementPtr UnscaledSDF ( )
virtual

◆ Update()

void Update ( )
overridevirtual

Update the model.

Reimplemented from Base.

◆ UpdateParameters()

virtual void UpdateParameters ( sdf::ElementPtr  _sdf)
overridevirtual

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from Entity.

Reimplemented in Actor.

◆ URI()

common::URI URI ( ) const
inherited

Return the common::URI of this entity.

The URI includes the world where the entity is contained and all the hierarchy of sub-entities that can compose this entity. E.g.: A link entity contains the name of the link and the model where the link is contained.

Returns
The URI of this entity.

Referenced by Base::Update().

◆ WindMode()

virtual bool WindMode ( ) const
virtual

Get the wind mode.

Returns
True if wind is enabled.

Reimplemented in Actor.

◆ WorldAngularAccel()

virtual ignition::math::Vector3d WorldAngularAccel ( ) const
overridevirtual

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

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

Reimplemented from Entity.

◆ WorldAngularVel()

virtual ignition::math::Vector3d WorldAngularVel ( ) const
overridevirtual

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

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

Reimplemented from Entity.

◆ WorldLinearAccel()

virtual ignition::math::Vector3d WorldLinearAccel ( ) const
overridevirtual

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

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

Reimplemented from Entity.

◆ WorldLinearVel()

virtual ignition::math::Vector3d WorldLinearVel ( ) const
overridevirtual

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

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

Reimplemented from Entity.

◆ WorldPose()

virtual const ignition::math::Pose3d& WorldPose ( ) const
inlinevirtualinherited

Get the absolute pose of the entity.

Returns
The absolute pose of the entity.

Reimplemented in Collision, and Light.

Member Data Documentation

◆ animation

common::PoseAnimationPtr animation
protectedinherited

Current pose animation.

◆ animationConnection

event::ConnectionPtr animationConnection
protectedinherited

Connection used to update an animation.

◆ animationStartPose

ignition::math::Pose3d animationStartPose
protectedinherited

Start pose of an animation.

◆ attachedModels

std::vector<ModelPtr> attachedModels
protected

◆ attachedModelsOffset

std::vector<ignition::math::Pose3d> attachedModelsOffset
protected

◆ children

Base_V children
protectedinherited

Children of this entity.

◆ connections

std::vector<event::ConnectionPtr> connections
protectedinherited

All our event connections.

◆ dirtyPose

ignition::math::Pose3d dirtyPose
protectedinherited

The pose set by a physics engine.

◆ introspectionItems

std::vector<common::URI> introspectionItems
protectedinherited

All the introspection items regsitered for this.

◆ jointPub

transport::PublisherPtr jointPub
protected

Publisher for joint info.

◆ node

transport::NodePtr node
protectedinherited

Communication node.

◆ nodeIgn

ignition::transport::Node nodeIgn
protectedinherited

Ignition communication node.

◆ parent

BasePtr parent
protectedinherited

Parent of this entity.

◆ parentEntity

EntityPtr parentEntity
protectedinherited

A helper that prevents numerous dynamic_casts.

◆ prevAnimationTime

common::Time prevAnimationTime
protectedinherited

Previous time an animation was updated.

◆ requestPub

transport::PublisherPtr requestPub
protectedinherited

Request publisher.

◆ requestPubIgn

ignition::transport::Node::Publisher requestPubIgn
protectedinherited

Request publisher.

◆ scale

ignition::math::Vector3d scale
protectedinherited

Scale of the entity.

◆ sdf

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

◆ visPub

transport::PublisherPtr visPub
protectedinherited

Visual publisher.

◆ visPubIgn

ignition::transport::Node::Publisher visPubIgn
protectedinherited

Visual publisher.

◆ visualMsg

msgs::Visual* visualMsg
protectedinherited

Visual message container.

◆ world

WorldPtr world
protectedinherited

Pointer to the world.

◆ worldPose

ignition::math::Pose3d worldPose
mutableprotectedinherited

World pose of the entity.


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