Ignition Gazebo

API Reference

5.0.0

Ign-rendering renderer. All ign-rendering calls should be performed inside this class as it makes sure that opengl calls in the underlying render engine do not interfere with QtQuick's opengl render operations. The main Render function will render to an offscreen texture and notify via signal and slots when it's ready to be displayed. More...

#include <Scene3D.hh>

Signals

void ContextMenuRequested (QString _entity)
 Signal fired when context menu event is triggered. More...
 
void FollowTargetChanged (const std::string &_target, bool _waitForTarget)
 When fired, the follow target changed. May not be fired for every target change. More...
 

Public Member Functions

 IgnRenderer ()
 Constructor. More...
 
 ~IgnRenderer () override
 Destructor. More...
 
math::Pose3d CameraPose () const
 Get the current camera pose. More...
 
void Destroy ()
 Destroy camera associated with this renderer. More...
 
math::Vector3d FollowOffset () const
 Get the camera follow offset position. More...
 
std::string FollowTarget () const
 Get the target which the user camera is following. More...
 
bool FollowWorldFrame () const
 Get whether the camera is following the entity in world frame. More...
 
bool GeneratePreview (const sdf::Root &_sdf)
 Generate a preview of a resource. More...
 
void HandleKeyPress (QKeyEvent *_e)
 Handle key press event for snapping. More...
 
void HandleKeyRelease (QKeyEvent *_e)
 Handle key release event for snapping. More...
 
void Initialize ()
 Initialize the render engine. More...
 
void NewHoverEvent (const math::Vector2i &_hoverPos)
 New hover event triggered. More...
 
void NewMouseEvent (const common::MouseEvent &_e, const math::Vector2d &_drag=math::Vector2d::Zero)
 New mouse event triggered. More...
 
void Render (RenderSync *_renderSync)
 Main render function. More...
 
class RenderUtilRenderUtil () const
 Set the renderer. More...
 
void RequestSelectionChange (Entity _selectedEntity, bool _deselectAll, bool _sendEvent)
 Request entity selection. This queues the selection to be handled later in the render thread. More...
 
math::Vector3d RPYSnap () const
 Get the RPY snap values. More...
 
math::Vector3d ScaleSnap () const
 Get the scale snap values. More...
 
math::Vector3d ScreenToPlane (const math::Vector2i &_screenPos) const
 Retrieve the point on a plane at z = 0 in the 3D scene hit by a ray cast from the given 2D screen coordinates. More...
 
math::Vector3d ScreenToScene (const math::Vector2i &_screenPos) const
 Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates. More...
 
void SetDropdownMenuEnabled (bool _enableDropdownMenu)
 Set if the dropdown menu is enabled or disabled. More...
 
void SetFollowOffset (const math::Vector3d &_offset)
 Set the camera follow offset position. More...
 
void SetFollowPGain (double _gain)
 Set the p gain for the camera follow movement. More...
 
void SetFollowTarget (const std::string &_target, bool _waitForTarget=false)
 Move the user camera to follow the speficied target. More...
 
void SetFollowWorldFrame (bool _worldFrame)
 True to set the camera to follow the target in world frame, false to follow in target's local frame. More...
 
void SetInitCameraPose (const math::Pose3d &_pose)
 Set the initial user camera pose. More...
 
void SetModel (const std::string &_model)
 Set the model to hover over the scene. More...
 
void SetModelPath (const std::string &_filePath)
 Set the path to the model to hover over the scene. More...
 
void SetMoveTo (const std::string &_target)
 Move the user camera to move to the speficied target. More...
 
void SetMoveToPose (const math::Pose3d &_pose)
 Set the world pose of the camera. More...
 
void SetRecordVideo (bool _record, const std::string &_format, const std::string &_savePath)
 Set whether to record video. More...
 
void SetRecordVideoBitrate (unsigned int _bitrate)
 Set video recorder bitrate in bps. More...
 
