Ignition Rendering

API Reference

6.3.1
ignition::rendering Namespace Reference

Rendering classes and function useful in robot applications. More...

Classes

class  ArrowVisual
 Represents a arrow composite visual. More...
 
class  AxisVisual
 Represents a axis composite visual. More...
 
class  BaseArrowVisual
 
class  BaseAxisVisual
 
class  BaseBoundingBoxCamera
 
class  BaseCamera
 
class  BaseCapsule
 Base implementation of a Capsule Geometry. More...
 
class  BaseCompositeStore
 
class  BaseCOMVisual
 Base implementation of an center of mass visual. More...
 
class  BaseDepthCamera
 
class  BaseDirectionalLight
 
class  BaseDistortionPass
 Base distortion render pass. More...
 
class  BaseGaussianNoisePass
 Base Gaussian noise render pass. More...
 
class  BaseGeometry
 
class  BaseGeometryStore
 
class  BaseGizmoVisual
 A base implementation of the GizmoVisual class. More...
 
class  BaseGpuRays
 
class  BaseGrid
 Base implementation of a grid geometry. More...
 
class  BaseHeightmap
 
class  BaseInertiaVisual
 Base implementation of an inertia visual. More...
 
class  BaseJointVisual
 Base implementation of a joint visual. More...
 
class  BaseLidarVisual
 Base implementation of a Lidar Visual. More...
 
class  BaseLight
 
class  BaseLightStore
 
class  BaseLightVisual
 Base implementation of a light visual. More...
 
class  BaseMap
 
class  BaseMarker
 Base implementation of a Marker geometry. More...
 
class  BaseMaterial
 
class  BaseMaterialMap
 
class  BaseMesh
 
class  BaseNode
 
class  BaseNodeCompositeStore
 
class  BaseNodeStore
 
class  BaseObject
 
class  BaseParticleEmitter
 A base implementation of the ParticleEmitter class. More...
 
class  BasePointLight
 
class  BaseRayQuery
 A Ray Query class used for computing ray object intersections. More...
 
class  BaseRenderEngine
 
class  BaseRenderPass
 Base render pass that can be applied to a render target. More...
 
class  BaseRenderTarget
 
class  BaseRenderTexture
 
class  BaseRenderWindow
 
class  BaseScene
 
class  BaseSceneStore
 
class  BaseSegmentationCamera
 
class  BaseSensor
 
class  BaseSensorStore
 
class  BaseSpotLight
 
class  BaseStore
 
class  BaseStoreWrapper
 
class  BaseSubMesh
 
class  BaseSubMeshStore
 
class  BaseText
 Base implementation of a text geometry. More...
 
class  BaseThermalCamera
 Base implementation of the ThermalCamera class. More...
 
class  BaseVisual
 
class  BaseVisualStore
 
class  BaseWireBox
 Base implementation of a wireframe box. More...
 
class  BoundingBox
 2D or 3D Bounding box. It stores the position / orientation / size info of the box and its label More...
 
class  BoundingBoxCamera
 Poseable BoundingBox camera used for rendering bounding boxes of objects in the scene. More...
 
class  Camera
 Posable camera used for rendering the scene graph. More...
 
class  Capsule
 Geometry for a capsule shape. More...
 
class  CompositeStore
 Represents a collection of Store objects, collectively working as a single composite store. More...
 
class  CompositeVisual
 Represents a predefined collection of geometries and visuals. More...
 
class  COMVisual
 Represents a center of mass visual. More...
 
class  DepthCamera
 
class  DirectionalLight
 Represents a infinite directional light. More...
 
class  DistortionPass
 A render pass that applies distortion to the render target. More...
 
class  GaussianNoisePass
 A render pass that applies Gaussian noise to the render target. More...
 
class  Geometry
 Represents a geometric shape to be rendered. More...
 
class  GizmoVisual
 A gizmo that contains rotate, translate, and scale visuals. More...
 
class  GpuRays
 Generate depth ray data. More...
 
class  GraphicsAPIUtils
 Utils to convert GraphicsAPI to and from strings. More...
 
class  Grid
 Represents a grid geometry drawn along the XY plane. If vertical cell count is specified then the grid becomes 3D. More...
 
class  Heightmap
 A terrain defined by a heightfield. More...
 
class  HeightmapBlend
 Blend information to be used between textures on heightmaps. More...
 
class  HeightmapDescriptor
 Describes how a Heightmap should be loaded. More...
 
class  HeightmapTexture
 Texture to be used on heightmaps. More...
 
class  Image
 Encapsulates a raw image buffer and relevant properties. More...
 
class  InertiaVisual
 Represents a inertia visual. More...
 
class  JointVisual
 Represents a joint visual. More...
 
class  LidarVisual
 A LidarVisual geometry class. The visual appearance is based on the type specified. More...
 
class  Light
 Represents a light source in the scene graph. More...
 
class  LightVisual
 Represents a light visual. More...
 
class  Map
 Storage map from std::string to template class T. More...
 
class  Marker
 A marker geometry class. The marker's visual appearance is based on the marker type specified. More...
 
class  Material
 Represents a surface material of a Geometry. More...
 
class  Mesh
 Represents a collection of mesh geometries. More...
 
struct  MeshDescriptor
 Describes how a Mesh should be loaded. More...
 
class  MoveToHelper
 Helper class for animating a user camera to move to a target entity. More...
 
class  Node
 Represents a single posable node in the scene graph. More...
 
class  Object
 Represents an object present in the scene graph. This includes sub-meshes, materials, render targets, as well as posable nodes. More...
 
class  OgreArrowVisual
 
class  OgreAxisVisual
 
class  OgreCamera
 
class  OgreCapsule
 Ogre 2.x implementation of a Capsule Visual. More...
 
class  OgreCOMVisual
 
class  OgreConversions
 Conversions Conversions.hh rendering/Conversions.hh. More...
 
class  OgreDepthCamera
 Depth camera used to render depth data into an image buffer. More...
 
class  OgreDirectionalLight
 
class  OgreDistortionPass
 Ogre implementation of the DistortionPass class. More...
 
class  OgreDynamicLines
 Class for drawing lines that can change. More...
 
class  OgreDynamicRenderable
 Abstract base class providing mechanisms for dynamically growing hardware buffers. More...
 
class  OgreGaussianNoisePass
 Ogre implementation of the GaussianNoisePass class. More...
 
class  OgreGeometry
 
class  OgreGizmoVisual
 
class  OgreGpuRays
 Gpu Rays used to render depth data into an image buffer. More...
 
class  OgreGrid
 Ogre implementation of a grid geometry. More...
 
class  OgreHeightmap
 Ogre implementation of a heightmap geometry. More...
 
class  OgreInertiaVisual
 
class  OgreJointVisual
 
class  OgreLidarVisual
 Ogre implementation of a Lidar Visual. More...
 
class  OgreLight
 
class  OgreLightVisual
 
class  OgreMarker
 Ogre implementation of a marker geometry. More...
 
class  OgreMaterial
 
class  OgreMaterialSwitcher
 Helper class to assign unique colors to renderables. More...
 
