Gazebo Rendering

API Reference

9.0.0~pre2

Ogre implementation of WideAngleCamera. More...

#include <Ogre2WideAngleCamera.hh>

Public Member Functions

virtual ~Ogre2WideAngleCamera () override
 Destructor.
 
void AddRenderPass (const RenderPassPtr &_pass) override
 Add a render pass to the camera.
 
MaterialPtr BackgroundMaterial () const
 Get the background material of this camera.
 
Ogre::Ray CameraToViewportRay (const math::Vector2d &_screenPos, uint32_t _faceIdx)
 It's the same as calling ogreCamera->getCameraToViewportRay but for the specific _faceIdx.
 
common::ConnectionPtr ConnectNewWideAngleFrame (std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber) override
 Subscribes a new listener to this camera's new frame event.
 
void Copy (Image &_image) const override
 Writes the last rendered image to the given image buffer. This function can be called multiple times after PostRender has been called, without rendering the scene again. Calling this function before a single image has been rendered will have undefined behavior.
 
virtual void CreateRenderTexture ()
 Create a texture.
 
virtual void Destroy () override
 Destroy any resources associated with this object. Invoking any other functions after destroying an object will result in undefined behavior.
 
void DestroyTextures ()
 Destroys all textures and workspaces, possibly for recreation.
 
uint32_t EnvTextureSize () const
 Gets the environment texture size.
 
virtual void Init () override
 
virtual void PostRender () override
 Render the camera.
 
virtual void PreRender () override
 Prepare this object and any of its children for rendering. This should be called for each object in a scene just before rendering, which can be achieved by a single call to Scene::PreRender.
 
math::Vector3d Project3d (const math::Vector3d &_pt) const override
 Project 3D world coordinates to screen coordinates.
 
void RemoveAllRenderPasses () override
 Remove all render passes from the camera.
 
void RemoveRenderPass (const RenderPassPtr &_pass) override
 Remove a render pass from the camera.
 
virtual void Render () override
 Implementation of the render call.
 
void SetBackgroundMaterial (MaterialPtr _material)
 Set the background material of this camera.
 
void SetEnvTextureSize (uint32_t _size)
 Sets environment texture size.
 
- Public Member Functions inherited from BaseWideAngleCamera< Ogre2Sensor >
virtual ~BaseWideAngleCamera ()
 Destructor.
 
virtual const CameraLensLens () const override
 Get the camera lens used by this wide angle camera.
 
virtual void SetLens (const CameraLens &_lens) override
 Set the camera lens to use for this wide angle camera.
 
- Public Member Functions inherited from WideAngleCamera
virtual ~WideAngleCamera ()
 Destructor.
 
- Public Member Functions inherited from Camera
virtual ~Camera ()
 Destructor.
 
- Public Member Functions inherited from Sensor
virtual ~Sensor ()
 Sensor.
 
- Public Member Functions inherited from Node
virtual ~Node ()
 Destructor.
 
- Public Member Functions inherited from Object
virtual ~Object ()
 Destructor.
 
virtual unsigned int Id () const =0
 Get the object ID. This ID will be unique across all objects inside a given scene, but necessarily true for objects across different scenes.
 
virtual std::string Name () const =0
 Get the object name. This name will be unique across all objects inside a given scene, but necessarily true for objects across different scenes.
 
virtual ScenePtr Scene () const =0
 Get the Scene that created this object.
 
- Public Member Functions inherited from BaseCamera< T >
virtual ~BaseCamera ()
 
virtual unsigned int AntiAliasing () const override
 Get the level of anti-aliasing used during rendering.
 
virtual double AspectRatio () const override
 Get the camera's aspect ratio.
 
virtual void Capture (Image &_image) override
 Renders a new frame and writes the results to the given image. This is a convenience function for single-camera scenes. It wraps the pre-render, render, post-render, and get-image calls into a single function. This should NOT be used in applications with multiple cameras or multiple consumers of a single camera's images.
 