void SetRecordVideoLockstep (bool _lockstep)
 Set whether to record video in lockstep mode. More...
 
void SetRecordVideoUseSimTime (bool _useSimTime)
 Set whether to record video using sim time as timestamp. More...
 
void SetRPYSnap (const math::Vector3d &_rpy)
 Set the RPY snap values. More...
 
void SetScaleSnap (const math::Vector3d &_scale)
 Set the scale snap values. More...
 
void SetTransformMode (const std::string &_mode)
 Set the transform mode. More...
 
void SetViewAngle (const math::Vector3d &_direction)
 Set the viewing angle of the camera. More...
 
void SetViewCollisionsTarget (const std::string &_target)
 View collisions of the specified target. More...
 
void SetXYZSnap (const math::Vector3d &_xyz)
 Set the XYZ snap values. More...
 
void SnapPoint (math::Vector3d &_point, math::Vector3d &_snapVals, double _sensitivity=0.4) const
 Snaps a point at intervals of a fixed distance. Currently used to give a snapping behavior when moving models with a mouse. More...
 
void TerminateSpawnPreview ()
 Delete the visuals generated while an entity is being spawned. More...
 
math::Vector3d XYZSnap () const
 Get the XYZ snap values. More...
 

Public Attributes

math::Pose3d cameraPose = math::Pose3d(0, 0, 2, 0, 0.4, 0)
 Initial Camera pose. More...
 
bool initialized = false
 True if engine has been initialized;. More...
 
bool textureDirty = false
 Flag to indicate texture size has changed. More...
 
GLuint textureId
 Render texture id Values is constantly constantly cycled/swapped/changed from a worker thread Don't read this directly. More...
 
QSize textureSize = QSize(1024, 1024)
 Render texture size. More...
 
uint32_t visibilityMask = 0xFFFFFFFFu
 Camera visibility mask. More...
 
std::string worldName
 Name of the world. More...
 

Detailed Description

Ign-rendering renderer. All ign-rendering calls should be performed inside this class as it makes sure that opengl calls in the underlying render engine do not interfere with QtQuick's opengl render operations. The main Render function will render to an offscreen texture and notify via signal and slots when it's ready to be displayed.

Constructor & Destructor Documentation

◆ IgnRenderer()

Constructor.

◆ ~IgnRenderer()

~IgnRenderer ( )
override

Destructor.

Member Function Documentation

◆ CameraPose()

math::Pose3d CameraPose ( ) const

Get the current camera pose.

Returns
Pose of the camera.

◆ ContextMenuRequested

void ContextMenuRequested ( QString  _entity)
signal

Signal fired when context menu event is triggered.

◆ Destroy()

void Destroy ( )

Destroy camera associated with this renderer.

◆ FollowOffset()

math::Vector3d FollowOffset ( ) const

Get the camera follow offset position.

Returns
Camera follow offset position.

◆ FollowTarget()

std::string FollowTarget ( ) const

Get the target which the user camera is following.

Returns
Target being followed

◆ FollowTargetChanged

void FollowTargetChanged ( const std::string _target,
bool  _waitForTarget 
)
signal

When fired, the follow target changed. May not be fired for every target change.

Parameters
[in]_targetTarget to follow
[in]_waitForTargetTrue to continuously look for the target

◆ FollowWorldFrame()

bool FollowWorldFrame ( ) const

Get whether the camera is following the entity in world frame.

Returns
True if follow mode is in world frame, false if local frame

◆ GeneratePreview()

bool GeneratePreview ( const sdf::Root &  _sdf)

Generate a preview of a resource.

Parameters
[in]_sdfThe SDF to be previewed.
Returns
True on success, false if failure

◆ HandleKeyPress()

void HandleKeyPress ( QKeyEvent *  _e)

Handle key press event for snapping.

Parameters
[in]_eThe key event to process.

◆ HandleKeyRelease()

void HandleKeyRelease ( QKeyEvent *  _e)

