OculusCamera Class Reference

A camera used for user visualization of a scene. More...

#include <rendering/rendering.hh>

Inherits Camera.

Public Member Functions

 OculusCamera (const std::string &_name, ScenePtr _scene)
 Constructor. More...
 
virtual ~OculusCamera ()
 Destructor. More...
 
void AdjustAspect (double _v)
 Change screen aspect ratio. 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...
 
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 DisconnectNewImageFrame (event::ConnectionPtr &_c)
 Disconnect from an image frame. More...
 
void EnableSaveFrame (const bool _enable)
 Enable or disable saving. More...
 
double FarClip () const
 Get the far clip distance. More...
 
void Fini ()
 Finialize. More...
 
float GetAspectRatio () const GAZEBO_DEPRECATED(7.0)
 Get the apect ratio. More...
 
virtual float GetAvgFPS () const GAZEBO_DEPRECATED(7.0)
 Get the average FPS. More...
 
void GetCameraToViewportRay (int _screenx, int _screeny, math::Vector3 &_origin, math::Vector3 &_dir) GAZEBO_DEPRECATED(7.0)
 Get a world space ray as cast from the camera through the viewport. More...
 
bool GetCaptureData () const GAZEBO_DEPRECATED(7.0)
 Return the value of this->captureData. More...
 
math::Vector3 GetDirection () const GAZEBO_DEPRECATED(7.0)
 Get the camera's direction vector. More...
 
DistortionPtr GetDistortion () const GAZEBO_DEPRECATED(7.0)
 Get the distortion model of this camera. More...
 
double GetFarClip () GAZEBO_DEPRECATED(7.0)
 Get the far clip distance. More...
 
math::Angle GetHFOV () const GAZEBO_DEPRECATED(7.0)
 Get the camera FOV (horizontal) More...
 
size_t GetImageByteSize () const GAZEBO_DEPRECATED(7.0)
 Get the image size in bytes. More...
 
virtual const unsigned char * GetImageData (unsigned int i=0) GAZEBO_DEPRECATED(7.0)
 Get a pointer to the image data. More...
 
unsigned int GetImageDepth () const GAZEBO_DEPRECATED(7.0)
 Get the depth of the image. More...
 
std::string GetImageFormat () const GAZEBO_DEPRECATED(7.0)
 Get the string representation of the image format. More...
 
virtual unsigned int GetImageHeight () const
 Get the height of the image. More...
 
virtual unsigned int GetImageWidth () const
 Get the width of the image. More...
 
bool GetInitialized () const GAZEBO_DEPRECATED(7.0)
 Return true if the camera has been initialized. More...
 
common::Time GetLastRenderWallTime () GAZEBO_DEPRECATED(7.0)
 Get the last time the camera was rendered. More...
 
std::string GetName () const GAZEBO_DEPRECATED(7.0)
 Get the camera's unscoped name. More...
 
double GetNearClip () GAZEBO_DEPRECATED(7.0)
 Get the near clip distance. More...
 
Ogre::Camera * GetOgreCamera () const GAZEBO_DEPRECATED(7.0)
 Get a pointer to the ogre camera. More...
 
std::string GetProjectionType () const GAZEBO_DEPRECATED(7.0)
 Return the projection type as a string. More...
 
double GetRenderRate () const GAZEBO_DEPRECATED(7.0)
 Get the render Hz rate. More...
 
Ogre::Texture * GetRenderTexture () const GAZEBO_DEPRECATED(7.0)
 Get the render texture. More...
 
math::Vector3 GetRight () GAZEBO_DEPRECATED(7.0)
 Get the viewport right vector. More...
 
ScenePtr GetScene () const
 Get the scene this camera is in. More...
 
Ogre::SceneNode * GetSceneNode () const GAZEBO_DEPRECATED(7.0)
 Get the camera's scene node. More...
 
std::string GetScopedName () const GAZEBO_DEPRECATED(7.0)
 Get the camera's scoped name (scene_name::camera_name) More...
 
std::string GetScreenshotPath () const GAZEBO_DEPRECATED(7.0)
 Get the path to saved screenshots. More...
 
unsigned int GetTextureHeight () const GAZEBO_DEPRECATED(7.0)
 Get the height of the off-screen render texture. More...
 
unsigned int GetTextureWidth () const GAZEBO_DEPRECATED(7.0)
 Get the width of the off-screen render texture. More...
 
virtual unsigned int GetTriangleCount () const GAZEBO_DEPRECATED(7.0)
 Get the triangle count. More...
 