class  OgreMesh
 
class  OgreMeshFactory
 
class  OgreNode
 
class  OgreObject
 
class  OgreParticleEmitter
 Class to manage a particle emitter. More...
 
class  OgrePointLight
 
class  OgreRayQuery
 A Ray Query class used for computing ray object intersections. More...
 
class  OgreRenderEngine
 
class  OgreRenderEnginePlugin
 Plugin for loading ogre render engine. More...
 
class  OgreRenderPass
 Ogre implementation of the RenderPass class. More...
 
class  OgreRenderTarget
 
class  OgreRenderTargetMaterial
 Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget. More...
 
class  OgreRenderTexture
 
class  OgreRenderWindow
 
class  OgreRTShaderSystem
 Implements Ogre's Run-Time Shader system. More...
 
class  OgreScene
 
class  OgreSelectionBuffer
 Generates a selection buffer object for a given camera. The selection buffer is used of entity selection. On setup, a unique color is assigned to each entity. Whenever a selection request is made, the selection buffer camera renders to a 1x1 sized offscreen buffer. The color value of that pixel gives the identity of the entity. More...
 
class  OgreSensor
 
class  OgreSpotLight
 
class  OgreSubMesh
 
class  OgreSubMeshStoreFactory
 
class  OgreText
 Ogre implementation of text geometry. More...
 
class  OgreThermalCamera
 Depth camera used to render thermal data into an image buffer. More...
 
class  OgreVisual
 
class  OgreWireBox
 Ogre implementation of a wire box geometry. More...
 
class  OrbitViewController
 A camera view controller. More...
 
class  OrthoViewController
 Orthographic view controller. More...
 
class  ParticleEmitter
 Class to manage a particle emitter. More...
 
class  PixelUtil
 Provides supporting functions for PixelFormat enum. More...
 
class  PointLight
 Represents a point light. More...
 
class  RayQuery
 A Ray Query class used for computing ray object intersections. More...
 
class  RayQueryResult
 A class that stores ray query intersection results. More...
 
class  RenderEngine
 An abstract interface to a concrete render-engine. A RenderEngine is responsible for initializing a render-engine as well as creating, storing, and destroying scenes. More...
 
class  RenderEngineManager
 Collection of render-engines. This provides access to all the render-engines available at runtime. RenderEngine objects should not be access directly, but instead via the RenderEngineManager to maintain a flexible render-engine agnostic design. More...
 
class  RenderEnginePlugin
 Base plugin class for render engines. More...
 
class  RenderPass
 A render pass can be added to a camera to affect how the scene is rendered. It can be used to add post-processing effects. Multiple passes can be chained together. More...
 
class  RenderPassFactory
 A factory interface for creating render passes. More...
 
class  RenderPassSystem
 A class for creating and managing render passes. More...
 
class  RenderTarget
 Represents a render-target to which cameras can render images. More...
 
class  RenderTexture
 Represents a off-screen render-texture to which cameras can render images. More...
 
class  RenderWindow
 Represents a on-screen render-window to which cameras can render images. More...
 
class  Scene
 Manages a single scene-graph. This class updates scene-wide properties and holds the root scene node. A Scene also serves as a factory for all scene objects. More...
 
class  SegmentationCamera
 Poseable Segmentation camera used for rendering the scene graph. This camera is designed to produce segmentation data, instead of a 2D image. More...
 
class  Sensor
 Represents a scene sensor. The most obvious example is a camera, but it can be anything that generates output from the scene. More...
 
class  ShaderParam
 a variant type that holds params that can be passed to a shader More...
 
class  ShaderParams
 a map that holds params to be passed to a shader More...
 
class  ShaderUtil
 Provides supporting functions for ShaderType enum. More...
 
class  SpotLight
 Represents a spotlight. More...
 
class  Store
 Multi-access storage structure of template class T. Template class T is expected to have functions GetId, GetName(), Destroy() which return unsigned int, std::string, and void respectively. This store will ensure that each element's name and ID are unique. More...
 
class  StoreWrapper
 Simple wrapper class that allows a Store of type Derived to be treated as a Store of type Base, where Derived is some class derived from Base. This is useful in storing Stores of different derived types in a single CompositeStore instance. More...
 
class  SubMesh
 Represents a single mesh geometry. More...
 
class  Text
 Represents a billboard text geometry that is always facing the camera. More...
 
class  ThermalCamera
 Thermal camera that produces temperature data. An object's temperature can be set through the Visual class using SetUserData with the key "temperature". Ambient temperature is returned for object that do not have this property set. Note that temperature variations for the environment and objects can be set using the Set*Range functions in this class. For simplicity, the variations are modeled as a function of depth (which is not how a real thermal sensor works). Ideally we support heatmaps for visuals in order to produce more realistic temperature output. More...
 
class  TransformController
 An transform tool for translating, rotating, and scaling objects. More...
 
class  ViewController
 A camera view controller. More...
 
class  Visual
 Represents a visual node in a scene graph. A Visual is the only node that can have Geometry and other Visual children. More...
 
class  WireBox
 Draws a wireframe box. More...
 

Typedefs

typedef shared_ptr< ArrowVisualArrowVisualPtr
 Shared pointer to ArrowVisual. More...
 
typedef shared_ptr< AxisVisualAxisVisualPtr
 Shared pointer to AxisVisual. More...
 
typedef shared_ptr< BaseNodeCompositeStoreBaseNodeCompositeStorePtr
 
typedef std::shared_ptr< BaseObjectBaseObjectPtr
 
typedef shared_ptr< BoundingBoxCameraBoundingBoxCameraPtr
 Shared pointer to BoundingBoxCamera. More...
 
typedef shared_ptr< CameraCameraPtr
 Shared pointer to Camera. More...
 
typedef shared_ptr< CapsuleCapsulePtr
 Shared pointer to Capsule. More...
 
typedef shared_ptr< COMVisualCOMVisualPtr
 Shared pointer to COMVisual. More...
 
typedef shared_ptr< const ArrowVisualConstArrowVisualPtr
 
typedef shared_ptr< const AxisVisualConstAxisVisualPtr
 
typedef shared_ptr< const BoundingBoxCameraConstBoundingBoxCameraPtr
 
typedef shared_ptr< const CameraConstCameraPtr
 
typedef shared_ptr< const DepthCameraConstDepthCameraPtr
 
typedef shared_ptr< const DirectionalLightConstDirectionalLightPtr
 
typedef shared_ptr< const GaussianNoisePassConstGaussianNoisePass
 Shared pointer to const GaussianNoisePass. More...
 
typedef shared_ptr< const GeometryConstGeometryPtr
 
typedef shared_ptr< const GizmoVisualConstGizmoVisualPtr
 
typedef shared_ptr< const GpuRaysConstGpuRaysPtr
 
typedef shared_ptr< const HeightmapConstHeightmapPtr
 
typedef shared_ptr< const ImageConstImagePtr
 
typedef shared_ptr< const JointVisualConstJointVisualPtr
 
typedef shared_ptr< const LidarVisualConstLidarVisualPtr
 
typedef shared_ptr< const LightConstLightPtr
 