Handle key release event for snapping.

Parameters
[in]_eThe key event to process.

◆ Initialize()

void Initialize ( )

Initialize the render engine.

◆ NewHoverEvent()

void NewHoverEvent ( const math::Vector2i _hoverPos)

New hover event triggered.

Parameters
[in]_hoverPosMouse hover screen position

◆ NewMouseEvent()

void NewMouseEvent ( const common::MouseEvent _e,
const math::Vector2d _drag = math::Vector2d::Zero 
)

New mouse event triggered.

Parameters
[in]_eNew mouse event
[in]_dragMouse move distance

◆ Render()

void Render ( RenderSync *  _renderSync)

Main render function.

Parameters
[in]_renderSyncRenderSync to safely synchronize Qt and worker thread (this)

◆ RenderUtil()

class RenderUtil* RenderUtil ( ) const

Set the renderer.

◆ RequestSelectionChange()

void RequestSelectionChange ( Entity  _selectedEntity,
bool  _deselectAll,
bool  _sendEvent 
)

Request entity selection. This queues the selection to be handled later in the render thread.

Parameters
[in]_selectedEntityEntity to be selected, or kNullEntity.
[in]_deselectAllTrue if all entities should be deselected.
[in]_sendEventTrue to emit an event to other widgets.

◆ RPYSnap()

math::Vector3d RPYSnap ( ) const

Get the RPY snap values.

Returns
RPY snapping values as a Vector3d

◆ ScaleSnap()

math::Vector3d ScaleSnap ( ) const

Get the scale snap values.

Returns
Scale snapping values as a Vector3d

◆ ScreenToPlane()

math::Vector3d ScreenToPlane ( const math::Vector2i _screenPos) const

Retrieve the point on a plane at z = 0 in the 3D scene hit by a ray cast from the given 2D screen coordinates.

Parameters
[in]_screenPod2D coordinates on the screen, in pixels.
Returns
3D coordinates of a point in the 3D scene.

◆ ScreenToScene()

math::Vector3d ScreenToScene ( const math::Vector2i _screenPos) const

Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates.

Parameters
[in]_screenPos2D coordinates on the screen, in pixels.
Returns
3D coordinates of a point in the 3D scene.

◆ SetDropdownMenuEnabled()

void SetDropdownMenuEnabled ( bool  _enableDropdownMenu)

Set if the dropdown menu is enabled or disabled.

Parameters
[in]_enableDropdownMenuThe boolean to enable or disable the dropdown menu

◆ SetFollowOffset()

void SetFollowOffset ( const math::Vector3d _offset)

Set the camera follow offset position.

Parameters
[in]_offsetCamera follow offset position.

◆ SetFollowPGain()

void SetFollowPGain ( double  _gain)

Set the p gain for the camera follow movement.

Parameters
[in]_gainCamera follow p gain.

◆ SetFollowTarget()

void SetFollowTarget ( const std::string _target,
bool  _waitForTarget = false 
)

Move the user camera to follow the speficied target.

Parameters
[in]_targetTarget to follow
[in]_waitForTargetTrue to continuously look for the target to follow. A typical use case is when following a target that is not present on startup but spawned later into simulation

◆ SetFollowWorldFrame()

void SetFollowWorldFrame ( bool  _worldFrame)

True to set the camera to follow the target in world frame, false to follow in target's local frame.

Parameters
[in]_gainCamera follow p gain.

◆ SetInitCameraPose()

void SetInitCameraPose ( const math::Pose3d _pose)

Set the initial user camera pose.

Parameters
[in]_posePose to set the camera to

◆ SetModel()

void SetModel ( const std::string _model)

Set the model to hover over the scene.

Parameters
[in]_modelSdf string of the model to load in for the user.

◆ SetModelPath()

void SetModelPath ( const std::string _filePath)

Set the path to the model to hover over the scene.

Parameters
[in]_filePathSdf path of the model to load in for the user.

◆ SetMoveTo()