math::Vector3 GetUp () GAZEBO_DEPRECATED(7.0)
 Get the viewport up vector. More...
 
math::Angle GetVFOV () const GAZEBO_DEPRECATED(7.0)
 Get the camera FOV (vertical) More...
 
Ogre::Viewport * GetViewport () const GAZEBO_DEPRECATED(7.0)
 Get a pointer to the Ogre::Viewport. More...
 
unsigned int GetViewportHeight () const GAZEBO_DEPRECATED(7.0)
 Get the viewport height in pixels. More...
 
unsigned int GetViewportWidth () const GAZEBO_DEPRECATED(7.0)
 Get the viewport width in pixels. More...
 
unsigned int GetWindowId () const GAZEBO_DEPRECATED(7.0)
 Get the ID of the window this camera is rendering into. More...
 
bool GetWorldPointOnPlane (int _x, int _y, const math::Plane &_plane, math::Vector3 &_result) GAZEBO_DEPRECATED(7.0)
 Get point on a plane. More...
 
math::Pose GetWorldPose () const GAZEBO_DEPRECATED(7.0)
 Get the world pose. More...
 
math::Vector3 GetWorldPosition () const GAZEBO_DEPRECATED(7.0)
 Get the camera position in the world. More...
 
math::Quaternion GetWorldRotation () const GAZEBO_DEPRECATED(7.0)
 Get the camera's orientation in the world. More...
 
double GetZValue (int _x, int _y) GAZEBO_DEPRECATED(7.0)
 Get the Z-buffer value at the given image coordinate. 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. 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...
 
virtual unsigned int ImageWidth () const
 Get the width of the image. More...
 
void Init ()
 Initialize. 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...
 
void Load (sdf::ElementPtr _sdf)
 Load the user camera. More...
 
void Load ()
 Generic load function. More...
 