typedef shared_ptr< const MaterialConstMaterialPtr
 
typedef shared_ptr< const MeshConstMeshPtr
 
typedef shared_ptr< const NodeConstNodePtr
 
typedef shared_ptr< const ObjectFactory > ConstObjectFactoryPtr
 
typedef shared_ptr< const ObjectConstObjectPtr
 
typedef shared_ptr< const ParticleEmitterConstParticleEmitterPtr
 
typedef shared_ptr< const PointLightConstPointLightPtr
 
typedef shared_ptr< const RayQueryConstRayQueryPtr
 
typedef shared_ptr< const RenderPassConstRenderPassPtr
 
typedef shared_ptr< const RenderPassSystemConstRenderPassSystemPtr
 
typedef shared_ptr< const RenderTargetConstRenderTargetPtr
 
typedef shared_ptr< const RenderTextureConstRenderTexturePtr
 
typedef shared_ptr< const RenderWindowConstRenderWindowPtr
 
typedef shared_ptr< const SceneConstScenePtr
 
typedef shared_ptr< const SegmentationCameraConstSegmentationCameraPtr
 
typedef shared_ptr< const SensorConstSensorPtr
 
typedef shared_ptr< const ShaderParamsConstShaderParamsPtr
 Shared pointer to const ShaderParams. More...
 
typedef shared_ptr< const SpotLightConstSpotLightPtr
 
typedef shared_ptr< const SubMeshConstSubMeshPtr
 
typedef shared_ptr< const TextConstTextPtr
 
typedef shared_ptr< const ThermalCameraConstThermalCameraPtr
 
typedef shared_ptr< const VisualConstVisualPtr
 
typedef shared_ptr< DepthCameraDepthCameraPtr
 Shared pointer to DepthCamera. More...
 
typedef shared_ptr< DirectionalLightDirectionalLightPtr
 Shared pointer to DirectionalLight. More...
 
typedef shared_ptr< DistortionPassDistortionPassPtr
 Shared pointer to DistortionPass. More...
 
typedef shared_ptr< GaussianNoisePassGaussianNoisePassPtr
 Shared pointer to GaussianNoisePass. More...
 
typedef shared_ptr< GeometryGeometryPtr
 Shared pointer to Geometry. More...
 
typedef Store< GeometryGeometryStore
 
typedef std::shared_ptr< GeometryStoreGeometryStorePtr
 
typedef shared_ptr< GizmoVisualGizmoVisualPtr
 Shared pointer to GizmoVisual. More...
 
typedef shared_ptr< GpuRaysGpuRaysPtr
 Shared pointer to GpuRays. More...
 
typedef shared_ptr< GridGridPtr
 Shared pointer to Grid. More...
 
typedef shared_ptr< HeightmapHeightmapPtr
 Shared pointer to Heightmap. More...
 
typedef shared_ptr< ImageImagePtr
 Shared pointer to Image. More...
 
typedef shared_ptr< InertiaVisualInertiaVisualPtr
 
typedef shared_ptr< JointVisualJointVisualPtr
 Shared pointer to JointVisual. More...
 
typedef shared_ptr< LidarVisualLidarVisualPtr
 Shared pointer to LidarVisual. More...
 
typedef shared_ptr< LightLightPtr
 Shared pointer to Light. More...
 
typedef Store< LightLightStore
 
typedef std::shared_ptr< LightStoreLightStorePtr
 
typedef shared_ptr< LightVisualLightVisualPtr
 Shared pointer to Light. More...
 
typedef shared_ptr< MarkerMarkerPtr
 Shared pointer to Marker. More...
 
typedef Map< MaterialMaterialMap
 
typedef std::shared_ptr< MaterialMapMaterialMapPtr
 
typedef shared_ptr< MaterialMaterialPtr
 Shared pointer to Material. More...
 
typedef shared_ptr< MeshMeshPtr
 Shared pointer to Mesh. More...
 
typedef CompositeStore< NodeNodeCompositeStore
 
typedef std::shared_ptr< NodeCompositeStoreNodeCompositeStorePtr
 
typedef shared_ptr< NodeNodePtr
 Shared pointer to Node. More...
 
typedef Store< NodeNodeStore
 
typedef std::shared_ptr< NodeStoreNodeStorePtr
 
typedef shared_ptr< ObjectFactory > ObjectFactoryPtr
 Shared pointer to ObjectFactory. More...
 
typedef shared_ptr< ObjectObjectPtr
 Shared pointer to Object. More...
 
typedef shared_ptr< OgreArrowVisualOgreArrowVisualPtr
 
typedef shared_ptr< OgreAxisVisualOgreAxisVisualPtr
 
typedef shared_ptr< OgreCameraOgreCameraPtr
 
typedef shared_ptr< OgreCapsuleOgreCapsulePtr
 
typedef shared_ptr< OgreCOMVisualOgreCOMVisualPtr
 
typedef shared_ptr< OgreDepthCameraOgreDepthCameraPtr
 
typedef shared_ptr< OgreDirectionalLightOgreDirectionalLightPtr
 
typedef shared_ptr< OgreGeometryOgreGeometryPtr
 
typedef BaseGeometryStore< OgreGeometryOgreGeometryStore
 
typedef shared_ptr< OgreGeometryStoreOgreGeometryStorePtr
 
typedef shared_ptr< OgreGizmoVisualOgreGizmoVisualPtr
 
typedef shared_ptr< OgreGpuRaysOgreGpuRaysPtr
 
typedef shared_ptr< OgreGridOgreGridPtr
 
typedef shared_ptr< OgreHeightmapOgreHeightmapPtr
 
typedef shared_ptr< OgreInertiaVisualOgreInertiaVisualPtr
 
typedef shared_ptr< OgreJointVisualOgreJointVisualPtr
 
typedef shared_ptr< OgreLidarVisualOgreLidarVisualPtr
 
typedef shared_ptr< OgreLightOgreLightPtr
 
typedef BaseLightStore< OgreLightOgreLightStore
 
typedef shared_ptr< OgreLightStoreOgreLightStorePtr
 
typedef shared_ptr< OgreLightVisualOgreLightVisualPtr
 
typedef shared_ptr< OgreMarkerOgreMarkerPtr
 
typedef BaseMaterialMap< OgreMaterialOgreMaterialMap
 
typedef shared_ptr< OgreMaterialMapOgreMaterialMapPtr
 
typedef shared_ptr< OgreMaterialOgreMaterialPtr
 
typedef shared_ptr< OgreMeshFactoryOgreMeshFactoryPtr
 
typedef shared_ptr< OgreMeshOgreMeshPtr
 
typedef shared_ptr< OgreNodeOgreNodePtr
 
typedef BaseNodeStore< OgreNodeOgreNodeStore
 
typedef shared_ptr< OgreNodeStoreOgreNodeStorePtr
 
typedef shared_ptr< OgreObjectOgreObjectPtr
 
typedef shared_ptr< OgreParticleEmitterOgreParticleEmitterPtr
 
typedef shared_ptr< OgrePointLightOgrePointLightPtr
 
