SimbodyCollision Class Reference

Simbody collisions. More...

#include <SimbodyCollision.hh>

Inherits Collision.

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

 SimbodyCollision (LinkPtr _parent)
 Constructor. More...
 
virtual ~SimbodyCollision ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
virtual ignition::math::Box BoundingBox () const
 Get the bounding box for this collision. More...
 
ignition::math::Box CollisionBoundingBox () const
 Returns collision bounding box. More...
 
const ignition::math::Pose3d & DirtyPose () const
 Returns Entity::dirtyPose. More...
 
void FillMsg (msgs::Collision &_msg)
 Fill a collision message. More...
 
virtual void Fini ()
 Finalize the collision. 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...
 
SimTK::ContactGeometry * GetCollisionShape () const
 Get the simbody collision shape. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
float GetLaserRetro () const
 Get the laser retro reflectiveness. More...
 
LinkPtr GetLink () const
 Get the link this collision belongs to. More...
 
virtual unsigned int GetMaxContacts ()
 returns number of contacts allowed for this collision. More...
 
ModelPtr GetModel () const
 Get the model this collision 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...
 
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...
 
ShapePtr GetShape () const
 Get the collision shape. More...
 
unsigned int GetShapeType () const
 Get the shape type. More...
 
CollisionState GetState ()
 Get the collision state. More...
 
SurfaceParamsPtr GetSurface () const
 Get the surface parameters. More...
 
unsigned int GetType () const
 Get the full type definition. More...
 
const WorldPtrGetWorld () const
 Get the World this object is in. 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 collision. 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 IsPlaceable () const
 Return whether this collision is movable. 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 _ptr)
 Load the collision. 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::Collision &_msg)
 Update parameters from a message. More...
 
virtual ignition::math::Vector3d RelativeAngularAccel () const
 Get the angular acceleration of the collision. More...
 
virtual ignition::math::Vector3d RelativeAngularVel () const
 Get the angular velocity of the collision. More...
 
virtual ignition::math::Vector3d RelativeLinearAccel () const
 Get the linear acceleration of the collision. More...
 
virtual ignition::math::Vector3d RelativeLinearVel () const
 Get the linear velocity of the collision. More...
 
ignition::math::Pose3d RelativePose () const
 Get the pose of the entity relative to its parent. 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 void Reset ()
 Reset the entity. More...
 
virtual void Reset (Base::EntityType _resetType)
 Calls recursive Reset on one of the Base::EntityType's. 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 SetCanonicalLink (bool _value)
 Set to true if this entity is a canonical link for a model. More...
 
virtual void SetCategoryBits (unsigned int _bits)
 Set the category bits, used during collision detection. More...
 
virtual void SetCollideBits (unsigned int _bits)
 Set the collide bits, used during collision detection. More...
 
void SetCollision (bool _placeable)
 Set the encapsulated collision object. More...
 
void SetCollisionShape (SimTK::ContactGeometry *_shape)
 Set the collision shape. More...
 
void SetInitialRelativePose (const ignition::math::Pose3d &_pose)
 Set the initial pose. More...
 
void SetLaserRetro (float _retro)
 Set the laser retro reflectiveness. More...
 
virtual void SetMaxContacts (unsigned int _maxContacts)
 Number of contacts allowed for this collision. More...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
void SetPlaceable (const bool _placeable)
 Set if this object is moveable. 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 collision. More...
 
virtual bool SetSelected (bool _show)
 Set whether this entity has been selected by the user through the gui. More...
 
void SetShape (ShapePtr _shape)
 Set the shape for this collision. More...
 
void SetState (const CollisionState &_state)
 Set the current collision state. More...
 
void SetStatic (const bool &_static)
 Set whether this entity is static: immovable. 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 SetWorldPoseDirty ()
 Indicate that the world pose should be recalculated. 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...
 
virtual void Update ()
 Update the object. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values. More...
 