virtual bool MoveToPosition (const math::Pose &_pose, double _time)
 Move the camera to a position (this is an animated motion). 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< math::Pose > &_pts, double _time, std::function< void()> _onComplete=NULL) GAZEBO_DEPRECATED(7.0)
 Move the camera to a series of poses (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...
 
void MoveToVisual (VisualPtr _visual)
 Move the camera to focus on a visual. More...
 
void MoveToVisual (const std::string &_visualName)
 Move the camera to focus on a visual. 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 math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the y-axis. 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...
 
std::string ProjectionType () const
 Return the projection type as a string. More...
 
bool Ready ()
 Used to check if Oculus is plugged in and can be used. More...
 
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...
 
void ResetSensor ()
 Reset the Oculus Rift sensor orientation. More...
 
void Resize (unsigned int _w, unsigned int _h)
 Resize the camera. More...
 
ignition::math::Vector3d Right () const
 Get the viewport right vector. More...
 
void Roll (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the x-axis. 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...
 
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...
 
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 (math::Angle _angle) GAZEBO_DEPRECATED(7.0)
 Set the camera FOV (horizontal) 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 to true to enable rendering. 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 math::Pose &_pose) GAZEBO_DEPRECATED(7.0)
 Set the global pose of the camera. More...
 
virtual void SetWorldPose (const ignition::math::Pose3d &_pose)
 Set the global pose of the camera. More...
 
void SetWorldPosition (const math::Vector3 &_pos) GAZEBO_DEPRECATED(7.0)
 Set the world position. More...
 
void SetWorldPosition (const ignition::math::Vector3d &_pos)
 Set the world position. More...
 
void SetWorldRotation (const math::Quaternion &_quat) GAZEBO_DEPRECATED(7.0)
 Set the world orientation. 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...
 
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 math::Vector3 &_direction) GAZEBO_DEPRECATED(7.0)
 Translate the camera. 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 ()
 Render the camera. 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 math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_WORLD) GAZEBO_DEPRECATED(7.0)
 Rotate the camera around the z-axis. 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 size_t GetImageByteSize (unsigned int _width, unsigned int _height, const std::string &_format) GAZEBO_DEPRECATED(7.0)
 Calculate image byte size base on a few parameters. 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 (VisualPtr _visual, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Set the camera to be attached to a visual. 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...
 
std::string FrameFilename ()
 Get the next frame filename based on SDF parameters. More...
 
std::string GetFrameFilename () GAZEBO_DEPRECATED(7.0)
 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 bool TrackVisualImpl (VisualPtr _visual)
 Set the camera to track a scene node. More...
 
bool TrackVisualImpl (const std::string &_visualName)
 Implementation of the Camera::TrackVisual call. More...
 
virtual void UpdateFOV ()
 Update the camera's field of view. 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...
 
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

A camera used for user visualization of a scene.

Constructor & Destructor Documentation

OculusCamera ( const std::string &  _name,
ScenePtr  _scene 
)

Constructor.

Parameters
[in]_nameName of the camera.
[in]_sceneScene to put the camera in.
virtual ~OculusCamera ( )
virtual

Destructor.

Member Function Documentation

void AdjustAspect ( double  _v)

Change screen aspect ratio.

Parameters
[in]_vAspect ratio.
virtual void AnimationComplete ( )
protectedvirtualinherited

Internal function used to indicate that an animation has completed.

Reimplemented in UserCamera.

float AspectRatio ( ) const
inherited

Get the apect ratio.

Returns
The aspect ratio (width / height) in pixels
void AttachToVisual ( const std::string &  _visualName,
const bool  _inheritOrientation,
const double  _minDist = 0.0,
const double  _maxDist = 0.0 
)
inherited

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
void AttachToVisual ( uint32_t  _id,
const bool  _inheritOrientation,
const double  _minDist = 0.0,
const double  _maxDist = 0.0 
)
inherited

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
virtual bool AttachToVisualImpl ( VisualPtr  _visual,
bool  _inheritOrientation,
double  _minDist = 0,
double  _maxDist = 0 
)
protectedvirtual

Set the camera to be attached to a visual.

This causes the camera to move in relation to the specified visual.

Parameters
[in]_visualThe visual to attach to.
[in]_inheritOrientationTrue if the camera should also rotate when the visual rotates.
[in]_minDistMinimum distance the camera can get to the visual.
[in]_maxDistMaximum distance the camera can get from the visual.
Returns
True if successfully attach to the visual.

Reimplemented from Camera.

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

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
virtual bool AttachToVisualImpl ( uint32_t  _id,
const bool  _inheritOrientation,
const double  _minDist = 0,
const double  _maxDist = 0 
)
protectedvirtualinherited

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
virtual float AvgFPS ( ) const
virtualinherited

Get the average FPS.

Returns
The average frames per second
void CameraToViewportRay ( const int  _screenx,
const int  _screeny,
ignition::math::Vector3d &  _origin,
ignition::math::Vector3d &  _dir 
) const
inherited

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
Deprecated:
See function that accepts ignition::math parameters.
bool CaptureData ( ) const
inherited

Return the value of this->captureData.

Returns
True if the camera is set to capture data.
event::ConnectionPtr ConnectNewImageFrame ( std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)
inherited

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.
void CreateRenderTexture ( const std::string &  _textureName)
inherited

Set the render target.

Parameters
[in]_textureNameName of the new render texture
ignition::math::Vector3d Direction ( ) const
inherited

Get the camera's direction vector.

Returns
Direction the camera is facing
void DisconnectNewImageFrame ( event::ConnectionPtr _c)
inherited

Disconnect from an image frame.

Parameters
[in]_cThe connection to disconnect
void EnableSaveFrame ( const bool  _enable)
inherited

Enable or disable saving.

Parameters
[in]_enableSet to True to enable saving of frames
double FarClip ( ) const
inherited

Get the far clip distance.

Returns
Far clip distance
void Fini ( )
virtual

Finialize.

Reimplemented from Camera.

std::string FrameFilename ( )
protectedinherited

Get the next frame filename based on SDF parameters.

Returns
The frame's filename
float GetAspectRatio ( ) const
inherited

Get the apect ratio.

Returns
The aspect ratio (width / height) in pixels
Deprecated:
See AspectRatio()
virtual float GetAvgFPS ( ) const
virtualinherited

Get the average FPS.

Returns
The average frames per second
Deprecated:
See AvgFPS()
void GetCameraToViewportRay ( int  _screenx,
int  _screeny,
math::Vector3 _origin,
math::Vector3 _dir 
)
inherited

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
Deprecated:
See function that accepts ignition::math parameters.
See Also
CameraToViewportRay
bool GetCaptureData ( ) const
inherited

Return the value of this->captureData.

Returns
True if the camera is set to capture data.
Deprecated:
See CaptureData()
math::Vector3 GetDirection ( ) const
inherited

Get the camera's direction vector.

Returns
Direction the camera is facing
Deprecated:
See function that returns an ignition::math object.
See Also
Direction
DistortionPtr GetDistortion ( ) const
inherited

Get the distortion model of this camera.

Returns
Distortion model.
Deprecated:
See LensDistortion() const;
double GetFarClip ( )
inherited

Get the far clip distance.

Returns
Far clip distance
Deprecated:
See FarClip()
std::string GetFrameFilename ( )
protectedinherited

Get the next frame filename based on SDF parameters.

Returns
The frame's filename
Deprecated:
See FrameFilename()
math::Angle GetHFOV ( ) const
inherited

Get the camera FOV (horizontal)

Returns
The horizontal field of view
Deprecated:
See function that returns an ignition::math object.
See Also
HFOV
size_t GetImageByteSize ( ) const
inherited

Get the image size in bytes.

Returns
Size in bytes
Deprecated:
See ImageByteSize()
static size_t GetImageByteSize ( unsigned int  _width,
unsigned int  _height,
const std::string &  _format 
)
staticinherited

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
Deprecated:
See ImageByteSize()
virtual const unsigned char* GetImageData ( unsigned int  i = 0)
virtualinherited

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.
Deprecated:
See ImageData()
unsigned int GetImageDepth ( ) const
inherited

Get the depth of the image.

Returns
Depth of the image
Deprecated:
See ImageDepth()
std::string GetImageFormat ( ) const
inherited

Get the string representation of the image format.

Returns
String representation of the image format.
Deprecated:
See ImageFormat()
virtual unsigned int GetImageHeight ( ) const
virtual

Get the height of the image.

Returns
Image height
Deprecated:
See ImageHeight()

Reimplemented from Camera.

virtual unsigned int GetImageWidth ( ) const
virtual

Get the width of the image.

Returns
Image width
Deprecated:
See ImageWidth()

Reimplemented from Camera.

bool GetInitialized ( ) const
inherited

Return true if the camera has been initialized.

Returns
True if initialized was successful
Deprecated:
See Initialized()
common::Time GetLastRenderWallTime ( )
inherited

Get the last time the camera was rendered.

Returns
Time the camera was last rendered
Deprecated:
See LastRenderWallTime()
std::string GetName ( ) const
inherited

Get the camera's unscoped name.

Returns
The name of the camera
Deprecated:
See Name()
double GetNearClip ( )
inherited

Get the near clip distance.

Returns
Near clip distance
Deprecated:
See NearClip()
Ogre::Camera* GetOgreCamera ( ) const
inherited

Get a pointer to the ogre camera.

Returns
Pointer to the OGRE camera
Deprecated:
See OgreCamera()
std::string GetProjectionType ( ) const
inherited

Return the projection type as a string.

Returns
"perspective" or "orthographic"
See Also
SetProjectionType(const std::string &_type)
Deprecated:
See ProjectionType()
double GetRenderRate ( ) const
inherited

Get the render Hz rate.

Returns
The Hz rate
Deprecated:
See RenderRate()
Ogre::Texture* GetRenderTexture ( ) const
inherited

Get the render texture.

Returns
Pointer to the render texture
Deprecated:
See RenderTexture()
math::Vector3 GetRight ( )
inherited

Get the viewport right vector.

Returns
The viewport right vector
Deprecated:
See function that returns an ignition::math object.
See Also
Right
ScenePtr GetScene ( ) const
inherited

Get the scene this camera is in.

Returns
Pointer to scene containing this camera
Ogre::SceneNode* GetSceneNode ( ) const
inherited

Get the camera's scene node.

Returns
The scene node the camera is attached to
Deprecated:
See SceneNode()
std::string GetScopedName ( ) const
inherited

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

Returns
The name of the camera
Deprecated:
See ScopedName()
std::string GetScreenshotPath ( ) const
inherited

Get the path to saved screenshots.

Returns
Path to saved screenshots.
Deprecated:
See ScreenshotPath()
unsigned int GetTextureHeight ( ) const
inherited

Get the height of the off-screen render texture.

Returns
Render texture height
Deprecated:
See TextureHeight()
unsigned int GetTextureWidth ( ) const
inherited

Get the width of the off-screen render texture.

Returns
Render texture width
Deprecated:
See TextureWidth()
virtual unsigned int GetTriangleCount ( ) const
virtualinherited

Get the triangle count.

Returns
The current triangle count
Deprecated:
See TriangleCount()
math::Vector3 GetUp ( )
inherited

Get the viewport up vector.

Returns
The viewport up vector
Deprecated:
See function that returns an ignition::math object.
See Also
Up
math::Angle GetVFOV ( ) const
inherited

Get the camera FOV (vertical)

Returns
The vertical field of view
Deprecated:
See function that returns an ignition::math object.
See Also
VFOV
Ogre::Viewport* GetViewport ( ) const
inherited

Get a pointer to the Ogre::Viewport.

Returns
Pointer to the Ogre::Viewport
Deprecated:
See OgreViewport()
unsigned int GetViewportHeight ( ) const
inherited

Get the viewport height in pixels.

Returns
The viewport height
Deprecated:
See ViewportHeight()
unsigned int GetViewportWidth ( ) const
inherited

Get the viewport width in pixels.

Returns
The viewport width
Deprecated:
See ViewportWidth()
unsigned int GetWindowId ( ) const
inherited

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

Returns
The ID of the window.
Deprecated:
See WindowId()
bool GetWorldPointOnPlane ( int  _x,
int  _y,
const math::Plane _plane,
math::Vector3 _result 
)
inherited

Get point on a plane.

Parameters
[in]_xX cooridnate in camera's viewport, in pixels
[in]_yY cooridnate 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
Deprecated:
See function that accepts ignition::math parameters.
See Also
WorldPointOnPlane
math::Pose GetWorldPose ( ) const
inherited

Get the world pose.

Returns
The pose of the camera in the world coordinate frame.
Deprecated:
See function that returns an ignition::math object
See Also
WorldPose
math::Vector3 GetWorldPosition ( ) const
inherited

Get the camera position in the world.

Returns
The world position of the camera
Deprecated:
See function that returns an ignition::math object
See Also
WorldPosition
math::Quaternion GetWorldRotation ( ) const
inherited

Get the camera's orientation in the world.

Returns
The camera's orientation as a math::Quaternion
Deprecated:
See function that returns an ignition::math object
See Also
WorldRotation
double GetZValue ( int  _x,
int  _y 
)
inherited

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.
Deprecated:
See ZValue()
ignition::math::Angle HFOV ( ) const
inherited

Get the camera FOV (horizontal)

Returns
The horizontal field of view
size_t ImageByteSize ( ) const
inherited

Get the image size in bytes.

Returns
Size in bytes
static size_t ImageByteSize ( const unsigned int  _width,
const unsigned int  _height,
const std::string &  _format 
)
staticinherited

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
virtual const unsigned char* ImageData ( const unsigned int  i = 0) const
virtualinherited

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.
unsigned int ImageDepth ( ) const
inherited

Get the depth of the image.

Returns
Depth of the image
std::string ImageFormat ( ) const
inherited

Get the string representation of the image format.

Returns
String representation of the image format.
virtual unsigned int ImageHeight ( ) const
virtualinherited

Get the height of the image.

Returns
Image height
virtual unsigned int ImageWidth ( ) const
virtualinherited

Get the width of the image.

Returns
Image width
void Init ( )
virtual

Initialize.

Reimplemented from Camera.

bool Initialized ( ) const
inherited

Return true if the camera has been initialized.

Returns
True if initialized was successful
bool IsAnimating ( ) const
inherited

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

bool IsVisible ( VisualPtr  _visual)
inherited

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
bool IsVisible ( const std::string &  _visualName)
inherited

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
common::Time LastRenderWallTime ( ) const
inherited

Get the last time the camera was rendered.

Returns
Time the camera was last rendered
DistortionPtr LensDistortion ( ) const
inherited

Get the distortion model of this camera.

Returns
Distortion model.
void Load ( sdf::ElementPtr  _sdf)
virtual

Load the user camera.

Parameters
[in]_sdfParameters for the camera.

Reimplemented from Camera.

void Load ( )
virtual

Generic load function.

Reimplemented from Camera.

virtual bool MoveToPosition ( const math::Pose _pose,
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
Deprecated:
See function that accepts ignition::math parameters.

Reimplemented from Camera.

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

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
bool MoveToPositions ( const std::vector< math::Pose > &  _pts,
double  _time,
std::function< void()>  _onComplete = NULL 
)
inherited

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
Deprecated:
See function that accepts ignition::math parameters.
bool MoveToPositions ( const std::vector< ignition::math::Pose3d > &  _pts,
const double  _time,
std::function< void()>  _onComplete = NULL 
)
inherited

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
void MoveToVisual ( VisualPtr  _visual)

Move the camera to focus on a visual.

Parameters
[in]_visualVisual to move the camera to.
void MoveToVisual ( const std::string &  _visualName)

Move the camera to focus on a visual.

Parameters
[in]_visualNameName of the visual to move the camera to.
std::string Name ( ) const
inherited

Get the camera's unscoped name.

Returns
The name of the camera
double NearClip ( ) const
inherited

Get the near clip distance.

Returns
Near clip distance
Ogre::Camera* OgreCamera ( ) const
inherited

Get a pointer to the ogre camera.

Returns
Pointer to the OGRE camera
Ogre::Viewport* OgreViewport ( ) const
inherited

Get a pointer to the Ogre::Viewport.

Returns
Pointer to the Ogre::Viewport
void Pitch ( const math::Angle _angle,
Ogre::Node::TransformSpace  _relativeTo = Ogre::Node::TS_LOCAL 
)
inherited

Rotate the camera around the y-axis.

Parameters
[in]_anglePitch amount
[in]_relativeToCoordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_LOCAL
Deprecated:
See function the accepts an ignition::math parameter
void Pitch ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_LOCAL 
)
inherited

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
virtual void PostRender ( )
virtual

Post render.

Reimplemented from Camera.

std::string ProjectionType ( ) const
inherited

Return the projection type as a string.

Returns
"perspective" or "orthographic"
See Also
SetProjectionType(const std::string &_type)
void ReadPixelBuffer ( )
protectedinherited

Read image data from pixel buffer.

bool Ready ( )

Used to check if Oculus is plugged in and can be used.

Returns
True when Oculus is ready to use.
void Render ( const bool  _force = false)
inherited

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.
virtual void RenderImpl ( )
protectedvirtual

Implementation of the render call.

Reimplemented from Camera.

double RenderRate ( ) const
inherited

Get the render Hz rate.

Returns
The Hz rate
Ogre::Texture* RenderTexture ( ) const
inherited

Get the render texture.

Returns
Pointer to the render texture
void ResetSensor ( )

Reset the Oculus Rift sensor orientation.

void Resize ( unsigned int  _w,
unsigned int  _h 
)

Resize the camera.

Parameters
[in]_wWidth of the camera image.
[in]_hHeight of the camera image.
ignition::math::Vector3d Right ( ) const
inherited

Get the viewport right vector.

Returns
The viewport right vector
void Roll ( const math::Angle _angle,
Ogre::Node::TransformSpace  _relativeTo = Ogre::Node::TS_LOCAL 
)
inherited

Rotate the camera around the x-axis.

Parameters
[in]_angleRotation amount
[in]_relativeToCoordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_LOCAL
Deprecated:
See function the accepts an ignition::math parameter
void Roll ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_LOCAL 
)
inherited

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
bool SaveFrame ( const std::string &  _filename)
inherited

