Ignition Rendering

API Reference

6.3.1
Camera Class Referenceabstract

Posable camera used for rendering the scene graph. More...

#include <ignition/rendering/Camera.hh>

Public Types

typedef std::function< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> NewFrameListener
 Callback function for new frame render event listeners. More...
 

Public Member Functions

virtual ~Camera ()
 Destructor. More...
 
virtual void AddRenderPass (const RenderPassPtr &_pass)=0
 Add a render pass to the camera. More...
 
virtual unsigned int AntiAliasing () const =0
 Get the level of anti-aliasing used during rendering. More...
 
virtual double AspectRatio () const =0
 Get the camera's aspect ratio. More...
 
virtual void Capture (Image &_image)=0
 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. More...
 
virtual common::ConnectionPtr ConnectNewImageFrame (NewFrameListener _listener)=0
 Subscribes a new listener to this camera's new frame event. More...
 
virtual void Copy (Image &_image) const =0
 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. More...
 
virtual Image CreateImage () const =0
 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. More...
 
virtual RenderWindowPtr CreateRenderWindow ()=0
 Create a render window. More...
 
virtual double FarClipPlane () const =0
 Get the camera's far clipping plane distance. More...
 
virtual math::Vector3d FollowOffset () const =0
 Get the follow offset vector in the frame specified at the time the follow target is set. More...
 
virtual double FollowPGain () const =0
 Get the camera follow movement P gain. More...
 
virtual NodePtr FollowTarget () const =0
 Get the target node being followed. More...
 
virtual math::Angle HFOV () const =0
 Get the camera's horizontal field-of-view. More...
 
virtual PixelFormat ImageFormat () const =0
 Get the image pixel format. If the image pixel format has not been set with a valid value, PF_UNKNOWN will be returned. More...
 
virtual unsigned int ImageHeight () const =0
 Get the image height in pixels. More...
 
virtual unsigned int ImageMemorySize () const =0
 Get the total image memory size in bytes. More...
 
virtual unsigned int ImageWidth () const =0
 Get the image width in pixels. More...
 
virtual double NearClipPlane () const =0
 Get the camera's near clipping plane distance. More...
 
virtual void PostRender ()=0
 Preforms any necessary final rendering work. Once rendering is complete the camera will alert any listeners of the new frame event. This function should only be called after a call to Render has successfully been executed. More...
 
virtual math::Vector2i Project (const math::Vector3d &_pt) const =0
 Project point in 3d world space to 2d screen space. More...
 
virtual math::Matrix4d ProjectionMatrix () const =0
 Get the projection matrix for this camera. More...
 
virtual CameraProjectionType ProjectionType () const =0
 Get the projection type for this camera. More...
 
virtual void RemoveRenderPass (const RenderPassPtr &_pass)=0
 Remove a render pass from the camera. More...
 
virtual void Render ()=0
 Renders the current scene using this camera. This function assumes PreRender() has already been called on the parent Scene, allowing the camera and the scene itself to prepare for rendering. More...
 
virtual RenderPassPtr RenderPassByIndex (unsigned int _index) const =0
 Get a render passes by index. More...
 
virtual unsigned int RenderPassCount () const =0
 Get the number of render passes applied to the camera. More...
 
virtual unsigned int RenderTextureGLId () const =0
 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. More...
 
virtual bool SaveFrame (const std::string &_name)=0
 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. More...
 
virtual void SetAntiAliasing (const unsigned int _aa)=0
 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. More...
 
virtual void SetAspectRatio (const double _ratio)=0
 Set the camera's aspect ratio. This value determines the cameras vertical field-of-view. It is often the. More...
 
virtual void SetFarClipPlane (const double _far)=0
 Set the camera's far clipping plane distance. More...
 
virtual void SetFollowOffset (const math::Vector3d &_offset)=0
 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. More...
 
virtual void SetFollowPGain (const double _pGain)=0
 Set follow P Gain. Determines how fast the camera moves to follow the target node. Valid range: [0-1]. More...
 