typedef shared_ptr< OgreRayQueryOgreRayQueryPtr
 
typedef shared_ptr< OgreRenderEngineOgreRenderEnginePtr
 
typedef shared_ptr< OgreRenderTargetMaterialOgreRenderTargetMaterialPtr
 
typedef shared_ptr< OgreRenderTargetOgreRenderTargetPtr
 
typedef shared_ptr< OgreRenderTextureOgreRenderTexturePtr
 
typedef shared_ptr< OgreRenderWindowOgreRenderWindowPtr
 
typedef shared_ptr< OgreSceneOgreScenePtr
 
typedef BaseSceneStore< OgreSceneOgreSceneStore
 
typedef shared_ptr< OgreSceneStoreOgreSceneStorePtr
 
typedef shared_ptr< OgreSensorOgreSensorPtr
 
typedef BaseSensorStore< OgreSensorOgreSensorStore
 
typedef shared_ptr< OgreSensorStoreOgreSensorStorePtr
 
typedef shared_ptr< OgreSpotLightOgreSpotLightPtr
 
typedef shared_ptr< OgreSubMeshOgreSubMeshPtr
 
typedef BaseSubMeshStore< OgreSubMeshOgreSubMeshStore
 
typedef shared_ptr< OgreSubMeshStoreOgreSubMeshStorePtr
 
typedef shared_ptr< OgreTextOgreTextPtr
 
typedef shared_ptr< OgreThermalCameraOgreThermalCameraPtr
 
typedef shared_ptr< OgreVisualOgreVisualPtr
 
typedef BaseVisualStore< OgreVisualOgreVisualStore
 
typedef shared_ptr< OgreVisualStoreOgreVisualStorePtr
 
typedef shared_ptr< OgreWireBoxOgreWireBoxPtr
 
typedef shared_ptr< ParticleEmitterParticleEmitterPtr
 Shared pointer to ParticleEmitter. More...
 
typedef shared_ptr< PointLightPointLightPtr
 Shared pointer to PointLight. More...
 
typedef shared_ptr< RayQueryRayQueryPtr
 Shared pointer to RayQuery. More...
 
typedef shared_ptr< RenderPassRenderPassPtr
 Shared pointer to RenderPass. More...
 
typedef shared_ptr< RenderPassSystemRenderPassSystemPtr
 Shared pointer to RenderPassSystem. More...
 
typedef shared_ptr< RenderTargetRenderTargetPtr
 Shared pointer to RenderTarget. More...
 
typedef shared_ptr< RenderTextureRenderTexturePtr
 Shared pointer to RenderTexture. More...
 
typedef shared_ptr< RenderWindowRenderWindowPtr
 Shared pointer to RenderWindow. More...
 
typedef shared_ptr< SceneScenePtr
 Shared pointer to Scene. More...
 
typedef Store< SceneSceneStore
 
typedef std::shared_ptr< SceneStoreSceneStorePtr
 
typedef shared_ptr< SegmentationCameraSegmentationCameraPtr
 Shared pointer to Segmentation Camera. More...
 
typedef shared_ptr< SensorSensorPtr
 Shared pointer to Sensor. More...
 
typedef Store< SensorSensorStore
 
typedef std::shared_ptr< SensorStoreSensorStorePtr
 
typedef shared_ptr< ShaderParamsShaderParamsPtr
 Shared pointer to ShaderParams. More...
 
template<class T >
using shared_ptr = std::shared_ptr< T >
 
typedef shared_ptr< SpotLightSpotLightPtr
 Shared pointer to SpotLight. More...
 
typedef shared_ptr< SubMeshSubMeshPtr
 Shared pointer to SubMesh. More...
 
typedef Store< SubMeshSubMeshStore
 
typedef std::shared_ptr< SubMeshStoreSubMeshStorePtr
 
typedef shared_ptr< TextTextPtr
 Shared pointer to Text. More...
 
typedef shared_ptr< ThermalCameraThermalCameraPtr
 Shared pointer to ThermalCamera. More...
 
using Variant = std::variant< std::monostate, int, float, double, std::string, bool, unsigned int >
 Alias for a variant that can hold various types of data. The first type of the variant is std::monostate in order to prevent default-constructed variants from holding a type (a default-constructed variant is returned when a user calls Node::UserData with a key that doesn't exist for the node. In this case, since the key doesn't exist, the variant that is returned shouldn't hold any types - an "empty variant" should be returned for keys that don't exist) More...
 
typedef shared_ptr< VisualVisualPtr
 Shared pointer to Visual. More...
 
typedef Store< VisualVisualStore
 
typedef std::shared_ptr< VisualStoreVisualStorePtr
 
typedef shared_ptr< WireBoxWireBoxPtr
 Shared pointer to WireBox. More...
 

Enumerations

enum  BoundingBoxType { BBT_FULLBOX2D = 0, BBT_VISIBLEBOX2D = 1, BBT_BOX3D = 2 }
 BoundingBox types for Visible / Full 2D Boxes / 3D Boxes. More...
 
enum  CameraProjectionType { CPT_PERSPECTIVE, CPT_ORTHOGRAPHIC }
 Enum for projection types. More...
 
enum  EmitterType {
  EM_POINT = 0, EM_BOX = 1, EM_CYLINDER = 2, EM_ELLIPSOID = 3,
  EM_NUM_EMITTERS = 4
}
 Enum for emitter types. More...
 
enum  GraphicsAPI : uint16_t {
  GRAPHICS_API_BEGIN = 0, UNKNOWN = GRAPHICS_API_BEGIN, OPENGL = 1, DIRECT3D11 = 2,
  VULKAN = 3, METAL = 4, GRAPHICS_API_END
}
 The graphics API used by the render engine. More...
 
enum  JointVisualType {
  JVT_NONE = 0, JVT_REVOLUTE = 1, JVT_REVOLUTE2 = 2, JVT_PRISMATIC = 3,
  JVT_UNIVERSAL = 4, JVT_BALL = 5, JVT_SCREW = 6, JVT_GEARBOX = 7,
  JVT_FIXED = 8
}
 Enum for JointVisual types. More...
 
enum  LidarVisualType { LVT_NONE = 0, LVT_RAY_LINES = 1, LVT_POINTS = 2, LVT_TRIANGLE_STRIPS = 3 }
 Enum for LidarVisual types. More...
 
enum  LightVisualType { LVT_EMPTY = 0, LVT_POINT = 1, LVT_DIRECTIONAL = 2, LVT_SPOT = 3 }
 Enum for LightVisual types. More...
 
enum  MarkerType {
  MT_NONE = 0, MT_BOX = 1, MT_CYLINDER = 2, MT_LINE_STRIP = 3,
  MT_LINE_LIST = 4, MT_POINTS = 5, MT_SPHERE = 6, MT_TEXT = 7,
  MT_TRIANGLE_FAN = 8, MT_TRIANGLE_LIST = 9, MT_TRIANGLE_STRIP = 10, MT_CAPSULE = 11
}
 Enum for marker types. More...
 
enum  MaterialType { MT_CLASSIC = 0, MT_PBS = 1 }
 An enum for the type of material. More...
 
