MultiRayShape Class Referenceabstract

Laser collision contains a set of ray-collisions, structured to simulate a laser range scanner. More...

#include <physics/physics.hh>

Inherits Shape.

Inherited by BulletMultiRayShape, DARTMultiRayShape, ODEMultiRayShape, and SimbodyMultiRayShape.

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

 MultiRayShape (CollisionPtr _parent)
 Constructor. More...
 
 MultiRayShape (PhysicsEnginePtr _physicsEngine)
 Constructor for a stand alone multiray shape. More...
 
virtual ~MultiRayShape ()
 Destructor. More...
 
void AddChild (BasePtr _child)
 Add a child to this entity. More...
 
virtual void AddRay (const ignition::math::Vector3d &_start, const ignition::math::Vector3d &_end)
 Add a ray to the collision. More...
 
void AddType (EntityType _type)
 Add a type specifier. More...
 
virtual double ComputeVolume () const
 Documentation inherited. More...
 
template<typename T >
event::ConnectionPtr ConnectNewLaserScans (T _subscriber)
 Connect a to the new laser scan signal. More...
 
void FillMsg (msgs::Geometry &_msg)
 This function is not implemented. 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 (unsigned int _index)
 Get detected fiducial value for a ray. More...
 
uint32_t GetId () const
 Return the ID of this entity. More...
 
double GetMaxRange () const
 Get the maximum range. More...
 
double GetMinRange () const
 Get the minimum range. 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...
 
double GetRange (unsigned int _index)
 Get detected range for a ray. More...
 
double GetResRange () const
 Get the range resolution. More...
 
double GetRetro (unsigned int _index)
 Get detected retro (intensity) value for a ray. More...
 
int GetSampleCount () const
 Get the horizontal sample count. More...
 
bool GetSaveable () const
 Get whether the object should be "saved", when the user selects to save the world to xml. More...
 
double GetScanResolution () const
 Get the horizontal resolution. 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...
 
int GetVerticalSampleCount () const
 Get the vertical sample count. More...
 
double GetVerticalScanResolution () const
 Get the vertical range resolution. 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 ()
 Init the shape. More...
 
bool IsSelected () const
 True if the entity is selected by the user. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load. More...
 
ignition::math::Angle MaxAngle () const
 Get the maximum angle. More...
 
ignition::math::Angle MinAngle () const
 Get the minimum angle. 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)
 This function is not implemented. More...
 
RayShapePtr Ray (const unsigned int _rayIndex) const
 Get a pointer to a ray. More...
 
unsigned int RayCount () const
 Get the number of rays. 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...
 
virtual void SetName (const std::string &_name)
 Set the name of the entity. More...
 
void SetParent (BasePtr _parent)
 Set the parent. More...
 
bool SetRay (const unsigned int _rayIndex, const ignition::math::Vector3d &_start, const ignition::math::Vector3d &_end)
 Set the points of a 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 multi ray shape. 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...
 
std::string TypeStr () const
 Get the string name for the entity type. More...
 
void Update ()
 Update the ray collisions. More...
 
virtual void UpdateParameters (sdf::ElementPtr _sdf)
 Update the parameters using new sdf values. More...
 
virtual void UpdateRays ()=0
 Method for updating the rays. More...
 
common::URI URI () const
 Return the common::URI of this entity. More...
 
ignition::math::Angle VerticalMaxAngle () const
 Get the vertical max angle. More...
 
ignition::math::Angle VerticalMinAngle () const
 Get the vertical min angle. 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

Base_V children
 Children of this entity. More...
 
CollisionPtr collisionParent
 This shape's collision parent. More...
 
sdf::ElementPtr horzElem
 Horizontal SDF element pointer. More...
 
std::vector< common::URIintrospectionItems
 All the introspection items regsitered for this. More...
 
event::EventT< void()> newLaserScans
 New laser scans event. More...
 
ignition::math::Pose3d offset
 Pose offset of all the rays. More...
 
BasePtr parent
 Parent of this entity. More...
 
sdf::ElementPtr rangeElem
 Range SDF element pointer. More...
 
sdf::ElementPtr rayElem
 Ray SDF element pointer. More...
 
std::vector< RayShapePtrrays
 Ray data. More...
 
ignition::math::Vector3d scale = ignition::math::Vector3d::One
 This shape's scale;. More...
 
sdf::ElementPtr scanElem
 Scan SDF element pointer. More...
 
sdf::ElementPtr sdf
 The SDF values for this object. More...
 
