|
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 | BaseProjector |
| A base implementation of the Projector class. More...
|
|
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 | BaseWideAngleCamera |
|
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 | CameraLens |
| Describes a lens of a camera as amapping function of type r = c1*f*fun(theta/c2+c3) More...
|
|
class | Capsule |
| 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. 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 | Ogre2ArrowVisual |
| Ogre2.x implementation of the arrow visual class. More...
|
|
class | Ogre2AxisVisual |
| Ogre2.x implementation of the axis visual class. More...
|
|
class | Ogre2BoundingBoxCamera |
| BoundingBox camera used to detect 2d / 3d bounding boxes of labeled objects in the scene. More...
|
|
class | Ogre2Camera |
| Ogre2.x implementation of the camera class. More...
|
|
class | Ogre2Capsule |
| Ogre 2.x implementation of a Capsule Geometry. More...
|
|
class | Ogre2COMVisual |
|
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 | Ogre2Heightmap |
| Ogre implementation of a heightmap geometry. More...
|
|
class | Ogre2InertiaVisual |
| Ogre2.x implementation of the inertia visual class. More...
|
|
class | Ogre2JointVisual |
|
class | Ogre2LidarVisual |
| Ogre 2.x implementation of a Lidar Visual. More...
|
|
class | Ogre2Light |
| Ogre 2.x implementation of the light class. More...
|
|
class | Ogre2LightVisual |
| Ogre2.x implementation of the light visual 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 | Ogre2ObjectInterface |
| Mixin class to provide direct access to Ogre objects. More...
|
|
class | Ogre2ParticleEmitter |
| Class to manage a particle emitter. More...
|
|
class | Ogre2PointLight |
| Ogre 2.x implementation of the point light class. More...
|
|
class | Ogre2Projector |
| Ogre 2.x implementation of a Projector 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 | Ogre2SceneExt |
| Ogre2 implementation of the scene extension API. More...
|
|
class | Ogre2SegmentationCamera |
| Segmentation camera used to label each pixel with a label id. Supports Semantic / Panoptic Segmentation. 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 | Ogre2WireBox |
| Ogre2 implementation of a wire box geometry. 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 | OgreObjectInterface |
| Mixin class to provide direct access to Ogre objects. More...
|
|
class | OgreParticleEmitter |
| Class to manage a particle emitter. More...
|
|
class | OgrePointLight |
|
class | OgreProjector |
| Ogre 1.x implementation of a Projector class. More...
|
|
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 | OgreSceneExt |
| Ogre implementation of the scene extension API. More...
|
|
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 | OgreWideAngleCamera |
| Ogre implementation of WideAngleCamera. More...
|
|
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 | Projector |
| A projector that projects a texture onto a surface. 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 | SceneExt |
| Scene Extension class. Provides API extension to the Scene class without breaking ABI. 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 | WideAngleCamera |
| Wide angle camera class. More...
|
|
class | WireBox |
| Draws a wireframe box. More...
|
|
|
typedef shared_ptr< ArrowVisual > | ArrowVisualPtr |
| Shared pointer to ArrowVisual. More...
|
|
typedef shared_ptr< AxisVisual > | AxisVisualPtr |
| Shared pointer to AxisVisual. More...
|
|
typedef shared_ptr< BaseNodeCompositeStore > | BaseNodeCompositeStorePtr |
|
typedef std::shared_ptr< BaseObject > | BaseObjectPtr |
|
typedef shared_ptr< BoundingBoxCamera > | BoundingBoxCameraPtr |
| Shared pointer to BoundingBoxCamera. More...
|
|
typedef shared_ptr< Camera > | CameraPtr |
| Shared pointer to Camera. More...
|
|
typedef shared_ptr< Capsule > | CapsulePtr |
| Shared pointer to Capsule. More...
|
|
typedef shared_ptr< COMVisual > | COMVisualPtr |
| Shared pointer to COMVisual. More...
|
|
typedef shared_ptr< const ArrowVisual > | ConstArrowVisualPtr |
|
typedef shared_ptr< const AxisVisual > | ConstAxisVisualPtr |
|
typedef shared_ptr< const BoundingBoxCamera > | ConstBoundingBoxCameraPtr |
|
typedef shared_ptr< const Camera > | ConstCameraPtr |
|
typedef shared_ptr< const DepthCamera > | ConstDepthCameraPtr |
|
typedef shared_ptr< const DirectionalLight > | ConstDirectionalLightPtr |
|
typedef shared_ptr< const GaussianNoisePass > | ConstGaussianNoisePass |
| Shared pointer to const GaussianNoisePass. More...
|
|
typedef shared_ptr< const Geometry > | ConstGeometryPtr |
|
typedef shared_ptr< const GizmoVisual > | ConstGizmoVisualPtr |
|
typedef shared_ptr< const GpuRays > | ConstGpuRaysPtr |
|
typedef shared_ptr< const Heightmap > | ConstHeightmapPtr |
|
typedef shared_ptr< const Image > | ConstImagePtr |
|
typedef shared_ptr< const JointVisual > | ConstJointVisualPtr |
|
typedef shared_ptr< const LidarVisual > | ConstLidarVisualPtr |
|
typedef shared_ptr< const Light > | ConstLightPtr |
|
typedef shared_ptr< const Material > | ConstMaterialPtr |
|
typedef shared_ptr< const Mesh > | ConstMeshPtr |
|
typedef shared_ptr< const Node > | ConstNodePtr |
|
typedef shared_ptr< const ObjectFactory > | ConstObjectFactoryPtr |
|
typedef shared_ptr< const Object > | ConstObjectPtr |
|
typedef shared_ptr< const ParticleEmitter > | ConstParticleEmitterPtr |
|
typedef shared_ptr< const PointLight > | ConstPointLightPtr |
|
typedef shared_ptr< const Projector > | ConstProjectorPtr |
|
typedef shared_ptr< const RayQuery > | ConstRayQueryPtr |
|
typedef shared_ptr< const RenderPass > | ConstRenderPassPtr |
|
typedef shared_ptr< const RenderPassSystem > | ConstRenderPassSystemPtr |
|
typedef shared_ptr< const RenderTarget > | ConstRenderTargetPtr |
|
typedef shared_ptr< const RenderTexture > | ConstRenderTexturePtr |
|
typedef shared_ptr< const RenderWindow > | ConstRenderWindowPtr |
|
typedef shared_ptr< const Scene > | ConstScenePtr |
|
typedef shared_ptr< const SegmentationCamera > | ConstSegmentationCameraPtr |
|
typedef shared_ptr< const Sensor > | ConstSensorPtr |
|
typedef shared_ptr< const ShaderParams > | ConstShaderParamsPtr |
| Shared pointer to const ShaderParams. More...
|
|
typedef shared_ptr< const SpotLight > | ConstSpotLightPtr |
|
typedef shared_ptr< const SubMesh > | ConstSubMeshPtr |
|
typedef shared_ptr< const Text > | ConstTextPtr |
|
typedef shared_ptr< const ThermalCamera > | ConstThermalCameraPtr |
|
typedef shared_ptr< const Visual > | ConstVisualPtr |
|
typedef shared_ptr< const WideAngleCamera > | ConstWideAngleCameraPtr |
|
typedef shared_ptr< DepthCamera > | DepthCameraPtr |
| Shared pointer to DepthCamera. More...
|
|
typedef shared_ptr< DirectionalLight > | DirectionalLightPtr |
| Shared pointer to DirectionalLight. More...
|
|
typedef shared_ptr< DistortionPass > | DistortionPassPtr |
| Shared pointer to DistortionPass. More...
|
|
typedef shared_ptr< GaussianNoisePass > | GaussianNoisePassPtr |
| Shared pointer to GaussianNoisePass. More...
|
|
typedef shared_ptr< Geometry > | GeometryPtr |
| Shared pointer to Geometry. More...
|
|
typedef Store< Geometry > | GeometryStore |
|
typedef std::shared_ptr< GeometryStore > | GeometryStorePtr |
|
typedef shared_ptr< GizmoVisual > | GizmoVisualPtr |
| Shared pointer to GizmoVisual. More...
|
|
typedef shared_ptr< GpuRays > | GpuRaysPtr |
| Shared pointer to GpuRays. More...
|
|
typedef shared_ptr< Grid > | GridPtr |
| Shared pointer to Grid. More...
|
|
typedef shared_ptr< Heightmap > | HeightmapPtr |
| Shared pointer to Heightmap. More...
|
|
using | IgnOgreRenderingMode = GzOgreRenderingMode |
|
typedef shared_ptr< Image > | ImagePtr |
| Shared pointer to Image. More...
|
|
typedef shared_ptr< InertiaVisual > | InertiaVisualPtr |
|
typedef shared_ptr< JointVisual > | JointVisualPtr |
| Shared pointer to JointVisual. More...
|
|
typedef shared_ptr< LidarVisual > | LidarVisualPtr |
| Shared pointer to LidarVisual. More...
|
|
typedef shared_ptr< Light > | LightPtr |
| Shared pointer to Light. More...
|
|
typedef Store< Light > | LightStore |
|
typedef std::shared_ptr< LightStore > | LightStorePtr |
|
typedef shared_ptr< LightVisual > | LightVisualPtr |
| Shared pointer to Light. More...
|
|
typedef shared_ptr< Marker > | MarkerPtr |
| Shared pointer to Marker. More...
|
|
typedef Map< Material > | MaterialMap |
|
typedef std::shared_ptr< MaterialMap > | MaterialMapPtr |
|
typedef shared_ptr< Material > | MaterialPtr |
| Shared pointer to Material. More...
|
|
typedef shared_ptr< Mesh > | MeshPtr |
| Shared pointer to Mesh. More...
|
|
typedef CompositeStore< Node > | NodeCompositeStore |
|
typedef std::shared_ptr< NodeCompositeStore > | NodeCompositeStorePtr |
|
typedef shared_ptr< Node > | NodePtr |
| Shared pointer to Node. More...
|
|
typedef Store< Node > | NodeStore |
|
typedef std::shared_ptr< NodeStore > | NodeStorePtr |
|
typedef shared_ptr< ObjectFactory > | ObjectFactoryPtr |
| Shared pointer to ObjectFactory. More...
|
|
typedef shared_ptr< Object > | ObjectPtr |
| Shared pointer to Object. More...
|
|
typedef shared_ptr< Ogre2ArrowVisual > | Ogre2ArrowVisualPtr |
|
typedef shared_ptr< Ogre2AxisVisual > | Ogre2AxisVisualPtr |
|
typedef shared_ptr< Ogre2BoundingBoxCamera > | Ogre2BoundingBoxCameraPtr |
|
typedef shared_ptr< Ogre2Camera > | Ogre2CameraPtr |
|
typedef shared_ptr< Ogre2Capsule > | Ogre2CapsulePtr |
|
typedef shared_ptr< Ogre2COMVisual > | Ogre2COMVisualPtr |
|
typedef shared_ptr< Ogre2DepthCamera > | Ogre2DepthCameraPtr |
|
typedef shared_ptr< Ogre2DirectionalLight > | Ogre2DirectionalLightPtr |
|
typedef shared_ptr< Ogre2Geometry > | Ogre2GeometryPtr |
|
typedef BaseGeometryStore< Ogre2Geometry > | Ogre2GeometryStore |
|
typedef shared_ptr< Ogre2GeometryStore > | Ogre2GeometryStorePtr |
|
typedef shared_ptr< Ogre2GizmoVisual > | Ogre2GizmoVisualPtr |
|
typedef shared_ptr< Ogre2GpuRays > | Ogre2GpuRaysPtr |
|
typedef shared_ptr< Ogre2Grid > | Ogre2GridPtr |
|
typedef shared_ptr< Ogre2Heightmap > | Ogre2HeightmapPtr |
|
typedef shared_ptr< Ogre2InertiaVisual > | Ogre2InertiaVisualPtr |
|
typedef shared_ptr< Ogre2JointVisual > | Ogre2JointVisualPtr |
|
typedef shared_ptr< Ogre2LidarVisual > | Ogre2LidarVisualPtr |
|
typedef shared_ptr< Ogre2Light > | Ogre2LightPtr |
|
typedef BaseLightStore< Ogre2Light > | Ogre2LightStore |
|
typedef shared_ptr< Ogre2LightStore > | Ogre2LightStorePtr |
|
typedef shared_ptr< Ogre2LightVisual > | Ogre2LightVisualPtr |
|
typedef shared_ptr< Ogre2Marker > | Ogre2MarkerPtr |
|
typedef BaseMaterialMap< Ogre2Material > | Ogre2MaterialMap |
|
typedef shared_ptr< Ogre2MaterialMap > | Ogre2MaterialMapPtr |
|
typedef shared_ptr< Ogre2Material > | Ogre2MaterialPtr |
|
typedef shared_ptr< Ogre2MeshFactory > | Ogre2MeshFactoryPtr |
|
typedef shared_ptr< Ogre2Mesh > | Ogre2MeshPtr |
|
typedef shared_ptr< Ogre2Node > | Ogre2NodePtr |
|
typedef BaseNodeStore< Ogre2Node > | Ogre2NodeStore |
|
typedef shared_ptr< Ogre2NodeStore > | Ogre2NodeStorePtr |
|
typedef shared_ptr< Ogre2ObjectInterface > | Ogre2ObjectInterfacePtr |
|
typedef shared_ptr< Ogre2Object > | Ogre2ObjectPtr |
|
typedef shared_ptr< Ogre2ParticleEmitter > | Ogre2ParticleEmitterPtr |
|
typedef shared_ptr< Ogre2PointLight > | Ogre2PointLightPtr |
|
typedef shared_ptr< Ogre2Projector > | Ogre2ProjectorPtr |
|
typedef shared_ptr< Ogre2RayQuery > | Ogre2RayQueryPtr |
|
typedef shared_ptr< Ogre2RenderEngine > | Ogre2RenderEnginePtr |
|
typedef shared_ptr< Ogre2RenderTargetMaterial > | Ogre2RenderTargetMaterialPtr |
|
typedef shared_ptr< Ogre2RenderTarget > | Ogre2RenderTargetPtr |
|
typedef shared_ptr< Ogre2RenderTexture > | Ogre2RenderTexturePtr |
|
typedef shared_ptr< Ogre2RenderWindow > | Ogre2RenderWindowPtr |
|
typedef shared_ptr< Ogre2Scene > | Ogre2ScenePtr |
|
typedef BaseSceneStore< Ogre2Scene > | Ogre2SceneStore |
|
typedef shared_ptr< Ogre2SceneStore > | Ogre2SceneStorePtr |
|
typedef shared_ptr< Ogre2SegmentationCamera > | Ogre2SegmentationCameraPtr |
|
typedef shared_ptr< Ogre2Sensor > | Ogre2SensorPtr |
|
typedef BaseSensorStore< Ogre2Sensor > | Ogre2SensorStore |
|
typedef shared_ptr< Ogre2SensorStore > | Ogre2SensorStorePtr |
|
typedef shared_ptr< Ogre2SpotLight > | Ogre2SpotLightPtr |
|
typedef shared_ptr< Ogre2SubMesh > | Ogre2SubMeshPtr |
|
typedef BaseSubMeshStore< Ogre2SubMesh > | Ogre2SubMeshStore |
|
typedef shared_ptr< Ogre2SubMeshStore > | Ogre2SubMeshStorePtr |
|
typedef shared_ptr< Ogre2ThermalCamera > | Ogre2ThermalCameraPtr |
|
typedef shared_ptr< Ogre2Visual > | Ogre2VisualPtr |
|
typedef BaseVisualStore< Ogre2Visual > | Ogre2VisualStore |
|
typedef shared_ptr< Ogre2VisualStore > | Ogre2VisualStorePtr |
|
typedef shared_ptr< Ogre2WireBox > | Ogre2WireBoxPtr |
|
typedef shared_ptr< OgreArrowVisual > | OgreArrowVisualPtr |
|
typedef shared_ptr< OgreAxisVisual > | OgreAxisVisualPtr |
|
typedef shared_ptr< OgreCamera > | OgreCameraPtr |
|
typedef shared_ptr< OgreCapsule > | OgreCapsulePtr |
|
typedef shared_ptr< OgreCOMVisual > | OgreCOMVisualPtr |
|
typedef shared_ptr< OgreDepthCamera > | OgreDepthCameraPtr |
|
typedef shared_ptr< OgreDirectionalLight > | OgreDirectionalLightPtr |
|
typedef shared_ptr< OgreGeometry > | OgreGeometryPtr |
|
typedef BaseGeometryStore< OgreGeometry > | OgreGeometryStore |
|
typedef shared_ptr< OgreGeometryStore > | OgreGeometryStorePtr |
|
typedef shared_ptr< OgreGizmoVisual > | OgreGizmoVisualPtr |
|
typedef shared_ptr< OgreGpuRays > | OgreGpuRaysPtr |
|
typedef shared_ptr< OgreGrid > | OgreGridPtr |
|
typedef shared_ptr< OgreHeightmap > | OgreHeightmapPtr |
|
typedef shared_ptr< OgreInertiaVisual > | OgreInertiaVisualPtr |
|
typedef shared_ptr< OgreJointVisual > | OgreJointVisualPtr |
|
typedef shared_ptr< OgreLidarVisual > | OgreLidarVisualPtr |
|
typedef shared_ptr< OgreLight > | OgreLightPtr |
|
typedef BaseLightStore< OgreLight > | OgreLightStore |
|
typedef shared_ptr< OgreLightStore > | OgreLightStorePtr |
|
typedef shared_ptr< OgreLightVisual > | OgreLightVisualPtr |
|
typedef shared_ptr< OgreMarker > | OgreMarkerPtr |
|
typedef BaseMaterialMap< OgreMaterial > | OgreMaterialMap |
|
typedef shared_ptr< OgreMaterialMap > | OgreMaterialMapPtr |
|
typedef shared_ptr< OgreMaterial > | OgreMaterialPtr |
|
typedef shared_ptr< OgreMeshFactory > | OgreMeshFactoryPtr |
|
typedef shared_ptr< OgreMesh > | OgreMeshPtr |
|
typedef shared_ptr< OgreNode > | OgreNodePtr |
|
typedef BaseNodeStore< OgreNode > | OgreNodeStore |
|
typedef shared_ptr< OgreNodeStore > | OgreNodeStorePtr |
|
typedef shared_ptr< OgreObjectInterface > | OgreObjectInterfacePtr |
|
typedef shared_ptr< OgreObject > | OgreObjectPtr |
|
typedef shared_ptr< OgreParticleEmitter > | OgreParticleEmitterPtr |
|
typedef shared_ptr< OgrePointLight > | OgrePointLightPtr |
|
typedef shared_ptr< OgreProjector > | OgreProjectorPtr |
|
typedef shared_ptr< OgreRayQuery > | OgreRayQueryPtr |
|
typedef shared_ptr< OgreRenderEngine > | OgreRenderEnginePtr |
|
typedef shared_ptr< OgreRenderTargetMaterial > | OgreRenderTargetMaterialPtr |
|
typedef shared_ptr< OgreRenderTarget > | OgreRenderTargetPtr |
|
typedef shared_ptr< OgreRenderTexture > | OgreRenderTexturePtr |
|
typedef shared_ptr< OgreRenderWindow > | OgreRenderWindowPtr |
|
typedef shared_ptr< OgreScene > | OgreScenePtr |
|
typedef BaseSceneStore< OgreScene > | OgreSceneStore |
|
typedef shared_ptr< OgreSceneStore > | OgreSceneStorePtr |
|
typedef shared_ptr< OgreSensor > | OgreSensorPtr |
|
typedef BaseSensorStore< OgreSensor > | OgreSensorStore |
|
typedef shared_ptr< OgreSensorStore > | OgreSensorStorePtr |
|
typedef shared_ptr< OgreSpotLight > | OgreSpotLightPtr |
|
typedef shared_ptr< OgreSubMesh > | OgreSubMeshPtr |
|
typedef BaseSubMeshStore< OgreSubMesh > | OgreSubMeshStore |
|
typedef shared_ptr< OgreSubMeshStore > | OgreSubMeshStorePtr |
|
typedef shared_ptr< OgreText > | OgreTextPtr |
|
typedef shared_ptr< OgreThermalCamera > | OgreThermalCameraPtr |
|
typedef shared_ptr< OgreVisual > | OgreVisualPtr |
|
typedef BaseVisualStore< OgreVisual > | OgreVisualStore |
|
typedef shared_ptr< OgreVisualStore > | OgreVisualStorePtr |
|
typedef shared_ptr< OgreWideAngleCamera > | OgreWideAngleCameraPtr |
|
typedef shared_ptr< OgreWireBox > | OgreWireBoxPtr |
|
typedef shared_ptr< ParticleEmitter > | ParticleEmitterPtr |
| Shared pointer to ParticleEmitter. More...
|
|
typedef shared_ptr< PointLight > | PointLightPtr |
| Shared pointer to PointLight. More...
|
|
typedef shared_ptr< Projector > | ProjectorPtr |
| Shared pointer to Projector. More...
|
|
typedef shared_ptr< RayQuery > | RayQueryPtr |
| Shared pointer to RayQuery. More...
|
|
typedef shared_ptr< RenderPass > | RenderPassPtr |
| Shared pointer to RenderPass. More...
|
|
typedef shared_ptr< RenderPassSystem > | RenderPassSystemPtr |
| Shared pointer to RenderPassSystem. More...
|
|
typedef shared_ptr< RenderTarget > | RenderTargetPtr |
| Shared pointer to RenderTarget. More...
|
|
typedef shared_ptr< RenderTexture > | RenderTexturePtr |
| Shared pointer to RenderTexture. More...
|
|
typedef shared_ptr< RenderWindow > | RenderWindowPtr |
| Shared pointer to RenderWindow. More...
|
|
typedef shared_ptr< Scene > | ScenePtr |
| Shared pointer to Scene. More...
|
|
typedef Store< Scene > | SceneStore |
|
typedef std::shared_ptr< SceneStore > | SceneStorePtr |
|
typedef shared_ptr< SegmentationCamera > | SegmentationCameraPtr |
| Shared pointer to Segmentation Camera. More...
|
|
typedef shared_ptr< Sensor > | SensorPtr |
| Shared pointer to Sensor. More...
|
|
typedef Store< Sensor > | SensorStore |
|
typedef std::shared_ptr< SensorStore > | SensorStorePtr |
|
typedef shared_ptr< ShaderParams > | ShaderParamsPtr |
| Shared pointer to ShaderParams. More...
|
|
template<class T > |
using | shared_ptr = std::shared_ptr< T > |
|
typedef shared_ptr< SpotLight > | SpotLightPtr |
| Shared pointer to SpotLight. More...
|
|
typedef shared_ptr< SubMesh > | SubMeshPtr |
| Shared pointer to SubMesh. More...
|
|
typedef Store< SubMesh > | SubMeshStore |
|
typedef std::shared_ptr< SubMeshStore > | SubMeshStorePtr |
|
typedef shared_ptr< Text > | TextPtr |
| Shared pointer to Text. More...
|
|
typedef shared_ptr< ThermalCamera > | ThermalCameraPtr |
| Shared pointer to ThermalCamera. More...
|
|
using | Variant = std::variant< std::monostate, int, float, double, std::string, bool, unsigned int, int64_t, uint64_t > |
| 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< Visual > | VisualPtr |
| Shared pointer to Visual. More...
|
|
typedef Store< Visual > | VisualStore |
|
typedef std::shared_ptr< VisualStore > | VisualStorePtr |
|
typedef shared_ptr< WideAngleCamera > | WideAngleCameraPtr |
| Shared pointer to Wide Angle Camera. More...
|
|
typedef shared_ptr< WireBox > | WireBoxPtr |
| Shared pointer to WireBox. More...
|
|
|
enum | AngleFunctionType { AFT_IDENTITY = 0,
AFT_SIN = 1,
AFT_TAN = 2
} |
| Enum for angle function types. More...
|
|
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 | GzOgreRenderingMode {
GORM_NORMAL = 0,
IORM_NORMAL = 0,
GORM_SOLID_COLOR = 1,
IORM_SOLID_COLOR = 1,
GORM_SOLID_THERMAL_COLOR_TEXTURED = 2,
IORM_SOLID_THERMAL_COLOR_TEXTURED = 2,
GORM_COUNT = 3,
IORM_COUNT = 3
} |
| Rendering modes so that GzHlms implementations follow alternate code paths or extra customizations when they're enabled. 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 | MappingFunctionType {
MFT_GNOMONIC = 0,
MFT_STEREOGRAPHIC = 1,
MFT_EQUIDISTANT = 2,
MFT_EQUISOLID_ANGLE = 3,
MFT_ORTHOGRAPHIC = 4,
MFT_CUSTOM = 5
} |
| Enum for mapping function 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_GBRG8 = 6,
PF_BAYER_GRBG8 = 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...
|
|
|
Image | convertRGBToBayer (const Image &_image, PixelFormat _bayerFormat) |
| convert an RGB image data into bayer image data More...
|
|
GraphicsAPI | defaultGraphicsAPI () |
| Convenience function to get the default graphics API based on current platform. More...
|
|
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...
|
|
std::string | getEngineInstallDir () |
| getEngineInstallDir return the install directory of the engines More...
|
|
std::string | getInstallPrefix () |
| getInstallPrefix return the install prefix of the library i.e. CMAKE_INSTALL_PREFIX unless the library has been moved More...
|
|
std::string | getResourcePath () |
| getResourcePath return the resource path 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...
|
|
gz::math::Matrix3d | projectionToCameraIntrinsic (const gz::math::Matrix4d &_projectionMatrix, double _width, double _height) |
| Convert a given camera projection matrix to an intrinsics matrix. Intrinsics matrix is different from the matrix returned by Camera::ProjectionMatrix(), which is used by OpenGL internally. The matrix returned contains the camera calibrated values. 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...
|
|
gz::math::AxisAlignedBox | transformAxisAlignedBox (const gz::math::AxisAlignedBox &_box, const gz::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 (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...
|
|