CBaseDepthCamera< T > | |
►CBaseDepthCamera< Ogre2Sensor > | |
COgre2DepthCamera | Depth camera used to render depth data into an image buffer |
►CBaseDepthCamera< OgreSensor > | |
COgreDepthCamera | Depth camera used to render depth data into an image buffer |
CBaseGeometryStore< T > | |
CBaseLightStore< T > | |
CBaseMaterialMap< T > | |
CBaseNodeStore< T > | |
CBaseSceneStore< T > | |
CBaseSensorStore< T > | |
CBaseSubMeshStore< T > | |
CBaseVisualStore< T > | |
CBoundingBox | 2D or 3D Bounding box. It stores the position / orientation / size info of the box and its label |
CCameraLens | Describes a lens of a camera as amapping function of type r = c1*f*fun(theta/c2+c3) |
►Cenable_shared_from_this | |
►CBaseObject | |
►COgre2Object | Ogre2.x implementation of the Object class |
►CBaseGeometry< Ogre2Object > | |
►COgre2Geometry | Ogre2.x implementation of the geometry class |
►CBaseCapsule< Ogre2Geometry > | |
COgre2Capsule | Ogre 2.x implementation of a Capsule Geometry |
►CBaseGrid< Ogre2Geometry > | |
COgre2Grid | Ogre2 implementation of a grid geometry |
►CBaseHeightmap< Ogre2Geometry > | |
COgre2Heightmap | Ogre implementation of a heightmap geometry |
►CBaseMarker< Ogre2Geometry > | |
COgre2Marker | Ogre 2.x implementation of a marker geometry |
►CBaseMesh< Ogre2Geometry > | |
COgre2Mesh | Ogre2.x implementation of the mesh class |
►CBaseWireBox< Ogre2Geometry > | |
COgre2WireBox | Ogre2 implementation of a wire box geometry |
►CBaseMaterial< Ogre2Object > | |
COgre2Material | Ogre 2.x implementation of the material class |
►CBaseNode< Ogre2Object > | |
►COgre2Node | Ogre2.x implementation of the Node class |
►CBaseLight< Ogre2Node > | |
►COgre2Light | Ogre 2.x implementation of the light class |
►CBaseDirectionalLight< Ogre2Light > | |
COgre2DirectionalLight | Ogre 2.x implementation of the directional light class |
►CBasePointLight< Ogre2Light > | |
COgre2PointLight | Ogre 2.x implementation of the point light class |
►CBaseSpotLight< Ogre2Light > | |
COgre2SpotLight | Ogre 2.x implementation of the spot light class |
►CBaseSensor< Ogre2Node > | |
►COgre2Sensor | Ogre2.x implementation of the sensor classs |
►CBaseBoundingBoxCamera< Ogre2Sensor > | |
COgre2BoundingBoxCamera | BoundingBox camera used to detect 2d / 3d bounding boxes of labeled objects in the scene |
►CBaseCamera< Ogre2Sensor > | |
CBaseBoundingBoxCamera< Ogre2Sensor > | |
►CBaseGpuRays< Ogre2Sensor > | |
COgre2GpuRays | 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 |
►CBaseSegmentationCamera< Ogre2Sensor > | |
COgre2SegmentationCamera | Segmentation camera used to label each pixel with a label id. Supports Semantic / Panoptic Segmentation |
►CBaseThermalCamera< Ogre2Sensor > | |
COgre2ThermalCamera | Thermal camera used to render thermal data into an image buffer |
COgre2Camera | Ogre2.x implementation of the camera class |
CBaseGpuRays< Ogre2Sensor > | |
CBaseSegmentationCamera< Ogre2Sensor > | |
CBaseThermalCamera< Ogre2Sensor > | |
►CBaseVisual< Ogre2Node > | |
►COgre2Visual | Ogre2.x implementation of the visual class |
►CBaseArrowVisual< Ogre2Visual > | |
COgre2ArrowVisual | Ogre2.x implementation of the arrow visual class |
►CBaseAxisVisual< Ogre2Visual > | |
COgre2AxisVisual | Ogre2.x implementation of the axis visual class |
►CBaseCOMVisual< Ogre2Visual > | |
COgre2COMVisual | |
►CBaseGizmoVisual< Ogre2Visual > | |
COgre2GizmoVisual | |
►CBaseInertiaVisual< Ogre2Visual > | |
COgre2InertiaVisual | Ogre2.x implementation of the inertia visual class |
►CBaseJointVisual< Ogre2Visual > | |
COgre2JointVisual | |
►CBaseLidarVisual< Ogre2Visual > | |
COgre2LidarVisual | Ogre 2.x implementation of a Lidar Visual |
►CBaseLightVisual< Ogre2Visual > | |
COgre2LightVisual | Ogre2.x implementation of the light visual class |
►CBaseParticleEmitter< Ogre2Visual > | |
COgre2ParticleEmitter | Class to manage a particle emitter |
►CBaseProjector< Ogre2Visual > | |
COgre2Projector | Ogre 2.x implementation of a Projector class |
►CBaseRayQuery< Ogre2Object > | |
COgre2RayQuery | A Ray Query class used for computing ray object intersections |
►CBaseRenderPass< Ogre2Object > | |
►COgre2RenderPass | Ogre2 Implementation of a render pass |
►CBaseGaussianNoisePass< Ogre2RenderPass > | |
COgre2GaussianNoisePass | Ogre2 Implementation of a Gaussian noise render pass |
►CBaseRenderTarget< Ogre2Object > | |
►COgre2RenderTarget | Ogre2.x implementation of the render target class |
►CBaseRenderTexture< Ogre2RenderTarget > | |
COgre2RenderTexture | Ogre2.x implementation of the render texture class |
►CBaseRenderWindow< Ogre2RenderTarget > | |
COgre2RenderWindow | Ogre2.x implementation of the render window class |
►CBaseSubMesh< Ogre2Object > | |
COgre2SubMesh | Ogre2.x implementation of the submesh class |
►COgreObject | |
►CBaseGeometry< OgreObject > | |
►COgreGeometry | |
►CBaseCapsule< OgreGeometry > | |
COgreCapsule | Ogre 2.x implementation of a Capsule Visual |
►CBaseGrid< OgreGeometry > | |
COgreGrid | Ogre implementation of a grid geometry |
►CBaseHeightmap< OgreGeometry > | |
COgreHeightmap | Ogre implementation of a heightmap geometry |
►CBaseMarker< OgreGeometry > | |
COgreMarker | Ogre implementation of a marker geometry |
►CBaseMesh< OgreGeometry > | |
COgreMesh | |
►CBaseText< OgreGeometry > | |
COgreText | Ogre implementation of text geometry |
►CBaseWireBox< OgreGeometry > | |
COgreWireBox | Ogre implementation of a wire box geometry |
►CBaseMaterial< OgreObject > | |
COgreMaterial | |
►CBaseNode< OgreObject > | |
►COgreNode | |
►CBaseLight< OgreNode > | |
►COgreLight | |
►CBaseDirectionalLight< OgreLight > | |
COgreDirectionalLight | |
►CBasePointLight< OgreLight > | |
COgrePointLight | |
►CBaseSpotLight< OgreLight > | |
COgreSpotLight | |
►CBaseSensor< OgreNode > | |
►COgreSensor | |
►CBaseCamera< OgreSensor > | |
►CBaseGpuRays< OgreSensor > | |
COgreGpuRays | Gpu Rays used to render depth data into an image buffer |
►CBaseThermalCamera< OgreSensor > | |
COgreThermalCamera | Depth camera used to render thermal data into an image buffer |
►CBaseWideAngleCamera< OgreSensor > | |
COgreWideAngleCamera | Ogre implementation of WideAngleCamera |
COgreCamera | |
CBaseGpuRays< OgreSensor > | |
CBaseThermalCamera< OgreSensor > | |
CBaseWideAngleCamera< OgreSensor > | |
►CBaseVisual< OgreNode > | |
►COgreVisual | |
►CBaseArrowVisual< OgreVisual > | |
COgreArrowVisual | |
►CBaseAxisVisual< OgreVisual > | |
COgreAxisVisual | |
►CBaseCOMVisual< OgreVisual > | |
COgreCOMVisual | |
►CBaseGizmoVisual< OgreVisual > | |
COgreGizmoVisual | |
►CBaseInertiaVisual< OgreVisual > | |
COgreInertiaVisual | |
►CBaseJointVisual< OgreVisual > | |
COgreJointVisual | |
►CBaseLidarVisual< OgreVisual > | |
COgreLidarVisual | Ogre implementation of a Lidar Visual |
►CBaseLightVisual< OgreVisual > | |
COgreLightVisual | |
►CBaseParticleEmitter< OgreVisual > | |
COgreParticleEmitter | Class to manage a particle emitter |
►CBaseProjector< OgreVisual > | |
COgreProjector | Ogre 1.x implementation of a Projector class |
►CBaseRayQuery< OgreObject > | |
COgreRayQuery | A Ray Query class used for computing ray object intersections |
►CBaseRenderPass< OgreObject > | |
►COgreRenderPass | Ogre implementation of the RenderPass class |
►CBaseDistortionPass< OgreRenderPass > | |
COgreDistortionPass | Ogre implementation of the DistortionPass class |
►CBaseGaussianNoisePass< OgreRenderPass > | |
COgreGaussianNoisePass | Ogre implementation of the GaussianNoisePass class |
►CBaseRenderTarget< OgreObject > | |
►COgreRenderTarget | |
►CBaseRenderTexture< OgreRenderTarget > | |
COgreRenderTexture | |
►CBaseRenderWindow< OgreRenderTarget > | |
COgreRenderWindow | |
►CBaseSubMesh< OgreObject > | |
COgreSubMesh | |
►Cenable_shared_from_this | |
►CBaseScene | |
COgre2Scene | Ogre2.x implementation of the scene class |
COgreScene | |
CGraphicsAPIUtils | Utils to convert GraphicsAPI to and from strings |
►CGZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING public virtual Object | |
CBaseObject | |
►CGZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING public virtual Scene | |
CBaseScene | |
CHeightmapBlend | Blend information to be used between textures on heightmaps |
CHeightmapDescriptor | Describes how a Heightmap should be loaded |
CHeightmapTexture | Texture to be used on heightmaps |
CImage | Encapsulates a raw image buffer and relevant properties |
►CListener | |
COgre2RenderTargetMaterial | Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget |
COgreMaterialSwitcher | Helper class to assign unique colors to renderables |
COgreRenderTargetMaterial | Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget |
►CListener | |
COgre2MaterialSwitcher | Helper class to assign unique colors to renderables |
COgre2RenderTargetMaterial | Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget |
►CListener | |
COgreWideAngleCamera | Ogre implementation of WideAngleCamera |
►CMap< T > | Storage map from std::string to template class T |
CBaseMap< T, U > | |
CMeshDescriptor | Describes how a Mesh should be loaded |
CMoveToHelper | Helper class for animating a user camera to move to a target entity |
►CObject | Represents an object present in the scene graph. This includes sub-meshes, materials, render targets, as well as posable nodes |
►CGeometry | Represents a geometric shape to be rendered |
CBaseGeometry< Ogre2Object > | |
CBaseGeometry< OgreObject > | |
CBaseGeometry< T > | |
►CCapsule | Geometry for a capsule shape. The APIs allow setting the capsule's radius and length directly which ensure that the the geometry remains the shape of a capsule. In comparison, if the size is changed via the parent Node's Set*Scale function, the capsule may become deformed |
CBaseCapsule< Ogre2Geometry > | |
CBaseCapsule< OgreGeometry > | |
CBaseCapsule< T > | Base implementation of a Capsule Geometry |
►CGrid | Represents a grid geometry drawn along the XY plane. If vertical cell count is specified then the grid becomes 3D |
CBaseGrid< Ogre2Geometry > | |
CBaseGrid< OgreGeometry > | |
CBaseGrid< T > | Base implementation of a grid geometry |
►CHeightmap | A terrain defined by a heightfield |
CBaseHeightmap< Ogre2Geometry > | |
CBaseHeightmap< OgreGeometry > | |
CBaseHeightmap< T > | |
►CMarker | A marker geometry class. The marker's visual appearance is based on the marker type specified |
CBaseMarker< Ogre2Geometry > | |
CBaseMarker< OgreGeometry > | |
CBaseMarker< T > | Base implementation of a Marker geometry |
►CMesh | Represents a collection of mesh geometries |
CBaseMesh< Ogre2Geometry > | |
CBaseMesh< OgreGeometry > | |
CBaseMesh< T > | |
►CText | Represents a billboard text geometry that is always facing the camera |
CBaseText< OgreGeometry > | |
CBaseText< T > | Base implementation of a text geometry |
►CWireBox | Draws a wireframe box |
CBaseWireBox< Ogre2Geometry > | |
CBaseWireBox< OgreGeometry > | |
CBaseWireBox< T > | Base implementation of a wireframe box |
►CMaterial | Represents a surface material of a Geometry |
CBaseMaterial< Ogre2Object > | |
CBaseMaterial< OgreObject > | |
CBaseMaterial< T > | |
►CNode | Represents a single posable node in the scene graph |
CBaseNode< Ogre2Object > | |
CBaseNode< OgreObject > | |
CBaseNode< T > | |
►CLight | Represents a light source in the scene graph |
CBaseLight< Ogre2Node > | |
CBaseLight< OgreNode > | |
CBaseLight< T > | |
►CDirectionalLight | Represents a infinite directional light |
CBaseDirectionalLight< Ogre2Light > | |
CBaseDirectionalLight< OgreLight > | |
CBaseDirectionalLight< T > | |
►CPointLight | Represents a point light |
CBasePointLight< Ogre2Light > | |
CBasePointLight< OgreLight > | |
CBasePointLight< T > | |
►CSpotLight | Represents a spotlight |
CBaseSpotLight< Ogre2Light > | |
CBaseSpotLight< OgreLight > | |
CBaseSpotLight< T > | |
►CSensor | Represents a scene sensor. The most obvious example is a camera, but it can be anything that generates output from the scene |
CBaseSensor< Ogre2Node > | |
CBaseSensor< OgreNode > | |
CBaseSensor< T > | |
►CCamera | Posable camera used for rendering the scene graph |
CBaseCamera< Ogre2Sensor > | |
CBaseCamera< OgreSensor > | |
►CBaseCamera< T > | |
CBaseBoundingBoxCamera< T > | |
CBaseGpuRays< T > | |
CBaseSegmentationCamera< T > | |
CBaseThermalCamera< T > | Base implementation of the ThermalCamera class |
CBaseWideAngleCamera< T > | |
►CBoundingBoxCamera | Poseable BoundingBox camera used for rendering bounding boxes of objects in the scene |
CBaseBoundingBoxCamera< Ogre2Sensor > | |
CBaseBoundingBoxCamera< T > | |
CDepthCamera | |
►CGpuRays | Generate depth ray data |
CBaseGpuRays< Ogre2Sensor > | |
CBaseGpuRays< OgreSensor > | |
CBaseGpuRays< T > | |
►CSegmentationCamera | Poseable Segmentation camera used for rendering the scene graph. This camera is designed to produce segmentation data, instead of a 2D image |
CBaseSegmentationCamera< Ogre2Sensor > | |
CBaseSegmentationCamera< T > | |
►CThermalCamera | 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 |
CBaseThermalCamera< Ogre2Sensor > | |
CBaseThermalCamera< OgreSensor > | |
CBaseThermalCamera< T > | Base implementation of the ThermalCamera class |
►CWideAngleCamera | Wide angle camera class |
CBaseWideAngleCamera< OgreSensor > | |
CBaseWideAngleCamera< T > | |
►CVisual | Represents a visual node in a scene graph. A Visual is the only node that can have Geometry and other Visual children |
CBaseVisual< Ogre2Node > | |
CBaseVisual< OgreNode > | |
CBaseVisual< T > | |
►CCompositeVisual | Represents a predefined collection of geometries and visuals |
►CArrowVisual | Represents a arrow composite visual |
CBaseArrowVisual< Ogre2Visual > | |
CBaseArrowVisual< OgreVisual > | |
CBaseArrowVisual< T > | |
►CAxisVisual | Represents a axis composite visual |
CBaseAxisVisual< Ogre2Visual > | |
CBaseAxisVisual< OgreVisual > | |
CBaseAxisVisual< T > | |
►CGizmoVisual | A gizmo that contains rotate, translate, and scale visuals |
CBaseGizmoVisual< Ogre2Visual > | |
CBaseGizmoVisual< OgreVisual > | |
CBaseGizmoVisual< T > | A base implementation of the GizmoVisual class |
►CCOMVisual | Represents a center of mass visual |
CBaseCOMVisual< Ogre2Visual > | |
CBaseCOMVisual< OgreVisual > | |
CBaseCOMVisual< T > | Base implementation of an center of mass visual |
►CInertiaVisual | Represents a inertia visual |
CBaseInertiaVisual< Ogre2Visual > | |
CBaseInertiaVisual< OgreVisual > | |
CBaseInertiaVisual< T > | Base implementation of an inertia visual |
►CJointVisual | Represents a joint visual |
CBaseJointVisual< Ogre2Visual > | |
CBaseJointVisual< OgreVisual > | |
CBaseJointVisual< T > | Base implementation of a joint visual |
►CLidarVisual | A LidarVisual geometry class. The visual appearance is based on the type specified |
CBaseLidarVisual< Ogre2Visual > | |
CBaseLidarVisual< OgreVisual > | |
CBaseLidarVisual< T > | Base implementation of a Lidar Visual |
►CLightVisual | Represents a light visual |
CBaseLightVisual< Ogre2Visual > | |
CBaseLightVisual< OgreVisual > | |
CBaseLightVisual< T > | Base implementation of a light visual |
►CParticleEmitter | Class to manage a particle emitter |
CBaseParticleEmitter< Ogre2Visual > | |
CBaseParticleEmitter< OgreVisual > | |
CBaseParticleEmitter< T > | A base implementation of the ParticleEmitter class |
►CProjector | A projector that projects a texture onto a surface |
CBaseProjector< Ogre2Visual > | |
CBaseProjector< OgreVisual > | |
CBaseProjector< T > | A base implementation of the Projector class |
►CRayQuery | A Ray Query class used for computing ray object intersections |
CBaseRayQuery< Ogre2Object > | |
CBaseRayQuery< OgreObject > | |
CBaseRayQuery< T > | A Ray Query class used for computing ray object intersections |
►CRenderPass | 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 |
CBaseRenderPass< Ogre2Object > | |
CBaseRenderPass< OgreObject > | |
CBaseRenderPass< T > | Base render pass that can be applied to a render target |
►CDistortionPass | A render pass that applies distortion to the render target |
CBaseDistortionPass< OgreRenderPass > | |
CBaseDistortionPass< T > | Base distortion render pass |
►CGaussianNoisePass | A render pass that applies Gaussian noise to the render target |
CBaseGaussianNoisePass< Ogre2RenderPass > | |
CBaseGaussianNoisePass< OgreRenderPass > | |
CBaseGaussianNoisePass< T > | Base Gaussian noise render pass |
►CRenderTarget | Represents a render-target to which cameras can render images |
CBaseRenderTarget< Ogre2Object > | |
CBaseRenderTarget< OgreObject > | |
CBaseRenderTarget< T > | |
►CRenderTexture | Represents a off-screen render-texture to which cameras can render images |
CBaseRenderTexture< Ogre2RenderTarget > | |
CBaseRenderTexture< OgreRenderTarget > | |
CBaseRenderTexture< T > | |
►CRenderWindow | Represents a on-screen render-window to which cameras can render images |
CBaseRenderWindow< Ogre2RenderTarget > | |
CBaseRenderWindow< OgreRenderTarget > | |
CBaseRenderWindow< T > | |
►CSubMesh | Represents a single mesh geometry |
CBaseSubMesh< Ogre2Object > | |
CBaseSubMesh< OgreObject > | |
CBaseSubMesh< T > | |
COgre2Conversions | Conversions Conversions.hh rendering/Conversions.hh |
COgre2DynamicRenderable | Dynamic renderable class that manages hardware buffers for a dynamic geometry |
COgre2MeshFactory | Ogre2.x implementation of the mesh factory class |
►COgre2ObjectInterface | Mixin class to provide direct access to Ogre objects |
COgre2Camera | Ogre2.x implementation of the camera class |
COgre2DepthCamera | Depth camera used to render depth data into an image buffer |
COgre2SegmentationCamera | Segmentation camera used to label each pixel with a label id. Supports Semantic / Panoptic Segmentation |
COgre2ThermalCamera | Thermal camera used to render thermal data into an image buffer |
COgre2SelectionBuffer | 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 |
COgre2SubMeshStoreFactory | Ogre2.x implementation of a submesh store factory class |
COgreConversions | Conversions Conversions.hh rendering/Conversions.hh |
COgreMeshFactory | |
►COgreObjectInterface | Mixin class to provide direct access to Ogre objects |
COgreCamera | |
COgreDepthCamera | Depth camera used to render depth data into an image buffer |
COgreThermalCamera | Depth camera used to render thermal data into an image buffer |
COgreSelectionBuffer | 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 |
COgreSubMeshStoreFactory | |
CPixelUtil | Provides supporting functions for PixelFormat enum |
CRayQueryResult | A class that stores ray query intersection results |
►CRenderEngine | 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 |
►CBaseRenderEngine | |
COgre2RenderEngine | 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 |
COgreRenderEngine | |
►CRenderEnginePlugin | Base plugin class for render engines |
COgre2RenderEnginePlugin | Plugin for loading ogre render engine |
COgreRenderEnginePlugin | Plugin for loading ogre render engine |
►CRenderObjectListener | |
COgreGpuRays | Gpu Rays used to render depth data into an image buffer |
CRenderPassFactory | A factory interface for creating render passes |
CRenderPassSystem | A class for creating and managing render passes |
►CRenderTargetListener | |
COgreMaterialSwitcher | Helper class to assign unique colors to renderables |
COgreRenderTargetMaterial | Causes all objects in a scene to be rendered with the same material when rendered by a given RenderTarget |
CScene | 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 |
►CSceneExt | Scene Extension class. Provides API extension to the Scene class without breaking ABI |
COgre2SceneExt | Ogre2 implementation of the scene extension API |
COgreSceneExt | Ogre implementation of the scene extension API |
CShaderParam | Variant type that holds params that can be passed to a shader |
CShaderParams | Map that holds params to be passed to a shader |
CShaderUtil | Provides supporting functions for ShaderType enum |
►CSimpleRenderable | |
►COgreDynamicRenderable | Abstract base class providing mechanisms for dynamically growing hardware buffers |
COgreDynamicLines | Class for drawing lines that can change |
►CSingletonT< Ogre2RenderEngine > [external] | |
COgre2RenderEngine | 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 |
►CSingletonT< OgreRenderEngine > [external] | |
COgreRenderEngine | |
►CSingletonT< OgreRTShaderSystem > [external] | |
COgreRTShaderSystem | Implements Ogre's Run-Time Shader system |
►CSingletonT< RenderEngineManager > [external] | |
CRenderEngineManager | 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 |
►CStore< T > | 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 |
CBaseStore< T, U > | |
►CCompositeStore< T > | Represents a collection of Store objects, collectively working as a single composite store |
CBaseCompositeStore< T > | |
►CStoreWrapper< T, U > | 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 |
CBaseStoreWrapper< T, U > | |
►CStore< Node > | |
►CCompositeStore< Node > | |
►CBaseCompositeStore< Node > | |
CBaseNodeCompositeStore | |
►CT | |
CBaseArrowVisual< T > | |
CBaseAxisVisual< T > | |
CBaseBoundingBoxCamera< T > | |
CBaseCamera< T > | |
CBaseCapsule< T > | Base implementation of a Capsule Geometry |
CBaseCOMVisual< T > | Base implementation of an center of mass visual |
CBaseDirectionalLight< T > | |
CBaseDistortionPass< T > | Base distortion render pass |
CBaseGaussianNoisePass< T > | Base Gaussian noise render pass |
CBaseGeometry< T > | |
CBaseGizmoVisual< T > | A base implementation of the GizmoVisual class |
CBaseGpuRays< T > | |
CBaseGrid< T > | Base implementation of a grid geometry |
CBaseHeightmap< T > | |
CBaseInertiaVisual< T > | Base implementation of an inertia visual |
CBaseJointVisual< T > | Base implementation of a joint visual |
CBaseLidarVisual< T > | Base implementation of a Lidar Visual |
CBaseLight< T > | |
CBaseLightVisual< T > | Base implementation of a light visual |
CBaseMarker< T > | Base implementation of a Marker geometry |
CBaseMaterial< T > | |
CBaseMesh< T > | |
CBaseNode< T > | |
CBaseParticleEmitter< T > | A base implementation of the ParticleEmitter class |
CBasePointLight< T > | |
CBaseProjector< T > | A base implementation of the Projector class |
CBaseRayQuery< T > | A Ray Query class used for computing ray object intersections |
CBaseRenderPass< T > | Base render pass that can be applied to a render target |
CBaseRenderTarget< T > | |
CBaseRenderTexture< T > | |
CBaseRenderWindow< T > | |
CBaseSegmentationCamera< T > | |
CBaseSensor< T > | |
CBaseSpotLight< T > | |
CBaseSubMesh< T > | |
CBaseText< T > | Base implementation of a text geometry |
CBaseThermalCamera< T > | Base implementation of the ThermalCamera class |
CBaseVisual< T > | |
CBaseWideAngleCamera< T > | |
CBaseWireBox< T > | Base implementation of a wireframe box |
CTransformController | An transform tool for translating, rotating, and scaling objects |
►CViewController | A camera view controller |
COrbitViewController | A camera view controller |
COrthoViewController | Orthographic view controller |