Save the last frame to disk.

Parameters
[in]_filenameFile in which to save a single frame
Returns
True if saving was successful
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 
)
staticinherited

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
Ogre::SceneNode* SceneNode ( ) const
inherited

Get the camera's scene node.

Returns
The scene node the camera is attached to
std::string ScopedName ( ) const
inherited

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

Returns
The name of the camera
std::string ScreenshotPath ( ) const
inherited

Get the path to saved screenshots.

Returns
Path to saved screenshots.
void SetAspectRatio ( float  _ratio)
inherited

Set the aspect ratio.

Parameters
[in]_ratioThe aspect ratio (width / height) in pixels
void SetCaptureData ( const bool  _value)
inherited

Set whether to capture data.

Parameters
[in]_valueSet to true to capture data into a memory buffer.
void SetCaptureDataOnce ( )
inherited

Capture data once and save to disk.

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

Set the clip distances.

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

Reimplemented in UserCamera.

void SetHFOV ( math::Angle  _angle)
inherited

Set the camera FOV (horizontal)

Parameters
[in]_angleHorizontal field of view
Deprecated:
See function the accepts an ignition::math parameter
void SetHFOV ( const ignition::math::Angle &  _angle)
inherited

Set the camera FOV (horizontal)

Parameters
[in]_angleHorizontal field of view
void SetImageHeight ( const unsigned int  _h)
inherited