virtual common::ConnectionPtr ConnectNewImageFrame (Camera::NewFrameListener _listener) override
 Subscribes a new listener to this camera's new frame event.
 
virtual Image CreateImage () const override
 Created an empty image buffer for capturing images. The resulting image will have sufficient memory allocated for subsequent calls to this camera's Capture function. However, any changes to this cameras properties may invalidate the condition.
 
virtual RenderWindowPtr CreateRenderWindow () override
 Create a render window.
 
virtual double FarClipPlane () const override
 Get the camera's far clipping plane distance.
 
virtual math::Vector3d FollowOffset () const override
 Get the follow offset vector in the frame specified at the time the follow target is set.
 
virtual double FollowPGain () const override
 Get the camera follow movement P gain.
 
virtual NodePtr FollowTarget () const override
 Get the target node being followed.
 
virtual math::Angle HFOV () const override
 Get the camera's horizontal field-of-view.
 
virtual PixelFormat ImageFormat () const override
 Get the image pixel format. If the image pixel format has not been set with a valid value, PF_UNKNOWN will be returned.
 
virtual unsigned int ImageHeight () const override
 Get the image height in pixels.
 
virtual unsigned int ImageMemorySize () const override
 Get the total image memory size in bytes.
 
virtual unsigned int ImageWidth () const override
 Get the image width in pixels.
 
virtual double NearClipPlane () const override
 Get the camera's near clipping plane distance.
 
virtual void PrepareForExternalSampling () override
 Right now this is Vulkan-only. This function needs to be called after rendering, and before handling the texture pointer (i.e. by calling RenderTextureMetalId()) so that external APIs (e.g. Qt) can sample the texture.
 
virtual math::Vector2i Project (const math::Vector3d &_pt) const override
 Project point in 3d world space to 2d screen space.
 
virtual math::Matrix4d ProjectionMatrix () const override
 Get the projection matrix for this camera.
 
virtual CameraProjectionType ProjectionType () const override
 Get the projection type for this camera.
 
virtual RenderPassPtr RenderPassByIndex (unsigned int _index) const override
 Get a render passes by index.
 
virtual unsigned int RenderPassCount () const override
 Get the number of render passes applied to the camera.
 
virtual unsigned int RenderTextureGLId () const override
 Get the OpenGL texture id associated with the render texture used by this camera. A valid id is returned only if the underlying render engine is OpenGL based.
 
virtual void RenderTextureMetalId (void *_textureIdPtr) const override
 Get the Metal texture id associated with the render texture used by this camera. A valid Id is obtained only if the underlying render engine is Metal based. The pointer set by this function must be released to an id<MTLTexture> using CFBridgingRelease.
 
virtual bool SaveFrame (const std::string &_name) override
 Writes the previously rendered frame to a file. This function can be called multiple times after PostRender has been called, without rendering the scene again. Calling this function before a single image has been rendered will have undefined behavior.
 
virtual void SetAntiAliasing (const unsigned int _aa) override
 Set the level of anti-aliasing used during rendering. If a value of 0 is given, no anti-aliasing will be performed. Higher values can significantly slow-down rendering times, depending on the underlying render engine.
 
virtual void SetAspectRatio (const double _ratio) override
 Set the camera's aspect ratio. This value determines the cameras vertical field-of-view. It is often the.
 
virtual void SetFarClipPlane (const double _far) override
 Set the camera's far clipping plane distance.
 
virtual void SetFollowOffset (const math::Vector3d &_offset) override
 Set offset of camera from target node being followed. The offset will be in the frame that is specified at the time the follow target is set.
 
virtual void SetFollowPGain (const double _pGain) override
 Set follow P Gain. Determines how fast the camera moves to follow the target node. Valid range: [0-1].
 
