Gazebo Sim

API Reference

8.7.0

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a light entity. More...

#include <gz/sim/Light.hh>

Public Member Functions

 Light (sim::Entity _entity=kNullEntity)
 Constructor. More...
 
std::optional< double > AttenuationConstant (const EntityComponentManager &_ecm) const
 Get the light attenuation constant value. Light attenuation is not applicable to directional lights. More...
 
std::optional< double > AttenuationLinear (const EntityComponentManager &_ecm) const
 Get the light attenuation linear value. Light attenuation is not applicable to directional lights. More...
 
std::optional< double > AttenuationQuadratic (const EntityComponentManager &_ecm) const
 Get the light attenuation quadratic value. Light attenuation is not applicable to directional lights. More...
 
std::optional< double > AttenuationRange (const EntityComponentManager &_ecm) const
 Get the light attenuation range. Light attenuation is not applicable to directional lights. More...
 
std::optional< bool > CastShadows (const EntityComponentManager &_ecm) const
 Get whether the light casts shadows. More...
 
std::optional< math::ColorDiffuseColor (const EntityComponentManager &_ecm) const
 Get the light diffuse color. More...
 
std::optional< math::Vector3dDirection (const EntityComponentManager &_ecm) const
 Get the light direction. More...
 
sim::Entity Entity () const
 Get the entity which this Light is related to. More...
 
std::optional< double > Intensity (const EntityComponentManager &_ecm) const
 Get the light intensity. More...
 
std::optional< std::stringName (const EntityComponentManager &_ecm) const
 Get the light's unscoped name. More...
 
std::optional< sim::EntityParent (const EntityComponentManager &_ecm) const
 Get the parent entity. This can be a world or a link. More...
 
std::optional< math::Pose3dPose (const EntityComponentManager &_ecm) const
 Get the pose of the light. The pose is given w.r.t the light's parent. which can be a world or a link. More...
 
void ResetEntity (sim::Entity _newEntity)
 Reset Entity to a new one. More...
 
void SetAttenuationConstant (EntityComponentManager &_ecm, double _value)
 Set attenuation constant value of this light. More...
 
void SetAttenuationLinear (EntityComponentManager &_ecm, double _value)
 Set attenuation linear value of this light. More...
 
void SetAttenuationQuadratic (EntityComponentManager &_ecm, double _value)
 Set attenuation quadratic value of this light. More...
 
void SetAttenuationRange (EntityComponentManager &_ecm, double _range)
 Set attenuation range of this light. More...
 
void SetCastShadows (EntityComponentManager &_ecm, bool _castShadows)
 Set whether the light casts shadows. More...
 
void SetDiffuseColor (EntityComponentManager &_ecm, const math::Color &_color)
 Set the diffuse color of this light. More...
 
void SetDirection (EntityComponentManager &_ecm, const math::Vector3d &_dir)
 Set light direction. Applies to directional lights. More...
 
void SetIntensity (EntityComponentManager &_ecm, double _value)
 Set light intensity. More...
 
void SetPose (EntityComponentManager &_ecm, const math::Pose3d &_pose)
 Set the pose of this light. More...
 
void SetSpecularColor (EntityComponentManager &_ecm, const math::Color &_color)
 Set the specular color of this light. More...
 
void SetSpotFalloff (EntityComponentManager &_ecm, double _falloff)
 Set fall off value for this light. Applies to spot lights only. More...
 
void SetSpotInnerAngle (EntityComponentManager &_ecm, const math::Angle &_angle)
 Set inner angle for this light. Applies to spot lights only. More...
 
void SetSpotOuterAngle (EntityComponentManager &_ecm, const math::Angle &_angle)
 Set outer angle for this light. Applies to spot lights only. More...
 
std::optional< math::ColorSpecularColor (const EntityComponentManager &_ecm) const
 Get the light specular color. More...
 
std::optional< double > SpotFalloff (const EntityComponentManager &_ecm) const
 Get the fall off value of light. Applies to spot lights only. More...
 
std::optional< math::AngleSpotInnerAngle (const EntityComponentManager &_ecm) const
 Get the inner angle of light. Applies to spot lights only. More...
 
std::optional< math::AngleSpotOuterAngle (const EntityComponentManager &_ecm) const
 Get the outer angle of light. Applies to spot lights only. More...
 
std::optional< std::stringType (const EntityComponentManager &_ecm) const
 Get the light type. More...
 
bool Valid (const EntityComponentManager &_ecm) const
 Check whether this light correctly refers to an entity that has a components::Light. More...
 

