Base class for Ray collision geometry. More...
#include <physics/physics.hh>
Inherits Shape.
Inherited by BulletRayShape, DARTRayShape, ODERayShape, and SimbodyRayShape.
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 | |
RayShape (PhysicsEnginePtr _physicsEngine) | |
Constructor for a global ray. More... | |
RayShape (CollisionPtr _parent) | |
Constructor. More... | |
virtual | ~RayShape () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
std::string | CollisionName () const |
Get the name of the object this ray collided with. More... | |
virtual double | ComputeVolume () const |
Documentation inherited. More... | |
ignition::math::Vector3d | End () const |
Get the end point. More... | |
void | FillMsg (msgs::Geometry &_msg) |
Fill a message with data from this object. More... | |
virtual void | Fini () |
Finialize the object. 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... | |
unsigned int | GetChildCount () const |
Get the number of children. More... | |
int | GetFiducial () const |
Get the fiducial id detected by this ray. More... | |
uint32_t | GetId () const |
Return the ID of this entity. More... | |
virtual void | GetIntersection (double &_dist, std::string &_entity)=0 |
Get the nearest intersection. More... | |
double | GetLength () const |
Get the length of the ray. More... | |
std::string | GetName () const |
Return the name of the entity. More... | |
BasePtr | GetParent () const |
Get the parent. More... | |
int | GetParentId () const |
Return the ID of the parent. More... | |
float | GetRetro () const |
Get the retro-reflectivness detected by this ray. 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... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
const WorldPtr & | GetWorld () const |
Get the World this object is in. More... | |
virtual void | GlobalPoints (ignition::math::Vector3d &_posA, ignition::math::Vector3d &_posB) |
Get the global starting and ending points. More... | |
bool | HasType (const EntityType &_t) const |
Returns true if this object's type definition has the given type. More... | |
virtual void | Init () |
In the ray. More... | |
bool | IsSelected () const |
True if the entity is selected by the user. More... | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load. More... | |
bool | operator== (const Base &_ent) const |
Returns true if the entities are the same. More... | |
void | Print (const std::string &_prefix) |
Print this object to screen via gzmsg. More... | |
virtual void | ProcessMsg (const msgs::Geometry &_msg) |
Update this shape from a message. More... | |
virtual void | RelativePoints (ignition::math::Vector3d &_posA, ignition::math::Vector3d &_posB) |
Get the relative starting and ending points. 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 object. More... | |
virtual void | Reset (Base::EntityType _resetType) |
Calls recursive Reset on one of the Base::EntityType's. More... | |
virtual ignition::math::Vector3d | Scale () const |
Get the scale of the shape. More... | |
ignition::math::Pose3d | SDFPoseRelativeToParent () const |
Get the SDF pose of the object according to the sdf 1.6 convention. More... | |
virtual std::optional< sdf::SemanticPose > | SDFSemanticPose () const |
Get the SDF SemanticPose object associated with the pose of this object. More... | |
void | SetFiducial (int _fid) |
Set the fiducial id detected by this ray. More... | |
virtual void | SetLength (double _len) |
Set the length of the ray. More... | |
virtual void | SetName (const std::string &_name) |
Set the name of the entity. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
virtual void | SetPoints (const ignition::math::Vector3d &_posStart, const ignition::math::Vector3d &_posEnd) |
Set the ray based on starting and ending points relative to the body. More... | |
void | SetRetro (float _retro) |
Set the retro-reflectivness detected by this ray. More... | |
void | SetSaveable (bool _v) |
Set whether the object should be "saved", when the user selects to save the world to xml. More... | |
virtual void | SetScale (const ignition::math::Vector3d &_scale) |
Set the scale of the ray. More... | |
virtual bool | SetSelected (bool _show) |
Set whether this entity has been selected by the user through the gui. More... | |
void | SetWorld (const WorldPtr &_newWorld) |
Set the world this object belongs to. More... | |
ignition::math::Vector3d | Start () const |
Get the start point. More... | |
std::string | TypeStr () const |
Get the string name for the entity type. More... | |
virtual void | Update ()=0 |
Update the ray collision. 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... | |
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... | |
void | SetCollisionName (const std::string &_name) |
Set the name of the object this ray has collided with. More... | |
virtual void | UnregisterIntrospectionItems () |
Unregister items in the introspection service. More... | |
Protected Attributes | |
Base_V | children |
Children of this entity. More... | |
CollisionPtr | collisionParent |
This shape's collision parent. More... | |
int | contactFiducial |
Fiducial ID value. More... | |
double | contactLen |
Length of the ray. More... | |
double | contactRetro |
Retro reflectance value. More... | |
ignition::math::Vector3d | globalEndPos |
End position of the ray in global cs. More... | |
ignition::math::Vector3d | globalStartPos |
Start position of the ray in global cs. More... | |
std::vector< common::URI > | introspectionItems |
All the introspection items regsitered for this. More... | |
BasePtr | parent |
Parent of this entity. More... | |
ignition::math::Vector3d | relativeEndPos |
End position of the ray, relative to the body. More... | |
ignition::math::Vector3d | relativeStartPos |
Start position of the ray, relative to the body. More... | |
ignition::math::Vector3d | scale = ignition::math::Vector3d::One |
This shape's scale;. More... | |
sdf::ElementPtr | sdf |
The SDF values for this object. More... | |
WorldPtr | world |
Pointer to the world. More... | |
Base class for Ray collision geometry.
|
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. |
|
explicit |
Constructor for a global ray.
[in] | _physicsEngine | Pointer to the physics engine. |
|
explicit |
Constructor.
[in] | _parent | Collision parent of the shape. |
|
virtual |
Destructor.
|
inherited |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
Referenced by Base::Update().
std::string CollisionName | ( | ) | const |
Get the name of the object this ray collided with.
|
protectedinherited |
Compute the scoped name of this object based on its parents.
Referenced by Base::Update().
|
virtual |
Documentation inherited.
Reimplemented from Shape.
ignition::math::Vector3d End | ( | ) | const |
Get the end point.
|
virtual |
Fill a message with data from this object.
[out] | _msg | Message to fill. Implement this function. |
Implements Shape.
|
virtualinherited |
Finialize the object.
Reimplemented in Actor, Joint, Model, Link, Entity, DARTModel, ODEJoint, Road, DARTCollision, DARTLink, BulletJoint, ODECollision, SimbodyLink, BulletLink, ODELink, and Collision.
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
Referenced by Base::Update().
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
Referenced by Base::Update().
|
inherited |
Get a child by name.
[in] | _name | Name of the child. |
|
inherited |
int GetFiducial | ( | ) | const |
Get the fiducial id detected by this ray.
|
inherited |
|
pure virtual |
Get the nearest intersection.
[out] | _dist | Distance to the intersection. |
[out] | _entity | Name of the entity the ray intersected with. |
Implemented in DARTRayShape, ODERayShape, SimbodyRayShape, and BulletRayShape.
double GetLength | ( | ) | const |
Get the length of the ray.
|
inherited |
|
inherited |
|
inherited |
float GetRetro | ( | ) | const |
Get the retro-reflectivness detected by this ray.
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
Referenced by Base::Update().
|
inherited |
Return the name of this entity with the model scope model1::...::modelN::entityName.
[in] | _prependWorldName | True to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName. |
Referenced by Base::Update().
|
virtualinherited |
Get the SDF values for the object.
Reimplemented in Actor, and Model.
Referenced by Base::Update().
|
inherited |
|
inherited |
Get the World this object is in.
Referenced by Base::Update().
|
virtual |
Get the global starting and ending points.
[out] | _posA | Returns the starting point. |
[out] | _posB | Returns the ending point. |
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
Referenced by Base::Update().
|
virtual |
In the ray.
Implements Shape.
|
inherited |
True if the entity is selected by the user.
Referenced by Base::Update().
|
virtualinherited |
Load.
[in] | node | Pointer to an SDF parameters |
Reimplemented in Joint, Actor, Model, SimbodySliderJoint, Entity, Link, BallJoint< ODEJoint >, BallJoint< DARTJoint >, BallJoint< SimbodyJoint >, BallJoint< BulletJoint >, UniversalJoint< ODEJoint >, UniversalJoint< DARTJoint >, UniversalJoint< SimbodyJoint >, UniversalJoint< BulletJoint >, HeightmapShape, MapShape, Hinge2Joint< ODEJoint >, Hinge2Joint< DARTJoint >, Hinge2Joint< SimbodyJoint >, Hinge2Joint< BulletJoint >, ODEJoint, BulletScrewJoint, GearboxJoint< ODEJoint >, HingeJoint< ODEJoint >, HingeJoint< DARTJoint >, HingeJoint< SimbodyJoint >, HingeJoint< BulletJoint >, BulletCollision, Collision, DARTModel, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, ScrewJoint< BulletJoint >, DARTJoint, Road, SliderJoint< ODEJoint >, SliderJoint< DARTJoint >, SliderJoint< SimbodyJoint >, SliderJoint< BulletJoint >, BulletBallJoint, BulletHinge2Joint, BulletJoint, ODECollision, SimbodyCollision, FixedJoint< ODEJoint >, FixedJoint< DARTJoint >, FixedJoint< SimbodyJoint >, FixedJoint< BulletJoint >, BulletUniversalJoint, DARTCollision, DARTLink, ODEHinge2Joint, ODEHingeJoint, ODESliderJoint, SimbodyFixedJoint, SimbodyUniversalJoint, ODEGearboxJoint, SimbodyLink, SimbodyScrewJoint, BulletFixedJoint, BulletHingeJoint, BulletLink, BulletSliderJoint, Light, SimbodyHinge2Joint, SimbodyHingeJoint, SimbodyJoint, DARTMeshShape, DARTScrewJoint, ODELink, DARTPolylineShape, DARTUniversalJoint, ODEFixedJoint, ODEMeshShape, ODEScrewJoint, SimbodyBallJoint, SimbodyMeshShape, BulletMeshShape, BulletPolylineShape, DARTBallJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, DARTSliderJoint, ODEPolylineShape, SimbodyModel, and SimbodyPolylineShape.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
Referenced by Base::Update().
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
Referenced by Base::Update().
|
virtual |
Update this shape from a message.
[in] | _msg | Message to update from. Implement this function. |
Implements Shape.
|
protectedvirtualinherited |
Register items in the introspection service.
Reimplemented in Link, Joint, and Model.
Referenced by Base::Update().
|
virtual |
Get the relative starting and ending points.
[in] | _posA | Returns the starting point. |
[in] | _posB | Returns the ending point. |
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
Referenced by Link::GetKinematic(), and Base::Update().
|
inherited |
Remove a child by name.
[in] | _name | Name of the child. |
|
inherited |
Remove a child by pointer.
[in] | _child | Pointer to the child. |
|
inherited |
Remove all children.
Referenced by Base::Update().
|
virtualinherited |
Reset the object.
Reimplemented in Actor, Joint, Model, Link, Entity, ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
Referenced by Base::Init().
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
virtualinherited |
|
inherited |
Get the SDF pose of the object according to the sdf 1.6 convention.
This convention is that the pose of an element is relative to its parent XML element, except for joints, whose pose is relative to the child link.
Referenced by Base::Update().
|
virtualinherited |
|
protected |
Set the name of the object this ray has collided with.
This function should only be called from a collision detection engine. Used by MultiRayShape
void SetFiducial | ( | int | _fid | ) |
Set the fiducial id detected by this ray.
[in] | _fid | Fiducial id detected by this ray. |
|
virtual |
Set the length of the ray.
[in] | _len | Length of the array. |
|
virtualinherited |
Set the name of the entity.
[in] | _name | New name. |
Reimplemented in Entity, and DARTJoint.
Referenced by Base::Update().
|
inherited |
|
virtual |
Set the ray based on starting and ending points relative to the body.
[in] | _posStart | Start position, relative the body. |
[in] | _posEnd | End position, relative to the body. |
Reimplemented in DARTRayShape, ODERayShape, BulletRayShape, and SimbodyRayShape.
void SetRetro | ( | float | _retro | ) |
Set the retro-reflectivness detected by this ray.
[in] | _retro | Retro reflectance value. |
|
inherited |
Set whether the object should be "saved", when the user selects to save the world to xml.
[in] | _v | Set to True if the object should be saved. |
Referenced by Base::Update().
|
virtual |
Set the scale of the ray.
Implements Shape.
|
virtualinherited |
Set whether this entity has been selected by the user through the gui.
[in] | _show | True to set this entity as selected. |
Reimplemented in Link.
Referenced by Base::Update().
|
inherited |
Set the world this object belongs to.
This will also set the world for all children.
[in] | _newWorld | The new World this object is part of. |
Referenced by Base::Update().
ignition::math::Vector3d Start | ( | ) | const |
Get the start point.
|
inherited |
Get the string name for the entity type.
Referenced by Base::Update().
|
protectedvirtualinherited |
Unregister items in the introspection service.
Referenced by Base::Update().
|
pure virtual |
Update the ray collision.
Reimplemented from Base.
Implemented in DARTRayShape, ODERayShape, SimbodyRayShape, and BulletRayShape.
|
virtualinherited |
|
inherited |
Return the common::URI of this entity.
The URI includes the world where the entity is contained and all the hierarchy of sub-entities that can compose this entity. E.g.: A link entity contains the name of the link and the model where the link is contained.
Referenced by Base::Update().
|
protectedinherited |
Children of this entity.
|
protectedinherited |
This shape's collision parent.
Referenced by ODEPlaneShape::CreatePlane(), BulletPlaneShape::CreatePlane(), ODEPlaneShape::SetAltitude(), SimbodySphereShape::SetRadius(), ODESphereShape::SetRadius(), BulletSphereShape::SetRadius(), ODECylinderShape::SetSize(), SimbodyBoxShape::SetSize(), SimbodyCylinderShape::SetSize(), BulletCylinderShape::SetSize(), ODEBoxShape::SetSize(), and BulletBoxShape::SetSize().
|
protected |
Fiducial ID value.
|
protected |
Length of the ray.
|
protected |
Retro reflectance value.
|
protected |
End position of the ray in global cs.
|
protected |
Start position of the ray in global cs.
|
protectedinherited |
All the introspection items regsitered for this.
|
protectedinherited |
Parent of this entity.
|
protected |
End position of the ray, relative to the body.
|
protected |
Start position of the ray, relative to the body.
|
protectedinherited |
This shape's scale;.
|
protectedinherited |
The SDF values for this object.
|
protectedinherited |
Pointer to the world.