All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::rendering::Camera Class Reference

Basic camera sensor. More...

#include <rendering/rendering.hh>

Inheritance diagram for gazebo::rendering::Camera:
Inheritance graph
[legend]

Public Member Functions

 Camera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
 Constructor. More...
 
virtual ~Camera ()
 Destructor. More...
 
void AttachToVisual (const std::string &_visualName, bool _inheritOrientation, double _minDist=0.0, double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
void AttachToVisual (uint32_t _id, bool _inheritOrientation, double _minDist=0.0, double _maxDist=0.0)
 Attach the camera to a scene node. More...
 
template<typename T >
event::ConnectionPtr ConnectNewImageFrame (T _subscriber)
 Connect to the new image signal. More...
 
void CreateRenderTexture (const std::string &_textureName)
 Set the render target. More...
 
void DisconnectNewImageFrame (event::ConnectionPtr &_c)
 Disconnect from an image frame. More...
 
void EnableSaveFrame (bool _enable)
 Enable or disable saving. More...
 
virtual void Fini ()
 Finalize the camera. More...
 
float GetAspectRatio () const
 Get the apect ratio. More...
 
virtual float GetAvgFPS ()
 Get the average FPS. More...
 
void GetCameraToViewportRay (int _screenx, int _screeny, math::Vector3 &_origin, math::Vector3 &_dir)
 Get a world space ray as cast from the camera through the viewport. More...
 
bool GetCaptureData () const
 Return the value of this->captureData. More...
 
math::Vector3 GetDirection () const
 Get the camera's direction vector. More...
 
double GetFarClip ()
 Get the far clip distance. More...
 
math::Angle GetHFOV () const
 Get the camera FOV (horizontal) More...
 
size_t GetImageByteSize () const
 Get the image size in bytes. More...
 
virtual const unsigned char * GetImageData (unsigned int i=0)
 Get a pointer to the image data. More...
 
unsigned int GetImageDepth () const
 Get the depth of the image. More...
 
std::string GetImageFormat () const
 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
 Return true if the camera has been initialized. More...
 
common::Time GetLastRenderWallTime ()
 Get the last time the camera was rendered. More...
 
std::string GetName () const
 Get the camera's name. More...
 
double GetNearClip ()
 Get the near clip distance. More...
 
Ogre::Camera * GetOgreCamera () const
 Get a pointer to the ogre camera. More...
 
Ogre::SceneNode * GetPitchNode () const
 Get the camera's pitch scene node. More...
 
double GetRenderRate () const
 Get the render Hz rate. More...
 
Ogre::Texture * GetRenderTexture () const
 Get the render texture. More...
 
math::Vector3 GetRight ()
 Get the viewport right vector. More...
 
ScenePtr GetScene () const
 Get the scene this camera is in. More...
 
Ogre::SceneNode * GetSceneNode () const
 Get the camera's scene node. More...
 
std::string GetScreenshotPath () const
 Get the path to saved screenshots. More...
 
unsigned int GetTextureHeight () const
 Get the height of the off-screen render texture. More...
 
unsigned int GetTextureWidth () const
 Get the width of the off-screen render texture. More...
 
virtual unsigned int GetTriangleCount ()
 Get the triangle count. More...
 
math::Vector3 GetUp ()
 Get the viewport up vector. More...
 
math::Angle GetVFOV () const
 Get the camera FOV (vertical) More...
 
Ogre::Viewport * GetViewport () const
 Get a pointer to the Ogre::Viewport. More...
 
unsigned int GetViewportHeight () const
 Get the viewport height in pixels. More...
 
unsigned int GetViewportWidth () const
 Get the viewport width in pixels. More...
 
unsigned int GetWindowId () const
 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)
 Get point on a plane. More...
 
math::Pose GetWorldPose ()
 Get the global pose of the camera. More...
 
math::Vector3 GetWorldPosition () const
 Get the camera position in the world. More...
 