virtual void SetFollowTarget (const NodePtr &_target, const math::Vector3d &_Offset, const bool _worldFrame) override
 Set a node for camera to follow. The camera will automatically update its position to keep itself at the specified offset distance from the target being followed. If null is specified, camera follow is disabled. In contrast to SetTrackTarget, the camera does not change its orientation when following is enabled.
 
virtual void SetHFOV (const math::Angle &_hfov) override
 Set the camera's horizontal field-of-view.
 
virtual void SetImageFormat (PixelFormat _format, bool _reinterpretable=false) override
 Set the image pixel format.
 
virtual void SetImageHeight (const unsigned int _height) override
 Set the image height in pixels.
 
virtual void SetImageWidth (const unsigned int _width) override
 Set the image width in pixels.
 
virtual void SetMaterial (const MaterialPtr &_material) override
 Set a material that the camera should see on all objects.
 
virtual void SetNearClipPlane (const double _near) override
 Set the camera's near clipping plane distance.
 
virtual void SetProjectionMatrix (const math::Matrix4d &_matrix) override
 Set the projection matrix for this camera. This overrides the standard projection matrix computed based on camera parameters.
 
virtual void SetProjectionType (CameraProjectionType _type) override
 Set the projection type for this camera This changes the projection matrix of the camera based on the camera projection type. A custom projection matrix can be specified via SetProjectionMatrix to override the provided one. To disable the custom projection matrix, just call this function again with the desired projection type.
 
virtual void SetShadowsDirty () override
 
virtual void SetTrackOffset (const math::Vector3d &_offset) override
 Set track offset. Camera will track a point that's at an offset from the target node. The offset will be in the frame that is specified at the time the track target is set.
 
virtual void SetTrackPGain (const double _pGain) override
 Set track P Gain. Determines how fast the camera rotates to look at the target node. Valid range: [0-1].
 
virtual void SetTrackTarget (const NodePtr &_target, const math::Vector3d &_offset, const bool _worldFrame) override
 Set a node for camera to track. The camera will automatically change its orientation to face the target being tracked. If null is specified, tracking is disabled. In contrast to SetFollowTarget the camera does not change its position when tracking is enabled.
 
virtual math::Vector3d TrackOffset () const override
 Get the track offset vector in the frame specified at the time the track target is set.
 
virtual double TrackPGain () const override
 Get the camera track rotation P gain.
 
virtual NodePtr TrackTarget () const override
 Get the target node being tracked.
 
virtual void Update () override
 Renders a new frame. This is a convenience function for single-camera scenes. It wraps the pre-render, render, and post-render into a single function. This should NOT be used in applications with multiple cameras or multiple consumers of a single camera's images.
 
virtual math::Matrix4d ViewMatrix () const override
 Get the view matrix for this camera.
 
virtual VisualPtr VisualAt (const gz::math::Vector2i &_mousePos) override
 Get the visual for a given mouse position param[in] _mousePos mouse position.
 
- Public Member Functions inherited from Ogre2Sensor
virtual ~Ogre2Sensor ()
 Destructor.
 
- Public Member Functions inherited from BaseSensor< Ogre2Node >
virtual ~BaseSensor ()
 
virtual void SetVisibilityMask (uint32_t _mask) override
 Set visibility mask.
 
virtual uint32_t VisibilityMask () const override
 Get visibility mask.
 
- Public Member Functions inherited from Ogre2Node
virtual ~Ogre2Node ()
 Destructor.
 
virtual bool HasParent () const override
 Determine if this Node is attached to another Node.
 
virtual bool InheritScale () const override
 Determine if this node inherits scale from this parent.
 
virtual math::Vector3d LocalScale () const override
 Get the local scale.
 
virtual Ogre::SceneNode * Node () const
 Get a pointer to the underlying scene node.
 
virtual NodePtr Parent () const override
 Get the parent Node.
 
virtual void SetInheritScale (bool _inherit) override
 Specify if this node inherits scale from its parent.
 
- Public Member Functions inherited from BaseNode< Ogre2Object >
virtual ~BaseNode ()
 