virtual void SetFollowTarget (const NodePtr &_target, const math::Vector3d &_offset=math::Vector3d::Zero, const bool _worldFrame=false)=0
 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. More...
 
virtual void SetHFOV (const math::Angle &_hfov)=0
 Set the camera's horizontal field-of-view. More...
 
virtual void SetImageFormat (PixelFormat _format)=0
 Set the image pixel format. More...
 
virtual void SetImageHeight (unsigned int _height)=0
 Set the image height in pixels. More...
 
virtual void SetImageWidth (unsigned int _width)=0
 Set the image width in pixels. More...
 
virtual void SetMaterial (const MaterialPtr &_material)=0
 Set a material that the camera should see on all objects. More...
 
virtual void SetNearClipPlane (const double _near)=0
 Set the camera's near clipping plane distance. More...
 
virtual void SetProjectionMatrix (const math::Matrix4d &_matrix)=0
 Set the projection matrix for this camera. This overrides the standard projection matrix computed based on camera parameters. More...
 
virtual void SetProjectionType (CameraProjectionType _type)=0
 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. More...
 
virtual void SetShadowsDirty ()=0
 
virtual void SetTrackOffset (const math::Vector3d &_offset)=0
 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. More...
 
virtual void SetTrackPGain (const double _pGain)=0
 Set track P Gain. Determines how fast the camera rotates to look at the target node. Valid range: [0-1]. More...
 
virtual void SetTrackTarget (const NodePtr &_target, const math::Vector3d &_offset=math::Vector3d::Zero, const bool _worldFrame=false)=0
 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. More...
 
virtual math::Vector3d TrackOffset () const =0
 Get the track offset vector in the frame specified at the time the track target is set. More...
 
virtual double TrackPGain () const =0
 Get the camera track rotation P gain. More...
 
virtual NodePtr TrackTarget () const =0
 Get the target node being tracked. More...
 
virtual void Update ()=0
 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. More...
 
virtual math::Matrix4d ViewMatrix () const =0
 Get the view matrix for this camera. More...
 
virtual VisualPtr VisualAt (const ignition::math::Vector2i &_mousePos)=0
 Get the visual for a given mouse position param[in] _mousePos mouse position. More...
 
- Public Member Functions inherited from Sensor
virtual ~Sensor ()
 Sensor. More...
 
virtual void SetVisibilityMask (uint32_t _mask)=0
 Set visibility mask. More...
 
virtual uint32_t VisibilityMask () const =0
 Get visibility mask. More...
 
- Public Member Functions inherited from Node
virtual ~Node ()
 Destructor. More...
 
virtual void AddChild (NodePtr _child)=0
 Add the given node to this node. If the given node is already a child, no work will be done. More...
 
virtual NodePtr ChildById (unsigned int _id) const =0
 Get node with given ID. If no child exists with given ID, NULL will be returned. More...
 
virtual NodePtr ChildByIndex (unsigned int _index) const =0
 Get node at given index. If no child exists at given index, NULL will be returned. More...
 
virtual NodePtr ChildByName (const std::string &_name) const =0
 Get node with given name. If no child exists with given name, NULL will be returned. More...
 
virtual unsigned int ChildCount () const =0
 Get number of child nodes. More...
 
virtual bool HasChild (ConstNodePtr _child) const =0
 Determine if given node is an attached child. More...
 
virtual bool HasChildId (unsigned int _id) const =0
 Determine if node with given ID is an attached child. More...
 
virtual bool HasChildName (const std::string &_name) const =0
 Determine if node with given name is an attached child. More...
 
virtual bool HasParent () const =0
 Determine if this Node is attached to another Node. More...
 
virtual bool HasUserData (const std::string &_key) const =0
 Check if node has custom data. More...
 
virtual bool InheritScale () const =0
 Determine if this node inherits scale from this parent. More...
 
virtual math::Pose3d InitialLocalPose () const =0
 Get the initial local pose. More...
 
virtual math::Pose3d LocalPose () const =0
 Get the local pose. More...
 