sdf::ElementPtr vertElem
 Vertical SDF element pointer. More...
 
WorldPtr world
 Pointer to the world. More...
 

Detailed Description

Laser collision contains a set of ray-collisions, structured to simulate a laser range scanner.

Member Enumeration Documentation

◆ EntityType

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

◆ MultiRayShape() [1/2]

MultiRayShape ( CollisionPtr  _parent)
explicit

Constructor.

Parameters
[in]_parentParent collision shape.

◆ MultiRayShape() [2/2]

MultiRayShape ( PhysicsEnginePtr  _physicsEngine)
explicit

Constructor for a stand alone multiray shape.

Stand alone means the multiray shape is not attached to a Collision object.

Example:

gazebo::physics::MultiRayShapePtr rays = boost::dynamic_pointer_cast<gazebo::physics::MultiRayShape>( world->Physics()->CreateShape("multiray", gazebo::physics::CollisionPtr()));

Parameters
[in]_physicsEnginePointer to the physics engine.

◆ ~MultiRayShape()

virtual ~MultiRayShape ( )
virtual

Destructor.

Member Function Documentation

◆ AddChild()

void AddChild ( BasePtr  _child)
inherited

Add a child to this entity.

Parameters
[in]_childChild entity.

Referenced by Base::Update().

◆ AddRay()

virtual void AddRay ( const ignition::math::Vector3d &  _start,
const ignition::math::Vector3d &  _end 
)
virtual

Add a ray to the collision.

Parameters
[in]_startStart of the ray.
[in]_endEnd of the ray.

Reimplemented in ODEMultiRayShape, DARTMultiRayShape, BulletMultiRayShape, and SimbodyMultiRayShape.

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ AddType()

void AddType ( EntityType  _type)
inherited

Add a type specifier.

Parameters
[in]_typeNew type to append to this objects type definition.

Referenced by Base::Update().

◆ ComputeScopedName()

void ComputeScopedName ( )
protectedinherited

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

See also
Base::GetScopedName

Referenced by Base::Update().

◆ ComputeVolume()

virtual double ComputeVolume ( ) const
virtual

Documentation inherited.

Reimplemented from Shape.

◆ ConnectNewLaserScans()

event::ConnectionPtr ConnectNewLaserScans ( _subscriber)
inline

Connect a to the new laser scan signal.

Parameters
[in]_subscriberCallback function.
Returns
The connection, which must be kept in scope.

References MultiRayShape::AddRay(), EventT< T >::Connect(), MultiRayShape::newLaserScans, MultiRayShape::Ray(), MultiRayShape::RayCount(), MultiRayShape::SetRay(), and MultiRayShape::UpdateRays().

◆ FillMsg()

void FillMsg ( msgs::Geometry &  _msg)
virtual

This function is not implemented.

Fill a message with this shape's values.

Parameters
[out]_msgMessage that contains the shape's values.

Implements Shape.

◆ Fini()

virtual void Fini ( )
virtualinherited

◆ GetByName()

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

Referenced by Base::Update().

◆ GetChild() [1/2]

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.

Referenced by Base::Update().

◆ GetChild() [2/2]

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

◆ GetChildCount()

unsigned int GetChildCount ( ) const
inherited

Get the number of children.

Returns
The number of children.

Referenced by Base::Update().

◆ GetFiducial()

int GetFiducial ( unsigned int  _index)

Get detected fiducial value for a ray.

Parameters
[in]_indexIndex of the ray.
Returns
Fiducial value for the ray.

◆ GetId()

uint32_t GetId ( ) const
inherited

Return the ID of this entity.

This id is unique.

Returns
Integer ID.

Referenced by Base::Update().

◆ GetMaxRange()

double GetMaxRange ( ) const

Get the maximum range.

Returns
Maximum range of all the rays.

◆ GetMinRange()

double GetMinRange ( ) const

Get the minimum range.

Returns
Minimum range of all the rays.

◆ GetName()

std::string GetName ( ) const
inherited

Return the name of the entity.

Returns
Name of the entity.

Referenced by Base::Update().

◆ GetParent()

BasePtr GetParent ( ) const
inherited

Get the parent.

Returns
Pointer to the parent entity.

Referenced by Base::Update().

◆ GetParentId()

int GetParentId ( ) const
inherited

Return the ID of the parent.

Returns
Integer ID.

Referenced by Base::Update().

◆ GetRange()

double GetRange ( unsigned int  _index)