virtual void AddChild (NodePtr _child) override
 Add the given node to this node. If the given node is already a child, no work will be done.
 
virtual NodePtr ChildById (unsigned int _id) const override
 Get node with given ID. If no child exists with given ID, NULL will be returned.
 
virtual NodePtr ChildByIndex (unsigned int _index) const override
 Get node at given index. If no child exists at given index, NULL will be returned.
 
virtual NodePtr ChildByName (const std::string &_name) const override
 Get node with given name. If no child exists with given name, NULL will be returned.
 
virtual unsigned int ChildCount () const override
 Get number of child nodes.
 
virtual bool HasChild (ConstNodePtr _child) const override
 Determine if given node is an attached child.
 
virtual bool HasChildId (unsigned int _id) const override
 Determine if node with given ID is an attached child.
 
virtual bool HasChildName (const std::string &_name) const override
 Determine if node with given name is an attached child.
 
virtual bool HasUserData (const std::string &_key) const override
 Check if node has custom data.
 
virtual math::Pose3d InitialLocalPose () const override
 Get the initial local pose.
 
virtual math::Pose3d LocalPose () const override
 Get the local pose.
 
virtual math::Vector3d LocalPosition () const override
 Get the local position.
 
virtual math::Quaterniond LocalRotation () const override
 Get the local rotation.
 
virtual math::Vector3d Origin () const override
 Get position of origin.
 
virtual NodePtr RemoveChild (NodePtr _child) override
 Remove (detach) the given node from this node. If the given node is not a child of this node, no work will be done.
 
virtual NodePtr RemoveChildById (unsigned int _id) override
 Remove (detach) the node with the given ID from this node. If the specified node is not a child of this node, no work will be done.
 
virtual NodePtr RemoveChildByIndex (unsigned int _index) override
 Remove (detach) the node at the given index from this node. If the specified node is not a child of this node, no work will be done.
 
virtual NodePtr RemoveChildByName (const std::string &_name) override
 Remove (detach) the node with the given name from this node. If the specified node is not a child of this node, no work will be done.
 
virtual void RemoveChildren () override
 Remove all child nodes from this node This detaches all the child nodes but does not destroy them.
 
virtual void RemoveParent () override
 Detach this Node from its parent. If this Node does not have a parent, no work will be done.
 
virtual void Scale (const math::Vector3d &_scale) override
 Scale the current scale by the given scalars.
 
virtual void Scale (double _scale) override
 Scale the current scale by the given scalar. The given scalar will be assigned to the x, y, and z coordinates.
 
virtual void Scale (double _x, double _y, double _z) override
 Scale the current scale by the given scalars.
 
virtual void SetLocalPose (const math::Pose3d &_pose) override
 Set the local pose.
 
virtual void SetLocalPosition (const math::Vector3d &_position) override
 Set the local position.
 
virtual void SetLocalPosition (double _x, double _y, double _z) override
 Set the local position.
 
virtual void SetLocalRotation (const math::Quaterniond &_rotation) override
 Set the local rotation.
 
virtual void SetLocalRotation (double _r, double _p, double _y) override
 Set the local rotation.
 
virtual void SetLocalRotation (double _w, double _x, double _y, double _z) override
 Set the local rotation.
 
virtual void SetLocalScale (const math::Vector3d &_scale) override
 Set the local scale.
 
virtual void SetLocalScale (double _scale) override
 Set the local scale. The given scale will be assigned to the x, y, and z coordinates.
 
virtual void SetLocalScale (double _x, double _y, double _z) override
 Set the local scale.
 
virtual void SetOrigin (const math::Vector3d &_origin) override
 Set position of origin. The position should be relative to the original origin of the geometry.
 
virtual void SetOrigin (double _x, double _y, double _z) override
 Set position of origin. The position should be relative to the original origin of the geometry.
 
virtual void SetUserData (const std::string &_key, Variant _value) override
 Store any custom data associated with this node.
 