Detailed Description

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a light entity.

For example, given a light's entity, find the value of its name component, one could use the entity-component manager (ecm) directly as follows:

std::string name = ecm.Component<components::Name>(entity)->Data();

Using this class however, the same information can be obtained with a simpler function call:

Light light(entity); std::string name = light.Name(ecm);

Constructor & Destructor Documentation

◆ Light()

Light ( sim::Entity  _entity = kNullEntity)
explicit

Constructor.

Parameters
[in]_entityLight entity

Member Function Documentation

◆ AttenuationConstant()

std::optional<double> AttenuationConstant ( const EntityComponentManager _ecm) const

Get the light attenuation constant value. Light attenuation is not applicable to directional lights.

Parameters
[in]_ecmEntity-component manager.
Returns
Attenuation constant value of light or nullopt if the entity does not have a components::Light component.

◆ AttenuationLinear()

std::optional<double> AttenuationLinear ( const EntityComponentManager _ecm) const

Get the light attenuation linear value. Light attenuation is not applicable to directional lights.

Parameters
[in]_ecmEntity-component manager.
Returns
Attenuation linear value of light or nullopt if the entity does not have a components::Light component.

◆ AttenuationQuadratic()

std::optional<double> AttenuationQuadratic ( const EntityComponentManager _ecm) const

Get the light attenuation quadratic value. Light attenuation is not applicable to directional lights.

Parameters
[in]_ecmEntity-component manager.
Returns
Attenuation quadratic value of light or nullopt if the entity does not have a components::Light component.

◆ AttenuationRange()

std::optional<double> AttenuationRange ( const EntityComponentManager _ecm) const

Get the light attenuation range. Light attenuation is not applicable to directional lights.

Parameters
[in]_ecmEntity-component manager.
Returns
Attenuation range of light or nullopt if the entity does not have a components::Light component.

◆ CastShadows()

std::optional<bool> CastShadows ( const EntityComponentManager _ecm) const

Get whether the light casts shadows.

Parameters
[in]_ecmEntity-component manager.
Returns
Cast shadow bool value of light or nullopt if the entity does not have a components::CastShadows component.

◆ DiffuseColor()

std::optional<math::Color> DiffuseColor ( const EntityComponentManager _ecm) const

Get the light diffuse color.

Parameters
[in]_ecmEntity-component manager.
Returns
Diffuse color of the light or nullopt if the entity does not have a components::Light component.

◆ Direction()

std::optional<math::Vector3d> Direction ( const EntityComponentManager _ecm) const

Get the light direction.

Parameters
[in]_ecmEntity-component manager.
Returns
Direction of light or nullopt if the entity does not have a components::Light component.

◆ Entity()

sim::Entity Entity ( ) const

Get the entity which this Light is related to.

Returns
Light entity.

◆ Intensity()

std::optional<double> Intensity ( const EntityComponentManager _ecm) const

Get the light intensity.

Parameters
[in]_ecmEntity-component manager.
Returns
Intensity of light or nullopt if the entity does not have a components::Light component.

◆ Name()

std::optional<std::string> Name ( const EntityComponentManager _ecm) const

Get the light's unscoped name.

Parameters
[in]_ecmEntity-component manager.
Returns
Light's name or nullopt if the entity does not have a components::Name component

◆ Parent()

std::optional<sim::Entity> Parent ( const EntityComponentManager _ecm) const

Get the parent entity. This can be a world or a link.

Parameters
[in]_ecmEntity-component manager.
Returns
Parent entity or nullopt if the entity does not have a components::ParentEntity component.

◆ Pose()

std::optional<math::Pose3d> Pose ( const EntityComponentManager _ecm) const

Get the pose of the light. The pose is given w.r.t the light's parent. which can be a world or a link.

Parameters
[in]_ecmEntity-component manager.
Returns
Pose of the light or nullopt if the entity does not have a components::Pose component.

◆ ResetEntity()

void ResetEntity ( sim::Entity  _newEntity)

Reset Entity to a new one.

Parameters
[in]_newEntityNew light entity.

◆ SetAttenuationConstant()

void SetAttenuationConstant ( EntityComponentManager _ecm,
double  _value 
)

Set attenuation constant value of this light.

Parameters
[in]_ecmEntity-component manager. Light attenuation is not applicable to directional lights.
[in]_valueAttenuation constant value to set

◆ SetAttenuationLinear()

void SetAttenuationLinear ( EntityComponentManager _ecm,
double  _value 
)