enum  PixelFormat {
  PF_UNKNOWN = 0, PF_L8 = 1, PF_R8G8B8 = 2, PF_B8G8R8 = 3,
  PF_BAYER_RGGB8 = 4, PF_BAYER_BGGR8 = 5, PF_BAYER_GBGR8 = 6, PF_BAYER_GRGB8 = 7,
  PF_FLOAT32_R = 8, PF_FLOAT32_RGBA = 9, PF_FLOAT32_RGB = 10, PF_L16 = 11,
  PF_R8G8B8A8 = 12, PF_COUNT = 13
}
 Image pixel format types. More...
 
enum  SegmentationType { ST_SEMANTIC = 0, ST_PANOPTIC = 1 }
 Segmentation types for Semantic / Panpoptic segmentation. More...
 
enum  ShaderType {
  ST_UNKNOWN = 0, ST_PIXEL = 1, ST_VERTEX = 2, ST_NORM_OBJ = 3,
  ST_NORM_TAN = 4, ST_COUNT = 5
}
 Available types of shaders. Note that not all rendering-engines will be able to use each type. They will instead default to the closest alternative. More...
 
enum  TextHorizontalAlign { LEFT = 0, CENTER = 1, RIGHT = 2 }
 Text Horizontal alignment. More...
 
enum  TextVerticalAlign { BOTTOM = 0, CENTER = 1, TOP = 2 }
 Text vertical alignment. More...
 
enum  TransformAxis {
  TA_NONE = 0, TA_TRANSLATION_X = 0x00000001, TA_TRANSLATION_Y = 0x00000002, TA_TRANSLATION_Z = 0x00000004,
  TA_ROTATION_X = 0x00000010, TA_ROTATION_Y = 0x00000020, TA_ROTATION_Z = 0x00000040, TA_SCALE_X = 0x00000100,
  TA_SCALE_Y = 0x00000200, TA_SCALE_Z = 0x00000400
}
 Unique identifiers for transformation axes. More...
 
enum  TransformMode {
  TM_NONE = 0, TM_TRANSLATION = TA_TRANSLATION_X | TA_TRANSLATION_Y | TA_TRANSLATION_Z, TM_ROTATION = TA_ROTATION_X | TA_ROTATION_Y | TA_ROTATION_Z, TM_SCALE = TA_SCALE_X | TA_SCALE_Y,
  TA_SCALEZ
}
 Unique identifiers for transformation modes. More...
 
enum  TransformSpace { TS_LOCAL, TS_WORLD }
 Unique identifiers for transformation spaces. More...
 

Functions

RenderEngineengine (const std::string &_name, const std::map< std::string, std::string > &_params={}, const std::string &_path="")
 Get the render-engine registered under the given name. If no render-engine is registered under the given name, NULL will be returned. If the engine is registered, but not loaded, this function will load it. More...
 
RenderEngineengine (const unsigned int _index, const std::map< std::string, std::string > &_params={}, const std::string &_path="")
 Get the render-engine registered at the given index. If no render-engine is registered at the given index, NULL will be returned. If the engine is registered, but not loaded, this function will load it. More...
 
unsigned int engineCount ()
 Get the number of available render-engines. More...
 
bool fini ()
 Destroy all render-engines and related resources. More...
 
bool hasEngine (const std::string &_name)
 Determine if a render-engine is registered under the given name. More...
 
bool init ()
 Initialized shared render-engine features. More...
 
bool isEngineLoaded (const std::string &_name)
 Determine if a render-engine is already loaded. More...
 
bool load ()
 Load shared render-engine resources. More...
 
std::vector< std::stringloadedEngines ()
 Get the names of all engines currently loaded. More...
 
void registerEngine (const std::string &_name, RenderEngine *_engine)
 Register a new render-engine under the given name. If the given name is already in use, the render-engine will not be registered. More...
 
ScenePtr sceneFromFirstRenderEngine ()
 Most applications will only have one rendering engine loaded at a time, and only one scene within that. This helper function gets the first scene that can be found in the first loaded rendering engine. More...
 
float screenScalingFactor ()
 Get the screen scaling factor. More...
 
math::Vector3d screenToPlane (const math::Vector2i &_screenPos, const CameraPtr &_camera, const RayQueryPtr &_rayQuery, const float _offset=0.0)
 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 CameraPtr &_camera, const RayQueryPtr &_rayQuery, float _maxDistance=10.0)
 Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates. More...
 
math::Vector3d screenToScene (const math::Vector2i &_screenPos, const CameraPtr &_camera, const RayQueryPtr &_rayQuery, RayQueryResult &_rayResult, float _maxDistance=10.0)
 Retrieve the first point on a surface in the 3D scene hit by a ray cast from the given 2D screen coordinates. More...
 
void setPluginPaths (const std::list< std::string > &_paths)
 Set the plugin paths from which render engines can be loaded. More...
 
ignition::math::AxisAlignedBox transformAxisAlignedBox (const ignition::math::AxisAlignedBox &_box, const ignition::math::Pose3d &_pose)
 Transform a bounding box. More...
 
bool unloadEngine (const std::string &_name)
 Unload the render-engine registered under the given name. More...
 
void unregisterEngine (const std::string &_name)
 Unregister a render-engine registered under the given name. If the no render-engine is registered under the given name no work will be done. More...
 
void unregisterEngine (RenderEngine *_engine)
 Unregister the given render-engine. If the given render-engine is not currently registered, no work will be done. More...
 
void unregisterEngine (const unsigned int _index)
 Unregister a render-engine at the given index. If the no render-engine is registered at the given index, no work will be done. More...
 

Variables

const std::string depth_fragment_shader_file
 
const std::string depth_vertex_shader_file
 
static const common::Pbr kDefaultPbr
 Default pbr material properties. More...
 

Detailed Description

Rendering classes and function useful in robot applications.

Typedef Documentation

◆ ArrowVisualPtr

Shared pointer to ArrowVisual.

Shared pointer to const ArrowVisual.

◆ AxisVisualPtr

Shared pointer to AxisVisual.

Shared pointer to const AxisVisual.

◆ BaseNodeCompositeStorePtr

◆ BaseObjectPtr

◆ BoundingBoxCameraPtr

Shared pointer to BoundingBoxCamera.

Shared pointer to const BoundingBox Camera.

◆ CameraPtr

const CameraPtr

Shared pointer to Camera.

Shared pointer to const Camera.

◆ CapsulePtr

Shared pointer to Capsule.

◆ COMVisualPtr

Shared pointer to COMVisual.

◆ ConstArrowVisualPtr

◆ ConstAxisVisualPtr

◆ ConstBoundingBoxCameraPtr

◆ ConstCameraPtr

◆ ConstDepthCameraPtr

◆ ConstDirectionalLightPtr

◆ ConstGaussianNoisePass

Shared pointer to const GaussianNoisePass.

◆ ConstGeometryPtr

◆ ConstGizmoVisualPtr

◆ ConstGpuRaysPtr

◆ ConstHeightmapPtr

◆ ConstImagePtr