virtual void SetWorldPose (const math::Pose3d &_pose) override
 Set the world pose.
 
virtual void SetWorldPosition (const math::Vector3d &_position) override
 Set the world position.
 
virtual void SetWorldPosition (double _x, double _y, double _z) override
 Set the world position.
 
virtual void SetWorldRotation (const math::Quaterniond &_rotation) override
 Set the world rotation.
 
virtual void SetWorldRotation (double _r, double _p, double _y) override
 Set the world rotation.
 
virtual void SetWorldRotation (double _w, double _x, double _y, double _z) override
 Set the world rotation.
 
virtual void SetWorldScale (const math::Vector3d &_scale) override
 Set the world scale.
 
virtual void SetWorldScale (double _scale) override
 Set the world scale. The given scale will be assigned to the x, y, and z coordinates.
 
virtual void SetWorldScale (double _x, double _y, double _z) override
 Set the world scale.
 
virtual Variant UserData (const std::string &_key) const override
 Get custom data stored in this node.
 
virtual math::Pose3d WorldPose () const override
 Get the world pose.
 
virtual math::Vector3d WorldPosition () const override
 Get the world position.
 
virtual math::Quaterniond WorldRotation () const override
 Get the world rotation.
 
virtual math::Vector3d WorldScale () const override
 Get the world scale.
 
virtual math::Pose3d WorldToLocal (const math::Pose3d &_pose) const override
 Convert given world pose to local pose.
 
- Public Member Functions inherited from Ogre2Object
virtual ~Ogre2Object ()
 Destructor.
 
virtual ScenePtr Scene () const override
 
- Public Member Functions inherited from BaseObject
virtual ~BaseObject ()
 
virtual unsigned int Id () const override
 
virtual std::string Name () const override
 

Protected Member Functions

 Ogre2WideAngleCamera ()
 Constructor.
 
void CreateCamera ()
 Create the camera.
 
void CreateFacesWorkspaces (bool _withMsaa)
 Creates the workspaces & their definitions.
 
void CreateStitchWorkspace ()
 Creates the stitch workspaces & their definitions.
 
void CreateStitchWorkspaceDefinition ()
 Creates the workspace definition for stitch (final) pass, including effects.
 
void CreateWideAngleTexture () override
 Set the camera's render target.
 
void CreateWorkspaceDefinition (bool _withMsaa)
 Creates the workspace definition, including effects.
 
void DestroyFacesWorkspaces ()
 Destroys the workspaces & their definitions.
 
void DestroyRenderTexture ()
 Destroy render texture created by CreateRenderTexture() Note: It's not virtual.
 
void DestroyStitchWorkspace ()
 Destroys the stitch workspaces & their definitions.
 
bool HasTempStitchTexture () const
 Returns true if we have a temp texture for Render passes with WideAngleCameraAfterStitching = true.
 
bool NeedsTempStitchTexture () const
 Returns what HasTempStitchTexture() should return.
 
virtual RenderTargetPtr RenderTarget () const override
 Get a pointer to the render target.
 
void SetupMSAA (Ogre::CompositorManager2 *_ogreCompMgr, uint8_t _msaa)
 Changes the Compositor Definition to use the MSAA settings we need. Do not call this if not using MSAA.
 
uint32_t TempStitchTextureChannel () const
 Returns what HasTempStitchTexture() should return.
 
void UpdateRenderPasses ()
 Checks if workspace nodes need to be updated since render passes can be toggled at any point.
 
std::string WorkspaceDefinitionName (uint32_t _faceIdx) const
 Returns the workspace name. It's unique for each camera.
 
std::string WorkspaceFinalPassDefinitionName () const
 Returns the workspace name for the final pass that stitches all faces.
 
- Protected Member Functions inherited from BaseWideAngleCamera< Ogre2Sensor >
 BaseWideAngleCamera ()
 Constructor.
 
- Protected Member Functions inherited from BaseCamera< T >
 BaseCamera ()
 