Set the image height.

Parameters
[in]_hImage height
void SetImageSize ( const unsigned int  _w,
const unsigned int  _h 
)
inherited

Set the image size.

Parameters
[in]_wImage width
[in]_hImage height
void SetImageWidth ( const unsigned int  _w)
inherited

Set the image height.

Parameters
[in]_wImage width
void SetName ( const std::string &  _name)
inherited

Set the camera's name.

Parameters
[in]_nameNew name for the camera
virtual bool SetProjectionType ( const std::string &  _type)
virtualinherited

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.

void SetRenderRate ( const double  _hz)
inherited

Set the render Hz rate.

Parameters
[in]_hzThe Hz rate
virtual void SetRenderTarget ( Ogre::RenderTarget *  _target)
virtual

Set to true to enable rendering.

Use this only if you really know what you're doing.

Parameters
[in]_targetThe new rendering target.

Reimplemented from Camera.

void SetSaveFramePathname ( const std::string &  _pathname)
inherited

Set the save frame pathname.

Parameters
[in]_pathnameDirectory in which to store saved image frames
void SetScene ( ScenePtr  _scene)
inherited

Set the scene this camera is viewing.

Parameters
[in]_scenePointer to the scene
void SetSceneNode ( Ogre::SceneNode *  _node)
inherited