Set attenuation linear value of this light.

Parameters
[in]_ecmEntity-component manager. Light attenuation is not applicable to directional lights.
[in]_valueAttenuation linear value to set

◆ SetAttenuationQuadratic()

void SetAttenuationQuadratic ( EntityComponentManager _ecm,
double  _value 
)

Set attenuation quadratic value of this light.

Parameters
[in]_ecmEntity-component manager. Light attenuation is not applicable to directional lights.
[in]_valueAttenuation quadratic value to set

◆ SetAttenuationRange()

void SetAttenuationRange ( EntityComponentManager _ecm,
double  _range 
)

Set attenuation range of this light.

Parameters
[in]_ecmEntity-component manager. Light attenuation is not applicable to directional lights.
[in]_rangeAttenuation range value to set.

◆ SetCastShadows()

void SetCastShadows ( EntityComponentManager _ecm,
bool  _castShadows 
)

Set whether the light casts shadows.

Parameters
[in]_ecmEntity-component manager.
[in]_boolTrue to cast shadows, false to not cast shadows.

◆ SetDiffuseColor()

void SetDiffuseColor ( EntityComponentManager _ecm,
const math::Color _color 
)

Set the diffuse color of this light.

Parameters
[in]_ecmEntity-component manager.
[in]_colorDiffuse color to set the light to

◆ SetDirection()

void SetDirection ( EntityComponentManager _ecm,
const math::Vector3d _dir 
)

Set light direction. Applies to directional lights.

Parameters
[in]_ecmEntity-component manager. and spot lights only.
[in]_dirDirection to set

◆ SetIntensity()

void SetIntensity ( EntityComponentManager _ecm,
double  _value 
)

Set light intensity.

Parameters
[in]_ecmEntity-component manager.
[in]_valueIntensity value

◆ SetPose()

void SetPose ( EntityComponentManager _ecm,
const math::Pose3d _pose 
)

Set the pose of this light.

Parameters
[in]_ecmEntity-component manager. Pose is set w.r.t. the light's parent which can be a world or a link.
[in]_posePose to set the light to.

◆ SetSpecularColor()

void SetSpecularColor ( EntityComponentManager _ecm,
const math::Color _color 
)

Set the specular color of this light.

Parameters
[in]_ecmEntity-component manager.
[in]_colorSpecular color to set the light to

◆ SetSpotFalloff()

void SetSpotFalloff ( EntityComponentManager _ecm,
double  _falloff 
)

Set fall off value for this light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
[in]_fallOffFall off value

◆ SetSpotInnerAngle()

void SetSpotInnerAngle ( EntityComponentManager _ecm,
const math::Angle _angle 
)

Set inner angle for this light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
[in]_angleAngle to set.

◆ SetSpotOuterAngle()

void SetSpotOuterAngle ( EntityComponentManager _ecm,
const math::Angle _angle 
)

Set outer angle for this light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
[in]_angleAngle to set.

◆ SpecularColor()

std::optional<math::Color> SpecularColor ( const EntityComponentManager _ecm) const

Get the light specular color.

Parameters
[in]_ecmEntity-component manager.
Returns
Specular color of the light or nullopt if the entity does not have a components::Light component.

◆ SpotFalloff()

std::optional<double> SpotFalloff ( const EntityComponentManager _ecm) const

Get the fall off value of light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
Returns
Fall off value of spot light or nullopt if the entity does not have a components::Light component.

◆ SpotInnerAngle()

std::optional<math::Angle> SpotInnerAngle ( const EntityComponentManager _ecm) const

Get the inner angle of light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
Returns
Inner angle of spot light or nullopt if the entity does not have a components::Light component.

◆ SpotOuterAngle()

std::optional<math::Angle> SpotOuterAngle ( const EntityComponentManager _ecm) const

Get the outer angle of light. Applies to spot lights only.

Parameters
[in]_ecmEntity-component manager.
Returns
Outer angle of spot light or nullopt if the entity does not have a components::Light component.

◆ Type()

std::optional<std::string> Type ( const EntityComponentManager _ecm) const

Get the light type.

Parameters
[in]_ecmEntity-component manager.
Returns
Type of the light or nullopt if the entity does not have a components::LightType component.

◆ Valid()

bool Valid ( const EntityComponentManager _ecm) const

Check whether this light correctly refers to an entity that has a components::Light.

Parameters
[in]_ecmEntity-component manager.
Returns
True if it's a valid light in the manager.

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