virtual void * CreateImageBuffer () const
 
virtual void Load () override
 
virtual void Reset ()
 
- Protected Member Functions inherited from Ogre2Sensor
 Ogre2Sensor ()
 Constructor.
 
- Protected Member Functions inherited from BaseSensor< Ogre2Node >
 BaseSensor ()
 
- Protected Member Functions inherited from Ogre2Node
 Ogre2Node ()
 Constructor.
 
virtual bool AttachChild (NodePtr _child) override
 
virtual NodeStorePtr Children () const override
 
virtual bool DetachChild (NodePtr _child) override
 
virtual void Load () override
 
virtual math::Pose3d RawLocalPose () const override
 
virtual math::Vector3d RawLocalPosition () const
 Get the raw local position of the node.
 
virtual math::Quaterniond RawLocalRotation () const
 Get the raw local rotation of the node.
 
virtual void SetLocalScaleImpl (const math::Vector3d &_scale) override
 Implementation of the SetLocalScale function.
 
virtual void SetParent (Ogre2NodePtr _parent)
 Set the parent node.
 
virtual void SetRawLocalPose (const math::Pose3d &_Pose3d) override
 
virtual void SetRawLocalPosition (const math::Vector3d &_position)
 Set the raw local position of the node.
 
virtual void SetRawLocalRotation (const math::Quaterniond &_rotation)
 Set the raw local rotation of the node.
 
- Protected Member Functions inherited from BaseNode< Ogre2Object >
 BaseNode ()
 
virtual void PreRenderChildren ()
 
- Protected Member Functions inherited from Ogre2Object
 Ogre2Object ()
 Constructor.
 
- Protected Member Functions inherited from BaseObject
 BaseObject ()
 

Additional Inherited Members

- Public Types inherited from Camera
typedef std::function< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> NewFrameListener
 Callback function for new frame render event listeners.
 
- Protected Attributes inherited from BaseWideAngleCamera< Ogre2Sensor >
CameraLens lens
 Camera lens used by this wide angle camera.
 
- Protected Attributes inherited from BaseCamera< T >
unsigned int antiAliasing = 0u
 Anti-aliasing.
 
double aspect = 1.3333333
 Aspect ratio.
 
double farClip = 1000.0
 Far clipping plane distance.
 
NodePtr followNode
 Target node to follow.
 
math::Vector3d followOffset
 Offset distance between camera and target node being followed.
 
double followPGain = 1.0
 P gain for follow mode. Determines how fast the camera moves to follow the target node. Valid range: [0-1].
 
bool followWorldFrame = false
 Follow target in world frame.
 
math::Angle hfov
 Horizontal camera field of view.
 
ImagePtr imageBuffer
 
double nearClip = 0.01
 Near clipping plane distance.
 
common::EventT< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> newFrameEvent
 
math::Matrix4d projectionMatrix
 Custom projection matrix.
 
CameraProjectionType projectionType = CPT_PERSPECTIVE
 Camera projection type.
 
NodePtr trackNode
 Target node to track if camera tracking is on.
 
math::Vector3d trackOffset
 Set camera to track a point offset in target node's local or world frame depending on trackWorldFrame.
 
double trackPGain = 1.0
 P gain for tracking. Determines how fast the camera rotates to look at the target node. Valid range: [0-1].
 
bool trackWorldFrame = false
 Track point relative to target in world frame.
 
- Protected Attributes inherited from BaseSensor< Ogre2Node >
uint32_t visibilityMask
 Camera's visibility mask.
 
- Protected Attributes inherited from Ogre2Node
Ogre2NodeStorePtr children
 A list of child nodes.
 
Ogre::SceneNode * ogreNode = nullptr
 The underlying ogre scene node.
 
Ogre2NodePtr parent
 Pointer to the parent ogre node.
 
- Protected Attributes inherited from BaseNode< Ogre2Object >
gz::math::Pose3d initialLocalPose
 Initial local pose for this node.
 
