#include <DARTLink.hh>
Inherits Link.
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 | |
DARTLink (EntityPtr _parent) | |
Constructor. More... | |
virtual | ~DARTLink () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddChildJoint (JointPtr _joint) |
Joints that have this Link as a parent Link. More... | |
void | AddDARTChildJoint (DARTJointPtr _dartChildJoint) |
Set child joint of this link. More... | |
virtual void | AddForce (const ignition::math::Vector3d &_force) |
Add a force to the body. More... | |
virtual void | AddForceAtRelativePosition (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_relpos) |
Add a force (in world frame coordinates) to the body at a position relative to the center of mass which is expressed in the link's own frame of reference. More... | |
virtual void | AddForceAtWorldPosition (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_pos) |
Add a force to the body using a global position. More... | |
virtual void | AddLinkForce (const ignition::math::Vector3d &_force, const ignition::math::Vector3d &_offset=ignition::math::Vector3d::Zero) |
Add a force expressed in the link frame. More... | |
void | AddParentJoint (JointPtr _joint) |
Joints that have this Link as a child Link. More... | |
virtual void | AddRelativeForce (const ignition::math::Vector3d &_force) |
Add a force to the body, components are relative to the body's own frame of reference. More... | |
virtual void | AddRelativeTorque (const ignition::math::Vector3d &_torque) |
Add a torque to the body, components are relative to the body's own frame of reference. More... | |
void | AddSlaveBodyNode (dart::dynamics::BodyNode *_dtBodyNode) |
Add pointer to a BodyNode representing a fragment of this link. More... | |
virtual void | AddTorque (const ignition::math::Vector3d &_torque) |
Add a torque to the body. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
void | AttachStaticModel (ModelPtr &_model, const ignition::math::Pose3d &_offset) |
Attach a static model to this link. More... | |
common::BatteryPtr | Battery (const std::string &_name) const |
Get a battery by name. More... | |
common::BatteryPtr | Battery (const size_t _index) const |
Get a battery based on an index. More... | |
size_t | BatteryCount () const |
Get the number of batteries in this link. More... | |
virtual ignition::math::Box | BoundingBox () const |
Get the bounding box for the link and all the child elements. More... | |
ignition::math::Box | CollisionBoundingBox () const |
Returns collision bounding box. More... | |
event::ConnectionPtr | ConnectEnabled (std::function< void(bool)> _subscriber) |
Connect to the add entity signal. More... | |
dart::dynamics::BodyNode * | DARTBodyNode () const |
Get pointer to DART BodyNode associated with this link. More... | |
DARTBodyNodePropPtr | DARTProperties () const |
Get DART BodyNode properties. More... | |
dart::simulation::WorldPtr | DARTWorld (void) const |
Get pointer to DART World associated with this link. More... | |
void | DetachAllStaticModels () |
Detach all static models from this link. More... | |
void | DetachStaticModel (const std::string &_modelName) |
Detach a static model from this link. More... | |
const ignition::math::Pose3d & | DirtyPose () const |
Returns Entity::dirtyPose. More... | |
void | FillMsg (msgs::Link &_msg) |
Fill a link message. More... | |
bool | FindAllConnectedLinksHelper (const LinkPtr &_originalParentLink, Link_V &_connectedLinks, bool _fistLink=false) |
Helper function to find all connected links of a link based on parent/child relations of joints. More... | |
virtual void | Fini () |
Finalize the entity. More... | |
double | GetAngularDamping () const |
Get the angular damping factor. 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... | |
Joint_V | GetChildJoints () const |
Get the child joints. More... | |
Link_V | GetChildJointsLinks () const |
Returns a vector of children Links connected by joints. More... | |
LinkPtr | GetChildLink (const std::string &_name) |
Get a child linke entity, if one exists. More... | |
CollisionPtr | GetCollision (const std::string &_name) |
Get a child collision by name. More... | |
CollisionPtr | GetCollision (unsigned int _index) const |
Get a child collision by index. More... | |
Collision_V | GetCollisions () const |
Get all the child collisions. More... | |
DARTModelPtr | GetDARTModel () const |
Get pointer to DART Model associated with this link. More... | |
DARTPhysicsPtr | GetDARTPhysics (void) const |
Get pointer to DART Physics engine associated with this link. More... | |
virtual bool | GetEnabled () const |
Get whether this body is enabled in the physics engine. More... | |
virtual bool | GetGravityMode () const |
Get the gravity mode. More... | |
uint32_t | GetId () const |
Return the ID of this entity. More... | |
InertialPtr | GetInertial () const |
Get the inertia of the link. More... | |
virtual bool | GetKinematic () const |
Implement this function. More... | |
double | GetLinearDamping () const |
Get the linear damping factor. More... | |
ModelPtr | GetModel () const |
Get the model that this body belongs to. 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... | |
Joint_V | GetParentJoints () const |
Get the parent joints. More... | |
Link_V | GetParentJointsLinks () const |
Returns a vector of parent Links connected by joints. More... | |
ModelPtr | GetParentModel () |
Get the parent model, if one exists. 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 () |
Get the SDF values for the object. More... | |
bool | GetSelfCollide () const |
Get Self-Collision Flag. More... | |
unsigned int | GetSensorCount () const |
Get sensor count. More... | |
std::string | GetSensorName (unsigned int _index) const |
Get sensor name. More... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
msgs::Visual | GetVisualMessage (const std::string &_name) const |
Returns the visual message specified by its name. More... | |
const WorldPtr & | GetWorld () const |
Get the World this object is in. More... | |
double | GetWorldEnergy () const |
Returns this link's total energy, or sum of Link::GetWorldEnergyPotential() and Link::GetWorldEnergyKinetic(). More... | |
double | GetWorldEnergyKinetic () const |
Returns this link's kinetic energy computed using link's CoG velocity in the inertial (world) frame. More... | |
double | GetWorldEnergyPotential () const |
Returns this link's potential energy, based on position in world frame and gravity. 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 body. 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 | IsSoftBody () const |
Get whether this link is soft body. More... | |
bool | IsStatic () const |
Return whether this entity is static. More... | |
virtual void | Load (sdf::ElementPtr _ptr) |
Load the body based on an SDF element. More... | |
void | MoveFrame (const ignition::math::Pose3d &_worldReferenceFrameSrc, const ignition::math::Pose3d &_worldReferenceFrameDst, const bool _preserveWorldVelocity=false) |
Move Link given source and target frames specified in world coordinates. More... | |
virtual void | OnPoseChange () |
This function is called when the entity's (or one of its parents) pose of the parent has changed. 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 | Print (const std::string &_prefix) |
Print this object to screen via gzmsg. More... | |
void | ProcessMsg (const msgs::Link &_msg) |
Update parameters from a message. More... | |
ignition::math::Vector3d | RelativeAngularAccel () const |
Get the angular acceleration of the body. More... | |
ignition::math::Vector3d | RelativeAngularVel () const |
Get the angular velocity of the body. More... | |
ignition::math::Vector3d | RelativeForce () const |
Get the force applied to the body. More... | |
ignition::math::Vector3d | RelativeLinearAccel () const |
Get the linear acceleration of the body. More... | |
ignition::math::Vector3d | RelativeLinearVel () const |
Get the linear velocity of the body. More... | |
ignition::math::Pose3d | RelativePose () const |
Get the pose of the entity relative to its parent. More... | |
ignition::math::Vector3d | RelativeTorque () const |
Get the torque applied to the body. More... | |
const ignition::math::Vector3d | RelativeWindLinearVel () const |
Returns this link's wind velocity. 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... | |
virtual void | RemoveChild (EntityPtr _child) |
void | RemoveChildJoint (const std::string &_jointName) |
Remove Joints that have this Link as a parent Link. More... | |
void | RemoveChildren () |
Remove all children. More... | |
void | RemoveCollision (const std::string &_name) |
Remove a collision from the link. More... | |
void | RemoveParentJoint (const std::string &_jointName) |
Remove Joints that have this Link as a child Link. More... | |
void | Reset () |
Reset the link. 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 link. More... | |
void | SetAngularAccel (const ignition::math::Vector3d &_accel) GAZEBO_DEPRECATED(9.0) |
Set the angular acceleration of the body. More... | |
virtual void | SetAngularDamping (double _damping) |
Set the angular damping factor. More... | |
virtual void | SetAngularVel (const ignition::math::Vector3d &_vel) |
Set the angular velocity of the body. 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... | |
virtual void | SetAutoDisable (bool _disable) |
Allow the link to 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) |
Set the collide mode of the body. More... | |
void | SetDARTBodyNode (dart::dynamics::BodyNode *_dtBodyNode) |
Set pointer to DART BodyNode associated with this link. More... | |
void | SetDARTParentJoint (DARTJointPtr _dartParentJoint) |
Set parent joint of this link. More... | |
virtual void | SetEnabled (bool _enable) const |
Set whether this body is enabled. More... | |
virtual void | SetForce (const ignition::math::Vector3d &_force) |
Set the force applied to the body. More... | |
virtual void | SetGravityMode (bool _mode) |
Set whether gravity affects this body. More... | |
void | SetInertial (const InertialPtr &_inertial) |
Set the mass of the link. More... | |
void | SetInitialRelativePose (const ignition::math::Pose3d &_pose) |
Set the initial pose. More... | |
virtual void | SetKinematic (const bool &_state) |
Implement this function. More... | |
void | SetLaserRetro (float _retro) |
Set the laser retro reflectiveness. More... | |
void | SetLinearAccel (const ignition::math::Vector3d &_accel) GAZEBO_DEPRECATED(9.0) |
Set the linear acceleration of the body. More... | |
virtual void | SetLinearDamping (double _damping) |
Set the linear damping factor. More... | |
virtual void | SetLinearVel (const ignition::math::Vector3d &_vel) |
Set the linear velocity of the body. More... | |
virtual void | SetLinkStatic (bool _static) |
Freeze link to ground (inertial frame). More... | |
virtual void | SetName (const std::string &_name) |
Set the name of the entity. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
void | SetPublishData (bool _enable) |
Enable/Disable link data publishing. 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) |
Set the scale of the link. More... | |
virtual bool | SetSelected (bool _set) |
Set whether this entity has been selected by the user through the gui. More... | |
virtual void | SetSelfCollide (bool _collide) |
Set whether this body will collide with others in the model. More... | |
void | SetState (const LinkState &_state) |
Set the current link state. More... | |
virtual void | SetStatic (const bool &_static) |
virtual void | SetTorque (const ignition::math::Vector3d &_torque) |
Set the torque applied to the body. More... | |
bool | SetVisualPose (const uint32_t _id, const ignition::math::Pose3d &_pose) |
Set the pose of a visual. More... | |
void | SetWindEnabled (const bool _enable) |
Enable/disable wind for this link. 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... | |
virtual void | StopAnimation () |
Stop the current animation, if any. More... | |
std::string | TypeStr () const |
Get the string name for the entity type. More... | |
void | Update (const common::UpdateInfo &_info) |
Update the collision. More... | |
virtual void | Update () |
Update the object. More... | |
void | updateDirtyPoseFromDARTTransformation () |
Store DART Transformation to Entity::dirtyPose and add this link to World::dirtyPoses so that World::Update() trigger Entity::SetWorldPose() for this link. More... | |
virtual void | UpdateMass () |
Update the mass matrix. More... | |
virtual void | UpdateParameters (sdf::ElementPtr _sdf) |
Update the parameters using new sdf values. More... | |
virtual void | UpdateSurface () |
Update surface parameters. More... | |
void | UpdateWind (const common::UpdateInfo &_info) |
Update the wind. More... | |
common::URI | URI () const |
Return the common::URI of this entity. More... | |
bool | VisualId (const std::string &_visName, uint32_t &_visualId) const |
Get the unique ID of a visual. More... | |
bool | VisualPose (const uint32_t _id, ignition::math::Pose3d &_pose) const |
Get the pose of a visual. More... | |
virtual bool | WindMode () const |
Get the wind mode. More... | |
ignition::math::Vector3d | WorldAngularAccel () const |
Get the angular acceleration of the body in the world frame, which is computed as (I^-1 * (T - w x L)), where I: inertia matrix in world frame T: sum of external torques in world frame L: angular momentum of CoG in world frame w: angular velocity in world frame. More... | |
ignition::math::Vector3d | WorldAngularMomentum () const |
Get the angular momentum of the body CoG in the world frame, which is computed as (I * w), where I: inertia matrix in world frame w: angular velocity in world frame. More... | |
virtual ignition::math::Vector3d | WorldAngularVel () const |
Get the angular velocity of the entity in the world frame. More... | |
virtual ignition::math::Vector3d | WorldCoGLinearVel () const |
Get the linear velocity at the body's center of gravity in the world frame. More... | |
ignition::math::Pose3d | WorldCoGPose () const |
Get the pose of the body's center of gravity in the world coordinate frame. More... | |
virtual ignition::math::Vector3d | WorldForce () const |
Get the force applied to the body in the world frame. More... | |
ignition::math::Pose3d | WorldInertialPose () const |
Get the world pose of the link inertia (cog position and Moment of Inertia frame). More... | |
ignition::math::Matrix3d | WorldInertiaMatrix () const |
Get the inertia matrix in the world frame. More... | |
ignition::math::Vector3d | WorldLinearAccel () const |
Get the linear acceleration of the body in the world frame. More... | |
virtual ignition::math::Vector3d | WorldLinearVel (const ignition::math::Vector3d &_offset=ignition::math::Vector3d::Zero) const |
Get the linear velocity of a point on the body in the world frame, using an offset expressed in a body-fixed frame. More... | |
virtual ignition::math::Vector3d | WorldLinearVel (const ignition::math::Vector3d &_offset, const ignition::math::Quaterniond &_q) const |
Get the linear velocity of a point on the body in the world frame, using an offset expressed in an arbitrary frame. More... | |
virtual ignition::math::Vector3d | WorldLinearVel () const |
Get the linear velocity of the origin of the link frame, expressed in the world frame. More... | |
virtual const ignition::math::Pose3d & | WorldPose () const |
Get the absolute pose of the entity. More... | |
virtual ignition::math::Vector3d | WorldTorque () const |
Get the torque applied to the body about the center of mass in world frame coordinates. More... | |
const ignition::math::Vector3d | WorldWindLinearVel () const |
Returns this link's wind velocity in the world coordinate frame. More... | |
Protected Types | |
typedef std::map< uint32_t, msgs::Visual > | Visuals_M |
Protected Member Functions | |
void | ComputeScopedName () |
Compute the scoped name of this object based on its parents. More... | |
virtual void | RegisterIntrospectionItems () |
Register items in the introspection service. More... | |
virtual void | UnregisterIntrospectionItems () |
Unregister items in the introspection service. More... | |
Protected Attributes | |
ignition::math::Vector3d | angularAccel |
Angular acceleration. More... | |
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 < ignition::math::Pose3d > | attachedModelsOffset |
Offsets for the attached models. 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... | |
InertialPtr | inertial |
Inertial properties. More... | |
bool | initialized = false |
This flag is set to true when the link is initialized. More... | |
std::vector< common::URI > | introspectionItems |
All the introspection items regsitered for this. More... | |
ignition::math::Vector3d | linearAccel |
Linear acceleration. 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... | |
Visuals_M | visuals |
Link visual elements. More... | |
WorldPtr | world |
Pointer to the world. More... | |
ignition::math::Pose3d | worldPose |
World pose of the entity. More... | |
DART Link class.
|
protectedinherited |
|
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 |
Add a child to this entity.
[in] | _child | Child entity. |
|
inherited |
void AddDARTChildJoint | ( | DARTJointPtr | _dartChildJoint | ) |
Set child joint of this link.
[in] | _dartChildJoint | Pointer to the child joint. |
|
virtual |
|
virtual |
Add a force (in world frame coordinates) to the body at a position relative to the center of mass which is expressed in the link's own frame of reference.
[in] | _force | Force to add. The force must be expressed in the world reference frame. |
[in] | _relPos | Position on the link to add the force. This position must be expressed in the link's coordinates with respect to the link's center of mass. |
Implements Link.
|
virtual |
Add a force to the body using a global position.
[in] | _force | Force to add. |
[in] | _pos | Position in global coord frame to add the force. |
Implements Link.
|
virtual |
Add a force expressed in the link frame.
[in] | _force | Force to add. The force must be expressed in the link-fixed reference frame. |
[in] | _offset | Offset position expressed in coordinates of the link frame with respect to the link frame's origin. It defaults to the link origin. |
Implements Link.
|
inherited |
|
virtual |
Add a force to the body, components are relative to the body's own frame of reference.
[in] | _force | Force to add. |
Implements Link.
|
virtual |
Add a torque to the body, components are relative to the body's own frame of reference.
[in] | _torque | Torque value to add. |
Implements Link.
void AddSlaveBodyNode | ( | dart::dynamics::BodyNode * | _dtBodyNode | ) |
Add pointer to a BodyNode representing a fragment of this link.
[in] | Pointer | to DART BodyNode. |
|
virtual |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
|
inherited |
Attach a static model to this link.
[in] | _model | Pointer to a static model. |
[in] | _offset | Pose relative to this link to place the model. |
|
inherited |
Get a battery by name.
[in] | _name | Name of the battery to get. |
|
inherited |
Get a battery based on an index.
|
inherited |
Get the number of batteries in this link.
|
virtualinherited |
Get the bounding box for the link and all the child elements.
Reimplemented from Entity.
|
inherited |
Returns collision bounding box.
|
protectedinherited |
Compute the scoped name of this object based on its parents.
|
inherited |
Connect to the add entity signal.
[in] | _subscriber | Subsciber callback function. |
dart::dynamics::BodyNode* DARTBodyNode | ( | ) | const |
Get pointer to DART BodyNode associated with this link.
DARTBodyNodePropPtr DARTProperties | ( | ) | const |
Get DART BodyNode properties.
dart::simulation::WorldPtr DARTWorld | ( | void | ) | const |
|
inherited |
Detach all static models from this link.
|
inherited |
Detach a static model from this link.
[in] | _modelName | Name of an attached model to detach. |
|
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.
|
inherited |
Fill a link message.
[out] | _msg | Message to fill |
|
inherited |
Helper function to find all connected links of a link based on parent/child relations of joints.
For example, if Link0 –> Link1 –> ... –> LinkN is a kinematic chain with Link0 being the base link. Then, call by Link1: Link1->FindAllConnectedLinksHelper(Link0, _list, true); should return true with _list containing Link1 through LinkN. In the case the _originalParentLink is part of a loop, _connectedLinks is cleared and the function returns false.
[in] | _originParentLink | if this link is a child link of the search, we've found a loop. |
in/out] | _connectedLinks aggregate list of connected links. | |
[in] | _fistLink | this is the first Link, skip over the parent link that matches the _originalParentLink. |
|
virtual |
Finalize the entity.
Reimplemented from Entity.
|
inherited |
Get the angular damping factor.
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
|
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 |
Get the number of children.
|
inherited |
Get the child joints.
|
inherited |
Returns a vector of children Links connected by joints.
|
inherited |
|
inherited |
Get a child collision by name.
[in] | _name | Name of the collision object. |
|
inherited |
Get a child collision by index.
[in] | _index | Index of the collision object. |
|
inherited |
Get all the child collisions.
DARTModelPtr GetDARTModel | ( | ) | const |
DARTPhysicsPtr GetDARTPhysics | ( | void | ) | const |
Get pointer to DART Physics engine associated with this link.
|
virtual |
Get whether this body is enabled in the physics engine.
Implements Link.
|
virtual |
|
inherited |
Return the ID of this entity.
This id is unique.
|
inlineinherited |
|
virtual |
Implement this function.
Get whether this body is in the kinematic state.
Reimplemented from Link.
|
inherited |
Get the linear damping factor.
|
inherited |
Get the model that this body belongs to.
|
inherited |
Return the name of the entity.
|
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 |
Get the parent.
|
inherited |
Return the ID of the parent.
|
inherited |
Get the parent joints.
|
inherited |
Returns a vector of parent Links connected by joints.
|
inherited |
Get the parent model, if one exists.
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
|
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. |
|
virtualinherited |
|
inherited |
Get Self-Collision Flag.
Two links within the same model will not collide if both have 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.
|
inherited |
Get sensor count.
This will return the number of sensors created by the link when it was loaded. This function is commonly used with Link::GetSensorName.
|
inherited |
Get sensor name.
Get the name of a sensor based on an index. The index should be in the range of 0...Link::GetSensorCount().
[in] | _index | Index of the sensor name. |
|
inherited |
Get the full type definition.
|
inherited |
Returns the visual message specified by its name.
[in] | name | of the visual message |
|
inherited |
|
inherited |
Returns this link's total energy, or sum of Link::GetWorldEnergyPotential() and Link::GetWorldEnergyKinetic().
|
inherited |
Returns this link's kinetic energy computed using link's CoG velocity in the inertial (world) frame.
|
inherited |
Returns this link's potential energy, based on position in world frame and gravity.
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
|
virtual |
Initialize the body.
Reimplemented from Link.
|
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.
bool IsSoftBody | ( | ) | const |
Get whether this link is soft body.
True if this link is soft body.
|
inherited |
Return whether this entity is static.
|
virtual |
|
inherited |
Move Link given source and target frames specified in world coordinates.
Assuming link's relative pose to source frame (_worldReferenceFrameSrc) remains unchanged relative to destination frame (_worldReferenceFrameDst).
[in] | _worldReferenceFrameSrc | initial reference frame to which this link is attached. |
[in] | _worldReferenceFrameDst | final location of the reference frame specified in world coordinates. |
[in] | _preserveWorldVelocity | True if to preserve the world velocity before move frame, default is false. |
|
virtual |
This function is called when the entity's (or one of its parents) pose of the parent has changed.
Reimplemented from Link.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
|
inherited |
|
inherited |
Move this entity to be ontop of the nearest entity below.
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
|
inherited |
Update parameters from a message.
[in] | _msg | Message to read. |
|
protectedvirtualinherited |
Register items in the introspection service.
Reimplemented from Base.
|
virtualinherited |
Get the angular acceleration of the body.
Reimplemented from Entity.
|
virtualinherited |
Get the angular velocity of the body.
Reimplemented from Entity.
|
inherited |
Get the force applied to the body.
|
virtualinherited |
Get the linear acceleration of the body.
Reimplemented from Entity.
|
virtualinherited |
|
inherited |
Get the pose of the entity relative to its parent.
|
inherited |
Get the torque applied to the body.
|
inherited |
Returns this link's wind velocity.
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
|
inherited |
Remove a child by name.
[in] | _name | Name of the child. |
|
inherited |
Remove a child by pointer.
[in] | _child | Pointer to the child. |
|
virtualinherited |
|
inherited |
|
inherited |
Remove all children.
|
inherited |
Remove a collision from the link.
int] | _name Name of the collision to remove. |
|
inherited |
|
virtualinherited |
Reset the link.
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 link.
|
inherited |
Set the angular acceleration of the body.
[in] | _accel | Angular acceleration. |
|
virtual |
|
virtual |
|
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. |
|
virtual |
Allow the link to auto disable.
[in] | _disable | If true, the link is allowed to auto disable. |
Implements Link.
|
inherited |
Set to true if this entity is a canonical link for a model.
[in] | _value | True if the link is canonical. |
|
inherited |
Set the collide mode of the body.
[in] | _mode | Collision Mode, this can be: [all|none|sensors|fixed|ghost] all: collides with everything none: collides with nothing sensors: collides with everything else but other sensors fixed: collides with everything else but other fixed ghost: collides with everything else but other ghost |
void SetDARTBodyNode | ( | dart::dynamics::BodyNode * | _dtBodyNode | ) |
Set pointer to DART BodyNode associated with this link.
[in] | Pointer | to DART BodyNode. |
void SetDARTParentJoint | ( | DARTJointPtr | _dartParentJoint | ) |
Set parent joint of this link.
[in] | _dartParentJoint | Pointer to the parent joint. |
|
virtual |
Set whether this body is enabled.
[in] | _enable | True to enable the link in the physics engine. |
Implements Link.
|
virtual |
|
virtual |
|
inherited |
Set the mass of the link.
[in] _inertial Inertial value for the link.
|
inherited |
Set the initial pose.
[in] | _pose | The initial pose. |
|
virtual |
Implement this function.
Set whether this body is in the kinematic state.
[in] | _kinematic | True to make the link kinematic only. |
Reimplemented from Link.
|
inherited |
Set the laser retro reflectiveness.
[in] | _retro | Retro value for all child collisions. |
|
inherited |
Set the linear acceleration of the body.
[in] | _accel | Linear acceleration. |
|
virtual |
|
virtual |
|
virtual |
Freeze link to ground (inertial frame).
[in] | _static | if true, freeze link to ground. Otherwise unfreeze link. |
Implements Link.
|
virtualinherited |
|
inherited |
Set the parent.
[in] | _parent | Parent object. |
|
inherited |
Enable/Disable link data publishing.
[in] | _enable | True to enable publishing, false to stop publishing |
|
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. |
|
inherited |
Set the scale of the link.
[in] | _scale | Scale to set the link to. |
|
virtualinherited |
Set whether this entity has been selected by the user through the gui.
[in] | _set | True to set the link as selected. |
Reimplemented from Base.
|
virtual |
Set whether this body will collide with others in the model.
[in] | _collide | True to enable collisions. |
Implements Link.
|
inherited |
Set the current link state.
[in] | _state | The state to set the link to. |
|
virtualinherited |
|
virtual |
|
inherited |
Set the pose of a visual.
[in] | _id | Unique ID of visual message. |
[in] | _pose | Pose relative to this link to place the visual. |
|
inherited |
Enable/disable wind for this link.
[in] | _enable | True to enable the wind. |
|
virtualinherited |
Set whether wind affects this body.
[in] | _mode | True to enable wind. |
|
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. |
|
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. |
|
virtualinherited |
Stop the current animation, if any.
Reimplemented in Model.
|
inherited |
Get the string name for the entity type.
|
protectedvirtualinherited |
Unregister items in the introspection service.
|
inherited |
Update the collision.
[in] | _info | Update information. |
|
inlinevirtualinherited |
Update the object.
Reimplemented in MultiRayShape, Joint, Actor, RayShape, Model, DARTModel, MapShape, DARTRayShape, ODERayShape, DARTMeshShape, ODEMeshShape, ODEPolylineShape, SimbodyRayShape, BulletRayShape, and MeshShape.
void updateDirtyPoseFromDARTTransformation | ( | ) |
Store DART Transformation to Entity::dirtyPose and add this link to World::dirtyPoses so that World::Update() trigger Entity::SetWorldPose() for this link.
|
virtual |
Update the mass matrix.
Reimplemented from Link.
|
virtualinherited |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to load from. |
Reimplemented from Entity.
|
inlinevirtualinherited |
Update surface parameters.
Reimplemented in ODELink.
|
inherited |
Update the wind.
[in] | _info | Update information. |
|
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.
|
inherited |
Get the unique ID of a visual.
[in] | _visName | Name of the visual. |
[out] | _visualId | The unique ID of the visual. |
|
inherited |
Get the pose of a visual.
[in] | _id | Unique ID of visual. |
[out] | _pose | Pose of the visual relative to this link. |
|
virtualinherited |
Get the wind mode.
|
virtualinherited |
Get the angular acceleration of the body in the world frame, which is computed as (I^-1 * (T - w x L)), where I: inertia matrix in world frame T: sum of external torques in world frame L: angular momentum of CoG in world frame w: angular velocity in world frame.
Reimplemented from Entity.
|
inherited |
Get the angular momentum of the body CoG in the world frame, which is computed as (I * w), where I: inertia matrix in world frame w: angular velocity in world frame.
|
virtual |
Get the angular velocity of the entity in the world frame.
Reimplemented from Entity.
|
virtual |
Get the linear velocity at the body's center of gravity in the world frame.
Implements Link.
|
inherited |
Get the pose of the body's center of gravity in the world coordinate frame.
|
virtual |
Get the force applied to the body in the world frame.
Implements Link.
|
inherited |
Get the world pose of the link inertia (cog position and Moment of Inertia frame).
This differs from GetWorldCoGPose(), which returns the cog position in the link frame (not the Moment of Inertia frame).
|
inherited |
Get the inertia matrix in the world frame.
|
virtualinherited |
Get the linear acceleration of the body in the world frame.
Reimplemented from Entity.
|
virtual |
Get the linear velocity of a point on the body in the world frame, using an offset expressed in a body-fixed frame.
If no offset is given, the velocity at the origin of the Link frame will be returned.
[in] | _offset | Offset of the point from the origin of the Link frame, expressed in the body-fixed frame. |
Implements Link.
|
virtual |
Get the linear velocity of a point on the body in the world frame, using an offset expressed in an arbitrary frame.
[in] | _offset | Offset from the origin of the link frame expressed in a frame defined by _q. |
[in] | _q | Describes the rotation of a reference frame relative to the world reference frame. |
Implements Link.
|
virtualinherited |
Get the linear velocity of the origin of the link frame, expressed in the world frame.
Reimplemented from Entity.
|
inlinevirtualinherited |
Get the absolute pose of the entity.
Reimplemented in Collision, and Light.
References Entity::worldPose.
|
virtual |
Get the torque applied to the body about the center of mass in world frame coordinates.
Implements Link.
|
inherited |
Returns this link's wind velocity in the world coordinate frame.
|
protectedinherited |
Angular acceleration.
deprecated
|
protectedinherited |
Current pose animation.
|
protectedinherited |
Connection used to update an animation.
|
protectedinherited |
Start pose of an animation.
|
protectedinherited |
Offsets for the attached models.
|
protectedinherited |
Children of this entity.
|
protectedinherited |
All our event connections.
|
protectedinherited |
The pose set by a physics engine.
|
protectedinherited |
Inertial properties.
Referenced by Link::GetInertial().
|
protectedinherited |
This flag is set to true when the link is initialized.
|
protectedinherited |
All the introspection items regsitered for this.
|
protectedinherited |
Linear acceleration.
deprecated
|
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.
Referenced by Entity::WorldPose().