Camera Class Reference

Basic camera sensor. More...

#include <rendering/rendering.hh>

Inherits enable_shared_from_this< Camera >.

Inherited by DepthCamera, GpuLaser, OculusCamera, UserCamera, and WideAngleCamera.

Public Member Functions

 Camera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
 Constructor. More...
 
virtual ~Camera ()
 Destructor. More...
 
float AspectRatio () const
 Get the apect ratio. More...
 
void AttachToVisual (const std::string &_visualName, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
void AttachToVisual (uint32_t _id, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
virtual float AvgFPS () const
 Get the average FPS. More...
 
virtual void CameraToViewportRay (const int _screenx, const int _screeny, ignition::math::Vector3d &_origin, ignition::math::Vector3d &_dir) const
 Get a world space ray as cast from the camera through the viewport. More...
 
bool CaptureData () const
 Return the value of this->captureData. More...
 
event::ConnectionPtr ConnectNewImageFrame (std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
 Connect to the new image signal. More...
 
void CreateRenderTexture (const std::string &_textureName)
 Set the render target. More...
 
ignition::math::Vector3d Direction () const
 Get the camera's direction vector. More...
 
void EnableSaveFrame (const bool _enable)
 Enable or disable saving. More...
 
double FarClip () const
 Get the far clip distance. More...
 
virtual void Fini ()
 Finalize the camera. More...
 
ScenePtr GetScene () const
 Get the scene this camera is in. More...
 
ignition::math::Angle HFOV () const
 Get the camera FOV (horizontal) More...
 
size_t ImageByteSize () const
 Get the image size in bytes. More...
 
virtual const unsigned char * ImageData (const unsigned int i=0) const
 Get a pointer to the image data. More...
 
unsigned int ImageDepth () const
 Get the depth of the image in bytes per pixel. More...
 
std::string ImageFormat () const
 Get the string representation of the image format. More...
 
virtual unsigned int ImageHeight () const
 Get the height of the image. More...
 
unsigned int ImageMemorySize () const
 Get the memory size of this image. More...
 
virtual unsigned int ImageWidth () const
 Get the width of the image. More...
 
virtual void Init ()
 Initialize the camera. More...
 
bool Initialized () const
 Return true if the camera has been initialized. More...
 
bool IsAnimating () const
 Return true if the camera is moving due to an animation. More...
 
bool IsVisible (VisualPtr _visual)
 Return true if the visual is within the camera's view frustum. More...
 
bool IsVisible (const std::string &_visualName)
 Return true if the visual is within the camera's view frustum. More...
 
common::Time LastRenderWallTime () const
 Get the last time the camera was rendered. More...
 
DistortionPtr LensDistortion () const
 Get the distortion model of this camera. More...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the camera with a set of parameters. More...
 
virtual void Load ()
 Load the camera with default parameters. More...
 
virtual bool MoveToPosition (const ignition::math::Pose3d &_pose, const double _time)
 Move the camera to a position (this is an animated motion). More...
 
bool MoveToPositions (const std::vector< ignition::math::Pose3d > &_pts, const double _time, std::function< void()> _onComplete=NULL)
 Move the camera to a series of poses (this is an animated motion). More...
 
std::string Name () const
 Get the camera's unscoped name. More...
 
double NearClip () const
 Get the near clip distance. More...
 
Ogre::Camera * OgreCamera () const
 Get a pointer to the ogre camera. More...
 
Ogre::Viewport * OgreViewport () const
 Get a pointer to the Ogre::Viewport. More...
 
void Pitch (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
 Rotate the camera around the y-axis. More...
 
virtual void PostRender ()
 Post render. More...
 
virtual ignition::math::Vector2i Project (const ignition::math::Vector3d &_pt) const
 Project 3D world coordinates to 2D screen coordinates. More...
 
ignition::math::Matrix4d ProjectionMatrix () const
 Return the projection matrix of this camera. More...
 
std::string ProjectionType () const
 Return the projection type as a string. More...
 
virtual void Render (const bool _force=false)
 Render the camera. More...
 
double RenderRate () const
 Get the render Hz rate. More...
 
Ogre::Texture * RenderTexture () const
 Get the render texture. More...
 
bool ResetVideo ()
 Reset video recording. More...
 
ignition::math::Vector3d Right () const
 Get the viewport right vector. More...
 
void Roll (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
 Rotate the camera around the x-axis. More...
 
bool SaveFrame (const std::string &_filename)
 Save the last frame to disk. More...
 
bool SaveVideo (const std::string &_filename)
 Save the last encoded video to disk. More...
 
Ogre::SceneNode * SceneNode () const
 Get the camera's scene node. More...
 
std::string ScopedName () const
 Get the camera's scoped name (scene_name::camera_name) More...
 
std::string ScreenshotPath () const
 Get the path to saved screenshots. More...
 
void SetAspectRatio (float _ratio)
 Set the aspect ratio. More...
 
virtual bool SetBackgroundColor (const ignition::math::Color &_color)
 Set background color for viewport (if viewport is not null) More...
 
void SetCaptureData (const bool _value)
 Set whether to capture data. More...
 
void SetCaptureDataOnce ()
 Capture data once and save to disk. More...
 
virtual void SetClipDist (const float _near, const float _far)
 Set the clip distances. More...
 
void SetHFOV (const ignition::math::Angle &_angle)
 Set the camera FOV (horizontal) More...
 
void SetImageHeight (const unsigned int _h)
 Set the image height. More...
 
void SetImageSize (const unsigned int _w, const unsigned int _h)
 Set the image size. More...
 
void SetImageWidth (const unsigned int _w)
 Set the image height. More...
 
void SetName (const std::string &_name)
 Set the camera's name. More...
 
virtual bool SetProjectionType (const std::string &_type)
 Set the type of projection used by the camera. More...
 
void SetRenderRate (const double _hz)
 Set the render Hz rate. More...
 
virtual void SetRenderTarget (Ogre::RenderTarget *_target)
 Set the camera's render target. More...
 
void SetSaveFramePathname (const std::string &_pathname)
 Set the save frame pathname. More...
 
void SetScene (ScenePtr _scene)
 Set the scene this camera is viewing. More...
 
void SetSceneNode (Ogre::SceneNode *_node)
 Set the camera's scene node. More...
 
void SetTrackInheritYaw (const bool _inheritYaw)
 Set whether this camera inherits the yaw rotation of the tracked model. More...
 
void SetTrackIsStatic (const bool _isStatic)
 Set whether this camera is static when tracking a model. More...
 
void SetTrackMaxDistance (const double _dist)
 Set the maximum distance between the camera and tracked visual. More...
 
void SetTrackMinDistance (const double _dist)
 Set the minimum distance between the camera and tracked visual. More...
 
void SetTrackPosition (const ignition::math::Vector3d &_pos)
 Set the position of the camera when tracking a visual. More...
 
void SetTrackUseModelFrame (const bool _useModelFrame)
 Set whether this camera's position is relative to tracked models. More...
 
void SetWindowId (unsigned int _windowId)
 
virtual void SetWorldPose (const ignition::math::Pose3d &_pose)
 Set the global pose of the camera. More...
 
void SetWorldPosition (const ignition::math::Vector3d &_pos)
 Set the world position. More...
 
void SetWorldRotation (const ignition::math::Quaterniond &_quat)
 Set the world orientation. More...
 
void ShowWireframe (const bool _s)
 Set whether to view the world in wireframe. More...
 
bool StartVideo (const std::string &_format, const std::string &_filename="")
 Turn on video recording. More...
 
bool StopVideo ()
 Turn off video recording. More...
 
unsigned int TextureHeight () const
 Get the height of the off-screen render texture. More...
 
unsigned int TextureWidth () const
 Get the width of the off-screen render texture. More...
 
void ToggleShowWireframe ()
 Toggle whether to view the world in wireframe. More...
 
VisualPtr TrackedVisual () const
 Get the visual tracked by this camera. More...
 
bool TrackInheritYaw () const
 Get whether this camera inherits the yaw rotation of the tracked model. More...
 
bool TrackIsStatic () const
 Get whether this camera is static when tracking a model. More...
 
double TrackMaxDistance () const
 Return the maximum distance to the tracked visual. More...
 
double TrackMinDistance () const
 Return the minimum distance to the tracked visual. More...
 
ignition::math::Vector3d TrackPosition () const
 Return the position of the camera when tracking a model. More...
 
bool TrackUseModelFrame () const
 Get whether this camera's position is relative to tracked models. More...
 
void TrackVisual (const std::string &_visualName)
 Set the camera to track a scene node. More...
 
void Translate (const ignition::math::Vector3d &_direction)
 Translate the camera. More...
 
virtual unsigned int TriangleCount () const
 Get the triangle count. More...
 
ignition::math::Vector3d Up () const
 Get the viewport up vector. More...
 
virtual void Update ()
 
void UpdateCameraIntrinsics (const double _cameraIntrinsicsFx, const double _cameraIntrinsicsFy, const double _cameraIntrinsicsCx, const double _cameraIntrinsicsCy, const double _cameraIntrinsicsS)
 Updates the camera intrinsics. More...
 
ignition::math::Angle VFOV () const
 Get the camera FOV (vertical) More...
 
unsigned int ViewportHeight () const
 Get the viewport height in pixels. More...
 
unsigned int ViewportWidth () const
 Get the viewport width in pixels. More...
 
unsigned int WindowId () const
 Get the ID of the window this camera is rendering into. More...
 
bool WorldPointOnPlane (const int _x, const int _y, const ignition::math::Planed &_plane, ignition::math::Vector3d &_result)
 Get point on a plane. More...
 
ignition::math::Pose3d WorldPose () const
 Get the world pose. More...
 
ignition::math::Vector3d WorldPosition () const
 Get the camera position in the world. More...
 
ignition::math::Quaterniond WorldRotation () const
 Get the camera's orientation in the world. More...
 
void Yaw (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_WORLD)
 Rotate the camera around the z-axis. More...
 
double ZValue (const int _x, const int _y)
 Get the Z-buffer value at the given image coordinate. More...
 

Static Public Member Functions

static ignition::math::Matrix4d BuildNDCMatrix (const double _left, const double _right, const double _bottom, const double _top, const double _near, const double _far)
 Computes the OpenGL NDC matrix. More...
 
static ignition::math::Matrix4d BuildPerspectiveMatrix (const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
 Computes the OpenGL perspective matrix. More...
 
static ignition::math::Matrix4d BuildProjectionMatrix (const double _imageWidth, const double _imageHeight, const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
 Computes the OpenGL projection matrix by multiplying the OpenGL Normalized Device Coordinates matrix (NDC) with the OpenGL perspective matrix openglProjectionMatrix = ndcMatrix * perspectiveMatrix. More...
 
static ignition::math::Matrix4d BuildProjectiveMatrix (const double _imageWidth, const double _imageHeight, const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
 Computes the OpenGL projective matrix by multiplying the OpenGL Normalized Device Coordinates matrix (NDC) with the OpenGL perspective matrix openglProjectiveMatrix = ndcMatrix * perspectiveMatrix. More...
 
static size_t ImageByteSize (const unsigned int _width, const unsigned int _height, const std::string &_format)
 Calculate image byte size base on a few parameters. More...
 
static bool SaveFrame (const unsigned char *_image, const unsigned int _width, const unsigned int _height, const int _depth, const std::string &_format, const std::string &_filename)
 Save a frame using an image buffer. More...
 

Protected Member Functions

virtual void AnimationComplete ()
 Internal function used to indicate that an animation has completed. More...
 
virtual bool AttachToVisualImpl (const std::string &_name, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (uint32_t _id, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (VisualPtr _visual, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
 Attach the camera to a visual. More...
 
std::string FrameFilename ()
 Get the next frame filename based on SDF parameters. More...
 
void ReadPixelBuffer ()
 Read image data from pixel buffer. More...
 
virtual void RenderImpl ()
 Implementation of the render call. More...
 
virtual void SetClipDist ()
 Set the clip distance based on stored SDF values. More...
 
virtual void SetFixedYawAxis (const bool _useFixed, const ignition::math::Vector3d &_fixedAxis=ignition::math::Vector3d::UnitY)
 Tell the camera whether to yaw around its own local Y axis or a fixed axis of choice. More...
 
bool TrackVisualImpl (const std::string &_visualName)
 Implementation of the Camera::TrackVisual call. More...
 
virtual bool TrackVisualImpl (VisualPtr _visual)
 Set the camera to track a scene node. More...
 
virtual void UpdateFOV ()
 Update the camera's field of view. More...
 

Static Protected Member Functions

static double LimitFOV (const double _fov)
 Limit field of view taking care of using a valid value for an OGRE camera. More...
 

Protected Attributes

Ogre::AnimationState * animState
 Animation state, used to animate the camera. More...
 
unsigned char * bayerFrameBuffer
 Buffer for a bayer image frame. More...
 
Ogre::Camera * camera
 The OGRE camera. More...
 
Ogre::SceneNode * cameraNode = nullptr
 Scene node that the camera is attached to. More...
 
ignition::math::Matrix4d cameraProjectiveMatrix
 Camera projective matrix. More...
 
bool cameraUsingIntrinsics
 Flag for signaling the usage of camera intrinsics within OGRE. More...
 
bool captureData
 True to capture frames into an image buffer. More...
 
bool captureDataOnce
 True to capture a frame once and save to disk. More...
 
std::vector< event::ConnectionPtrconnections
 The camera's event connections. More...
 
int imageFormat
 Format for saving images. More...
 
int imageHeight
 Save image height. More...
 
int imageWidth
 Save image width. More...
 
bool initialized
 True if initialized. More...
 
common::Time lastRenderWallTime
 Time the last frame was rendered. More...
 
std::string name
 Name of the camera. More...
 
bool newData
 True if new data is available. More...
 
event::EventT< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> newImageFrame
 Event triggered when a new frame is generated. More...
 
std::function< void()> onAnimationComplete
 User callback for when an animation completes. More...
 
common::Time prevAnimTime
 Previous time the camera animation was updated. More...
 
Ogre::RenderTarget * renderTarget
 Target that renders frames. More...
 
Ogre::Texture * renderTexture
 Texture that receives results from rendering. More...
 
std::list< msgs::Request > requests
 List of requests. More...
 
unsigned int saveCount
 Number of saved frames. More...
 
unsigned char * saveFrameBuffer
 Buffer for a single image frame. More...
 
ScenePtr scene
 Pointer to the scene. More...
 
Ogre::SceneNode * sceneNode
 Scene node that controls camera position and orientation. More...
 
std::string scopedName
 Scene scoped name of the camera. More...
 
std::string scopedUniqueName
 Scene scoped name of the camera with a unique ID. More...
 
std::string screenshotPath
 Path to saved screenshots. More...
 
sdf::ElementPtr sdf
 Camera's SDF values. More...
 
unsigned int textureHeight
 Height of the render texture. More...
 
unsigned int textureWidth
 Width of the render texture. More...
 
Ogre::Viewport * viewport
 Viewport the ogre camera uses. More...
 
unsigned int windowId
 ID of the window that the camera is attached to. More...
 

Detailed Description

Basic camera sensor.

This is the base class for all cameras.

Constructor & Destructor Documentation

◆ Camera()

Camera ( const std::string &  _namePrefix,
ScenePtr  _scene,
bool  _autoRender = true 
)

Constructor.

Parameters
[in]_namePrefixUnique prefix name for the camera.
[in]_sceneScene that will contain the camera
[in]_autoRenderAlmost everyone should leave this as true.

◆ ~Camera()

virtual ~Camera ( )
virtual

Destructor.

Member Function Documentation

◆ AnimationComplete()

virtual void AnimationComplete ( )
protectedvirtual

Internal function used to indicate that an animation has completed.

Reimplemented in UserCamera.

◆ AspectRatio()

float AspectRatio ( ) const

Get the apect ratio.

Returns
The aspect ratio (width / height) in pixels

◆ AttachToVisual() [1/2]

void AttachToVisual ( const std::string &  _visualName,
const bool  _inheritOrientation,
const double  _minDist = 0.0,
const double  _maxDist = 0.0 
)

Attach the camera to a scene node.

Parameters
[in]_visualNameName of the visual to attach the camera to
[in]_inheritOrientationTrue means camera acquires the visual's orientation
[in]_minDistMinimum distance the camera is allowed to get to the visual
[in]_maxDistMaximum distance the camera is allowd to get from the visual

◆ AttachToVisual() [2/2]

void AttachToVisual ( uint32_t  _id,
const bool  _inheritOrientation,
const double  _minDist = 0.0,
const double  _maxDist = 0.0 
)

Attach the camera to a scene node.

Parameters
[in]_idID of the visual to attach the camera to
[in]_inheritOrientationTrue means camera acquires the visual's orientation
[in]_minDistMinimum distance the camera is allowed to get to the visual
[in]_maxDistMaximum distance the camera is allowd to get from the visual

◆ AttachToVisualImpl() [1/3]

virtual bool AttachToVisualImpl ( const std::string &  _name,
const bool  _inheritOrientation,
const double  _minDist = 0,
const double  _maxDist = 0 
)
protectedvirtual

Attach the camera to a scene node.

Parameters
[in]_visualNameName of the visual to attach the camera to
[in]_inheritOrientationTrue means camera acquires the visual's orientation
[in]_minDistMinimum distance the camera is allowed to get to the visual
[in]_maxDistMaximum distance the camera is allowd to get from the visual
Returns
True on success

◆ AttachToVisualImpl() [2/3]

virtual bool AttachToVisualImpl ( uint32_t  _id,
const bool  _inheritOrientation,
const double  _minDist = 0,
const double  _maxDist = 0 
)
protectedvirtual

Attach the camera to a scene node.

Parameters
[in]_idID of the visual to attach the camera to
[in]_inheritOrientationTrue means camera acquires the visual's orientation
[in]_minDistMinimum distance the camera is allowed to get to the visual
[in]_maxDistMaximum distance the camera is allowd to get from the visual
Returns
True on success

◆ AttachToVisualImpl() [3/3]

virtual bool AttachToVisualImpl ( VisualPtr  _visual,
const bool  _inheritOrientation,
const double  _minDist = 0,
const double  _maxDist = 0 
)
protectedvirtual

Attach the camera to a visual.

Parameters
[in]_visualThe visual to attach the camera to
[in]_inheritOrientationTrue means camera acquires the visual's orientation
[in]_minDistMinimum distance the camera is allowed to get to the visual
[in]_maxDistMaximum distance the camera is allowd to get from the visual
Returns
True on success

Reimplemented in UserCamera, and OculusCamera.

◆ AvgFPS()

virtual float AvgFPS ( ) const
virtual

Get the average FPS.

Returns
The average frames per second

◆ BuildNDCMatrix()

static ignition::math::Matrix4d BuildNDCMatrix ( const double  _left,
const double  _right,
const double  _bottom,
const double  _top,
const double  _near,
const double  _far 
)
static

Computes the OpenGL NDC matrix.

Parameters
[in]_leftLeft vertical clipping plane
[in]_rightRight vertical clipping plane
[in]_bottomBottom horizontal clipping plane
[in]_topTop horizontal clipping plane
[in]_nearDistance to the nearer depth clipping plane This value is negative if the plane is to be behind the camera
[in]_farDistance to the farther depth clipping plane This value is negative if the plane is to be behind the camera
Returns
OpenGL NDC (Normalized Device Coordinates) matrix

◆ BuildPerspectiveMatrix()

static ignition::math::Matrix4d BuildPerspectiveMatrix ( const double  _intrinsicsFx,
const double  _intrinsicsFy,
const double  _intrinsicsCx,
const double  _intrinsicsCy,
const double  _intrinsicsS,
const double  _clipNear,
const double  _clipFar 
)
static

Computes the OpenGL perspective matrix.

Parameters
[in]_intrinsicsFxHorizontal focal length (in pixels)
[in]_intrinsicsFyVertical focal length (in pixels)
[in]_intrinsicsCxX coordinate of principal point in pixels
[in]_intrinsicsCyY coordinate of principal point in pixels
[in]_intrinsicsSSkew coefficient defining the angle between the x and y pixel axes
[in]_clipNearDistance to the nearer depth clipping plane This value is negative if the plane is to be behind the camera
[in]_clipFarDistance to the farther depth clipping plane This value is negative if the plane is to be behind the camera
Returns
OpenGL perspective matrix

◆ BuildProjectionMatrix()

static ignition::math::Matrix4d BuildProjectionMatrix ( const double  _imageWidth,
const double  _imageHeight,
const double  _intrinsicsFx,
const double  _intrinsicsFy,
const double  _intrinsicsCx,
const double  _intrinsicsCy,
const double  _intrinsicsS,
const double  _clipNear,
const double  _clipFar 
)
static

Computes the OpenGL projection matrix by multiplying the OpenGL Normalized Device Coordinates matrix (NDC) with the OpenGL perspective matrix openglProjectionMatrix = ndcMatrix * perspectiveMatrix.

Parameters
[in]_imageWidthImage width (in pixels)
[in]_imageHeightImage height (in pixels)
[in]_intrinsicsFxHorizontal focal length (in pixels)
[in]_intrinsicsFyVertical focal length (in pixels)
[in]_intrinsicsCxX coordinate of principal point in pixels
[in]_intrinsicsCyY coordinate of principal point in pixels
[in]_intrinsicsSSkew coefficient defining the angle between the x and y pixel axes
[in]_clipNearDistance to the nearer depth clipping plane This value is negative if the plane is to be behind the camera
[in]_clipFarDistance to the farther depth clipping plane This value is negative if the plane is to be behind the camera
Returns
OpenGL projection matrix

◆ BuildProjectiveMatrix()

static ignition::math::Matrix4d BuildProjectiveMatrix ( const double  _imageWidth,
const double  _imageHeight,
const double  _intrinsicsFx,
const double  _intrinsicsFy,
const double  _intrinsicsCx,
const double  _intrinsicsCy,
const double  _intrinsicsS,
const double  _clipNear,
const double  _clipFar 
)
static

Computes the OpenGL projective matrix by multiplying the OpenGL Normalized Device Coordinates matrix (NDC) with the OpenGL perspective matrix openglProjectiveMatrix = ndcMatrix * perspectiveMatrix.

Parameters
[in]_imageWidthImage width (in pixels)
[in]_imageHeightImage height (in pixels)
[in]_intrinsicsFxHorizontal focal length (in pixels)
[in]_intrinsicsFyVertical focal length (in pixels)
[in]_intrinsicsCxX coordinate of principal point in pixels
[in]_intrinsicsCyY coordinate of principal point in pixels
[in]_intrinsicsSSkew coefficient defining the angle between the x and y pixel axes
[in]_clipNearDistance to the nearer depth clipping plane This value is negative if the plane is to be behind the camera
[in]_clipFarDistance to the farther depth clipping plane This value is negative if the plane is to be behind the camera
Returns
OpenGL projective matrix
Deprecated:
See BuildProjectionMatrix().

◆ CameraToViewportRay()

virtual void CameraToViewportRay ( const int  _screenx,
const int  _screeny,
ignition::math::Vector3d &  _origin,
ignition::math::Vector3d &  _dir 
) const
virtual

Get a world space ray as cast from the camera through the viewport.

Parameters
[in]_screenxX coordinate in the camera's viewport, in pixels.
[in]_screenyY coordinate in the camera's viewport, in pixels.
[out]_originOrigin in the world coordinate frame of the resulting ray
[out]_dirDirection of the resulting ray

Reimplemented in UserCamera.

◆ CaptureData()

bool CaptureData ( ) const

Return the value of this->captureData.

Returns
True if the camera is set to capture data.

◆ ConnectNewImageFrame()

event::ConnectionPtr ConnectNewImageFrame ( std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)

Connect to the new image signal.

Parameters
[in]_subscriberCallback that is called when a new image is generated
Returns
A pointer to the connection. This must be kept in scope.

◆ CreateRenderTexture()

void CreateRenderTexture ( const std::string &  _textureName)

Set the render target.

Parameters
[in]_textureNameName of the new render texture

◆ Direction()

ignition::math::Vector3d Direction ( ) const

Get the camera's direction vector.

Returns
Direction the camera is facing

◆ EnableSaveFrame()

void EnableSaveFrame ( const bool  _enable)

Enable or disable saving.

Parameters
[in]_enableSet to True to enable saving of frames

◆ FarClip()

double FarClip ( ) const

Get the far clip distance.

Returns
Far clip distance

◆ Fini()

virtual void Fini ( )
virtual

Finalize the camera.

This function is called before the camera is destructed

Reimplemented in WideAngleCamera, UserCamera, GpuLaser, DepthCamera, and OculusCamera.

◆ FrameFilename()

std::string FrameFilename ( )
protected

Get the next frame filename based on SDF parameters.

Returns
The frame's filename

◆ GetScene()

ScenePtr GetScene ( ) const

Get the scene this camera is in.

Returns
Pointer to scene containing this camera

◆ HFOV()

ignition::math::Angle HFOV ( ) const

Get the camera FOV (horizontal)

Returns
The horizontal field of view

◆ ImageByteSize() [1/2]

size_t ImageByteSize ( ) const

Get the image size in bytes.

Returns
Size in bytes

◆ ImageByteSize() [2/2]

static size_t ImageByteSize ( const unsigned int  _width,
const unsigned int  _height,
const std::string &  _format 
)
static

Calculate image byte size base on a few parameters.

Parameters
[in]_widthWidth of an image
[in]_heightHeight of an image
[in]_formatImage format
Returns
Size of an image based on the parameters

◆ ImageData()

virtual const unsigned char* ImageData ( const unsigned int  i = 0) const
virtual

Get a pointer to the image data.

Get the raw image data from a camera's buffer.

Parameters
[in]_iIndex of the camera's texture (0 = RGB, 1 = depth).
Returns
Pointer to the raw data, null if data is not available.

◆ ImageDepth()

unsigned int ImageDepth ( ) const

Get the depth of the image in bytes per pixel.

Returns
Depth of the image in bytes per pixel

◆ ImageFormat()

std::string ImageFormat ( ) const

Get the string representation of the image format.

Returns
String representation of the image format.

◆ ImageHeight()

virtual unsigned int ImageHeight ( ) const
virtual

Get the height of the image.

Returns
Image height

◆ ImageMemorySize()

unsigned int ImageMemorySize ( ) const

Get the memory size of this image.

Returns
Image memory size in bytes

◆ ImageWidth()

virtual unsigned int ImageWidth ( ) const
virtual

Get the width of the image.

Returns
Image width

◆ Init()

virtual void Init ( )
virtual

Initialize the camera.

Reimplemented in WideAngleCamera, GpuLaser, DepthCamera, UserCamera, and OculusCamera.

◆ Initialized()

bool Initialized ( ) const

Return true if the camera has been initialized.

Returns
True if initialized was successful

◆ IsAnimating()

bool IsAnimating ( ) const

Return true if the camera is moving due to an animation.

◆ IsVisible() [1/2]

bool IsVisible ( VisualPtr  _visual)

Return true if the visual is within the camera's view frustum.

Parameters
[in]_visualThe visual to check for visibility
Returns
True if the _visual is in the camera's frustum

◆ IsVisible() [2/2]

bool IsVisible ( const std::string &  _visualName)

Return true if the visual is within the camera's view frustum.

Parameters
[in]_visualNameName of the visual to check for visibility
Returns
True if the _visual is in the camera's frustum

◆ LastRenderWallTime()

common::Time LastRenderWallTime ( ) const

Get the last time the camera was rendered.

Returns
Time the camera was last rendered

◆ LensDistortion()

DistortionPtr LensDistortion ( ) const

Get the distortion model of this camera.

Returns
Distortion model.

◆ LimitFOV()

static double LimitFOV ( const double  _fov)
staticprotected

Limit field of view taking care of using a valid value for an OGRE camera.

Parameters
[in]_fovexpected field of view
Returns
valid field of view

◆ Load() [1/2]

virtual void Load ( sdf::ElementPtr  _sdf)
virtual

Load the camera with a set of parameters.

Parameters
[in]_sdfThe SDF camera info

Reimplemented in GpuLaser, DepthCamera, UserCamera, and OculusCamera.

◆ Load() [2/2]

virtual void Load ( )
virtual

Load the camera with default parameters.

Reimplemented in WideAngleCamera, GpuLaser, DepthCamera, UserCamera, and OculusCamera.

◆ MoveToPosition()

virtual bool MoveToPosition ( const ignition::math::Pose3d &  _pose,
const double  _time 
)
virtual

Move the camera to a position (this is an animated motion).

See also
Camera::MoveToPositions
Parameters
[in]_poseEnd position of the camera
[in]_timeDuration of the camera's movement

◆ MoveToPositions()

bool MoveToPositions ( const std::vector< ignition::math::Pose3d > &  _pts,
const double  _time,
std::function< void()>  _onComplete = NULL 
)

Move the camera to a series of poses (this is an animated motion).

See also
Camera::MoveToPosition
Parameters
[in]_ptsVector of poses to move to
[in]_timeDuration of the entire move
[in]_onCompleteCallback that is called when the move is complete

◆ Name()

std::string Name ( ) const

Get the camera's unscoped name.

Returns
The name of the camera

◆ NearClip()

double NearClip ( ) const

Get the near clip distance.

Returns
Near clip distance

◆ OgreCamera()

Ogre::Camera* OgreCamera ( ) const

Get a pointer to the ogre camera.

Returns
Pointer to the OGRE camera

◆ OgreViewport()

Ogre::Viewport* OgreViewport ( ) const

Get a pointer to the Ogre::Viewport.

Returns
Pointer to the Ogre::Viewport

◆ Pitch()

void Pitch ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_LOCAL 
)

Rotate the camera around the y-axis.

Parameters
[in]_anglePitch amount
[in]_relativeToCoordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_LOCAL

◆ PostRender()

virtual void PostRender ( )
virtual

Post render.

Called afer the render signal.

Reimplemented in UserCamera, GpuLaser, DepthCamera, and OculusCamera.

◆ Project()

virtual ignition::math::Vector2i Project ( const ignition::math::Vector3d &  _pt) const
virtual

Project 3D world coordinates to 2D screen coordinates.

Parameters
[in]_pt3D world coodinates
Returns
_pt 2D screen coordinates

Reimplemented in UserCamera.

◆ ProjectionMatrix()

ignition::math::Matrix4d ProjectionMatrix ( ) const

Return the projection matrix of this camera.

Returns
the projection matrix

◆ ProjectionType()

std::string ProjectionType ( ) const

Return the projection type as a string.

Returns
"perspective" or "orthographic"
See also
SetProjectionType(const std::string &_type)

◆ ReadPixelBuffer()

void ReadPixelBuffer ( )
protected

Read image data from pixel buffer.

◆ Render()

virtual void Render ( const bool  _force = false)
virtual

Render the camera.

Called after the pre-render signal. This function will generate camera images.

Parameters
[in]_forceForce camera to render. Ignore camera update rate.

Reimplemented in UserCamera.

◆ RenderImpl()

virtual void RenderImpl ( )
protectedvirtual

Implementation of the render call.

Reimplemented in WideAngleCamera, and OculusCamera.

◆ RenderRate()

double RenderRate ( ) const

Get the render Hz rate.

Returns
The Hz rate

◆ RenderTexture()

Ogre::Texture* RenderTexture ( ) const

Get the render texture.

Returns
Pointer to the render texture

◆ ResetVideo()

bool ResetVideo ( )

Reset video recording.

This will call common::VideoEncoder::Reset, which will cleanup temporary files and set video encoding values to their default settings.

See also
common::VideoEncoder::Reset
Returns
True if reset was succesful. Currently this function will always return true.

◆ Right()

ignition::math::Vector3d Right ( ) const

Get the viewport right vector.

Returns
The viewport right vector

◆ Roll()

void Roll ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_LOCAL 
)

Rotate the camera around the x-axis.

Parameters
[in]_angleRotation amount
[in]_relativeToCoordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_LOCAL

◆ SaveFrame() [1/2]

bool SaveFrame ( const std::string &  _filename)

Save the last frame to disk.

Parameters
[in]_filenameFile in which to save a single frame
Returns
True if saving was successful

◆ SaveFrame() [2/2]

static bool SaveFrame ( const unsigned char *  _image,
const unsigned int  _width,
const unsigned int  _height,
const int  _depth,
const std::string &  _format,
const std::string &  _filename 
)
static

Save a frame using an image buffer.

Parameters
[in]_imageThe raw image buffer
[in]_widthWidth of the image
[in]_heightHeight of the image
[in]_depthDepth of the image data
[in]_formatFormat the image data is in
[in]_filenameName of the file in which to write the frame
Returns
True if saving was successful

◆ SaveVideo()

bool SaveVideo ( const std::string &  _filename)

Save the last encoded video to disk.

Parameters
[in]_filenameFile in which to save the encoded video
Returns
True if saving was successful. The return value is set by common::VideoEncoder::SaveToFile().
See also
common::VideoEncoder::SaveToFile

◆ SceneNode()

Ogre::SceneNode* SceneNode ( ) const

Get the camera's scene node.

Returns
The scene node the camera is attached to

◆ ScopedName()

std::string ScopedName ( ) const

Get the camera's scoped name (scene_name::camera_name)

Returns
The name of the camera

◆ ScreenshotPath()

std::string ScreenshotPath ( ) const

Get the path to saved screenshots.

Returns
Path to saved screenshots.

◆ SetAspectRatio()

void SetAspectRatio ( float  _ratio)

Set the aspect ratio.

Parameters
[in]_ratioThe aspect ratio (width / height) in pixels

◆ SetBackgroundColor()

virtual bool SetBackgroundColor ( const ignition::math::Color &  _color)
virtual

Set background color for viewport (if viewport is not null)

Parameters
[in]_colorBackground color.
Returns
True if successful. False if viewport is null

Reimplemented in WideAngleCamera.

◆ SetCaptureData()

void SetCaptureData ( const bool  _value)

Set whether to capture data.

Parameters
[in]_valueSet to true to capture data into a memory buffer.

◆ SetCaptureDataOnce()

void SetCaptureDataOnce ( )

Capture data once and save to disk.

◆ SetClipDist() [1/2]

virtual void SetClipDist ( const float  _near,
const float  _far 
)
virtual

Set the clip distances.

Parameters
[in]_nearNear clip distance in meters
[in]_farFar clip distance in meters

Reimplemented in UserCamera.

◆ SetClipDist() [2/2]

virtual void SetClipDist ( )
protectedvirtual

Set the clip distance based on stored SDF values.

Reimplemented in WideAngleCamera.

◆ SetFixedYawAxis()

virtual void SetFixedYawAxis ( const bool  _useFixed,
const ignition::math::Vector3d &  _fixedAxis = ignition::math::Vector3d::UnitY 
)
protectedvirtual

Tell the camera whether to yaw around its own local Y axis or a fixed axis of choice.

Parameters
[in]_useFixedIf true, the axis passed in the second parameter will always be the yaw axis no matter what the camera orientation. If false, the camera yaws around the local Y.
[in]_fixedAxisThe axis to use if the first parameter is true.

◆ SetHFOV()

void SetHFOV ( const ignition::math::Angle &  _angle)

Set the camera FOV (horizontal)

Parameters
[in]_angleHorizontal field of view

◆ SetImageHeight()

void SetImageHeight ( const unsigned int  _h)

Set the image height.

Parameters
[in]_hImage height

◆ SetImageSize()

void SetImageSize ( const unsigned int  _w,
const unsigned int  _h 
)

Set the image size.

Parameters
[in]_wImage width
[in]_hImage height

◆ SetImageWidth()

void SetImageWidth ( const unsigned int  _w)

Set the image height.

Parameters
[in]_wImage width

◆ SetName()

void SetName ( const std::string &  _name)

Set the camera's name.

Parameters
[in]_nameNew name for the camera

◆ SetProjectionType()

virtual bool SetProjectionType ( const std::string &  _type)
virtual

Set the type of projection used by the camera.

Parameters
[in]_typeThe type of projection: "perspective" or "orthographic".
Returns
True if successful.
See also
GetProjectionType()

Reimplemented in UserCamera.

◆ SetRenderRate()

void SetRenderRate ( const double  _hz)

Set the render Hz rate.

Parameters
[in]_hzThe Hz rate

◆ SetRenderTarget()

virtual void SetRenderTarget ( Ogre::RenderTarget *  _target)
virtual

Set the camera's render target.

Parameters
[in]_targetPointer to the render target

Reimplemented in WideAngleCamera, UserCamera, and OculusCamera.

◆ SetSaveFramePathname()

void SetSaveFramePathname ( const std::string &  _pathname)

Set the save frame pathname.

Parameters
[in]_pathnameDirectory in which to store saved image frames

◆ SetScene()

void SetScene ( ScenePtr  _scene)

Set the scene this camera is viewing.

Parameters
[in]_scenePointer to the scene

◆ SetSceneNode()

void SetSceneNode ( Ogre::SceneNode *  _node)

Set the camera's scene node.

Parameters
[in]_nodeThe scene nodes to attach the camera to

◆ SetTrackInheritYaw()

void SetTrackInheritYaw ( const bool  _inheritYaw)

Set whether this camera inherits the yaw rotation of the tracked model.

Parameters
[in]_inheritYawTrue means camera inherits the yaw rotation of the tracked model.
See also
TrackInheritYaw()

◆ SetTrackIsStatic()

void SetTrackIsStatic ( const bool  _isStatic)

Set whether this camera is static when tracking a model.

Parameters
[in]_isStaticTrue means camera is static when tracking a model.
See also
TrackIsStatic()

◆ SetTrackMaxDistance()

void SetTrackMaxDistance ( const double  _dist)

Set the maximum distance between the camera and tracked visual.

Parameters
[in]_distMaximum distance between camera and visual.
See also
TrackMaxDistance()

◆ SetTrackMinDistance()

void SetTrackMinDistance ( const double  _dist)

Set the minimum distance between the camera and tracked visual.

Parameters
[in]_distMinimum distance between camera and visual.
See also
TrackMinDistance()

◆ SetTrackPosition()

void SetTrackPosition ( const ignition::math::Vector3d &  _pos)

Set the position of the camera when tracking a visual.

Parameters
[in]_posPosition of the camera.
See also
TrackPosition()

◆ SetTrackUseModelFrame()

void SetTrackUseModelFrame ( const bool  _useModelFrame)

Set whether this camera's position is relative to tracked models.

Parameters
[in]_useModelFrameTrue means camera's position is relative to tracked models.
See also
TrackUseModelFrame()

◆ SetWindowId()

void SetWindowId ( unsigned int  _windowId)

◆ SetWorldPose()

virtual void SetWorldPose ( const ignition::math::Pose3d &  _pose)
virtual

Set the global pose of the camera.

Parameters
[in]_poseThe new ignition::math::Pose3d of the camera

Reimplemented in UserCamera.

◆ SetWorldPosition()

void SetWorldPosition ( const ignition::math::Vector3d &  _pos)

Set the world position.

Parameters
[in]_posThe new position of the camera

◆ SetWorldRotation()

void SetWorldRotation ( const ignition::math::Quaterniond &  _quat)

Set the world orientation.

Parameters
[in]_quatThe new orientation of the camera

◆ ShowWireframe()

void ShowWireframe ( const bool  _s)

Set whether to view the world in wireframe.

Parameters
[in]_sSet to True to render objects as wireframe

◆ StartVideo()

bool StartVideo ( const std::string &  _format,
const std::string &  _filename = "" 
)

Turn on video recording.

Parameters
[in]_formatString that represents the video type. Supported types include: "avi", "ogv", mp4", "v4l2". If using "v4l2", you must also specify a _filename.
[in]_filenameName of the file that stores the video while it is being created. This is a temporary file when recording to disk, or a video4linux loopback device like /dev/video0 when the _format is "v4l2". If blank, a default temporary file is used. However, the "v4l2" _format must be accompanied with a video loopback device filename.
Returns
True on success. The return value is set by common::VideoEncoder::Start().
See also
common::VideoEncoder::Start

◆ StopVideo()

bool StopVideo ( )

Turn off video recording.

Returns
True on success. The return value is set by common::VideoEncoder::Stop().
See also
common::VideoEncoder::Stop

◆ TextureHeight()

unsigned int TextureHeight ( ) const

Get the height of the off-screen render texture.

Returns
Render texture height

◆ TextureWidth()

unsigned int TextureWidth ( ) const

Get the width of the off-screen render texture.

Returns
Render texture width

◆ ToggleShowWireframe()

void ToggleShowWireframe ( )

Toggle whether to view the world in wireframe.

◆ TrackedVisual()

VisualPtr TrackedVisual ( ) const

Get the visual tracked by this camera.

Returns
Tracked visual.

◆ TrackInheritYaw()

bool TrackInheritYaw ( ) const

Get whether this camera inherits the yaw rotation of the tracked model.

Returns
True if the camera inherits the yaw rotation of the tracked model.
See also
SetTrackInheritYaw(const bool _inheritYaw)

◆ TrackIsStatic()

bool TrackIsStatic ( ) const

Get whether this camera is static when tracking a model.

Returns
True if camera is static when tracking a model.
See also
SetTrackIsStatic(const bool _isStatic)

◆ TrackMaxDistance()

double TrackMaxDistance ( ) const

Return the maximum distance to the tracked visual.

Returns
Maximum distance to the model.
See also
SetTrackMaxDistance(const double _dist)

◆ TrackMinDistance()

double TrackMinDistance ( ) const

Return the minimum distance to the tracked visual.

Returns
Minimum distance to the model.
See also
SetTrackMinDistance(const double _dist)

◆ TrackPosition()

ignition::math::Vector3d TrackPosition ( ) const

Return the position of the camera when tracking a model.

Returns
Position of the camera.
See also
SetTrackPosition(const ignition::math::Vector3d &_pos)

◆ TrackUseModelFrame()

bool TrackUseModelFrame ( ) const

Get whether this camera's position is relative to tracked models.

Returns
True if camera's position is relative to tracked models.
See also
SetTrackUseModelFrame(const bool _useModelFrame)

◆ TrackVisual()

void TrackVisual ( const std::string &  _visualName)

Set the camera to track a scene node.

Parameters
[in]_visualNameName of the visual to track

◆ TrackVisualImpl() [1/2]

bool TrackVisualImpl ( const std::string &  _visualName)
protected

Implementation of the Camera::TrackVisual call.

Parameters
[in]_visualNameName of the visual to track
Returns
True if able to track the visual

◆ TrackVisualImpl() [2/2]

virtual bool TrackVisualImpl ( VisualPtr  _visual)
protectedvirtual

Set the camera to track a scene node.

Parameters
[in]_visualThe visual to track
Returns
True if able to track the visual

Reimplemented in UserCamera, and OculusCamera.

◆ Translate()

void Translate ( const ignition::math::Vector3d &  _direction)

Translate the camera.

Parameters
[in]_directionThe translation vector

◆ TriangleCount()

virtual unsigned int TriangleCount ( ) const
virtual

Get the triangle count.

Returns
The current triangle count

◆ Up()

ignition::math::Vector3d Up ( ) const

Get the viewport up vector.

Returns
The viewport up vector

◆ Update()

virtual void Update ( )
virtual

Reimplemented in UserCamera, and OculusCamera.

◆ UpdateCameraIntrinsics()

void UpdateCameraIntrinsics ( const double  _cameraIntrinsicsFx,
const double  _cameraIntrinsicsFy,
const double  _cameraIntrinsicsCx,
const double  _cameraIntrinsicsCy,
const double  _cameraIntrinsicsS 
)

Updates the camera intrinsics.

Parameters
[in]_intrinsicsFxHorizontal focal length (in pixels)
[in]_intrinsicsFyVertical focal length (in pixels)
[in]_intrinsicsCxX coordinate of principal point in pixels
[in]_intrinsicsCyY coordinate of principal point in pixels
[in]_intrinsicsSSkew coefficient defining the angle between the x and y pixel axes

◆ UpdateFOV()

virtual void UpdateFOV ( )
protectedvirtual

Update the camera's field of view.

Reimplemented in UserCamera, and WideAngleCamera.

◆ VFOV()

ignition::math::Angle VFOV ( ) const

Get the camera FOV (vertical)

Returns
The vertical field of view

◆ ViewportHeight()

unsigned int ViewportHeight ( ) const

Get the viewport height in pixels.

Returns
The viewport height

◆ ViewportWidth()

unsigned int ViewportWidth ( ) const

Get the viewport width in pixels.

Returns
The viewport width

◆ WindowId()

unsigned int WindowId ( ) const

Get the ID of the window this camera is rendering into.

Returns
The ID of the window.

◆ WorldPointOnPlane()

bool WorldPointOnPlane ( const int  _x,
const int  _y,
const ignition::math::Planed &  _plane,
ignition::math::Vector3d &  _result 
)

Get point on a plane.

Parameters
[in]_xX coordinate in camera's viewport, in pixels
[in]_yY coordinate in camera's viewport, in pixels
[in]_planePlane on which to find the intersecting point
[out]_resultPoint on the plane
Returns
True if a valid point was found

◆ WorldPose()

ignition::math::Pose3d WorldPose ( ) const

Get the world pose.

Returns
The pose of the camera in the world coordinate frame.

◆ WorldPosition()

ignition::math::Vector3d WorldPosition ( ) const

Get the camera position in the world.

Returns
The world position of the camera

◆ WorldRotation()

ignition::math::Quaterniond WorldRotation ( ) const

Get the camera's orientation in the world.

Returns
The camera's orientation as an ignition::math::Quaterniond

◆ Yaw()

void Yaw ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_WORLD 
)

Rotate the camera around the z-axis.

Parameters
[in]_angleRotation amount
[in]_relativeToCoordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_WORLD

◆ ZValue()

double ZValue ( const int  _x,
const int  _y 
)

Get the Z-buffer value at the given image coordinate.

Parameters
[in]_xImage coordinate; (0, 0) specifies the top-left corner.
[in]_yImage coordinate; (0, 0) specifies the top-left corner.
Returns
Image z value; note that this is abitrarily scaled and is not the same as the depth value.

Member Data Documentation

◆ animState

Ogre::AnimationState* animState
protected

Animation state, used to animate the camera.

◆ bayerFrameBuffer

unsigned char* bayerFrameBuffer
protected

Buffer for a bayer image frame.

◆ camera

Ogre::Camera* camera
protected

The OGRE camera.

◆ cameraNode

Ogre::SceneNode* cameraNode = nullptr
protected

Scene node that the camera is attached to.

◆ cameraProjectiveMatrix

ignition::math::Matrix4d cameraProjectiveMatrix
protected

Camera projective matrix.

◆ cameraUsingIntrinsics

bool cameraUsingIntrinsics
protected

Flag for signaling the usage of camera intrinsics within OGRE.

◆ captureData

bool captureData
protected

True to capture frames into an image buffer.

◆ captureDataOnce

bool captureDataOnce
protected

True to capture a frame once and save to disk.

◆ connections

std::vector<event::ConnectionPtr> connections
protected

The camera's event connections.

◆ imageFormat

int imageFormat
protected

Format for saving images.

◆ imageHeight

int imageHeight
protected

Save image height.

◆ imageWidth

int imageWidth
protected

Save image width.

◆ initialized

bool initialized
protected

True if initialized.

◆ lastRenderWallTime

common::Time lastRenderWallTime
protected

Time the last frame was rendered.

◆ name

std::string name
protected

Name of the camera.

◆ newData

bool newData
protected

True if new data is available.

◆ newImageFrame

event::EventT<void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> newImageFrame
protected

Event triggered when a new frame is generated.

◆ onAnimationComplete

std::function<void()> onAnimationComplete
protected

User callback for when an animation completes.

◆ prevAnimTime

common::Time prevAnimTime
protected

Previous time the camera animation was updated.

◆ renderTarget

Ogre::RenderTarget* renderTarget
protected

Target that renders frames.

◆ renderTexture

Ogre::Texture* renderTexture
protected

Texture that receives results from rendering.

◆ requests

std::list<msgs::Request> requests
protected

List of requests.

◆ saveCount

unsigned int saveCount
protected

Number of saved frames.

◆ saveFrameBuffer

unsigned char* saveFrameBuffer
protected

Buffer for a single image frame.

◆ scene

ScenePtr scene
protected

Pointer to the scene.

◆ sceneNode

Ogre::SceneNode* sceneNode
protected

Scene node that controls camera position and orientation.

◆ scopedName

std::string scopedName
protected

Scene scoped name of the camera.

◆ scopedUniqueName

std::string scopedUniqueName
protected

Scene scoped name of the camera with a unique ID.

◆ screenshotPath

std::string screenshotPath
protected

Path to saved screenshots.

◆ sdf

sdf::ElementPtr sdf
protected

Camera's SDF values.

◆ textureHeight

unsigned int textureHeight
protected

Height of the render texture.

◆ textureWidth

unsigned int textureWidth
protected

Width of the render texture.

◆ viewport

Ogre::Viewport* viewport
protected

Viewport the ogre camera uses.

◆ windowId

unsigned int windowId
protected

ID of the window that the camera is attached to.


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