bool initialLocalPoseSet
 Flag to indicate whether initial local pose is set for this node.
 
math::Vector3d origin
 
std::map< std::string, VariantuserData
 A map of custom key value data.
 
- Protected Attributes inherited from Ogre2Object
Ogre2ScenePtr scene
 Pointer to the ogre scene.
 
- Protected Attributes inherited from BaseObject
unsigned int id
 
std::string name
 

Detailed Description

Ogre implementation of WideAngleCamera.

Constructor & Destructor Documentation

◆ Ogre2WideAngleCamera()

Ogre2WideAngleCamera ( )
protected

Constructor.

◆ ~Ogre2WideAngleCamera()

virtual ~Ogre2WideAngleCamera ( )
overridevirtual

Destructor.

Member Function Documentation

◆ AddRenderPass()

void AddRenderPass ( const RenderPassPtr _pass)
overridevirtual

Add a render pass to the camera.

Parameters
[in]_passNew render pass to add

Implements Camera.

◆ BackgroundMaterial()

MaterialPtr BackgroundMaterial ( ) const

Get the background material of this camera.

Returns
background material

◆ CameraToViewportRay()

Ogre::Ray CameraToViewportRay ( const math::Vector2d _screenPos,
uint32_t  _faceIdx 
)

It's the same as calling ogreCamera->getCameraToViewportRay but for the specific _faceIdx.

Parameters
_screenPosScreen space position
_faceIdxFace index in range [0; 6). See RayQuery::SetFromCamera for what each value means
Returns
Ogre Ray pointing towards screenPos from the given face idx

◆ ConnectNewWideAngleFrame()

common::ConnectionPtr ConnectNewWideAngleFrame ( std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)
overridevirtual

Subscribes a new listener to this camera's new frame event.

Parameters
[in]_subscriberNew camera listener callback

Reimplemented from BaseWideAngleCamera< Ogre2Sensor >.

◆ Copy()

void Copy ( Image _image) const
overridevirtual

Writes the last rendered image to the given image buffer. This function can be called multiple times after PostRender has been called, without rendering the scene again. Calling this function before a single image has been rendered will have undefined behavior.

Parameters
[out]_imageOutput image buffer

Implements Camera.

◆ CreateCamera()

void CreateCamera ( )
protected

Create the camera.

◆ CreateFacesWorkspaces()

void CreateFacesWorkspaces ( bool  _withMsaa)
protected

Creates the workspaces & their definitions.

Parameters
[in]_withMsaaWhether the version we're retrieving is the MSAA

◆ CreateRenderTexture()

virtual void CreateRenderTexture ( )
virtual

Create a texture.

◆ CreateStitchWorkspace()

void CreateStitchWorkspace ( )
protected

Creates the stitch workspaces & their definitions.

◆ CreateStitchWorkspaceDefinition()

void CreateStitchWorkspaceDefinition ( )
protected

Creates the workspace definition for stitch (final) pass, including effects.

◆ CreateWideAngleTexture()

void CreateWideAngleTexture ( )
overrideprotectedvirtual

Set the camera's render target.

Reimplemented from BaseWideAngleCamera< Ogre2Sensor >.

◆ CreateWorkspaceDefinition()

void CreateWorkspaceDefinition ( bool  _withMsaa)
protected

Creates the workspace definition, including effects.

Parameters
[in]_withMsaaWhether the camera is using MSAA

◆ Destroy()

virtual void Destroy ( )
overridevirtual

Destroy any resources associated with this object. Invoking any other functions after destroying an object will result in undefined behavior.

Implements Object.

◆ DestroyFacesWorkspaces()

void DestroyFacesWorkspaces ( )
protected

Destroys the workspaces & their definitions.

◆ DestroyRenderTexture()

void DestroyRenderTexture ( )
protected

Destroy render texture created by CreateRenderTexture() Note: It's not virtual.

◆ DestroyStitchWorkspace()

void DestroyStitchWorkspace ( )
protected

