SimbodyRayShape Class Reference

Ray shape for simbody. More...

#include <SimbodyRayShape.hh>

Inherits RayShape.

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

 SimbodyRayShape (PhysicsEnginePtr _physicsEngine)
 Constructor. More...
 
 SimbodyRayShape (CollisionPtr _collision)
 Constructor. More...
 
virtual ~SimbodyRayShape ()
 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)
 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 WorldPtrGetWorld () 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...
 
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 ()
 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::URIintrospectionItems
 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...
 

Detailed Description

Ray shape for simbody.

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

SimbodyRayShape ( PhysicsEnginePtr  _physicsEngine)
explicit

Constructor.

Parameters
[in]_physicsEnginePointer to the physics engine.
SimbodyRayShape ( CollisionPtr  _collision)
explicit

Constructor.

Parameters
[in]_collisionCollision the ray is attached to.
virtual ~SimbodyRayShape ( )
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.
std::string CollisionName ( ) const
inherited

Get the name of the object this ray collided with.

Returns
Collision object name
void ComputeScopedName ( )
protectedinherited

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

See Also
Base::GetScopedName
virtual double ComputeVolume ( ) const
virtualinherited

Documentation inherited.

Reimplemented from Shape.

ignition::math::Vector3d End ( ) const
inherited

Get the end point.

Returns
Position of the ray end
void FillMsg ( msgs::Geometry &  _msg)
virtualinherited

Fill a message with data from this object.

Parameters
[out]_msgMessage to fill. Implement this function.

Implements Shape.

virtual void Fini ( )
virtualinherited
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
unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.
int GetFiducial ( ) const
inherited

Get the fiducial id detected by this ray.

Returns
Fiducial id detected.
uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.
virtual void GetIntersection ( double &  _dist,
std::string &  _entity 
)
virtual

Get the nearest intersection.

Parameters
[out]_distDistance to the intersection.
[out]_entityName of the entity the ray intersected with.

Implements RayShape.

double GetLength ( ) const
inherited

Get the length of the ray.

Returns
The ray length.
std::string GetName ( ) const
inherited

Return the name of the entity.

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

Get the retro-reflectivness detected by this ray.

Returns
Retro reflectance value.
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.

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.
virtual void GlobalPoints ( ignition::math::Vector3d &  _posA,
ignition::math::Vector3d &  _posB 
)
virtualinherited

Get the global starting and ending points.

Parameters
[out]_posAReturns the starting point.
[out]_posBReturns the ending point.
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

In the ray.

Implements Shape.

bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.
virtual void Load ( sdf::ElementPtr  _sdf)
virtualinherited

Load.

Parameters
[in]nodePointer to an SDF parameters

Reimplemented in Joint, Actor, Model, Link, SimbodySliderJoint, Entity, BallJoint< ODEJoint >, BallJoint< DARTJoint >, BallJoint< SimbodyJoint >, BallJoint< BulletJoint >, UniversalJoint< ODEJoint >, UniversalJoint< DARTJoint >, UniversalJoint< SimbodyJoint >, UniversalJoint< BulletJoint >, MapShape, GearboxJoint< ODEJoint >, Hinge2Joint< ODEJoint >, Hinge2Joint< DARTJoint >, Hinge2Joint< SimbodyJoint >, Hinge2Joint< BulletJoint >, HeightmapShape, ODEJoint, BulletScrewJoint, HingeJoint< ODEJoint >, HingeJoint< DARTJoint >, HingeJoint< SimbodyJoint >, HingeJoint< BulletJoint >, BulletCollision, Collision, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, ScrewJoint< BulletJoint >, DARTJoint, Road, SliderJoint< ODEJoint >, SliderJoint< DARTJoint >, SliderJoint< SimbodyJoint >, SliderJoint< BulletJoint >, BulletBallJoint, BulletHinge2Joint, BulletJoint, DARTModel, ODECollision, SimbodyCollision, FixedJoint< ODEJoint >, FixedJoint< DARTJoint >, FixedJoint< SimbodyJoint >, FixedJoint< BulletJoint >, BulletUniversalJoint, DARTCollision, DARTLink, ODEHinge2Joint, ODEHingeJoint, ODESliderJoint, SimbodyFixedJoint, SimbodyUniversalJoint, SimbodyLink, SimbodyScrewJoint, BulletFixedJoint, BulletHingeJoint, BulletLink, BulletSliderJoint, SimbodyHinge2Joint, SimbodyHingeJoint, SimbodyJoint, DARTMeshShape, DARTScrewJoint, ODEGearboxJoint, ODELink, DARTPolylineShape, DARTUniversalJoint, ODEFixedJoint, ODEMeshShape, ODEScrewJoint, SimbodyBallJoint, SimbodyMeshShape, BulletMeshShape, BulletPolylineShape, DARTBallJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, DARTSliderJoint, ODEPolylineShape, SimbodyModel, and SimbodyPolylineShape.

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 Print ( const std::string &  _prefix)
inherited

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.
virtual void ProcessMsg ( const msgs::Geometry &  _msg)
virtualinherited