common::URI URI () const
 Return the common::URI of this entity. More...
 
virtual ignition::math::Vector3d WorldAngularAccel () const
 Get the angular acceleration of the collision in the world frame. More...
 
virtual ignition::math::Vector3d WorldAngularVel () const
 Get the angular velocity of the collision in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearAccel () const
 Get the linear acceleration of the collision in the world frame. More...
 
virtual ignition::math::Vector3d WorldLinearVel () const
 Get the linear velocity of the collision 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 RegisterIntrospectionItems ()
 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...
 
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...
 
LinkPtr link
 The link this collision belongs to. 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...
 
bool placeable
 Flag for placeable. 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...
 
ShapePtr shape
 Pointer to physics::Shape. More...
 
SurfaceParamsPtr surface
 The surface parameters. 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

Simbody collisions.

Member Enumeration Documentation

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

SimbodyCollision ( LinkPtr  _parent)
explicit

Constructor.

virtual ~SimbodyCollision ( )
virtual

Destructor.

Member Function Documentation

void AddChild ( BasePtr  _child)
inherited

Add a child to this entity.

Parameters
[in]_childChild entity.
void AddType ( EntityType  _type)
inherited

Add a type specifier.

Parameters
[in]_typeNew type to append to this objects type definition.
virtual ignition::math::Box BoundingBox ( ) const
virtual

Get the bounding box for this collision.

Returns
The bounding box.

Implements Collision.

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

Returns collision bounding box.

Returns
Collsion bounding box.
void ComputeScopedName ( )
protectedinherited

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

See Also
Base::GetScopedName
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.
void FillMsg ( msgs::Collision &  _msg)
inherited

Fill a collision message.

Parameters
[out]_msgThe message to fill with this collision's data.
virtual void Fini ( )
virtualinherited

Finalize the collision.

Reimplemented from Entity.

Reimplemented in DARTCollision, and ODECollision.

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
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.
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
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.
unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.
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.
SimTK::ContactGeometry* GetCollisionShape ( ) const

Get the simbody collision shape.

Returns
SimTK geometry used as the collision shape.
uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.
float GetLaserRetro ( ) const
inherited

Get the laser retro reflectiveness.

Returns
The laser retro value.
LinkPtr GetLink ( ) const
inherited

Get the link this collision belongs to.

Returns
The parent Link.
virtual unsigned int GetMaxContacts ( )
virtualinherited

returns number of contacts allowed for this collision.

This overrides global value (in PhysicsEngine) if specified.

Returns
max num contacts allowed for this collision.
ModelPtr GetModel ( ) const
inherited

Get the model this collision belongs to.

Returns
The parent model.
std::string GetName ( ) const
inherited

Return the name of the entity.

Returns
Name of the entity.
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.
BasePtr GetParent ( ) const
inherited

Get the parent.

Returns
Pointer to the parent entity.
int GetParentId ( ) const
inherited

Return the ID of the parent.

Returns
Integer ID.
ModelPtr GetParentModel ( )
inherited

Get the parent model, if one exists.

Returns
Pointer to a model, or NULL if no parent model exists.
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.
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.
virtual const sdf::ElementPtr GetSDF ( )
virtualinherited

Get the SDF values for the object.

Returns
The SDF values for the object.

Reimplemented in Actor, and Model.

ShapePtr GetShape ( ) const
inherited

Get the collision shape.

Returns
The collision shape.
unsigned int GetShapeType ( ) const
inherited

Get the shape type.

Returns
The shape type.
See Also
EntityType
CollisionState GetState ( )
inherited

Get the collision state.

Returns
The collision state.
SurfaceParamsPtr GetSurface ( ) const
inlineinherited

Get the surface parameters.

Returns
The surface parameters.

References Collision::surface.

unsigned int GetType ( ) const
inherited

Get the full type definition.

Returns
The full type definition.
const WorldPtr& GetWorld ( ) const
inherited

Get the World this object is in.