virtual math::Vector3d LocalPosition () const =0
 Get the local position. More...
 
virtual math::Quaterniond LocalRotation () const =0
 Get the local rotation. More...
 
virtual math::Vector3d LocalScale () const =0
 Get the local scale. More...
 
virtual math::Vector3d Origin () const =0
 Get position of origin. More...
 
virtual NodePtr Parent () const =0
 Get the parent Node. More...
 
virtual NodePtr RemoveChild (NodePtr _child)=0
 Remove (detach) the given node from this node. If the given node is not a child of this node, no work will be done. More...
 
virtual NodePtr RemoveChildById (unsigned int _id)=0
 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. More...
 
virtual NodePtr RemoveChildByIndex (unsigned int _index)=0
 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. More...
 
virtual NodePtr RemoveChildByName (const std::string &_name)=0
 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. More...
 
virtual void RemoveChildren ()=0
 Remove all child nodes from this node This detaches all the child nodes but does not destroy them. More...
 
virtual void RemoveParent ()=0
 Detach this Node from its parent. If this Node does not have a parent, no work will be done. More...
 
virtual void Scale (double _scale)=0
 Scale the current scale by the given scalar. The given scalar will be assigned to the x, y, and z coordinates. More...
 
virtual void Scale (double _x, double _y, double _z)=0
 Scale the current scale by the given scalars. More...
 
virtual void Scale (const math::Vector3d &_scale)=0
 Scale the current scale by the given scalars. More...
 
virtual void SetInheritScale (bool _inherit)=0
 Specify if this node inherits scale from its parent. More...
 
virtual void SetLocalPose (const math::Pose3d &_pose)=0
 Set the local pose. More...
 
virtual void SetLocalPosition (double _x, double _y, double _z)=0
 Set the local position. More...
 
virtual void SetLocalPosition (const math::Vector3d &_position)=0
 Set the local position. More...
 
virtual void SetLocalRotation (double _r, double _p, double _y)=0
 Set the local rotation. More...
 
virtual void SetLocalRotation (double _w, double _x, double _y, double _z)=0
 Set the local rotation. More...
 
virtual void SetLocalRotation (const math::Quaterniond &_rotation)=0
 Set the local rotation. More...
 
virtual void SetLocalScale (double _scale)=0
 Set the local scale. The given scale will be assigned to the x, y, and z coordinates. More...
 
virtual void SetLocalScale (double _x, double _y, double _z)=0
 Set the local scale. More...
 
virtual void SetLocalScale (const math::Vector3d &_scale)=0
 Set the local scale. More...
 
virtual void SetOrigin (double _x, double _y, double _z)=0
 Set position of origin. The position should be relative to the original origin of the geometry. More...
 
virtual void SetOrigin (const math::Vector3d &_origin)=0
 Set position of origin. The position should be relative to the original origin of the geometry. More...
 
virtual void SetUserData (const std::string &_key, Variant _value)=0
 Store any custom data associated with this node. More...
 
virtual void SetWorldPose (const math::Pose3d &_pose)=0
 Set the world pose. More...
 
virtual void SetWorldPosition (double _x, double _y, double _z)=0
 Set the world position. More...
 
virtual void SetWorldPosition (const math::Vector3d &_position)=0
 Set the world position. More...
 
virtual void SetWorldRotation (double _r, double _p, double _y)=0
 Set the world rotation. More...
 
virtual void SetWorldRotation (double _w, double _x, double _y, double _z)=0
 Set the world rotation. More...
 
virtual void SetWorldRotation (const math::Quaterniond &_rotation)=0
 Set the world rotation. More...
 
virtual void SetWorldScale (double _scale)=0
 Set the world scale. The given scale will be assigned to the x, y, and z coordinates. More...
 
virtual void SetWorldScale (double _x, double _y, double _z)=0
 Set the world scale. More...
 
virtual void SetWorldScale (const math::Vector3d &_scale)=0
 Set the world scale. More...
 
