Gazebo Gazebo

API Reference

3.15.1
RenderUtil Class Reference

#include <ignition/gazebo/gui/plugins/RenderUtil.hh>

Public Member Functions

 RenderUtil ()
 Constructor. More...
 
 ~RenderUtil ()
 Destructor. More...
 
void DeselectAllEntities ()
 Clears the set of selected entities and lowlights all of them. More...
 
std::string EngineName () const
 Get the name of the rendering engine used. More...
 
Entity EntityFromNode (const rendering::NodePtr &_node)
 Get the entity for a given node. More...
 
void Init ()
 Initialize the renderer. Must be called in the rendering thread. More...
 
class MarkerManagerMarkerManager ()
 Get the marker manager Returns reference to the marker manager. More...
 
int PendingSensors () const
 Count of pending sensors. Must be called in the rendering thread. More...
 
rendering::ScenePtr Scene () const
 Get a pointer to the scene. More...
 
class SceneManagerSceneManager ()
 Get the scene manager Returns reference to the scene manager. More...
 
std::string SceneName () const
 Get the name of the rendering scene used. More...
 
std::vector< EntitySelectedEntities () const
 Get the entities currently selected, in order of selection. More...
 
rendering::NodePtr SelectedEntity () const
 Get the entity being selected. This will only return the last entity selected. TODO(anyone) Deprecate in favour of SelectedEntities. More...
 
void SetAmbientLight (const math::Color &_ambient)
 Set ambient light of render window. This will override other sources, such as from SDF. More...
 
void SetBackgroundColor (const math::Color &_color)
 Set background color of render window. This will override other sources, such as from SDF. More...
 
void SetEnableSensors (bool _enable, std::function< std::string(const sdf::Sensor &, const std::string &)> _createSensorCb={})
 Set whether to create rendering sensors. More...
 
void SetEngineName (const std::string &_engineName)
 Set the rendering engine to use. More...
 
void SetSceneName (const std::string &_sceneName)
 Set the scene to use. More...
 
void SetSelectedEntity (rendering::NodePtr _node)
 Set the entity being selected. More...
 
void SetTransformActive (bool _active)
 Set whether the transform controls are currently being dragged. More...
 
void SetUseCurrentGLContext (bool _enable)
 Set whether to use the current GL context. More...
 
void ShowGrid ()
 Show grid view in the scene. More...
 
std::chrono::steady_clock::duration SimTime () const
 Get simulation time that the current rendering state corresponds to. More...
 
void Update ()
 Main update function. Must be called in the rendering thread. More...
 
void UpdateFromECM (const UpdateInfo &_info, const EntityComponentManager &_ecm)
 Helper PostUpdate function for updating the scene. More...
 
void ViewCollisions (const Entity &_entity)
 View collisions of specified entity which are shown in orange. More...
 

Constructor & Destructor Documentation

◆ RenderUtil()

RenderUtil ( )
explicit

Constructor.

◆ ~RenderUtil()

~RenderUtil ( )

Destructor.

Member Function Documentation

◆ DeselectAllEntities()

void DeselectAllEntities ( )

Clears the set of selected entities and lowlights all of them.

◆ EngineName()

std::string EngineName ( ) const

Get the name of the rendering engine used.

Returns
Name of the rendering engine

◆ EntityFromNode()

Entity EntityFromNode ( const rendering::NodePtr &  _node)

Get the entity for a given node.

Parameters
[in]_nodeNode to get the entity for.
Returns
The entity for that node, or kNullEntity for no entity.
Deprecated:
Use gz::rendering::Visual::UserData instead.

◆ Init()

void Init ( )

Initialize the renderer. Must be called in the rendering thread.

◆ MarkerManager()

Get the marker manager Returns reference to the marker manager.

◆ PendingSensors()

int PendingSensors ( ) const

Count of pending sensors. Must be called in the rendering thread.

Returns
Number of sensors to be added on the next Update call

In the case that RenderUtil has not been initialized, this method will return -1.

◆ Scene()

rendering::ScenePtr Scene ( ) const

Get a pointer to the scene.

Returns
Pointer to the scene

◆ SceneManager()

Get the scene manager Returns reference to the scene manager.

◆ SceneName()

std::string SceneName ( ) const

Get the name of the rendering scene used.

Returns
Name of the rendering scene.

◆ SelectedEntities()

std::vector<Entity> SelectedEntities ( ) const

Get the entities currently selected, in order of selection.

Returns
Vector of currently selected entities

◆ SelectedEntity()

rendering::NodePtr SelectedEntity ( ) const

Get the entity being selected. This will only return the last entity selected. TODO(anyone) Deprecate in favour of SelectedEntities.

◆ SetAmbientLight()

void SetAmbientLight ( const math::Color _ambient)

Set ambient light of render window. This will override other sources, such as from SDF.

Parameters
[in]_ambientColor of ambient light

◆ SetBackgroundColor()

void SetBackgroundColor ( const math::Color _color)

Set background color of render window. This will override other sources, such as from SDF.

Parameters
[in]_colorColor of render window background

◆ SetEnableSensors()

void SetEnableSensors ( bool  _enable,
std::function< std::string(const sdf::Sensor &, const std::string &)>  _createSensorCb = {} 
)

Set whether to create rendering sensors.

Parameters
[in]_enableTrue to create rendering sensors
[in]_createSensorCbCallback function for creating the sensors The callback function args are: sensor sdf, and parent name, and returns the name of the rendering sensor created.

◆ SetEngineName()

void SetEngineName ( const std::string _engineName)

Set the rendering engine to use.

Parameters
[in]_engineNameName of the rendering engine.

◆ SetSceneName()

void SetSceneName ( const std::string _sceneName)

Set the scene to use.

Parameters
[in]_sceneNameName of the engine.

◆ SetSelectedEntity()

void SetSelectedEntity ( rendering::NodePtr  _node)

Set the entity being selected.

Parameters
[in]_nodeNode representing the selected entity TODO(anyone) Make const ref when merging forward

◆ SetTransformActive()

void SetTransformActive ( bool  _active)

Set whether the transform controls are currently being dragged.

Parameters
[in]_activeTrue if active.

◆ SetUseCurrentGLContext()

void SetUseCurrentGLContext ( bool  _enable)

Set whether to use the current GL context.

Parameters
[in]_enableTrue to use the current GL context

◆ ShowGrid()

void ShowGrid ( )

Show grid view in the scene.

◆ SimTime()

std::chrono::steady_clock::duration SimTime ( ) const

Get simulation time that the current rendering state corresponds to.

Returns
Simulation time.

◆ Update()

void Update ( )

Main update function. Must be called in the rendering thread.

◆ UpdateFromECM()

void UpdateFromECM ( const UpdateInfo _info,
const EntityComponentManager _ecm 
)

Helper PostUpdate function for updating the scene.

◆ ViewCollisions()

void ViewCollisions ( const Entity _entity)

View collisions of specified entity which are shown in orange.

Parameters
[in]_entityEntity to view collisions

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