Returns
The World this object is part of.
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.
virtual void Init ( )
virtualinherited

Initialize the collision.

Reimplemented from Base.

Reimplemented in DARTCollision.

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

Get the initial relative pose.

Returns
The initial relative pose.
bool IsCanonicalLink ( ) const
inlineinherited

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

Returns
True if the link is canonical.
bool IsPlaceable ( ) const
inherited

Return whether this collision is movable.

Example on an immovable object is a ray.

Returns
True if the object is immovable.
bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.
bool IsStatic ( ) const
inherited

Return whether this entity is static.

Returns
True if static.
virtual void Load ( sdf::ElementPtr  _sdf)
virtual

Load the collision.

Parameters
[in]_sdfSDF to load from.

Reimplemented from Collision.

virtual void OnPoseChange ( )
virtual

This function is called when the entity's (or one of its parents) pose of the parent has changed.

Implements Entity.

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.
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.
void PlaceOnNearestEntityBelow ( )
inherited

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

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

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.
void ProcessMsg ( const msgs::Collision &  _msg)
inherited

Update parameters from a message.

Parameters
[in]_msgMessage to update from.
virtual void RegisterIntrospectionItems ( )
protectedvirtualinherited

Register items in the introspection service.

Reimplemented in Link, Joint, and Model.

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

Get the angular acceleration of the collision.

Returns
The angular acceleration of the collision.

Reimplemented from Entity.

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

Get the angular velocity of the collision.

Returns
The angular velocity of the collision.

Reimplemented from Entity.

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

Get the linear acceleration of the collision.

Returns
The linear acceleration of the collision.

Reimplemented from Entity.

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

Get the linear velocity of the collision.

Returns
The linear velocity relative to the parent model.

Reimplemented from Entity.

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.
virtual void RemoveChild ( unsigned int  _id)
virtualinherited

Remove a child from this entity.

Parameters
[in]_idID of the child to remove.
void RemoveChild ( const std::string &  _name)
inherited

Remove a child by name.

Parameters
[in]_nameName of the child.
void RemoveChild ( physics::BasePtr  _child)
inherited

Remove a child by pointer.

Parameters
[in]_childPointer to the child.
void RemoveChildren ( )
inherited

Remove all children.

virtual void Reset ( )
virtualinherited

Reset the entity.

Reimplemented from Base.

Reimplemented in Actor, Model, and Link.

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

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

Parameters
[in]_resetTypeThe type of reset operation
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.
void SetAnimation ( common::PoseAnimationPtr  _anim)
inherited

Set an animation for this entity.

Parameters
[in]_animPose animation.
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.
virtual void SetCategoryBits ( unsigned int  _bits)
virtual

Set the category bits, used during collision detection.

Parameters
[in]_bitsThe bits to set.

Implements Collision.

virtual void SetCollideBits ( unsigned int  _bits)
virtual

Set the collide bits, used during collision detection.

Parameters
[in]_bitsThe bits to set.

Implements Collision.

void SetCollision ( bool  _placeable)
inherited

Set the encapsulated collision object.

Has a side effect of changing the collision bit masks

Parameters
[in]_placeableTrue to make the object movable.
void SetCollisionShape ( SimTK::ContactGeometry *  _shape)

Set the collision shape.

Parameters
[in]_shapeSimTK geometry to use as the collision SimTK geometry to use as the collision shape.
void SetInitialRelativePose ( const ignition::math::Pose3d &  _pose)
inherited

Set the initial pose.

Parameters
[in]_poseThe initial pose.
void SetLaserRetro ( float  _retro)
inherited

Set the laser retro reflectiveness.

Parameters
[in]_retroThe laser retro value.
virtual void SetMaxContacts ( unsigned int  _maxContacts)
virtualinherited

Number of contacts allowed for this collision.

This overrides global value (in PhysicsEngine) if specified.

Parameters
[in]_maxContactsmax num contacts allowed for this collision.
virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameThe new name.