void SetMoveTo ( const std::string _target)

Move the user camera to move to the speficied target.

Parameters
[in]_targetTarget to move the camera to

◆ SetMoveToPose()

void SetMoveToPose ( const math::Pose3d _pose)

Set the world pose of the camera.

Parameters
[in]_poseThe world pose to set the camera to.

◆ SetRecordVideo()

void SetRecordVideo ( bool  _record,
const std::string _format,
const std::string _savePath 
)

Set whether to record video.

Parameters
[in]_recordTrue to start video recording, false to stop.
[in]_formatVideo encoding format: "mp4", "ogv"
[in]_savePathPath to save the recorded video.

◆ SetRecordVideoBitrate()

void SetRecordVideoBitrate ( unsigned int  _bitrate)

Set video recorder bitrate in bps.

Parameters
[in]_bitrateBit rate to set to

◆ SetRecordVideoLockstep()

void SetRecordVideoLockstep ( bool  _lockstep)

Set whether to record video in lockstep mode.

Parameters
[in]_trueTrue to record video in lockstep mode

◆ SetRecordVideoUseSimTime()

void SetRecordVideoUseSimTime ( bool  _useSimTime)

Set whether to record video using sim time as timestamp.

Parameters
[in]_trueTrue record video using sim time

◆ SetRPYSnap()

void SetRPYSnap ( const math::Vector3d _rpy)

Set the RPY snap values.

Parameters
[in]_rpyThe RPY snap values

◆ SetScaleSnap()

void SetScaleSnap ( const math::Vector3d _scale)

Set the scale snap values.

Parameters
[in]_scaleThe scale snap values

◆ SetTransformMode()

void SetTransformMode ( const std::string _mode)

Set the transform mode.

Parameters
[in]_modeNew transform mode to set to

◆ SetViewAngle()

void SetViewAngle ( const math::Vector3d _direction)

Set the viewing angle of the camera.

Parameters
[in]_directionThe pose to assume relative to the entit(y/ies). (0, 0, 0) indicates to return the camera back to the home pose originally loaded in from the sdf

◆ SetViewCollisionsTarget()

void SetViewCollisionsTarget ( const std::string _target)

View collisions of the specified target.

Parameters
[in]_targetTarget to view collisions

◆ SetXYZSnap()

void SetXYZSnap ( const math::Vector3d _xyz)

Set the XYZ snap values.

Parameters
[in]_xyzThe XYZ snap values

◆ SnapPoint()

void SnapPoint ( math::Vector3d _point,
math::Vector3d _snapVals,
double  _sensitivity = 0.4 
) const

Snaps a point at intervals of a fixed distance. Currently used to give a snapping behavior when moving models with a mouse.

Parameters
[in]_pointInput point to snap.
[in]_snapValsThe snapping values to use for each corresponding coordinate in _point
[in]_sensitivitySensitivity of a point snapping, in terms of a percentage of the interval.

◆ TerminateSpawnPreview()

void TerminateSpawnPreview ( )

Delete the visuals generated while an entity is being spawned.

◆ XYZSnap()

math::Vector3d XYZSnap ( ) const

Get the XYZ snap values.

Returns
XYZ snapping values as a Vector3d

Member Data Documentation

◆ cameraPose

math::Pose3d cameraPose = math::Pose3d(0, 0, 2, 0, 0.4, 0)

Initial Camera pose.

◆ initialized

bool initialized = false

True if engine has been initialized;.

◆ textureDirty

bool textureDirty = false

Flag to indicate texture size has changed.

◆ textureId

GLuint textureId

Render texture id Values is constantly constantly cycled/swapped/changed from a worker thread Don't read this directly.

◆ textureSize

QSize textureSize = QSize(1024, 1024)

Render texture size.

◆ visibilityMask

uint32_t visibilityMask = 0xFFFFFFFFu

Camera visibility mask.

◆ worldName

std::string worldName

Name of the world.


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