typedef shared_ptr<const Image> ConstImagePtr

◆ ConstJointVisualPtr

◆ ConstLidarVisualPtr

◆ ConstLightPtr

typedef shared_ptr<const Light> ConstLightPtr

◆ ConstMaterialPtr

◆ ConstMeshPtr

typedef shared_ptr<const Mesh> ConstMeshPtr

◆ ConstNodePtr

typedef shared_ptr<const Node> ConstNodePtr

◆ ConstObjectFactoryPtr

typedef shared_ptr<const ObjectFactory> ConstObjectFactoryPtr

◆ ConstObjectPtr

◆ ConstParticleEmitterPtr

◆ ConstPointLightPtr

◆ ConstRayQueryPtr

◆ ConstRenderPassPtr

◆ ConstRenderPassSystemPtr

◆ ConstRenderTargetPtr

◆ ConstRenderTexturePtr

◆ ConstRenderWindowPtr

◆ ConstScenePtr

typedef shared_ptr<const Scene> ConstScenePtr

◆ ConstSegmentationCameraPtr

◆ ConstSensorPtr

◆ ConstShaderParamsPtr

Shared pointer to const ShaderParams.

◆ ConstSpotLightPtr

◆ ConstSubMeshPtr

◆ ConstTextPtr

typedef shared_ptr<const Text> ConstTextPtr

◆ ConstThermalCameraPtr

◆ ConstVisualPtr

◆ DepthCameraPtr

Shared pointer to DepthCamera.

Shared pointer to const DepthCamera.

◆ DirectionalLightPtr

Shared pointer to DirectionalLight.

Shared pointer to const DirectionalLight.

◆ DistortionPassPtr

Shared pointer to DistortionPass.

◆ GaussianNoisePassPtr

◆ GeometryPtr

const GeometryPtr

Shared pointer to Geometry.

Shared pointer to const Geometry.

◆ GeometryStore

◆ GeometryStorePtr

◆ GizmoVisualPtr

Shared pointer to GizmoVisual.

Shared pointer to const GizmoVisual.

◆ GpuRaysPtr

const GpuRaysPtr

Shared pointer to GpuRays.

Shared pointer to const GpuRays.

◆ GridPtr

Shared pointer to Grid.

◆ HeightmapPtr

const HeightmapPtr

Shared pointer to Heightmap.

Shared pointer to const Heightmap.

◆ ImagePtr

const ImagePtr

Shared pointer to Image.

Shared pointer to const Image.

◆ InertiaVisualPtr

◆ JointVisualPtr

Shared pointer to JointVisual.

Shared pointer to const JointVisual.

◆ LidarVisualPtr

Shared pointer to LidarVisual.

Shared pointer to const LidarVisual.

◆ LightPtr

const LightPtr

Shared pointer to Light.

Shared pointer to const Light.

◆ LightStore

◆ LightStorePtr

◆ LightVisualPtr

Shared pointer to Light.

◆ MarkerPtr

Shared pointer to Marker.

◆ MaterialMap

◆ MaterialMapPtr

◆ MaterialPtr

const MaterialPtr

Shared pointer to Material.

Shared pointer to const Material.

◆ MeshPtr

const MeshPtr

Shared pointer to Mesh.

Shared pointer to const Mesh.

◆ NodeCompositeStore

◆ NodeCompositeStorePtr

◆ NodePtr

const NodePtr

Shared pointer to Node.

Shared pointer to const Node.

◆ NodeStore

typedef Store<Node> NodeStore

◆ NodeStorePtr

◆ ObjectFactoryPtr

Shared pointer to ObjectFactory.

Shared pointer to const ObjectFactory.

◆ ObjectPtr

const ObjectPtr

Shared pointer to Object.

Shared pointer to const Object.

◆ OgreArrowVisualPtr

◆ OgreAxisVisualPtr

◆ OgreCameraPtr

◆ OgreCapsulePtr

◆ OgreCOMVisualPtr

◆ OgreDepthCameraPtr

◆ OgreDirectionalLightPtr

◆ OgreGeometryPtr

◆ OgreGeometryStore

◆ OgreGeometryStorePtr

◆ OgreGizmoVisualPtr

◆ OgreGpuRaysPtr

◆ OgreGridPtr

◆ OgreHeightmapPtr

◆ OgreInertiaVisualPtr

◆ OgreJointVisualPtr

◆ OgreLidarVisualPtr

◆ OgreLightPtr

◆ OgreLightStore

◆ OgreLightStorePtr

◆ OgreLightVisualPtr

◆ OgreMarkerPtr

◆ OgreMaterialMap

◆ OgreMaterialMapPtr

◆ OgreMaterialPtr

◆ OgreMeshFactoryPtr

◆ OgreMeshPtr

◆ OgreNodePtr

◆ OgreNodeStore

◆ OgreNodeStorePtr

◆ OgreObjectPtr

◆ OgreParticleEmitterPtr

◆ OgrePointLightPtr

◆ OgreRayQueryPtr

◆ OgreRenderEnginePtr

◆ OgreRenderTargetMaterialPtr

◆ OgreRenderTargetPtr

◆ OgreRenderTexturePtr

◆ OgreRenderWindowPtr

◆ OgreScenePtr

◆ OgreSceneStore

◆ OgreSceneStorePtr

◆ OgreSensorPtr

◆ OgreSensorStore

◆ OgreSensorStorePtr

◆ OgreSpotLightPtr

◆ OgreSubMeshPtr

◆ OgreSubMeshStore

◆ OgreSubMeshStorePtr

◆ OgreTextPtr

◆ OgreThermalCameraPtr

◆ OgreVisualPtr

◆ OgreVisualStore

◆ OgreVisualStorePtr

◆ OgreWireBoxPtr

◆ ParticleEmitterPtr

Shared pointer to ParticleEmitter.

Shared pointer to const ParticleEmitter.

◆ PointLightPtr

Shared pointer to PointLight.

Shared pointer to const PointLight.

◆ RayQueryPtr

Shared pointer to RayQuery.

◆ RenderPassPtr

Shared pointer to RenderPass.

Shared pointer to const RenderPass.

◆ RenderPassSystemPtr

Shared pointer to RenderPassSystem.

Shared pointer to const RenderPassSystem.

◆ RenderTargetPtr

Shared pointer to RenderTarget.

Shared pointer to const RenderTarget.

◆ RenderTexturePtr

Shared pointer to RenderTexture.

Shared pointer to const RenderTexture.

◆ RenderWindowPtr

Shared pointer to RenderWindow.

Shared pointer to const RenderWindow.

◆ ScenePtr

const ScenePtr

Shared pointer to Scene.

Shared pointer to const Scene.

◆ SceneStore

◆ SceneStorePtr

◆ SegmentationCameraPtr

Shared pointer to Segmentation Camera.

Shared pointer to const Segmentation Camera.

◆ SensorPtr

const SensorPtr

Shared pointer to Sensor.

Shared pointer to const Sensor.

◆ SensorStore

◆ SensorStorePtr

◆ ShaderParamsPtr

Shared pointer to ShaderParams.

◆ shared_ptr