Set the camera's scene node.

Parameters
[in]_nodeThe scene nodes to attach the camera to
void SetTrackInheritYaw ( const bool  _inheritYaw)
inherited

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()
void SetTrackIsStatic ( const bool  _isStatic)
inherited

Set whether this camera is static when tracking a model.

Parameters
[in]_isStaticTrue means camera is static when tracking a model.
See Also
TrackIsStatic()
void SetTrackMaxDistance ( const double  _dist)
inherited

Set the maximum distance between the camera and tracked visual.

Parameters
[in]_distMaximum distance between camera and visual.
See Also
TrackMaxDistance()
void SetTrackMinDistance ( const double  _dist)
inherited

Set the minimum distance between the camera and tracked visual.

Parameters
[in]_distMinimum distance between camera and visual.
See Also
TrackMinDistance()
void SetTrackPosition ( const ignition::math::Vector3d &  _pos)
inherited

Set the position of the camera when tracking a visual.

Parameters
[in]_posPosition of the camera.
See Also
TrackPosition()
void SetTrackUseModelFrame ( const bool  _useModelFrame)
inherited

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()
void SetWindowId ( unsigned int  _windowId)
inherited
virtual void SetWorldPose ( const math::Pose _pose)
virtualinherited

Set the global pose of the camera.