Reimplemented from Base.

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.
void SetPlaceable ( const bool  _placeable)
inherited

Set if this object is moveable.

Parameters
[in]_placeableTrue to make the object movable.
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.
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.
void SetScale ( const ignition::math::Vector3d &  _scale)
inherited

Set the scale of the collision.

Parameters
[in]_scaleScale to set the collision to.
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.

void SetShape ( ShapePtr  _shape)
inherited

Set the shape for this collision.

Parameters
[in]_shapeThe shape for this collision object.
void SetState ( const CollisionState _state)
inherited

Set the current collision state.

Parameters
[in]Thecollision state.
void SetStatic ( const bool &  _static)
inherited

Set whether this entity is static: immovable.

Parameters
[in]_staticTrue = static.
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.
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.
void SetWorldPoseDirty ( )
inherited

Indicate that the world pose should be recalculated.

The recalculation will be done when Collision::GetWorldPose is called.

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.
virtual void StopAnimation ( )
virtualinherited

Stop the current animation, if any.

Reimplemented in Model.

std::string TypeStr ( ) const
inherited

Get the string name for the entity type.

Returns
The string name for this entity.
virtual void UnregisterIntrospectionItems ( )
protectedvirtualinherited

Unregister items in the introspection service.

virtual void Update ( )
inlinevirtualinherited
virtual void UpdateParameters ( sdf::ElementPtr  _sdf)
virtualinherited

Update the parameters using new sdf values.

Parameters
[in]_sdfSDF values to update from.

Reimplemented from Entity.

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.
virtual ignition::math::Vector3d WorldAngularAccel ( ) const
virtualinherited

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

Returns
The angular acceleration of the collision in the world frame.

Reimplemented from Entity.

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

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

Returns
The angular velocity of the collision in the world frame.

Reimplemented from Entity.

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

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

Returns
The linear acceleration of the collision in the world frame.

Reimplemented from Entity.

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

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

Returns
The linear velocity of the collision in the world frame.

Reimplemented from Entity.

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

Get the absolute pose of the entity.

Returns
The absolute pose of the entity.

Reimplemented from Entity.

Referenced by ODEPlaneShape::CreatePlane().

Member Data Documentation

common::PoseAnimationPtr animation
protectedinherited

Current pose animation.

event::ConnectionPtr animationConnection
protectedinherited

Connection used to update an animation.

ignition::math::Pose3d animationStartPose
protectedinherited

Start pose of an animation.

Base_V children
protectedinherited

Children of this entity.

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

All our event connections.

ignition::math::Pose3d dirtyPose
protectedinherited

The pose set by a physics engine.

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

All the introspection items regsitered for this.

LinkPtr link
protectedinherited

The link this collision belongs to.

transport::NodePtr node
protectedinherited

Communication node.

ignition::transport::Node nodeIgn
protectedinherited

Ignition communication node.

BasePtr parent
protectedinherited

Parent of this entity.

EntityPtr parentEntity
protectedinherited

A helper that prevents numerous dynamic_casts.

bool placeable
protectedinherited

Flag for placeable.

common::Time prevAnimationTime
protectedinherited

Previous time an animation was updated.

transport::PublisherPtr requestPub
protectedinherited

Request publisher.

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

Request publisher.

ignition::math::Vector3d scale
protectedinherited

Scale of the entity.

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

ShapePtr shape
protectedinherited

Pointer to physics::Shape.

SurfaceParamsPtr surface
protectedinherited

The surface parameters.

Referenced by Collision::GetSurface().

transport::PublisherPtr visPub
protectedinherited

Visual publisher.

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

Visual publisher.

msgs::Visual* visualMsg
protectedinherited

Visual message container.

WorldPtr world
protectedinherited

Pointer to the world.

ignition::math::Pose3d worldPose
mutableprotectedinherited

World pose of the entity.

Referenced by Entity::WorldPose().


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