◆ SpotLightPtr

const SpotLightPtr

Shared pointer to SpotLight.

Shared pointer to const SpotLight.

◆ SubMeshPtr

const SubMeshPtr

Shared pointer to SubMesh.

Shared pointer to const SubMesh.

◆ SubMeshStore

◆ SubMeshStorePtr

◆ TextPtr

Shared pointer to Text.

◆ ThermalCameraPtr

Shared pointer to ThermalCamera.

Shared pointer to const ThermalCamera.

◆ Variant

using Variant = std::variant<std::monostate, int, float, double, std::string, bool, unsigned int>

Alias for a variant that can hold various types of data. The first type of the variant is std::monostate in order to prevent default-constructed variants from holding a type (a default-constructed variant is returned when a user calls Node::UserData with a key that doesn't exist for the node. In this case, since the key doesn't exist, the variant that is returned shouldn't hold any types - an "empty variant" should be returned for keys that don't exist)

◆ VisualPtr

const VisualPtr

Shared pointer to Visual.

Shared pointer to const Visual.

◆ VisualStore

◆ VisualStorePtr

◆ WireBoxPtr

Shared pointer to WireBox.

Enumeration Type Documentation

◆ BoundingBoxType

enum BoundingBoxType
strong

BoundingBox types for Visible / Full 2D Boxes / 3D Boxes.

Enumerator
BBT_FULLBOX2D 

2D box that shows the full box of occluded objects

BBT_VISIBLEBOX2D 

2D box that shows the visible part of the occluded object

BBT_BOX3D 

3D oriented box

◆ CameraProjectionType

Enum for projection types.

Enumerator
CPT_PERSPECTIVE 

Perspective projection.

CPT_ORTHOGRAPHIC 

Orthographic projection.

◆ EmitterType

Enum for emitter types.

Enumerator
EM_POINT 

Point emitter.

EM_BOX 

Box emitter.

EM_CYLINDER 

Cylinder emitter.

EM_ELLIPSOID 

Ellipsoid emitter.

EM_NUM_EMITTERS 

Total number of emitters (keep always at the end).

◆ GraphicsAPI

enum GraphicsAPI : uint16_t
strong

The graphics API used by the render engine.

Enumerator
GRAPHICS_API_BEGIN 
UNKNOWN 

Unknown graphics interface.

OPENGL 

OpenGL graphics interface.

DIRECT3D11 

Direct3D11 graphics interface.

VULKAN 

Vulkan graphics interface.

METAL 

Metal graphics interface.

GRAPHICS_API_END 

◆ JointVisualType

Enum for JointVisual types.

Enumerator
JVT_NONE 

No type.

JVT_REVOLUTE 

Revolute joint type.

JVT_REVOLUTE2 

Revolute2 joint type.

JVT_PRISMATIC 

Prismatic joint type.

JVT_UNIVERSAL 

Universal joint type.

JVT_BALL 

Ball joint type.

JVT_SCREW 

Screw joint type.

JVT_GEARBOX 

Gearbox joint type.

JVT_FIXED 

Fixed joint type.

◆ LidarVisualType

Enum for LidarVisual types.

Enumerator
LVT_NONE 

No type.

LVT_RAY_LINES 

Ray line visual.

LVT_POINTS 

Points visual.

LVT_TRIANGLE_STRIPS 

Triangle strips visual.

◆ LightVisualType

Enum for LightVisual types.

Enumerator
LVT_EMPTY 

No type.

LVT_POINT 

Point light.

LVT_DIRECTIONAL 

Directional light.

LVT_SPOT 

Spot light.

◆ MarkerType

enum MarkerType

Enum for marker types.

Enumerator
MT_NONE 

No type.

MT_BOX 

Box geometry.

MT_CYLINDER 

Cylinder geometry.

MT_LINE_STRIP 

Line strip primitive.

MT_LINE_LIST 

Line list primitive.

MT_POINTS 

Points primitive.

MT_SPHERE 

Sphere geometry.

MT_TEXT 

Text geometry.

MT_TRIANGLE_FAN 

Triangle fan primitive.

MT_TRIANGLE_LIST 

Triangle list primitive.

MT_TRIANGLE_STRIP 

Triangle strip primitive.

MT_CAPSULE 

Capsule geometry.

◆ MaterialType

An enum for the type of material.

Enumerator
MT_CLASSIC 

Classic shading, i.e. variants of Phong.

MT_PBS 

Physically Based Shading.

◆ PixelFormat

Image pixel format types.

PixelFormat.hh ignition/rendering/PixelFormat.hh

Enumerator
PF_UNKNOWN 

< Unknown or errant type

PF_L8 

< Grayscale, 1-byte per channel

PF_R8G8B8 

< RGB, 1-byte per channel

PF_B8G8R8 

< BGR, 1-byte per channel

PF_BAYER_RGGB8 

< Bayer RGGB, 1-byte per channel

PF_BAYER_BGGR8 

< Bayer BGGR, 1-byte per channel

PF_BAYER_GBGR8 

< Bayer GBGR, 1-byte per channel

PF_BAYER_GRGB8 

< Bayer GRGB, 1-byte per channel

PF_FLOAT32_R 
PF_FLOAT32_RGBA 
PF_FLOAT32_RGB 
PF_L16 
PF_R8G8B8A8 

< RGBA, 1-byte per channel

PF_COUNT 

< Number of pixel format types

◆ SegmentationType

enum SegmentationType
strong

Segmentation types for Semantic / Panpoptic segmentation.

Enumerator
ST_SEMANTIC 

Pixels of same label from different items have the same color & id.

ST_PANOPTIC 

Pixels of same label from different items, have different color & id. 1 channel for label id & 2 channels for instance id.

◆ ShaderType

enum ShaderType

Available types of shaders. Note that not all rendering-engines will be able to use each type. They will instead default to the closest alternative.

ShaderType.hh ignition/rendering/ShaderType.hh

Enumerator
ST_UNKNOWN 

Unknown or errant type.

ST_PIXEL 

Per pixel lighting shader.

ST_VERTEX 

Per vertex lighting shader.

ST_NORM_OBJ 

Object-space normal map shader.

ST_NORM_TAN 

Tangent-space normal map shader.

ST_COUNT 

Total number of shader types.

◆ TextHorizontalAlign

enum TextHorizontalAlign
strong

Text Horizontal alignment.

Enumerator
LEFT 

Left alignment.

CENTER 

Center alignment.

RIGHT 

Right alignment.

◆ TextVerticalAlign

enum TextVerticalAlign
strong

Text vertical alignment.

Enumerator
BOTTOM 

Align bottom.

CENTER 

Align center.

TOP 

Align top.

◆ TransformAxis

Unique identifiers for transformation axes.

Enumerator
TA_NONE 

No axis.

TA_TRANSLATION_X 

Translation in x.

TA_TRANSLATION_Y 

Translation in y.

TA_TRANSLATION_Z 

Translation in z.

TA_ROTATION_X 

Rotation in x.

TA_ROTATION_Y 

Rotation in y.

TA_ROTATION_Z 

Rotation in z.

