DART model class. More...
#include <DARTModel.hh>
Inherits Model.
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 | |
DARTModel (BasePtr _parent) | |
Constructor. More... | |
virtual | ~DARTModel () |
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... | |
void | BackupState () |
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 JointPtr | CreateJoint (const std::string &_name, const std::string &_type, physics::LinkPtr _parent, physics::LinkPtr _child) |
Create a joint for this model. More... | |
virtual 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... | |
dart::dynamics::SkeletonPtr | DARTSkeleton () |
Get pointer to DART Skeleton. More... | |
dart::simulation::WorldPtr | DARTWorld (void) const |
Get pointer to DART World. 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 () |
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... | |
DARTPhysicsPtr | GetDARTPhysics (void) const |
Get pointer to DART Physics. 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_V & | GetJoints () const |
Get the joints. More... | |
LinkPtr | GetLink (const std::string &_name="canonical") const |
Get a link by name. More... | |
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. 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 WorldPtr & | GetWorld () 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 () |
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... | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the entity. 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_V & | NestedModels () 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... | |
void | RestoreState () |
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< Model > | shared_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 () |
virtual void | Update () |
Update the object. 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< ModelPtr > | attachedModels |
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::ConnectionPtr > | connections |
All our event connections. More... | |
ignition::math::Pose3d | dirtyPose |
The pose set by a physics engine. More... | |
std::vector< common::URI > | introspectionItems |
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... | |
DART model class.
|
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. |
|
virtual |
Destructor.
|
inherited |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
Referenced by Base::Update().
|
inherited |
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 BackupState | ( | ) |
|
overridevirtualinherited |
|
inherited |
Returns collision bounding box.
|
protectedinherited |
Compute the scoped name of this object based on its parents.
Referenced by Base::Update().
|
virtual |
Create a joint for this model.
[in] | _name | name of joint |
[in] | _type | type of joint |
[in] | _parent | parent link of joint |
[in] | _child | child link of joint |
common::Exception | When _type is not recognized |
Reimplemented from Model.
|
virtual |
Create a joint for this model.
[in] | _sdf | SDF parameters for <joint> |
common::Exception | When _type is not recognized |
Reimplemented from Model.
|
inherited |
Create a new link for this model.
[in] | _name | name of the new link |
dart::dynamics::SkeletonPtr DARTSkeleton | ( | ) |
Get pointer to DART Skeleton.
dart::simulation::WorldPtr DARTWorld | ( | void | ) | const |
|
inherited |
Detach a static model from this model.
[in] | _model | Name of an attached static model to remove. |
|
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.
|
virtualinherited |
Fill a model message.
[in] | _msg | Message to fill using this model's data. |
|
virtual |
Finalize the model.
Reimplemented from Model.
|
inherited |
Return the value of the SDF <allow_auto_disable> element.
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
Referenced by Base::Update().
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
Referenced by Base::Update().
|
inherited |
Get a child by name.
[in] | _name | Name of the child. |
|
inherited |
Get a child collision entity, if one exists.
[in] | _name | Name of the child collision object. |
|
inherited |
|
inherited |
DARTPhysicsPtr GetDARTPhysics | ( | void | ) | const |
Get pointer to DART Physics.
|
inherited |
Get a gripper based on an index.
|
inherited |
Get the number of grippers in this model.
|
inherited |
|
inherited |
Get a joint.
name | The name of the joint, specified in the world file |
|
inherited |
Get a handle to the Controller for the joints in this model.
|
inherited |
Get the number of joints.
|
inherited |
Get the joints.
|
inherited |
Get a link by name.
[in] | _name | Name of the link to get. |
|
inherited |
|
inherited |
|
inherited |
Get the distance to the nearest entity below (along the Z-axis) this entity.
[out] | _distBelow | The distance to the nearest entity below. |
[out] | _entityName | The name of the nearest entity below. |
|
inherited |
|
inherited |
|
inherited |
Get the parent model, if one exists.
|
inherited |
Get the number of plugins this model has.
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
Referenced by Base::Update().
|
inherited |
Return the name of this entity with the model scope model1::...::modelN::entityName.
[in] | _prependWorldName | True to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName. |
Referenced by Base::Update().
|
overridevirtualinherited |
|
inherited |
Get the SDF DOM for the model.
|
virtualinherited |
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.
Reimplemented in Actor.
|
inherited |
Get the number of sensors attached to this model.
This will count all the sensors attached to all the links.
|
inherited |
|
inherited |
Get the World this object is in.
Referenced by Base::Update().
|
inherited |
Returns this model's total energy, or sum of Model::GetWorldEnergyPotential() and Model::GetWorldEnergyKinetic().
|
inherited |
Returns sum of the kinetic energies of all links in this model.
Computed using link's CoG velocity in the inertial (world) frame.
|
inherited |
Returns the potential energy of all links and joint springs in the model.
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
Referenced by Base::Update().
|
virtual |
Initialize the model.
Reimplemented from Model.
|
inherited |
Get the initial relative pose.
|
inlineinherited |
A helper function that checks if this is a canonical body.
|
inherited |
True if the entity is selected by the user.
Referenced by Base::Update().
|
inherited |
Return whether this entity is static.
|
virtual |
|
inherited |
Load all the joints.
|
inherited |
Load all plugins.
Load all plugins specified in the SDF for the model.
|
inherited |
Get a nested model that is a direct child of this model.
[in] | _name | Name of the child model to get. |
|
inherited |
Get all the nested models.
|
overrideprotectedvirtualinherited |
Callback when the pose of the model has been changed.
Implements Entity.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
Referenced by Base::Update().
|
inherited |
|
inherited |
Move this entity to be ontop of the nearest entity below.
|
inherited |
Get information about plugins in this model or one of its children, according to the given _pluginUri.
Some accepted URI patterns:
[in] | _pluginUri | URI for the desired plugin(s). |
[out] | _plugins | Message containing vector of plugins. |
[out] | _success | True if the info was successfully obtained. |
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
Referenced by Base::Update().
|
inherited |
Update parameters from a model message.
[in] | _msg | Message to process. |
|
overrideprotectedvirtualinherited |
Register items in the introspection service.
Reimplemented from Base.
|
overridevirtualinherited |
Get the angular acceleration of the entity.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the angular velocity of the entity.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the linear acceleration of the entity.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the linear velocity of the entity.
Reimplemented from Entity.
|
inherited |
Get the pose of the entity relative to its parent.
|
virtualinherited |
Remove a child.
[in] | _child | Remove a child entity. |
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
Referenced by Link::GetKinematic(), and Base::Update().
|
inherited |
Remove a child by name.
[in] | _name | Name of the child. |
|
inherited |
Remove a child by pointer.
[in] | _child | Pointer to the child. |
|
inherited |
Remove all children.
Referenced by Base::Update().
|
virtual |
Remove a joint for this model.
[in] | _name | name of joint |
Reimplemented from Model.
|
overridevirtualinherited |
Reset the model.
Reimplemented from Entity.
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
inherited |
Reset the velocity, acceleration, force and torque of all child links.
void RestoreState | ( | ) |
|
inherited |
Get the scale of model.
|
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.
Referenced by Base::Update().
|
overridevirtualinherited |
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.
|
inherited |
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.
[in] | _name | Unscoped sensor name. |
|
inherited |
Set the angular velocity of the model, and all its links.
[in] | _vel | The new angular velocity. |
|
inherited |
Set an animation for this entity.
[in] | _anim | Pose animation. |
[in] | _onComplete | Callback for when the animation completes. |
|
inherited |
Set an animation for this entity.
[in] | _anim | Pose animation. |
|
inherited |
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. |
|
inherited |
Set to true if this entity is a canonical link for a model.
[in] | _value | True if the link is canonical. |
|
inherited |
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 |
|
inherited |
Enable all the links in all the models.
[in] | _enabled | True to enable all the links. |
|
inherited |
Set the gravity mode of the model.
[in] | _value | True to enable gravity. |
|
inherited |
Set the initial pose.
[in] | _pose | The initial pose. |
|
inherited |
Joint Animation.
[in] | _anim | Map of joint names to their position animation. |
[in] | _onComplete | Callback function for when the animation completes. |
|
inherited |
Set the positions of a Joint by name.
[in] | _jointName | Name of the joint to set. |
[in] | _position | Position to set the joint to. |
|
inherited |
Set the positions of a set of joints.
[in] | _jointPositions | Map of joint names to their positions. |
|
inherited |
Set the laser retro reflectiveness of the model.
[in] | _retro | Retro reflectance value. |
|
inherited |
Set the linear velocity of the model, and all its links.
[in] | _vel | The new linear velocity. |
|
inherited |
|
inherited |
|
virtualinherited |
|
inherited |
|
inherited |
Set the pose of the entity relative to its parent.
[in] | _pose | The new pose. |
[in] | _notify | True = tell children of the pose change. |
[in] | _publish | True to publish the pose. |
|
inherited |
Set whether the object should be "saved", when the user selects to save the world to xml.
[in] | _v | Set to True if the object should be saved. |
Referenced by Base::Update().
|
inherited |
Set the scale of model.
[in] | _scale | Scale to set the model to. |
[in] | _publish | True to publish a message for the client with the new scale. |
|
virtualinherited |
Set whether this entity has been selected by the user through the gui.
[in] | _show | True to set this entity as selected. |
Reimplemented in Link.
Referenced by Base::Update().
|
virtualinherited |
Set this model's self_collide property.
[in] | _self_collide | True if self-collisions enabled by default. |
Reimplemented in Actor.
|
inherited |
Set the current model state.
[in] | _state | State to set the model to. |
|
inherited |
Set whether this entity is static: immovable.
[in] | _static | True = static. |
Referenced by Link::UpdateSurface().
|
virtualinherited |
Set whether wind affects this body.
[in] | _mode | True to enable wind. |
Reimplemented in Actor.
|
inherited |
Set the world this object belongs to.
This will also set the world for all children.
[in] | _newWorld | The new World this object is part of. |
Referenced by Base::Update().
|
inherited |
Set the world pose of the entity.
[in] | _pose | The new world pose. |
[in] | _notify | True = tell children of the pose change. |
[in] | _publish | True to publish the pose. |
|
inherited |
Set angular and linear rates of an physics::Entity.
[in] | _linear | Linear twist. |
[in] | _angular | Angular twist. |
[in] | _updateChildren | True to pass this update to child entities. |
|
inherited |
Allow Model class to share itself as a boost shared_ptr.
|
overridevirtualinherited |
Stop the current animations.
Reimplemented from Entity.
|
inherited |
Get the string name for the entity type.
Referenced by Base::Update().
|
protectedvirtualinherited |
Unregister items in the introspection service.
Referenced by Base::Update().
|
virtualinherited |
|
virtual |
Update the object.
Reimplemented from Base.
|
overridevirtualinherited |
|
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.
Referenced by Base::Update().
|
virtualinherited |
|
overridevirtualinherited |
Get the angular acceleration of the entity in the world frame.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the angular velocity of the entity in the world frame.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the linear acceleration of the entity in the world frame.
Reimplemented from Entity.
|
overridevirtualinherited |
Get the linear velocity of the entity in the world frame.
Reimplemented from Entity.
|
inlinevirtualinherited |
|
protectedinherited |
Current pose animation.
|
protectedinherited |
Connection used to update an animation.
|
protectedinherited |
Start pose of an animation.
|
protectedinherited |
used by Model::AttachStaticModel
|
protectedinherited |
used by Model::AttachStaticModel
|
protectedinherited |
Children of this entity.
|
protectedinherited |
All our event connections.
|
protectedinherited |
The pose set by a physics engine.
|
protectedinherited |
All the introspection items regsitered for this.
|
protectedinherited |
Publisher for joint info.
|
protectedinherited |
Communication node.
|
protectedinherited |
Ignition communication node.
|
protectedinherited |
Parent of this entity.
|
protectedinherited |
A helper that prevents numerous dynamic_casts.
|
protectedinherited |
Previous time an animation was updated.
|
protectedinherited |
Request publisher.
|
protectedinherited |
Request publisher.
|
protectedinherited |
Scale of the entity.
|
protectedinherited |
The SDF values for this object.
|
protectedinherited |
Visual publisher.
|
protectedinherited |
Visual publisher.
|
protectedinherited |
Visual message container.
|
protectedinherited |
Pointer to the world.
|
mutableprotectedinherited |
World pose of the entity.