Public Member Functions | Protected Attributes | List of all members
gazebo::rendering::DepthCamera Class Reference

Depth camera used to render depth data into an image buffer. More...

#include <rendering/rendering.hh>

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

Public Member Functions

 DepthCamera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
 Constructor. More...
 
virtual ~DepthCamera ()
 Destructor. More...
 
template<typename T >
event::ConnectionPtr ConnectNewDepthFrame (T _subscriber)
 Connect a to the new depth image signal. More...
 
template<typename T >
event::ConnectionPtr ConnectNewRGBPointCloud (T _subscriber)
 Connect a to the new rgb point cloud signal. More...
 
void CreateDepthTexture (const std::string &_textureName)
 Create a texture which will hold the depth data. More...
 
void DisconnectNewDepthFrame (event::ConnectionPtr &_c)
 Disconnect from an depth image singal. More...
 
void DisconnectNewRGBPointCloud (event::ConnectionPtr &c)
 Disconnect from an rgb point cloud singal. More...
 
void Fini ()
 Finalize the camera. More...
 
virtual const float * GetDepthData ()
 All things needed to get back z buffer for depth data. More...
 
void Init ()
 Initialize the camera. More...
 
void Load (sdf::ElementPtr _sdf)
 Load the camera with a set of parmeters. More...
 
void Load ()
 Load the camera with default parmeters. More...
 
virtual void PostRender ()
 Render the camera. More...
 
virtual void SetDepthTarget (Ogre::RenderTarget *_target)
 Set the render target, which renders the depth data. More...
 
- Public Member Functions inherited from gazebo::rendering::Camera
 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...
 
float GetAspectRatio () const
 Get the apect ratio. More...
 
virtual float GetAvgFPS () const
 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...
 
DistortionPtr GetDistortion () const
 Get the distortion model of this camera. 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 unscoped name. More...
 
double GetNearClip ()
 Get the near clip distance. More...
 
Ogre::Camera * GetOgreCamera () const
 Get a pointer to the ogre camera. More...
 
std::string GetProjectionType () const
 Return the projection type as a string. 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 GetScopedName () const
 Get the camera's scoped name (scene_name::camera_name) 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 () const
 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 () const
 Get the world pose. 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...
 
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 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...
 
void Pitch (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL)
 Rotate the camera around the y-axis. More...
 
void Render (bool _force=false)
 Render the camera. More...
 
void Roll (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL)
 Rotate the camera around the x-axis. More...
 
void RotatePitch (math::Angle _angle) GAZEBO_DEPRECATED(4.0)
 Rotate the camera around the y-axis. More...
 
void RotateYaw (math::Angle _angle) GAZEBO_DEPRECATED(4.0)
 Rotate the camera around the z-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...
 
virtual 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...
 
virtual bool SetProjectionType (const std::string &_type)
 Set the type of projection used by the camera. 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 ()
 
void Yaw (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_WORLD)
 Rotate the camera around the z-axis. More...
 

Protected Attributes

Ogre::RenderTarget * depthTarget
 Pointer to the depth target. More...
 
Ogre::Texture * depthTexture
 Pointer to the depth texture. More...
 
Ogre::Viewport * depthViewport
 Pointer to the depth viewport. More...
 
- Protected Attributes inherited from gazebo::rendering::Camera
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...
 
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...
 

Additional Inherited Members

- Static Public Member Functions inherited from gazebo::rendering::Camera
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 inherited from gazebo::rendering::Camera
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...
 
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...
 

Detailed Description

Depth camera used to render depth data into an image buffer.

Constructor & Destructor Documentation

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

Destructor.

Member Function Documentation

template<typename T >
event::ConnectionPtr gazebo::rendering::DepthCamera::ConnectNewDepthFrame ( _subscriber)
inline

Connect a to the new depth image signal.

Parameters
[in]_subscriberSubscriber callback function
Returns
Pointer to the new Connection. This must be kept in scope
template<typename T >
event::ConnectionPtr gazebo::rendering::DepthCamera::ConnectNewRGBPointCloud ( _subscriber)
inline

Connect a to the new rgb point cloud signal.

Parameters
[in]_subscriberSubscriber callback function
Returns
Pointer to the new Connection. This must be kept in scope
void gazebo::rendering::DepthCamera::CreateDepthTexture ( const std::string &  _textureName)

Create a texture which will hold the depth data.

Parameters
[in]_textureNameName of the texture to create
void gazebo::rendering::DepthCamera::DisconnectNewDepthFrame ( event::ConnectionPtr _c)
inline

Disconnect from an depth image singal.

Parameters
[in]_cThe connection to disconnect
void gazebo::rendering::DepthCamera::DisconnectNewRGBPointCloud ( event::ConnectionPtr c)
inline

Disconnect from an rgb point cloud singal.

Parameters
[in]_cThe connection to disconnect
void gazebo::rendering::DepthCamera::Fini ( )
virtual

Finalize the camera.

Reimplemented from gazebo::rendering::Camera.

virtual const float* gazebo::rendering::DepthCamera::GetDepthData ( )
virtual

All things needed to get back z buffer for depth data.

Returns
The z-buffer as a float array
void gazebo::rendering::DepthCamera::Init ( )
virtual

Initialize the camera.

Reimplemented from gazebo::rendering::Camera.

void gazebo::rendering::DepthCamera::Load ( sdf::ElementPtr  _sdf)
virtual

Load the camera with a set of parmeters.

Parameters
[in]_sdfThe SDF camera info

Reimplemented from gazebo::rendering::Camera.

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

Load the camera with default parmeters.

Reimplemented from gazebo::rendering::Camera.

virtual void gazebo::rendering::DepthCamera::PostRender ( )
virtual

Render the camera.

Reimplemented from gazebo::rendering::Camera.

virtual void gazebo::rendering::DepthCamera::SetDepthTarget ( Ogre::RenderTarget *  _target)
virtual

Set the render target, which renders the depth data.

Parameters
[in]_targetPointer to the render target

Member Data Documentation

Ogre::RenderTarget* gazebo::rendering::DepthCamera::depthTarget
protected

Pointer to the depth target.

Ogre::Texture* gazebo::rendering::DepthCamera::depthTexture
protected

Pointer to the depth texture.

Ogre::Viewport* gazebo::rendering::DepthCamera::depthViewport
protected

Pointer to the depth viewport.


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