virtual Variant UserData (const std::string &_key) const =0
 Get custom data stored in this node. More...
 
virtual math::Pose3d WorldPose () const =0
 Get the world pose. More...
 
virtual math::Vector3d WorldPosition () const =0
 Get the world position. More...
 
virtual math::Quaterniond WorldRotation () const =0
 Get the world rotation. More...
 
virtual math::Vector3d WorldScale () const =0
 Get the world scale. More...
 
virtual math::Pose3d WorldToLocal (const math::Pose3d &_pose) const =0
 Convert given world pose to local pose. More...
 
- Public Member Functions inherited from Object
virtual ~Object ()
 Destructor. More...
 
virtual void Destroy ()=0
 Destroy any resources associated with this object. Invoking any other functions after destroying an object will result in undefined behavior. More...
 
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. More...
 
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. More...
 
virtual void PreRender ()=0
 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. More...
 
virtual ScenePtr Scene () const =0
 Get the Scene that created this object. More...
 

Detailed Description

Posable camera used for rendering the scene graph.

Poseable depth camera used for rendering the scene graph. This camera is designed to produced depth data, instead of a 2D image.

Member Typedef Documentation

◆ NewFrameListener

typedef std::function<void(const void*, unsigned int, unsigned int, unsigned int, const std::string&)> NewFrameListener

Callback function for new frame render event listeners.

Constructor & Destructor Documentation

◆ ~Camera()

Member Function Documentation

◆ AddRenderPass()

virtual void AddRenderPass ( const RenderPassPtr _pass)
pure virtual

Add a render pass to the camera.

Parameters
[in]_passNew render pass to add

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ AntiAliasing()

virtual unsigned int AntiAliasing ( ) const
pure virtual

Get the level of anti-aliasing used during rendering.

Returns
The level of anti-aliasing used during rendering

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ AspectRatio()

virtual double AspectRatio ( ) const
pure virtual

Get the camera's aspect ratio.

Returns
The camera's aspect ratio

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ Capture()

virtual void Capture ( Image _image)
pure virtual

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.

Parameters
[out]_imageOutput image buffer

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ConnectNewImageFrame()

virtual common::ConnectionPtr ConnectNewImageFrame ( NewFrameListener  _listener)
pure virtual

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

Parameters
[in]_listenerNew camera listener callback

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ Copy()

virtual void Copy ( Image _image) const
pure virtual

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

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ CreateImage()

virtual Image CreateImage ( ) const
pure virtual

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.

Returns
A newly allocated Image for storing this cameras images

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ CreateRenderWindow()

virtual RenderWindowPtr CreateRenderWindow ( )
pure virtual

Create a render window.

Returns
A pointer to the render window.

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ FarClipPlane()

virtual double FarClipPlane ( ) const
pure virtual

Get the camera's far clipping plane distance.

Returns
Far clipping plane distance

Implemented in OgreDepthCamera, BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ FollowOffset()

virtual math::Vector3d FollowOffset ( ) const
pure virtual

Get the follow offset vector in the frame specified at the time the follow target is set.

Returns
Offset of camera from target.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ FollowPGain()

virtual double FollowPGain ( ) const
pure virtual

Get the camera follow movement P gain.

Returns
P gain for camera following

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ FollowTarget()

virtual NodePtr FollowTarget ( ) const
pure virtual

Get the target node being followed.

Returns
Target node being tracked.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ HFOV()

virtual math::Angle HFOV ( ) const
pure virtual

Get the camera's horizontal field-of-view.

Returns
Angle containing the camera's horizontal field-of-view

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ImageFormat()

virtual PixelFormat ImageFormat ( ) const
pure virtual

Get the image pixel format. If the image pixel format has not been set with a valid value, PF_UNKNOWN will be returned.

Returns
The image pixel format

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ImageHeight()

virtual unsigned int ImageHeight ( ) const
pure virtual

Get the image height in pixels.

Returns
The image height in pixels

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ImageMemorySize()

virtual unsigned int ImageMemorySize ( ) const
pure virtual