Get detected range for a ray.

Parameters
[in]_indexIndex of the ray.
Returns
Returns DBL_MAX for no detection.

◆ GetResRange()

double GetResRange ( ) const

Get the range resolution.

Returns
Range resolution of all the rays.

◆ GetRetro()

double GetRetro ( unsigned int  _index)

Get detected retro (intensity) value for a ray.

Parameters
[in]_indexIndex of the ray.
Returns
Retro value for the ray.

◆ GetSampleCount()

int GetSampleCount ( ) const

Get the horizontal sample count.

Returns
Horizontal sample count.

◆ GetSaveable()

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.

Referenced by Base::Update().

◆ GetScanResolution()

double GetScanResolution ( ) const

Get the horizontal resolution.

Returns
Horizontal resolution.

◆ GetScopedName()

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.

Referenced by Base::Update().

◆ GetSDF()

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.

Referenced by Base::Update().

◆ GetType()

unsigned int GetType ( ) const
inherited

Get the full type definition.

Returns
The full type definition.

Referenced by Base::Update().

◆ GetVerticalSampleCount()

int GetVerticalSampleCount ( ) const

Get the vertical sample count.

Returns
Verical sample count.

◆ GetVerticalScanResolution()

double GetVerticalScanResolution ( ) const

Get the vertical range resolution.

Returns
Vertical range resolution.

◆ GetWorld()

const WorldPtr& GetWorld ( ) const
inherited

Get the World this object is in.

Returns
The World this object is part of.

Referenced by Base::Update().

◆ HasType()

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.

Referenced by Base::Update().

◆ Init()

virtual void Init ( )
virtual

Init the shape.

Implements Shape.

◆ IsSelected()

bool IsSelected ( ) const
inherited

True if the entity is selected by the user.

Returns
True if the entity is selected.

Referenced by Base::Update().

◆ Load()

virtual void Load ( sdf::ElementPtr  _sdf)
virtualinherited

Load.

Parameters
[in]nodePointer 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.

◆ MaxAngle()

ignition::math::Angle MaxAngle ( ) const

Get the maximum angle.

Returns
Maximum angle of ray scan.

◆ MinAngle()

ignition::math::Angle MinAngle ( ) const

Get the minimum angle.

Returns
Minimum angle of ray scan.

◆ operator==()

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.

Referenced by Base::Update().

◆ Print()

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

Print this object to screen via gzmsg.

Parameters
[in]_prefixUsually a set of spaces.

Referenced by Base::Update().

◆ ProcessMsg()

virtual void ProcessMsg ( const msgs::Geometry &  _msg)
virtual

This function is not implemented.

Update the ray based on a message.

Parameters
[in]_msgMessage to update from.

Implements Shape.

◆ Ray()

RayShapePtr Ray ( const unsigned int  _rayIndex) const

Get a pointer to a ray.

Parameters
[in]_rayIndexindex to the ray
Returns
Pointer to the ray, or NULL on error
See also
RayCount()

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ RayCount()

unsigned int RayCount ( ) const

Get the number of rays.

Returns
Number of rays in this shape.

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ RegisterIntrospectionItems()

virtual void RegisterIntrospectionItems ( )
protectedvirtualinherited

Register items in the introspection service.

Reimplemented in Link, Joint, and Model.

Referenced by Base::Update().

◆ RemoveChild() [1/3]

virtual void RemoveChild ( unsigned int  _id)
virtualinherited

Remove a child from this entity.

Parameters
[in]_idID of the child to remove.

Referenced by Link::GetKinematic(), and Base::Update().

◆ RemoveChild() [2/3]

void RemoveChild ( const std::string &  _name)
inherited

Remove a child by name.

Parameters
[in]_nameName of the child.

◆ RemoveChild() [3/3]

void RemoveChild ( physics::BasePtr  _child)
inherited

Remove a child by pointer.

Parameters
[in]_childPointer to the child.

◆ RemoveChildren()

void RemoveChildren ( )
inherited

Remove all children.

Referenced by Base::Update().

◆ Reset() [1/2]

virtual void Reset ( )
virtualinherited

Reset the object.

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

Referenced by Base::Init().

◆ Reset() [2/2]

virtual void Reset ( Base::EntityType  _resetType)
virtualinherited

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

Parameters
[in]_resetTypeThe type of reset operation

◆ Scale()

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

Get the scale of the shape.

Returns
Scale of the shape.

Reimplemented in MapShape.