Destroys the stitch workspaces & their definitions.

◆ DestroyTextures()

void DestroyTextures ( )

Destroys all textures and workspaces, possibly for recreation.

◆ EnvTextureSize()

uint32_t EnvTextureSize ( ) const

Gets the environment texture size.

Returns
Texture size

◆ HasTempStitchTexture()

bool HasTempStitchTexture ( ) const
protected

Returns true if we have a temp texture for Render passes with WideAngleCameraAfterStitching = true.

Returns
See description.

◆ Init()

virtual void Init ( )
overridevirtual

Reimplemented from Ogre2Node.

◆ NeedsTempStitchTexture()

bool NeedsTempStitchTexture ( ) const
protected

Returns what HasTempStitchTexture() should return.

Returns
True if there are RenderPases with WideAngleCameraAfterStitching = true. False otherwise.

◆ PostRender()

virtual void PostRender ( )
overridevirtual

Render the camera.

Implements Camera.

◆ PreRender()

virtual void PreRender ( )
overridevirtual

Prepare this object and any of its children for rendering. This should be called for each object in a scene just before rendering, which can be achieved by a single call to Scene::PreRender.

Implements Object.

◆ Project3d()

math::Vector3d Project3d ( const math::Vector3d _pt) const
overridevirtual

Project 3D world coordinates to screen coordinates.

Parameters
[in]_pt3D world coodinates
Returns
Screen coordinates. Z is the distance of point from camera optical center.

Reimplemented from BaseWideAngleCamera< Ogre2Sensor >.

◆ RemoveAllRenderPasses()

void RemoveAllRenderPasses ( )
overridevirtual

Remove all render passes from the camera.

Implements Camera.

◆ RemoveRenderPass()

void RemoveRenderPass ( const RenderPassPtr _pass)
overridevirtual

Remove a render pass from the camera.

Parameters
[in]_passrender pass to remove

Implements Camera.

◆ Render()

virtual void Render ( )
overridevirtual

Implementation of the render call.

Implements Camera.

◆ RenderTarget()

virtual RenderTargetPtr RenderTarget ( ) const
overrideprotectedvirtual

Get a pointer to the render target.

Returns
Pointer to the render target

Implements BaseCamera< T >.

◆ SetBackgroundMaterial()

void SetBackgroundMaterial ( MaterialPtr  _material)

Set the background material of this camera.

Parameters
[in]_materialMaterial to set the background to

◆ SetEnvTextureSize()

void SetEnvTextureSize ( uint32_t  _size)

Sets environment texture size.

Parameters
[in]_sizeTexture size

◆ SetupMSAA()

void SetupMSAA ( Ogre::CompositorManager2 *  _ogreCompMgr,
uint8_t  _msaa 
)
protected

Changes the Compositor Definition to use the MSAA settings we need. Do not call this if not using MSAA.

Parameters
[in]_ogreCompMgrOgre's Compositor Manager
[in]_msaaValue in range [2; 256)

◆ TempStitchTextureChannel()

uint32_t TempStitchTextureChannel ( ) const
protected

Returns what HasTempStitchTexture() should return.

Returns
Returns which channel kStichTmpTexture should be in. Depends on whether number of render passes with RenderPass::WideAngleCameraAfterStitching == true is odd or even

◆ UpdateRenderPasses()

void UpdateRenderPasses ( )
protected

Checks if workspace nodes need to be updated since render passes can be toggled at any point.

◆ WorkspaceDefinitionName()

std::string WorkspaceDefinitionName ( uint32_t  _faceIdx) const
protected

Returns the workspace name. It's unique for each camera.

Parameters
[in]_faceIdxFace index in range [0; 6)
Returns
Workspace definition's name

◆ WorkspaceFinalPassDefinitionName()

std::string WorkspaceFinalPassDefinitionName ( ) const
protected

Returns the workspace name for the final pass that stitches all faces.

Returns
Workspace definition's name

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