Get the total image memory size in bytes.

Returns
The image memory size in bytes

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ImageWidth()

virtual unsigned int ImageWidth ( ) const
pure virtual

Get the image width in pixels.

Returns
The image width in pixels

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ NearClipPlane()

virtual double NearClipPlane ( ) const
pure virtual

Get the camera's near clipping plane distance.

Returns
Near clipping plane distance

Implemented in OgreDepthCamera, BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ PostRender()

virtual void PostRender ( )
pure virtual

Preforms any necessary final rendering work. Once rendering is complete the camera will alert any listeners of the new frame event. This function should only be called after a call to Render has successfully been executed.

Implements Object.

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, OgreDepthCamera, OgreGpuRays, and OgreThermalCamera.

Referenced by Camera::~Camera().

◆ Project()

virtual math::Vector2i Project ( const math::Vector3d _pt) const
pure virtual

Project point in 3d world space to 2d screen space.

Parameters
[in]_ptPoint in 3d world space
Returns
Point in 2d screen space

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ProjectionMatrix()

virtual math::Matrix4d ProjectionMatrix ( ) const
pure virtual

Get the projection matrix for this camera.

Returns
Camera projection matrix

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ ProjectionType()

virtual CameraProjectionType ProjectionType ( ) const
pure virtual

Get the projection type for this camera.

Returns
Camera projection type

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ RemoveRenderPass()

virtual void RemoveRenderPass ( const RenderPassPtr _pass)
pure virtual

Remove a render pass from the camera.

Parameters
[in]_passrender pass to remove

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ Render()

virtual void Render ( )
pure virtual

Renders the current scene using this camera. This function assumes PreRender() has already been called on the parent Scene, allowing the camera and the scene itself to prepare for rendering.

Implemented in OgreDepthCamera, OgreThermalCamera, and OgreCamera.

Referenced by BaseCamera< OgreSensor >::Update(), and Camera::~Camera().

◆ RenderPassByIndex()

virtual RenderPassPtr RenderPassByIndex ( unsigned int  _index) const
pure virtual

Get a render passes by index.

Returns
Render pass at the specified index

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ RenderPassCount()

virtual unsigned int RenderPassCount ( ) const
pure virtual

Get the number of render passes applied to the camera.

Returns
Number of render passes applied

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ RenderTextureGLId()

virtual unsigned int RenderTextureGLId ( ) const
pure virtual

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.

Returns
Texture Id of type GLuint.

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SaveFrame()

virtual bool SaveFrame ( const std::string _name)
pure virtual

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.

Parameters
[in]_nameName of the output file

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetAntiAliasing()

virtual void SetAntiAliasing ( const unsigned int  _aa)
pure virtual

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.

Parameters
[in]_aaLevel of anti-aliasing used during rendering

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetAspectRatio()

virtual void SetAspectRatio ( const double  _ratio)
pure virtual

Set the camera's aspect ratio. This value determines the cameras vertical field-of-view. It is often the.

image_height /
image_width

but this is not necessarily true.

Returns
The camera's aspect ratio

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetFarClipPlane()

virtual void SetFarClipPlane ( const double  _far)
pure virtual

Set the camera's far clipping plane distance.

Parameters
[in]_farFar clipping plane distance

Implemented in OgreDepthCamera, BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetFollowOffset()

virtual void SetFollowOffset ( const math::Vector3d _offset)
pure virtual

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.

Parameters
[in]_offsetOffset distance from target node.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetFollowPGain()

virtual void SetFollowPGain ( const double  _pGain)
pure virtual

Set follow P Gain. Determines how fast the camera moves to follow the target node. Valid range: [0-1].

Parameters
[in]_pGainP gain for camera following

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetFollowTarget()

virtual void SetFollowTarget ( const NodePtr _target,
const math::Vector3d _offset = math::Vector3d::Zero,
const bool  _worldFrame = false 
)
pure virtual

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.