Parameters
[in]_poseThe new math::Pose of the camera
Deprecated:
See function that accepts an ignition::math parameter.

Reimplemented in UserCamera.

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

Set the global pose of the camera.

Parameters
[in]_poseThe new ignition::math::Pose3d of the camera
void SetWorldPosition ( const math::Vector3 _pos)
inherited

Set the world position.

Parameters
[in]_posThe new position of the camera
Deprecated:
See function that accepts an ignition::math parameter
void SetWorldPosition ( const ignition::math::Vector3d &  _pos)
inherited

Set the world position.

Parameters
[in]_posThe new position of the camera
void SetWorldRotation ( const math::Quaternion _quat)
inherited

Set the world orientation.

Parameters
[in]_quatThe new orientation of the camera
Deprecated:
See function that accepts an ignition::math parameter
void SetWorldRotation ( const ignition::math::Quaterniond &  _quat)
inherited

Set the world orientation.

Parameters
[in]_quatThe new orientation of the camera
void ShowWireframe ( const bool  _s)
inherited

Set whether to view the world in wireframe.

Parameters
[in]_sSet to True to render objects as wireframe
unsigned int TextureHeight ( ) const
inherited

Get the height of the off-screen render texture.

Returns
Render texture height
unsigned int TextureWidth ( ) const
inherited

Get the width of the off-screen render texture.

Returns
Render texture width
void ToggleShowWireframe ( )
inherited

Toggle whether to view the world in wireframe.

VisualPtr TrackedVisual ( ) const
inherited

Get the visual tracked by this camera.

Returns
Tracked visual.
bool TrackInheritYaw ( ) const
inherited

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)
bool TrackIsStatic ( ) const
inherited

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)
double TrackMaxDistance ( ) const
inherited

Return the maximum distance to the tracked visual.

Returns
Maximum distance to the model.
See Also
SetTrackMaxDistance(const double _dist)
double TrackMinDistance ( ) const
inherited

Return the minimum distance to the tracked visual.

Returns
Minimum distance to the model.
See Also
SetTrackMinDistance(const double _dist)
ignition::math::Vector3d TrackPosition ( ) const
inherited

Return the position of the camera when tracking a model.

Returns
Position of the camera.
See Also
SetTrackPosition(const ignition::math::Vector3d &_pos)
bool TrackUseModelFrame ( ) const
inherited

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)
void TrackVisual ( const std::string &  _visualName)
inherited

Set the camera to track a scene node.

Parameters
[in]_visualNameName of the visual to track
virtual bool TrackVisualImpl ( VisualPtr  _visual)
protectedvirtual

Set the camera to track a scene node.

Tracking just causes the camera to rotate to follow the visual.

Parameters
[in]_visualVisual to track.
Returns
True if the camera is now tracking the visual.

Reimplemented from Camera.

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

Implementation of the Camera::TrackVisual call.

Parameters
[in]_visualNameName of the visual to track
Returns
True if able to track the visual
void Translate ( const math::Vector3 _direction)
inherited