◆ SDFPoseRelativeToParent()

ignition::math::Pose3d SDFPoseRelativeToParent ( ) const
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.

Returns
The pose of the object resolved according to the sdf 1.6 convention

Referenced by Base::Update().

◆ SDFSemanticPose()

virtual std::optional<sdf::SemanticPose> SDFSemanticPose ( ) const
virtualinherited

Get the SDF SemanticPose object associated with the pose of this object.

Objects that support frame semantics need to override this function and provide this function.

Reimplemented in Link, Joint, Model, Collision, and Light.

Referenced by Base::Update().

◆ SetName()

virtual void SetName ( const std::string &  _name)
virtualinherited

Set the name of the entity.

Parameters
[in]_nameNew name.

Reimplemented in Entity, and DARTJoint.

Referenced by Base::Update().

◆ SetParent()

void SetParent ( BasePtr  _parent)
inherited

Set the parent.

Parameters
[in]_parentParent object.

Referenced by Base::Update().

◆ SetRay()

bool SetRay ( const unsigned int  _rayIndex,
const ignition::math::Vector3d &  _start,
const ignition::math::Vector3d &  _end 
)

Set the points of a ray.

Parameters
[in]_rayIndexIndex of the ray to set.
[in]_startStart of the ray.
[in]_endEnd of the ray.
Returns
True if the ray was set. False can be returned if the _rayIndex is invalid.

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ SetSaveable()

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.

Referenced by Base::Update().

◆ SetScale()

virtual void SetScale ( const ignition::math::Vector3d &  _scale)
virtual

Set the scale of the multi ray shape.

Returns
_scale Scale to set the multi ray shape to.

Implements Shape.

◆ SetSelected()

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.

Referenced by Base::Update().

◆ SetWorld()

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.

Referenced by Base::Update().

◆ TypeStr()

std::string TypeStr ( ) const
inherited

Get the string name for the entity type.

Returns
The string name for this entity.

Referenced by Base::Update().

◆ UnregisterIntrospectionItems()

virtual void UnregisterIntrospectionItems ( )
protectedvirtualinherited

Unregister items in the introspection service.

Referenced by Base::Update().

◆ Update()

void Update ( )
virtual

Update the ray collisions.

Reimplemented from Base.

◆ UpdateParameters()

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 Actor, Joint, Model, Link, Entity, and Collision.

Referenced by Base::Update().

◆ UpdateRays()

virtual void UpdateRays ( )
pure virtual

Method for updating the rays.

This function is normally called automatically, such as when a laser sensor is updated. Only call this function on a standalone multiray shape.

See also
explicit MultiRayShape(PhysicsEnginePtr _physicsEngine)

Implemented in DARTMultiRayShape, ODEMultiRayShape, BulletMultiRayShape, and SimbodyMultiRayShape.

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ URI()

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.

Referenced by Base::Update().

◆ VerticalMaxAngle()

ignition::math::Angle VerticalMaxAngle ( ) const

Get the vertical max angle.

Returns
Vertical max angle.

◆ VerticalMinAngle()

ignition::math::Angle VerticalMinAngle ( ) const

Get the vertical min angle.

Returns
Vertical min angle.

Member Data Documentation

◆ children

Base_V children
protectedinherited

Children of this entity.

◆ collisionParent

◆ horzElem

sdf::ElementPtr horzElem
protected

Horizontal SDF element pointer.

◆ introspectionItems

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

All the introspection items regsitered for this.

◆ newLaserScans

event::EventT<void()> newLaserScans
protected

New laser scans event.

Referenced by MultiRayShape::ConnectNewLaserScans().

◆ offset

ignition::math::Pose3d offset
protected

Pose offset of all the rays.

◆ parent

BasePtr parent
protectedinherited

Parent of this entity.

◆ rangeElem

sdf::ElementPtr rangeElem
protected

Range SDF element pointer.

◆ rayElem

sdf::ElementPtr rayElem
protected

Ray SDF element pointer.

◆ rays

std::vector<RayShapePtr> rays
protected

Ray data.

◆ scale

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

This shape's scale;.

◆ scanElem

sdf::ElementPtr scanElem
protected

Scan SDF element pointer.

◆ sdf

sdf::ElementPtr sdf
protectedinherited

The SDF values for this object.

◆ vertElem

sdf::ElementPtr vertElem
protected

Vertical SDF element pointer.

◆ world

WorldPtr world
protectedinherited

Pointer to the world.


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