Parameters
[in]_targetTarget node to follow
[in]_offsetTether the camera at an offset distance from the target node.
[in]_worldFrameTrue to follow the target node at a distance that's fixed in world frame. Default is false which means the camera follows at fixed distance in target node's local frame.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetHFOV()

virtual void SetHFOV ( const math::Angle _hfov)
pure virtual

Set the camera's horizontal field-of-view.

Parameters
[in]_hfovDesired horizontal field-of-view

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetImageFormat()

virtual void SetImageFormat ( PixelFormat  _format)
pure virtual

Set the image pixel format.

Parameters
[in]_formatNew image pixel format

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetImageHeight()

virtual void SetImageHeight ( unsigned int  _height)
pure virtual

Set the image height in pixels.

Parameters
[in]_heightNew image height in pixels

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetImageWidth()

virtual void SetImageWidth ( unsigned int  _width)
pure virtual

Set the image width in pixels.

Parameters
[in]_widthNew image width in pixels

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetMaterial()

virtual void SetMaterial ( const MaterialPtr _material)
pure virtual

Set a material that the camera should see on all objects.

Parameters
[in]_materiala material instance

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetNearClipPlane()

virtual void SetNearClipPlane ( const double  _near)
pure virtual

Set the camera's near clipping plane distance.

Parameters
[in]_nearNear clipping plane distance

Implemented in OgreDepthCamera, BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetProjectionMatrix()

virtual void SetProjectionMatrix ( const math::Matrix4d _matrix)
pure virtual

Set the projection matrix for this camera. This overrides the standard projection matrix computed based on camera parameters.

Parameters
[in]_matrixCamera projection matrix

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetProjectionType()

virtual void SetProjectionType ( CameraProjectionType  _type)
pure virtual

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.

Parameters
[in]_typeCamera projection type
See also
SetProjectionMatrix

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ SetShadowsDirty()

virtual void SetShadowsDirty ( )
pure virtual

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetTrackOffset()

virtual void SetTrackOffset ( const math::Vector3d _offset)
pure virtual

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.

Parameters
[in]_offsetPoint offset to track

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetTrackPGain()

virtual void SetTrackPGain ( const double  _pGain)
pure virtual

Set track P Gain. Determines how fast the camera rotates to look at the target node. Valid range: [0-1].

Parameters
[in]_pGainP gain for camera tracking

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ SetTrackTarget()

virtual void SetTrackTarget ( const NodePtr _target,
const math::Vector3d _offset = math::Vector3d::Zero,
const bool  _worldFrame = false 
)
pure virtual

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.

Parameters
[in]_targetTarget node to track
[in]_offsetTrack a point that is at an offset relative to target.
[in]_worldFrameIf true, the offset point to track will be treated in world frame and its position relative to the target node remains fixed regardless of the target node's rotation. Default is false, which means the camera tracks the point in target node's local frame.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ TrackOffset()

virtual math::Vector3d TrackOffset ( ) const
pure virtual

Get the track offset vector in the frame specified at the time the track target is set.

Returns
Point offset from target.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ TrackPGain()

virtual double TrackPGain ( ) const
pure virtual

Get the camera track rotation P gain.

Returns
P gain for camera tracking

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ TrackTarget()

virtual NodePtr TrackTarget ( ) const
pure virtual

Get the target node being tracked.

Returns
Target node being tracked.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ Update()

virtual void Update ( )
pure virtual

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.

Implemented in BaseCamera< T >, and BaseCamera< OgreSensor >.

Referenced by Camera::~Camera().

◆ ViewMatrix()

virtual math::Matrix4d ViewMatrix ( ) const
pure virtual

Get the view matrix for this camera.

Returns
Camera view matrix

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().

◆ VisualAt()

virtual VisualPtr VisualAt ( const ignition::math::Vector2i _mousePos)
pure virtual

Get the visual for a given mouse position param[in] _mousePos mouse position.

Implemented in BaseCamera< T >, BaseCamera< OgreSensor >, and OgreCamera.

Referenced by Camera::~Camera().


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