TA_SCALE_X 

Scale in x.

TA_SCALE_Y 

Scale in y.

TA_SCALE_Z 

Scale in z.

◆ TransformMode

Unique identifiers for transformation modes.

Enumerator
TM_NONE 

Inactive state.

TM_TRANSLATION 

Translation mode.

TM_ROTATION 

Rotation mode.

TM_SCALE 

Scale mode.

TA_SCALEZ 

◆ TransformSpace

Unique identifiers for transformation spaces.

Enumerator
TS_LOCAL 

transformation in local frame

TS_WORLD 

transformation in world frame

Function Documentation

◆ engine() [1/2]

RenderEngine* ignition::rendering::engine ( const std::string _name,
const std::map< std::string, std::string > &  _params = {},
const std::string _path = "" 
)

Get the render-engine registered under the given name. If no render-engine is registered under the given name, NULL will be returned. If the engine is registered, but not loaded, this function will load it.

Parameters
[in]_nameName of the desired render-engine
[in]_paramsParameters to be passed to the render engine.
[in]_pathAnother search path for rendering engine plugin.
Returns
The specified render-engine

◆ engine() [2/2]

RenderEngine* ignition::rendering::engine ( const unsigned int  _index,
const std::map< std::string, std::string > &  _params = {},
const std::string _path = "" 
)

Get the render-engine registered at the given index. If no render-engine is registered at the given index, NULL will be returned. If the engine is registered, but not loaded, this function will load it.

Parameters
[in]_indexIndex of the desired render-engine
[in]_paramsParameters to be passed to the render engine.
[in]_pathAnother search path for rendering engine plugin.
Returns
The specified render-engine

◆ engineCount()

unsigned int ignition::rendering::engineCount ( )

Get the number of available render-engines.

Returns
The number of available render-engines

◆ fini()

bool ignition::rendering::fini ( )

Destroy all render-engines and related resources.

Returns
True if successful

◆ hasEngine()

bool ignition::rendering::hasEngine ( const std::string _name)

Determine if a render-engine is registered under the given name.

Parameters
[in]_nameName of the desired render-engine
Returns
True if a render-engine is registered under the given name

◆ init()

bool ignition::rendering::init ( )

Initialized shared render-engine features.

Returns
True if successful

◆ isEngineLoaded()

bool ignition::rendering::isEngineLoaded ( const std::string _name)

Determine if a render-engine is already loaded.

Parameters
[in]_nameName of the desired render-engine
Returns
True if a render-engine is loaded under the given name

◆ load()

bool ignition::rendering::load ( )

Load shared render-engine resources.

Returns
True if successful

◆ loadedEngines()

std::vector<std::string> ignition::rendering::loadedEngines ( )

Get the names of all engines currently loaded.

Returns
All the engines currently loaded.

◆ registerEngine()

void ignition::rendering::registerEngine ( const std::string _name,
RenderEngine _engine 
)

Register a new render-engine under the given name. If the given name is already in use, the render-engine will not be registered.

Parameters
[in]_nameName the render-engine will be registered under
[in]_engineRender-engine to be registered

◆ sceneFromFirstRenderEngine()

ScenePtr ignition::rendering::sceneFromFirstRenderEngine ( )

Most applications will only have one rendering engine loaded at a time, and only one scene within that. This helper function gets the first scene that can be found in the first loaded rendering engine.

It's not recommended to call this function when there's more than one engine or scene.

Returns
Pointer to a scene that was found, null if no scene is loaded.

◆ screenScalingFactor()

float ignition::rendering::screenScalingFactor ( )

Get the screen scaling factor.

Returns
The screen scaling factor.

◆ screenToPlane()

math::Vector3d ignition::rendering::screenToPlane ( const math::Vector2i _screenPos,
const CameraPtr _camera,
const RayQueryPtr _rayQuery,
const float  _offset = 0.0 
)

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]_screenPos2D coordinates on the screen, in pixels.
[in]_cameraUser camera
[in]_rayQueryRay query for mouse clicks
[in]_offsetOffset along the plane normal
Returns
3D coordinates of a point in the 3D scene.

◆ screenToScene() [1/2]

math::Vector3d ignition::rendering::screenToScene ( const math::Vector2i _screenPos,
const CameraPtr _camera,
const RayQueryPtr _rayQuery,
float  _maxDistance = 10.0 
)

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.
[in]_cameraUser camera
[in]_rayQueryRay query for mouse clicks
[in]_maxDistancemaximum distance to check the collision
Returns
3D coordinates of a point in the 3D scene.

◆ screenToScene() [2/2]

math::Vector3d ignition::rendering::screenToScene ( const math::Vector2i _screenPos,
const CameraPtr _camera,
const RayQueryPtr _rayQuery,
RayQueryResult _rayResult,
float  _maxDistance = 10.0 
)

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.
[in]_cameraUser camera
[in]_rayQueryRay query for mouse clicks
[in,out]_rayResultRay query result
[in]_maxDistancemaximum distance to check the collision
Returns
3D coordinates of a point in the 3D scene.

◆ setPluginPaths()

void ignition::rendering::setPluginPaths ( const std::list< std::string > &  _paths)

Set the plugin paths from which render engines can be loaded.

Parameters
[in]_pathsThe list of the plugin paths

◆ transformAxisAlignedBox()

ignition::math::AxisAlignedBox ignition::rendering::transformAxisAlignedBox ( const ignition::math::AxisAlignedBox _box,
const ignition::math::Pose3d _pose 
)

Transform a bounding box.

Parameters
[in]_boxThe bounding box.
[in]_posePose used to transform the bounding box.
Returns
Vertices of the transformed bounding box in world coordinates.

◆ unloadEngine()

bool ignition::rendering::unloadEngine ( const std::string _name)

Unload the render-engine registered under the given name.

Parameters
[in]_nameName of the desired render-engine
Returns
True if the engine is unloaded

◆ unregisterEngine() [1/3]

void ignition::rendering::unregisterEngine ( const std::string _name)

Unregister a render-engine registered under the given name. If the no render-engine is registered under the given name no work will be done.

Parameters
[in]_nameName of the render-engine to unregister

◆ unregisterEngine() [2/3]

void ignition::rendering::unregisterEngine ( RenderEngine _engine)

Unregister the given render-engine. If the given render-engine is not currently registered, no work will be done.

Parameters
[in]_engineRender-engine to unregister

◆ unregisterEngine() [3/3]

void ignition::rendering::unregisterEngine ( const unsigned int  _index)

Unregister a render-engine at the given index. If the no render-engine is registered at the given index, no work will be done.

Parameters
[in]_indexIndex of the render-engine to unregister

Variable Documentation

◆ depth_fragment_shader_file

const std::string depth_fragment_shader_file
Initial value:
=
"depth_fragment_shader.glsl"

◆ depth_vertex_shader_file

const std::string depth_vertex_shader_file
Initial value:
=
"depth_vertex_shader.glsl"

◆ kDefaultPbr

const common::Pbr kDefaultPbr
static

Default pbr material properties.

Referenced by BaseMaterial< OgreObject >::CopyFrom().