Translate the camera.

Parameters
[in]_directionThe translation vector
Deprecated:
See function that accepts an ignition::math parameter
void Translate ( const ignition::math::Vector3d &  _direction)
inherited

Translate the camera.

Parameters
[in]_directionThe translation vector
virtual unsigned int TriangleCount ( ) const
virtualinherited

Get the triangle count.

Returns
The current triangle count
ignition::math::Vector3d Up ( ) const
inherited

Get the viewport up vector.

Returns
The viewport up vector
virtual void Update ( )
virtual

Render the camera.

Reimplemented from Camera.

virtual void UpdateFOV ( )
protectedvirtualinherited

Update the camera's field of view.

Reimplemented in UserCamera.

ignition::math::Angle VFOV ( ) const
inherited

Get the camera FOV (vertical)

Returns
The vertical field of view
Deprecated:
See function that returns an ignition::math object.
See Also
VFOV
unsigned int ViewportHeight ( ) const
inherited

Get the viewport height in pixels.

Returns
The viewport height
unsigned int ViewportWidth ( ) const
inherited

Get the viewport width in pixels.

Returns
The viewport width
unsigned int WindowId ( ) const
inherited

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

Returns
The ID of the window.
bool WorldPointOnPlane ( const int  _x,
const int  _y,
const ignition::math::Planed &  _plane,
ignition::math::Vector3d &  _result 
)
inherited

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
ignition::math::Pose3d WorldPose ( ) const
inherited

Get the world pose.

Returns
The pose of the camera in the world coordinate frame.
ignition::math::Vector3d WorldPosition ( ) const
inherited

Get the camera position in the world.

Returns
The world position of the camera
ignition::math::Quaterniond WorldRotation ( ) const
inherited

Get the camera's orientation in the world.

Returns
The camera's orientation as an ignition::math::Quaterniond
void Yaw ( const math::Angle _angle,
Ogre::Node::TransformSpace  _relativeTo = Ogre::Node::TS_WORLD 
)
inherited

Rotate the camera around the z-axis.

Parameters
[in]_angleRotation amount
[in]_relativeToCoordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_WORLD
Deprecated:
See function the accepts an ignition::math parameter
void Yaw ( const ignition::math::Angle &  _angle,
ReferenceFrame  _relativeTo = RF_WORLD 
)
inherited

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
double ZValue ( const int  _x,
const int  _y 
)
inherited

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

Ogre::AnimationState* animState
protectedinherited

Animation state, used to animate the camera.

unsigned char* bayerFrameBuffer
protectedinherited

Buffer for a bayer image frame.

Ogre::Camera* camera
protectedinherited

The OGRE camera.

bool captureData
protectedinherited

True to capture frames into an image buffer.

bool captureDataOnce
protectedinherited

True to capture a frame once and save to disk.

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

The camera's event connections.

int imageFormat
protectedinherited

Format for saving images.

int imageHeight
protectedinherited

Save image height.

int imageWidth
protectedinherited

Save image width.

bool initialized
protectedinherited

True if initialized.

common::Time lastRenderWallTime
protectedinherited

Time the last frame was rendered.

std::string name
protectedinherited

Name of the camera.

bool newData
protectedinherited

True if new data is available.

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

Event triggered when a new frame is generated.

std::function<void()> onAnimationComplete
protectedinherited

User callback for when an animation completes.

common::Time prevAnimTime
protectedinherited

Previous time the camera animation was updated.

Ogre::RenderTarget* renderTarget
protectedinherited

Target that renders frames.

Ogre::Texture* renderTexture
protectedinherited

Texture that receives results from rendering.

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

List of requests.

unsigned int saveCount
protectedinherited

Number of saved frames.

unsigned char* saveFrameBuffer
protectedinherited

Buffer for a single image frame.

ScenePtr scene
protectedinherited

Pointer to the scene.

Ogre::SceneNode* sceneNode
protectedinherited

Scene node that controls camera position and orientation.

std::string scopedName
protectedinherited

Scene scoped name of the camera.

std::string scopedUniqueName
protectedinherited

Scene scoped name of the camera with a unique ID.

std::string screenshotPath
protectedinherited

Path to saved screenshots.

sdf::ElementPtr sdf
protectedinherited

Camera's SDF values.

unsigned int textureHeight
protectedinherited

Height of the render texture.

unsigned int textureWidth
protectedinherited

Width of the render texture.

Ogre::Viewport* viewport
protectedinherited

Viewport the ogre camera uses.

unsigned int windowId
protectedinherited

ID of the window that the camera is attached to.


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