math::Quaternion GetWorldRotation () const
 Get the camera's orientation in the world. More...
 
double GetZValue (int _x, int _y)
 Get the Z-buffer value at the given image coordinate. More...
 
virtual void Init ()
 Initialize the camera. 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...
 
virtual void Load (sdf::ElementPtr _sdf)
 Load the camera with a set of parmeters. More...
 
virtual void Load ()
 Load the camera with default parmeters. More...
 
virtual bool MoveToPosition (const math::Pose &_pose, double _time)
 Move the camera to a position (this is an animated motion). More...
 
bool MoveToPositions (const std::vector< math::Pose > &_pts, double _time, boost::function< void()> _onComplete=NULL)
 Move the camera to a series of poses (this is an animated motion). More...
 
virtual void PostRender ()
 Post render. More...
 
void Render ()
 Render the camera. More...
 
void Render (bool _force)
 Render the camera. More...
 
void RotatePitch (math::Angle _angle)
 Rotate the camera around the pitch axis. More...
 
void RotateYaw (math::Angle _angle)
 Rotate the camera around the yaw axis. More...
 
bool SaveFrame (const std::string &_filename)
 Save the last frame to disk. More...
 
void SetAspectRatio (float _ratio)
 Set the aspect ratio. More...
 
void SetCaptureData (bool _value)
 Set whether to capture data. More...
 
void SetCaptureDataOnce ()
 Capture data once and save to disk. More...
 
void SetClipDist (float _near, float _far)
 Set the clip distances. More...
 
void SetHFOV (math::Angle _angle)
 Set the camera FOV (horizontal) More...
 
void SetImageHeight (unsigned int _h)
 Set the image height. More...
 
void SetImageSize (unsigned int _w, unsigned int _h)
 Set the image size. More...
 
void SetImageWidth (unsigned int _w)
 Set the image height. More...
 
void SetName (const std::string &_name)
 Set the camera's name. More...
 
