Base class for all collision entities. More...
#include <Collision.hh>
Inherits Entity.
Inherited by BulletCollision, DARTCollision, ODECollision, and SimbodyCollision.
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 | |
Collision (LinkPtr _link) | |
Constructor. More... | |
virtual | ~Collision () |
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 =0 |
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... | |
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 WorldPtr & | GetWorld () 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 _sdf) |
Load the collision. 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)=0 |
Set the category bits, used during collision detection. More... | |
virtual void | SetCollideBits (unsigned int _bits)=0 |
Set the collide bits, used during collision detection. More... | |
void | SetCollision (bool _placeable) |
Set the encapsulated collision object. 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 | OnPoseChange ()=0 |
This function is called when the entity's (or one of its parents) pose of the parent has changed. 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::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... | |
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... | |
Base class for all collision entities.
|
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.
[in] | _link | Link that contains this collision object. |
|
virtual |
Destructor.
|
inherited |
Add a child to this entity.
[in] | _child | Child entity. |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
|
pure virtual |
Get the bounding box for this collision.
Reimplemented from Entity.
Implemented in ODECollision, BulletCollision, DARTCollision, and SimbodyCollision.
|
inherited |
Returns collision bounding box.
|
protectedinherited |
Compute the scoped name of this object based on its parents.
|
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.
void FillMsg | ( | msgs::Collision & | _msg | ) |
Fill a collision message.
[out] | _msg | The message to fill with this collision's data. |
|
virtual |
Finalize the collision.
Reimplemented from Entity.
Reimplemented in DARTCollision, and ODECollision.
|
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 |
|
inherited |
Return the ID of this entity.
This id is unique.
float GetLaserRetro | ( | ) | const |
Get the laser retro reflectiveness.
|
virtual |
returns number of contacts allowed for this collision.
This overrides global value (in PhysicsEngine) if specified.
ModelPtr GetModel | ( | ) | const |
Get the model this collision 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 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 |
ShapePtr GetShape | ( | ) | const |
Get the collision shape.
unsigned int GetShapeType | ( | ) | const |
CollisionState GetState | ( | ) |
Get the collision state.
|
inline |
|
inherited |
Get the full type definition.
|
inherited |
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
|
virtual |
|
inherited |
Get the initial relative pose.
|
inlineinherited |
A helper function that checks if this is a canonical body.
bool IsPlaceable | ( | ) | const |
Return whether this collision is movable.
Example on an immovable object is a ray.
|
inherited |
True if the entity is selected by the user.
|
inherited |
Return whether this entity is static.
|
virtual |
Load the collision.
[in] | _sdf | SDF to load from. |
Reimplemented from Entity.
Reimplemented in BulletCollision, ODECollision, SimbodyCollision, and DARTCollision.
|
protectedpure virtualinherited |
This function is called when the entity's (or one of its parents) pose of the parent has changed.
Implemented in Link, Model, ODECollision, Light, DARTCollision, DARTLink, SimbodyLink, BulletCollision, BulletLink, ODELink, and SimbodyCollision.
|
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. |
void ProcessMsg | ( | const msgs::Collision & | _msg | ) |
Update parameters from a message.
[in] | _msg | Message to update from. |
|
protectedvirtualinherited |
|
virtual |
Get the angular acceleration of the collision.
Reimplemented from Entity.
|
virtual |
Get the angular velocity of the collision.
Reimplemented from Entity.
|
virtual |
Get the linear acceleration of the collision.
Reimplemented from Entity.
|
virtual |
Get the linear velocity of the collision.
Reimplemented from Entity.
|
inherited |
Get the pose of the entity relative to its parent.
|
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. |
|
inherited |
Remove all children.
|
virtualinherited |
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
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 |
Set to true if this entity is a canonical link for a model.
[in] | _value | True if the link is canonical. |
|
pure virtual |
Set the category bits, used during collision detection.
[in] | _bits | The bits to set. |
Implemented in ODECollision, DARTCollision, BulletCollision, and SimbodyCollision.
|
pure virtual |
Set the collide bits, used during collision detection.
[in] | _bits | The bits to set. |
Implemented in ODECollision, BulletCollision, DARTCollision, and SimbodyCollision.
void SetCollision | ( | bool | _placeable | ) |
Set the encapsulated collision object.
Has a side effect of changing the collision bit masks
[in] | _placeable | True to make the object movable. |
|
inherited |
Set the initial pose.
[in] | _pose | The initial pose. |
void SetLaserRetro | ( | float | _retro | ) |
Set the laser retro reflectiveness.
[in] | _retro | The laser retro value. |
|
virtual |
Number of contacts allowed for this collision.
This overrides global value (in PhysicsEngine) if specified.
[in] | _maxContacts | max num contacts allowed for this collision. |
|
virtualinherited |
|
inherited |
Set the parent.
[in] | _parent | Parent object. |
void SetPlaceable | ( | const bool | _placeable | ) |
Set if this object is moveable.
[in] | _placeable | True to make the object movable. |
|
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. |
void SetScale | ( | const ignition::math::Vector3d & | _scale | ) |
Set the scale of the collision.
[in] | _scale | Scale to set the collision to. |
|
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.
void SetShape | ( | ShapePtr | _shape | ) |
Set the shape for this collision.
[in] | _shape | The shape for this collision object. |
void SetState | ( | const CollisionState & | _state | ) |
Set the current collision state.
[in] | The | collision state. |
|
inherited |
Set whether this entity is static: immovable.
[in] | _static | True = static. |
|
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. |
void SetWorldPoseDirty | ( | ) |
Indicate that the world pose should be recalculated.
The recalculation will be done when Collision::GetWorldPose is called.
|
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.
|
inlinevirtualinherited |
Update the object.
Reimplemented in MultiRayShape, Joint, Actor, RayShape, Model, DARTModel, MapShape, DARTRayShape, ODERayShape, DARTMeshShape, ODEMeshShape, ODEPolylineShape, SimbodyRayShape, BulletRayShape, and MeshShape.
|
virtual |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to update from. |
Reimplemented from Entity.
|
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.
|
virtual |
Get the angular acceleration of the collision in the world frame.
Reimplemented from Entity.
|
virtual |
Get the angular velocity of the collision in the world frame.
Reimplemented from Entity.
|
virtual |
Get the linear acceleration of the collision in the world frame.
Reimplemented from Entity.
|
virtual |
Get the linear velocity of the collision in the world frame.
Reimplemented from Entity.
|
virtual |
Get the absolute pose of the entity.
Reimplemented from Entity.
Referenced by ODEPlaneShape::CreatePlane().
|
protectedinherited |
Current pose animation.
|
protectedinherited |
Connection used to update an animation.
|
protectedinherited |
Start pose of an animation.
|
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.
|
protected |
The link this collision belongs to.
|
protectedinherited |
Communication node.
|
protectedinherited |
Ignition communication node.
|
protectedinherited |
Parent of this entity.
|
protectedinherited |
A helper that prevents numerous dynamic_casts.
|
protected |
Flag for placeable.
|
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.
|
protected |
Pointer to physics::Shape.
|
protected |
The surface parameters.
Referenced by Collision::GetSurface().
|
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().