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 | BaseCamera |
class | BaseCompositeStore |
class | BaseDepthCamera |
class | BaseDirectionalLight |
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 | BaseLight |
class | BaseLightStore |
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 | 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 | 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 | Camera |
Posable camera used for rendering the scene graph. 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 | DepthCamera |
class | DirectionalLight |
Represents a infinite directional light. 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 | Grid |
Represents a grid geometry drawn along the XY plane. If vertical cell count is specified then the grid becomes 3D. More... | |
class | Image |
Encapsulates a raw image buffer and relevant properties. More... | |
class | Light |
Represents a light source in the scene graph. 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 | Ogre2ArrowVisual |
class | Ogre2AxisVisual |
class | Ogre2Camera |
Ogre2.x implementation of the camera class. More... | |
class | Ogre2Conversions |
Conversions Conversions.hh rendering/Conversions.hh. More... | |
class | Ogre2DepthCamera |
Depth camera used to render depth data into an image buffer. More... | |
class | Ogre2DirectionalLight |
Ogre 2.x implementation of the directional light class. More... | |
class | Ogre2DynamicRenderable |
Dynamic renderable class that manages hardware buffers for a dynamic geometry. More... | |
class | Ogre2GaussianNoisePass |
Ogre2 Implementation of a Gaussian noise render pass. More... | |
class | Ogre2Geometry |
Ogre2.x implementation of the geometry class. More... | |
class | Ogre2GizmoVisual |
class | Ogre2GpuRays |
Gpu Rays used to render range data into an image buffer The ogre2 implementation takes a 2 pass process to generate the final range data. 1st Pass: Creates a cubemap of range data. The cubemap is created from six cameras looking in all directions. Depending on the min/max angles specified, not all cameras need to be created. Internally in the 1st pass shaders, we reconstruct 3d viewspace pos from depth buffer data then convert them into ranges, i.e. length(pos.xyz). 2nd Pass: Samples range data from cubemap using predefined rays. The rays are generated based on the specified vertical and horizontal min/max angles and no. of samples. Each ray is a direction vector that is used to sample/lookup the range data stored in the faces of the cubemap. More... | |
class | Ogre2Grid |
Ogre2 implementation of a grid geometry. More... | |
class | Ogre2Light |
Ogre 2.x implementation of the light class. More... | |
class | Ogre2Marker |
Ogre 2.x implementation of a marker geometry. More... | |
class | Ogre2Material |
Ogre 2.x implementation of the material class. More... | |
class | Ogre2MaterialSwitcher |
Helper class to assign unique colors to renderables. More... | |
class | Ogre2Mesh |
Ogre2.x implementation of the mesh class. More... | |
class | Ogre2MeshFactory |
Ogre2.x implementation of the mesh factory class. More... | |
class | Ogre2Node |
Ogre2.x implementation of the Node class. More... | |
class | Ogre2Object |
Ogre2.x implementation of the Object class. More... | |
class | Ogre2PointLight |
Ogre 2.x implementation of the point light class. More... | |
class | Ogre2RayQuery |
A Ray Query class used for computing ray object intersections. More... | |
class | Ogre2RenderEngine |
Ogre2 render engine class. A singleton class that manages the underlying ogre2 render engine, loads its plugins, and creates resources needed for the engine to run. More... | |
class | Ogre2RenderEnginePlugin |
Plugin for loading ogre render engine. More... | |
class | Ogre2RenderPass |
Ogre2 Implementation of a render pass. More... | |
class | Ogre2RenderTarget |
Ogre2.x implementation of the render target class. More... | |
class | Ogre2RenderTargetMaterial |
Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget. More... | |
class | Ogre2RenderTexture |
Ogre2.x implementation of the render texture class. More... | |
class | Ogre2RenderWindow |
Ogre2.x implementation of the render window class. More... | |
class | Ogre2Scene |
Ogre2.x implementation of the scene class. More... | |
class | Ogre2SelectionBuffer |
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 | Ogre2Sensor |
Ogre2.x implementation of the sensor classs. More... | |
class | Ogre2SpotLight |
Ogre 2.x implementation of the spot light class. More... | |
class | Ogre2SubMesh |
Ogre2.x implementation of the submesh class. More... | |
class | Ogre2SubMeshStoreFactory |
Ogre2.x implementation of a submesh store factory class. More... | |
class | Ogre2ThermalCamera |
Thermal camera used to render thermal data into an image buffer. More... | |
class | Ogre2Visual |
Ogre2.x implementation of the visual class. More... | |
class | OgreArrowVisual |
class | OgreAxisVisual |
class | OgreCamera |
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 | 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 | OgreLight |
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 | 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 | OrbitViewController |
A camera view controller. 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 | 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... | |
Enumerations | |
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 } |
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_COUNT = 12 } |
Image pixel format types. 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 | |
RenderEngine * | 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. More... | |
RenderEngine * | 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. 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::string > | loadedEngines () |
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... | |
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 (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... | |
void | unregisterEngine (RenderEngine *_engine) |
Unregister the given render-engine. If the given render-engine is not currently registered, 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
const ArrowVisualPtr |
Shared pointer to ArrowVisual.
Shared pointer to const ArrowVisual.
◆ AxisVisualPtr
const AxisVisualPtr |
Shared pointer to AxisVisual.
Shared pointer to const AxisVisual.
◆ BaseNodeCompositeStorePtr
◆ BaseObjectPtr
typedef std::shared_ptr<BaseObject> BaseObjectPtr |
◆ CameraPtr
◆ ConstArrowVisualPtr
typedef shared_ptr<const ArrowVisual> ConstArrowVisualPtr |
◆ ConstAxisVisualPtr
typedef shared_ptr<const AxisVisual> ConstAxisVisualPtr |
◆ ConstCameraPtr
typedef shared_ptr<const Camera> ConstCameraPtr |
◆ ConstDepthCameraPtr
typedef shared_ptr<const DepthCamera> ConstDepthCameraPtr |
◆ ConstDirectionalLightPtr
typedef shared_ptr<const DirectionalLight> ConstDirectionalLightPtr |
◆ ConstGaussianNoisePass
const ConstGaussianNoisePass |
Shared pointer to const GaussianNoisePass.
◆ ConstGeometryPtr
typedef shared_ptr<const Geometry> ConstGeometryPtr |
◆ ConstGizmoVisualPtr
typedef shared_ptr<const GizmoVisual> ConstGizmoVisualPtr |
◆ ConstGpuRaysPtr
typedef shared_ptr<const GpuRays> ConstGpuRaysPtr |
◆ ConstImagePtr
typedef shared_ptr<const Image> ConstImagePtr |
◆ ConstJointVisualPtr
typedef shared_ptr<const JointVisual> ConstJointVisualPtr |
◆ ConstLightPtr
typedef shared_ptr<const Light> ConstLightPtr |
◆ ConstMaterialPtr
typedef shared_ptr<const Material> ConstMaterialPtr |
◆ ConstMeshPtr
typedef shared_ptr<const Mesh> ConstMeshPtr |
◆ ConstNodePtr
typedef shared_ptr<const Node> ConstNodePtr |
◆ ConstObjectFactoryPtr
typedef shared_ptr<const ObjectFactory> ConstObjectFactoryPtr |
◆ ConstObjectPtr
typedef shared_ptr<const Object> ConstObjectPtr |
◆ ConstPointLightPtr
typedef shared_ptr<const PointLight> ConstPointLightPtr |
◆ ConstRayQueryPtr
typedef shared_ptr<const RayQuery> ConstRayQueryPtr |
◆ ConstRenderPassPtr
typedef shared_ptr<const RenderPass> ConstRenderPassPtr |
◆ ConstRenderPassSystemPtr
typedef shared_ptr<const RenderPassSystem> ConstRenderPassSystemPtr |
◆ ConstRenderTargetPtr
typedef shared_ptr<const RenderTarget> ConstRenderTargetPtr |
◆ ConstRenderTexturePtr
typedef shared_ptr<const RenderTexture> ConstRenderTexturePtr |
◆ ConstRenderWindowPtr
typedef shared_ptr<const RenderWindow> ConstRenderWindowPtr |
◆ ConstScenePtr
typedef shared_ptr<const Scene> ConstScenePtr |
◆ ConstSensorPtr
typedef shared_ptr<const Sensor> ConstSensorPtr |
◆ ConstShaderParamsPtr
typedef shared_ptr<const ShaderParams> ConstShaderParamsPtr |
Shared pointer to const ShaderParams.
◆ ConstSpotLightPtr
typedef shared_ptr<const SpotLight> ConstSpotLightPtr |
◆ ConstSubMeshPtr
typedef shared_ptr<const SubMesh> ConstSubMeshPtr |
◆ ConstTextPtr
typedef shared_ptr<const Text> ConstTextPtr |
◆ ConstThermalCameraPtr
typedef shared_ptr<const ThermalCamera> ConstThermalCameraPtr |
◆ ConstVisualPtr
typedef shared_ptr<const Visual> ConstVisualPtr |
◆ DepthCameraPtr
const DepthCameraPtr |
Shared pointer to DepthCamera.
Shared pointer to const DepthCamera.
◆ DirectionalLightPtr
const DirectionalLightPtr |
Shared pointer to DirectionalLight.
Shared pointer to const DirectionalLight.
◆ GaussianNoisePassPtr
Shared pointer to GaussianNoisePass.
◆ GeometryPtr
const GeometryPtr |
◆ GeometryStore
typedef Store<Geometry> GeometryStore |
◆ GeometryStorePtr
typedef std::shared_ptr<GeometryStore> GeometryStorePtr |
◆ GizmoVisualPtr
const GizmoVisualPtr |
Shared pointer to GizmoVisual.
Shared pointer to const GizmoVisual.
◆ GpuRaysPtr
const GpuRaysPtr |
◆ GridPtr
◆ ImagePtr
◆ JointVisualPtr
const JointVisualPtr |
Shared pointer to JointVisual.
Shared pointer to const JointVisual.
◆ LightPtr
◆ LightStore
typedef Store<Light> LightStore |
◆ LightStorePtr
typedef std::shared_ptr<LightStore> LightStorePtr |
◆ MarkerPtr
◆ MaterialMap
typedef Map<Material> MaterialMap |
◆ MaterialMapPtr
typedef std::shared_ptr<MaterialMap> MaterialMapPtr |
◆ MaterialPtr
const MaterialPtr |
◆ MeshPtr
◆ NodeCompositeStore
typedef CompositeStore<Node> NodeCompositeStore |
◆ NodeCompositeStorePtr
◆ NodePtr
◆ NodeStore
◆ NodeStorePtr
typedef std::shared_ptr<NodeStore> NodeStorePtr |
◆ ObjectFactoryPtr
const ObjectFactoryPtr |
Shared pointer to ObjectFactory.
Shared pointer to const ObjectFactory.
◆ ObjectPtr
◆ Ogre2ArrowVisualPtr
◆ Ogre2AxisVisualPtr
typedef shared_ptr<Ogre2AxisVisual> Ogre2AxisVisualPtr |
◆ Ogre2CameraPtr
typedef shared_ptr<Ogre2Camera> Ogre2CameraPtr |
◆ Ogre2DepthCameraPtr
◆ Ogre2DirectionalLightPtr
◆ Ogre2GeometryPtr
typedef shared_ptr<Ogre2Geometry> Ogre2GeometryPtr |
◆ Ogre2GeometryStore
typedef BaseGeometryStore< Ogre2Geometry > Ogre2GeometryStore |
◆ Ogre2GeometryStorePtr
◆ Ogre2GizmoVisualPtr
◆ Ogre2GpuRaysPtr
typedef shared_ptr<Ogre2GpuRays> Ogre2GpuRaysPtr |
◆ Ogre2GridPtr
typedef shared_ptr<Ogre2Grid> Ogre2GridPtr |
◆ Ogre2LightPtr
typedef shared_ptr<Ogre2Light> Ogre2LightPtr |
◆ Ogre2LightStore
typedef BaseLightStore< Ogre2Light > Ogre2LightStore |
◆ Ogre2LightStorePtr
typedef std::shared_ptr< Ogre2LightStore > Ogre2LightStorePtr |
◆ Ogre2MarkerPtr
typedef shared_ptr<Ogre2Marker> Ogre2MarkerPtr |
◆ Ogre2MaterialMap
typedef BaseMaterialMap<Ogre2Material> Ogre2MaterialMap |
◆ Ogre2MaterialMapPtr
◆ Ogre2MaterialPtr
typedef shared_ptr<Ogre2Material> Ogre2MaterialPtr |
◆ Ogre2MeshFactoryPtr
◆ Ogre2MeshPtr
typedef shared_ptr<Ogre2Mesh> Ogre2MeshPtr |
◆ Ogre2NodePtr
typedef shared_ptr<Ogre2Node> Ogre2NodePtr |
◆ Ogre2NodeStore
typedef BaseNodeStore< Ogre2Node > Ogre2NodeStore |
◆ Ogre2NodeStorePtr
typedef std::shared_ptr< Ogre2NodeStore > Ogre2NodeStorePtr |
◆ Ogre2ObjectPtr
typedef shared_ptr<Ogre2Object> Ogre2ObjectPtr |
◆ Ogre2PointLightPtr
typedef shared_ptr<Ogre2PointLight> Ogre2PointLightPtr |
◆ Ogre2RayQueryPtr
typedef shared_ptr<Ogre2RayQuery> Ogre2RayQueryPtr |
◆ Ogre2RenderEnginePtr
◆ Ogre2RenderTargetMaterialPtr
◆ Ogre2RenderTargetPtr
◆ Ogre2RenderTexturePtr
◆ Ogre2RenderWindowPtr
◆ Ogre2ScenePtr
typedef shared_ptr<Ogre2Scene> Ogre2ScenePtr |
◆ Ogre2SceneStore
typedef BaseSceneStore< Ogre2Scene > Ogre2SceneStore |
◆ Ogre2SceneStorePtr
typedef std::shared_ptr< Ogre2SceneStore > Ogre2SceneStorePtr |
◆ Ogre2SensorPtr
typedef shared_ptr<Ogre2Sensor> Ogre2SensorPtr |
◆ Ogre2SensorStore
typedef BaseSensorStore< Ogre2Sensor > Ogre2SensorStore |
◆ Ogre2SensorStorePtr
typedef std::shared_ptr< Ogre2SensorStore > Ogre2SensorStorePtr |
◆ Ogre2SpotLightPtr
typedef shared_ptr<Ogre2SpotLight> Ogre2SpotLightPtr |
◆ Ogre2SubMeshPtr
typedef shared_ptr<Ogre2SubMesh> Ogre2SubMeshPtr |
◆ Ogre2SubMeshStore
typedef BaseSubMeshStore< Ogre2SubMesh > Ogre2SubMeshStore |
◆ Ogre2SubMeshStorePtr
typedef std::shared_ptr< Ogre2SubMeshStore > Ogre2SubMeshStorePtr |
◆ Ogre2ThermalCameraPtr
◆ Ogre2VisualPtr
typedef shared_ptr<Ogre2Visual> Ogre2VisualPtr |
◆ Ogre2VisualStore
typedef BaseVisualStore< Ogre2Visual > Ogre2VisualStore |
◆ Ogre2VisualStorePtr
typedef std::shared_ptr< Ogre2VisualStore > Ogre2VisualStorePtr |
◆ OgreArrowVisualPtr
typedef shared_ptr<OgreArrowVisual> OgreArrowVisualPtr |
◆ OgreAxisVisualPtr
typedef shared_ptr<OgreAxisVisual> OgreAxisVisualPtr |
◆ OgreCameraPtr
typedef shared_ptr<OgreCamera> OgreCameraPtr |
◆ OgreDepthCameraPtr
typedef shared_ptr<OgreDepthCamera> OgreDepthCameraPtr |
◆ OgreDirectionalLightPtr
◆ OgreGeometryPtr
typedef shared_ptr<OgreGeometry> OgreGeometryPtr |
◆ OgreGeometryStore
typedef BaseGeometryStore< OgreGeometry > OgreGeometryStore |
◆ OgreGeometryStorePtr
typedef std::shared_ptr< OgreGeometryStore > OgreGeometryStorePtr |
◆ OgreGizmoVisualPtr
typedef shared_ptr<OgreGizmoVisual> OgreGizmoVisualPtr |
◆ OgreGpuRaysPtr
typedef shared_ptr<OgreGpuRays> OgreGpuRaysPtr |
◆ OgreGridPtr
typedef shared_ptr<OgreGrid> OgreGridPtr |
◆ OgreJointVisualPtr
typedef shared_ptr<OgreJointVisual> OgreJointVisualPtr |
◆ OgreLightPtr
typedef shared_ptr<OgreLight> OgreLightPtr |
◆ OgreLightStore
typedef BaseLightStore< OgreLight > OgreLightStore |
◆ OgreLightStorePtr
typedef std::shared_ptr< OgreLightStore > OgreLightStorePtr |
◆ OgreMarkerPtr
typedef shared_ptr<OgreMarker> OgreMarkerPtr |
◆ OgreMaterialMap
typedef BaseMaterialMap< OgreMaterial > OgreMaterialMap |
◆ OgreMaterialMapPtr
typedef std::shared_ptr< OgreMaterialMap > OgreMaterialMapPtr |
◆ OgreMaterialPtr
typedef shared_ptr<OgreMaterial> OgreMaterialPtr |
◆ OgreMeshFactoryPtr
typedef shared_ptr<OgreMeshFactory> OgreMeshFactoryPtr |
◆ OgreMeshPtr
typedef shared_ptr<OgreMesh> OgreMeshPtr |
◆ OgreNodePtr
typedef shared_ptr<OgreNode> OgreNodePtr |
◆ OgreNodeStore
typedef BaseNodeStore< OgreNode > OgreNodeStore |
◆ OgreNodeStorePtr
typedef std::shared_ptr< OgreNodeStore > OgreNodeStorePtr |
◆ OgreObjectPtr
typedef shared_ptr<OgreObject> OgreObjectPtr |
◆ OgrePointLightPtr
typedef shared_ptr<OgrePointLight> OgrePointLightPtr |
◆ OgreRayQueryPtr
typedef shared_ptr<OgreRayQuery> OgreRayQueryPtr |
◆ OgreRenderEnginePtr
◆ OgreRenderTargetMaterialPtr
◆ OgreRenderTargetPtr
◆ OgreRenderTexturePtr
◆ OgreRenderWindowPtr
◆ OgreScenePtr
typedef shared_ptr<OgreScene> OgreScenePtr |
◆ OgreSceneStore
typedef BaseSceneStore< OgreScene > OgreSceneStore |
◆ OgreSceneStorePtr
typedef std::shared_ptr< OgreSceneStore > OgreSceneStorePtr |
◆ OgreSensorPtr
typedef shared_ptr<OgreSensor> OgreSensorPtr |
◆ OgreSensorStore
typedef BaseSensorStore< OgreSensor > OgreSensorStore |
◆ OgreSensorStorePtr
typedef std::shared_ptr< OgreSensorStore > OgreSensorStorePtr |
◆ OgreSpotLightPtr
typedef shared_ptr<OgreSpotLight> OgreSpotLightPtr |
◆ OgreSubMeshPtr
typedef shared_ptr<OgreSubMesh> OgreSubMeshPtr |
◆ OgreSubMeshStore
typedef BaseSubMeshStore< OgreSubMesh > OgreSubMeshStore |
◆ OgreSubMeshStorePtr
typedef std::shared_ptr< OgreSubMeshStore > OgreSubMeshStorePtr |
◆ OgreTextPtr
typedef shared_ptr<OgreText> OgreTextPtr |
◆ OgreThermalCameraPtr
◆ OgreVisualPtr
typedef shared_ptr<OgreVisual> OgreVisualPtr |
◆ OgreVisualStore
typedef BaseVisualStore< OgreVisual > OgreVisualStore |
◆ OgreVisualStorePtr
typedef std::shared_ptr< OgreVisualStore > OgreVisualStorePtr |
◆ PointLightPtr
const PointLightPtr |
Shared pointer to PointLight.
Shared pointer to const PointLight.
◆ RayQueryPtr
Shared pointer to RayQuery.
◆ RenderPassPtr
const RenderPassPtr |
Shared pointer to RenderPass.
Shared pointer to const RenderPass.
◆ RenderPassSystemPtr
const RenderPassSystemPtr |
Shared pointer to RenderPassSystem.
Shared pointer to const RenderPassSystem.
◆ RenderTargetPtr
const RenderTargetPtr |
Shared pointer to RenderTarget.
Shared pointer to const RenderTarget.
◆ RenderTexturePtr
const RenderTexturePtr |
Shared pointer to RenderTexture.
Shared pointer to const RenderTexture.
◆ RenderWindowPtr
const RenderWindowPtr |
Shared pointer to RenderWindow.
Shared pointer to const RenderWindow.
◆ ScenePtr
◆ SceneStore
typedef Store<Scene> SceneStore |
◆ SceneStorePtr
typedef std::shared_ptr<SceneStore> SceneStorePtr |
◆ SensorPtr
◆ SensorStore
typedef Store<Sensor> SensorStore |
◆ SensorStorePtr
typedef std::shared_ptr<SensorStore> SensorStorePtr |
◆ ShaderParamsPtr
typedef shared_ptr<ShaderParams> ShaderParamsPtr |
Shared pointer to ShaderParams.
◆ shared_ptr
using shared_ptr = std::shared_ptr<T> |
◆ SpotLightPtr
const SpotLightPtr |
◆ SubMeshPtr
const SubMeshPtr |
◆ SubMeshStore
typedef Store<SubMesh> SubMeshStore |
◆ SubMeshStorePtr
typedef std::shared_ptr<SubMeshStore> SubMeshStorePtr |
◆ TextPtr
◆ ThermalCameraPtr
const ThermalCameraPtr |
Shared pointer to ThermalCamera.
Shared pointer to const ThermalCamera.
◆ Variant
using Variant = std::variant<int, float, double, std::string> |
◆ VisualPtr
◆ VisualStore
typedef Store<Visual> VisualStore |
◆ VisualStorePtr
typedef std::shared_ptr<VisualStore> VisualStorePtr |
Enumeration Type Documentation
◆ 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. |
◆ MaterialType
enum MaterialType |
◆ PixelFormat
enum PixelFormat |
Image pixel format types.
PixelFormat.hh ignition/rendering/PixelFormat.hh
◆ 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
◆ TextHorizontalAlign
|
strong |
Text Horizontal alignment.
Enumerator | |
---|---|
LEFT | Left alignment. |
CENTER | Center alignment. |
RIGHT | Right alignment. |
◆ TextVerticalAlign
|
strong |
Text vertical alignment.
Enumerator | |
---|---|
BOTTOM | Align bottom. |
CENTER | Align center. |
TOP | Align top. |
◆ TransformAxis
enum TransformAxis |
Unique identifiers for transformation axes.
◆ TransformMode
enum TransformMode |
◆ TransformSpace
enum TransformSpace |
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] _name Name of the desired render-engine [in] _params Parameters to be passed to the render engine. [in] _path Another 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] _index Index of the desired render-engine [in] _params Parameters to be passed to the render engine. [in] _path Another 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] _name Name 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] _name Name 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] _name Name the render-engine will be registered under [in] _engine Render-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] _screenPos 2D coordinates on the screen, in pixels. [in] _camera User camera [in] _rayQuery Ray query for mouse clicks [in] _offset Offset 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] _screenPos 2D coordinates on the screen, in pixels. [in] _camera User camera [in] _rayQuery Ray query for mouse clicks [in] _maxDistance maximum 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] _screenPos 2D coordinates on the screen, in pixels. [in] _camera User camera [in] _rayQuery Ray query for mouse clicks [in,out] _rayResult Ray query result [in] _maxDistance maximum 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] _paths The list of the plugin paths
◆ unloadEngine()
bool ignition::rendering::unloadEngine | ( | const std::string & | _name | ) |
Unload the render-engine registered under the given name.
- Parameters
-
[in] _name Name 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] _name Name of the render-engine to unregister
◆ unregisterEngine() [2/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] _index Index of the render-engine to unregister
◆ unregisterEngine() [3/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] _engine Render-engine to unregister
Variable Documentation
◆ depth_fragment_shader_file
const std::string depth_fragment_shader_file |
◆ depth_vertex_shader_file
const std::string depth_vertex_shader_file |
◆ kDefaultPbr
|
static |
Default pbr material properties.
Referenced by BaseMaterial< OgreObject >::CopyFrom(), and BaseMaterial< OgreObject >::Reset().