Update this shape from a message.

Parameters
[in]_msgMessage to update from. Implement this function.

Implements Shape.

virtual void RegisterIntrospectionItems ( )
protectedvirtualinherited

Register items in the introspection service.

Reimplemented in Link, Joint, and Model.

virtual void RelativePoints ( ignition::math::Vector3d &  _posA,
ignition::math::Vector3d &  _posB 
)
virtualinherited

Get the relative starting and ending points.

Parameters
[in]_posAReturns the starting point.
[in]_posBReturns the ending point.
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 object.

Reimplemented in Joint, Actor, Model, Link, Entity, ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

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

Parameters
[in]_resetTypeThe type of reset operation
virtual ignition::math::Vector3d Scale ( ) const
virtualinherited

Get the scale of the shape.

Returns
Scale of the shape.

Reimplemented in MapShape.

void SetCollisionName ( const std::string &  _name)
protectedinherited

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)
inherited

Set the fiducial id detected by this ray.

Parameters
[in]_fidFiducial id detected by this ray.
virtual void SetLength ( double  _len)
virtualinherited

Set the length of the ray.

Parameters
[in]_lenLength of the array.
virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameNew name.

Reimplemented in Entity.

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.
virtual void SetPoints ( const ignition::math::Vector3d &  _posStart,
const ignition::math::Vector3d &  _posEnd 
)
virtual

Set the ray based on starting and ending points relative to the body.

Parameters
[in]_posStartStart position, relative the body.
[in]_posEndEnd position, relative to the body.

Reimplemented from RayShape.

void SetRetro ( float  _retro)
inherited

Set the retro-reflectivness detected by this ray.

Parameters
[in]_retroRetro reflectance value.
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.
virtual void SetScale ( const ignition::math::Vector3d &  _scale)
virtualinherited

Set the scale of the ray.

Implements Shape.

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 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.
ignition::math::Vector3d Start ( ) const
inherited

Get the start point.

Returns
Position of the ray start
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 ( )
virtual

Update the ray collision.

Implements RayShape.

virtual void UpdateParameters ( sdf::ElementPtr  _sdf)
virtualinherited

Update the parameters using new sdf values.

Parameters
[in]_sdfUpdate the object's parameters based on SDF values.

Reimplemented in Joint, Actor, Link, Model, Entity, and Collision.

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.

Member Data Documentation

Base_V children
protectedinherited

Children of this entity.

int contactFiducial
protectedinherited

Fiducial ID value.

double contactLen
protectedinherited

Length of the ray.

double contactRetro
protectedinherited

Retro reflectance value.

ignition::math::Vector3d globalEndPos
protectedinherited

End position of the ray in global cs.

ignition::math::Vector3d globalStartPos
protectedinherited

Start position of the ray in global cs.

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

All the introspection items regsitered for this.

BasePtr parent
protectedinherited

Parent of this entity.

ignition::math::Vector3d relativeEndPos
protectedinherited

End position of the ray, relative to the body.

ignition::math::Vector3d relativeStartPos
protectedinherited

Start position of the ray, relative to the body.

ignition::math::Vector3d scale = ignition::math::Vector3d::One
protectedinherited

This shape's scale;.

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

WorldPtr world
protectedinherited

Pointer to the world.


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