void SetRenderRate (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 SetWindowId (unsigned int _windowId)
 
virtual void SetWorldPose (const math::Pose &_pose)
 Set the global pose of the camera. More...
 
void SetWorldPosition (const math::Vector3 &_pos)
 Set the world position. More...
 
void SetWorldRotation (const math::Quaternion &_quat)
 Set the world orientation. More...
 
void ShowWireframe (bool _s)
 Set whether to view the world in wireframe. More...
 
void ToggleShowWireframe ()
 Toggle whether to view the world in wireframe. More...
 
void TrackVisual (const std::string &_visualName)
 Set the camera to track a scene node. More...
 
void Translate (const math::Vector3 &_direction)
 Translate the camera. More...
 
virtual void Update ()
 

Static Public Member Functions

static size_t GetImageByteSize (unsigned int _width, unsigned int _height, const std::string &_format)
 Calculate image byte size base on a few parameters. More...
 
static bool SaveFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, 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, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (uint32_t _id, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Attach the camera to a scene node. More...
 
virtual bool AttachToVisualImpl (VisualPtr _visual, bool _inheritOrientation, double _minDist=0, double _maxDist=0)
 Attach the camera to a visual. More...
 
std::string GetFrameFilename ()
 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...
 
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...
 

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...
 
boost::function< void()> onAnimationComplete
 User callback for when an animation completes. More...
 
Ogre::SceneNode * pitchNode
 Scene nod that controls camera pitch. 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
 
ScenePtr scene
 Pointer to the scene. More...
 
Ogre::SceneNode * sceneNode
 Scene node that controls camera position. 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

gazebo::rendering::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.
virtual gazebo::rendering::Camera::~Camera ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::rendering::Camera::AnimationComplete ( )
protectedvirtual

Internal function used to indicate that an animation has completed.

Reimplemented in gazebo::rendering::UserCamera.

void gazebo::rendering::Camera::AttachToVisual ( const std::string &  _visualName,
bool  _inheritOrientation,
double  _minDist = 0.0,
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
void gazebo::rendering::Camera::AttachToVisual ( uint32_t  _id,
bool  _inheritOrientation,
double  _minDist = 0.0,
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
virtual bool gazebo::rendering::Camera::AttachToVisualImpl ( const std::string &  _name,
bool  _inheritOrientation,
double  _minDist = 0,
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
virtual bool gazebo::rendering::Camera::AttachToVisualImpl ( uint32_t  _id,
bool  _inheritOrientation,
double  _minDist = 0,
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
virtual bool gazebo::rendering::Camera::AttachToVisualImpl ( VisualPtr  _visual,
bool  _inheritOrientation,
double  _minDist = 0,
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 gazebo::rendering::UserCamera.

template<typename T >
event::ConnectionPtr gazebo::rendering::Camera::ConnectNewImageFrame ( _subscriber)
inline

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.

References gazebo::event::EventT< T >::Connect(), and newImageFrame.

void gazebo::rendering::Camera::CreateRenderTexture ( const std::string &  _textureName)

Set the render target.

Parameters
[in]_textureNameName of the new render texture
void gazebo::rendering::Camera::DisconnectNewImageFrame ( event::ConnectionPtr _c)
inline

Disconnect from an image frame.

Parameters
[in]_cThe connection to disconnect

References gazebo::event::EventT< T >::Disconnect(), and newImageFrame.

void gazebo::rendering::Camera::EnableSaveFrame ( bool  _enable)

Enable or disable saving.

Parameters
[in]_enableSet to True to enable saving of frames
virtual void gazebo::rendering::Camera::Fini ( )
virtual

Finalize the camera.

This function is called before the camera is destructed

Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.

float gazebo::rendering::Camera::GetAspectRatio ( ) const

Get the apect ratio.

Returns
The aspect ratio (width / height) in pixels
virtual float gazebo::rendering::Camera::GetAvgFPS ( )
inlinevirtual

Get the average FPS.

Returns
The average frames per second
void gazebo::rendering::Camera::GetCameraToViewportRay ( int  _screenx,
int  _screeny,
math::Vector3 _origin,
math::Vector3 _dir 
)

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
bool gazebo::rendering::Camera::GetCaptureData ( ) const

Return the value of this->captureData.

Returns
True if the camera is set to capture data.
math::Vector3 gazebo::rendering::Camera::GetDirection ( ) const

Get the camera's direction vector.

Returns
Direction the camera is facing
double gazebo::rendering::Camera::GetFarClip ( )

Get the far clip distance.

Returns
Far clip distance
std::string gazebo::rendering::Camera::GetFrameFilename ( )
protected

Get the next frame filename based on SDF parameters.

Returns
The frame's filename
math::Angle gazebo::rendering::Camera::GetHFOV ( ) const

Get the camera FOV (horizontal)

Returns
The horizontal field of view
size_t gazebo::rendering::Camera::GetImageByteSize ( ) const

Get the image size in bytes.

Returns
Size in bytes
static size_t gazebo::rendering::Camera::GetImageByteSize ( unsigned int  _width,
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
virtual const unsigned char* gazebo::rendering::Camera::GetImageData ( unsigned int  i = 0)
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.
unsigned int gazebo::rendering::Camera::GetImageDepth ( ) const

Get the depth of the image.

Returns
Depth of the image
std::string gazebo::rendering::Camera::GetImageFormat ( ) const

Get the string representation of the image format.

Returns
String representation of the image format.
virtual unsigned int gazebo::rendering::Camera::GetImageHeight ( ) const
virtual

Get the height of the image.

Returns
Image height

Reimplemented in gazebo::rendering::UserCamera.

virtual unsigned int gazebo::rendering::Camera::GetImageWidth ( ) const
virtual

Get the width of the image.

Returns
Image width

Reimplemented in gazebo::rendering::UserCamera.

bool gazebo::rendering::Camera::GetInitialized ( ) const

Return true if the camera has been initialized.

Returns
True if initialized was successful
common::Time gazebo::rendering::Camera::GetLastRenderWallTime ( )

Get the last time the camera was rendered.

Returns
Time the camera was last rendered
std::string gazebo::rendering::Camera::GetName ( ) const

Get the camera's name.

Returns
The name of the camera
double gazebo::rendering::Camera::GetNearClip ( )

Get the near clip distance.

Returns
Near clip distance
Ogre::Camera* gazebo::rendering::Camera::GetOgreCamera ( ) const

Get a pointer to the ogre camera.

Returns
Pointer to the OGRE camera
Ogre::SceneNode* gazebo::rendering::Camera::GetPitchNode ( ) const

Get the camera's pitch scene node.

Returns
The pitch node the camera is attached to
double gazebo::rendering::Camera::GetRenderRate ( ) const

Get the render Hz rate.

Returns
The Hz rate
Ogre::Texture* gazebo::rendering::Camera::GetRenderTexture ( ) const

Get the render texture.

Returns
Pointer to the render texture
math::Vector3 gazebo::rendering::Camera::GetRight ( )

Get the viewport right vector.

Returns
The viewport right vector
ScenePtr gazebo::rendering::Camera::GetScene ( ) const

Get the scene this camera is in.

Returns
Pointer to scene containing this camera
Ogre::SceneNode* gazebo::rendering::Camera::GetSceneNode ( ) const

Get the camera's scene node.

Returns
The scene node the camera is attached to
std::string gazebo::rendering::Camera::GetScreenshotPath ( ) const

Get the path to saved screenshots.

Returns
Path to saved screenshots.
unsigned int gazebo::rendering::Camera::GetTextureHeight ( ) const

Get the height of the off-screen render texture.

Returns
Render texture height
unsigned int gazebo::rendering::Camera::GetTextureWidth ( ) const

Get the width of the off-screen render texture.

Returns
Render texture width
virtual unsigned int gazebo::rendering::Camera::GetTriangleCount ( )
inlinevirtual

Get the triangle count.

Returns
The current triangle count
math::Vector3 gazebo::rendering::Camera::GetUp ( )

Get the viewport up vector.

Returns
The viewport up vector
math::Angle gazebo::rendering::Camera::GetVFOV ( ) const

Get the camera FOV (vertical)

Returns
The vertical field of view
Ogre::Viewport* gazebo::rendering::Camera::GetViewport ( ) const

Get a pointer to the Ogre::Viewport.

Returns
Pointer to the Ogre::Viewport
unsigned int gazebo::rendering::Camera::GetViewportHeight ( ) const

Get the viewport height in pixels.

Returns
The viewport height
unsigned int gazebo::rendering::Camera::GetViewportWidth ( ) const

Get the viewport width in pixels.

Returns
The viewport width
unsigned int gazebo::rendering::Camera::GetWindowId ( ) const

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

Returns
The ID of the window.
bool gazebo::rendering::Camera::GetWorldPointOnPlane ( int  _x,
int  _y,
const math::Plane _plane,
math::Vector3 _result 
)

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
math::Pose gazebo::rendering::Camera::GetWorldPose ( )

Get the global pose of the camera.

Returns
Pose of the camera in the world coordinate frame
math::Vector3 gazebo::rendering::Camera::GetWorldPosition ( ) const

Get the camera position in the world.

Returns
The world position of the camera
math::Quaternion gazebo::rendering::Camera::GetWorldRotation ( ) const

Get the camera's orientation in the world.

Returns
The camera's orientation as a math::Quaternion
double gazebo::rendering::Camera::GetZValue ( int  _x,
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.
virtual void gazebo::rendering::Camera::Init ( )
virtual
bool gazebo::rendering::Camera::IsAnimating ( ) const

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

bool gazebo::rendering::Camera::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
bool gazebo::rendering::Camera::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
virtual void gazebo::rendering::Camera::Load ( sdf::ElementPtr  _sdf)
virtual

Load the camera with a set of parmeters.

Parameters
[in]_sdfThe SDF camera info

Reimplemented in gazebo::rendering::UserCamera.

virtual void gazebo::rendering::Camera::Load ( )
virtual

Load the camera with default parmeters.

Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.

virtual bool gazebo::rendering::Camera::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

Reimplemented in gazebo::rendering::UserCamera.

bool gazebo::rendering::Camera::MoveToPositions ( const std::vector< math::Pose > &  _pts,
double  _time,
boost::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
virtual void gazebo::rendering::Camera::PostRender ( )
virtual

Post render.

Called afer the render signal.

Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.

void gazebo::rendering::Camera::ReadPixelBuffer ( )
protected

Read image data from pixel buffer.

void gazebo::rendering::Camera::Render ( )

Render the camera.

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

void gazebo::rendering::Camera::Render ( bool  _force)

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 gazebo::rendering::Camera::RenderImpl ( )
protectedvirtual

Implementation of the render call.

void gazebo::rendering::Camera::RotatePitch ( math::Angle  _angle)

Rotate the camera around the pitch axis.

Parameters
[in]_anglePitch amount
void gazebo::rendering::Camera::RotateYaw ( math::Angle  _angle)

Rotate the camera around the yaw axis.

Parameters
[in]_angleRotation amount
bool gazebo::rendering::Camera::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
static bool gazebo::rendering::Camera::SaveFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
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
void gazebo::rendering::Camera::SetAspectRatio ( float  _ratio)

Set the aspect ratio.

Parameters
[in]_ratioThe aspect ratio (width / height) in pixels
void gazebo::rendering::Camera::SetCaptureData ( bool  _value)

Set whether to capture data.

Parameters
[in]_valueSet to true to capture data into a memory buffer.
void gazebo::rendering::Camera::SetCaptureDataOnce ( )

Capture data once and save to disk.

void gazebo::rendering::Camera::SetClipDist ( float  _near,
float  _far 
)

Set the clip distances.

Parameters
[in]_nearNear clip distance in meters
[in]_farFar clip distance in meters
void gazebo::rendering::Camera::SetHFOV ( math::Angle  _angle)

Set the camera FOV (horizontal)

Parameters
[in]_radiansHorizontal field of view
void gazebo::rendering::Camera::SetImageHeight ( unsigned int  _h)

Set the image height.

Parameters
[in]_hImage height
void gazebo::rendering::Camera::SetImageSize ( unsigned int  _w,
unsigned int  _h 
)

Set the image size.

Parameters
[in]_wImage width
[in]_hImage height
void gazebo::rendering::Camera::SetImageWidth ( unsigned int  _w)

Set the image height.

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

Set the camera's name.

Parameters
[in]_nameNew name for the camera
void gazebo::rendering::Camera::SetRenderRate ( double  _hz)

Set the render Hz rate.

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

Set the camera's render target.

Parameters
[in]_targetPointer to the render target

Reimplemented in gazebo::rendering::UserCamera.

void gazebo::rendering::Camera::SetSaveFramePathname ( const std::string &  _pathname)

Set the save frame pathname.

Parameters
[in]_pathnameDirectory in which to store saved image frames
void gazebo::rendering::Camera::SetScene ( ScenePtr  _scene)

Set the scene this camera is viewing.

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

Set the camera's scene node.

Parameters
[in]_nodeThe scene nodes to attach the camera to
void gazebo::rendering::Camera::SetWindowId ( unsigned int  _windowId)
virtual void gazebo::rendering::Camera::SetWorldPose ( const math::Pose _pose)
virtual

Set the global pose of the camera.

Parameters
[in]_poseThe new math::Pose of the camera

Reimplemented in gazebo::rendering::UserCamera.

void gazebo::rendering::Camera::SetWorldPosition ( const math::Vector3 _pos)

Set the world position.

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

Set the world orientation.

Parameters
[in]_quatThe new orientation of the camera
void gazebo::rendering::Camera::ShowWireframe ( bool  _s)

Set whether to view the world in wireframe.

Parameters
[in]_sSet to True to render objects as wireframe
void gazebo::rendering::Camera::ToggleShowWireframe ( )

Toggle whether to view the world in wireframe.

void gazebo::rendering::Camera::TrackVisual ( const std::string &  _visualName)

Set the camera to track a scene node.

Parameters
[in]_visualNameName of the visual to track
bool gazebo::rendering::Camera::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
virtual bool gazebo::rendering::Camera::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 gazebo::rendering::UserCamera.

void gazebo::rendering::Camera::Translate ( const math::Vector3 _direction)

Translate the camera.

Parameters
[in]_directionThe translation vector
virtual void gazebo::rendering::Camera::Update ( )
virtual

Reimplemented in gazebo::rendering::UserCamera.

Member Data Documentation

Ogre::AnimationState* gazebo::rendering::Camera::animState
protected

Animation state, used to animate the camera.

unsigned char* gazebo::rendering::Camera::bayerFrameBuffer
protected

Buffer for a bayer image frame.

Ogre::Camera* gazebo::rendering::Camera::camera
protected

The OGRE camera.

bool gazebo::rendering::Camera::captureData
protected

True to capture frames into an image buffer.

bool gazebo::rendering::Camera::captureDataOnce
protected

True to capture a frame once and save to disk.

std::vector<event::ConnectionPtr> gazebo::rendering::Camera::connections
protected

The camera's event connections.

int gazebo::rendering::Camera::imageFormat
protected

Format for saving images.

int gazebo::rendering::Camera::imageHeight
protected

Save image height.

int gazebo::rendering::Camera::imageWidth
protected

Save image width.

bool gazebo::rendering::Camera::initialized
protected

True if initialized.

common::Time gazebo::rendering::Camera::lastRenderWallTime
protected

Time the last frame was rendered.

std::string gazebo::rendering::Camera::name
protected

Name of the camera.

bool gazebo::rendering::Camera::newData
protected

True if new data is available.

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

Event triggered when a new frame is generated.

Referenced by ConnectNewImageFrame(), and DisconnectNewImageFrame().

boost::function<void()> gazebo::rendering::Camera::onAnimationComplete
protected

User callback for when an animation completes.

Ogre::SceneNode* gazebo::rendering::Camera::pitchNode
protected

Scene nod that controls camera pitch.

common::Time gazebo::rendering::Camera::prevAnimTime
protected

Previous time the camera animation was updated.

Ogre::RenderTarget* gazebo::rendering::Camera::renderTarget
protected

Target that renders frames.

Ogre::Texture* gazebo::rendering::Camera::renderTexture
protected

Texture that receives results from rendering.

std::list<msgs::Request> gazebo::rendering::Camera::requests
protected

List of requests.

unsigned int gazebo::rendering::Camera::saveCount
protected

Number of saved frames.

unsigned char* gazebo::rendering::Camera::saveFrameBuffer
protected
ScenePtr gazebo::rendering::Camera::scene
protected

Pointer to the scene.

Ogre::SceneNode* gazebo::rendering::Camera::sceneNode
protected

Scene node that controls camera position.

std::string gazebo::rendering::Camera::screenshotPath
protected

Path to saved screenshots.

sdf::ElementPtr gazebo::rendering::Camera::sdf
protected

Camera's SDF values.

unsigned int gazebo::rendering::Camera::textureHeight
protected

Height of the render texture.

unsigned int gazebo::rendering::Camera::textureWidth
protected

Width of the render texture.

Ogre::Viewport* gazebo::rendering::Camera::viewport
protected

Viewport the ogre camera uses.

unsigned int gazebo::rendering::Camera::windowId
protected

ID of the window that the camera is attached to.


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