Gazebo Rendering

API Reference

7.4.2

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

#include <rendering/ogre/OgreDepthCamera.hh>

Public Member Functions

virtual ~OgreDepthCamera ()
 Destructor. More...
 
virtual Ogre::Camera * Camera () const override
 Access the Ogre::Camera object. More...
 
virtual gz::common::ConnectionPtr ConnectNewDepthFrame (std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber) override
 Connect a to the new depth image signal. More...
 
virtual gz::common::ConnectionPtr ConnectNewRgbPointCloud (std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber) override
 Connect a to the new rgb point cloud signal. More...
 
virtual void CreateDepthTexture () override
 Create a texture which will hold the depth data. More...
 
virtual const float * DepthData () const override
 All things needed to get back z buffer for depth data. More...
 
virtual void Destroy () override
 
double FarClipPlane () const override
 Get the far clip distance. More...
 
virtual void Init () override
 Initialize the camera. More...
 
double NearClipPlane () const override
 Get the near clip distance. More...
 
virtual void PostRender () override
 Render the camera. More...
 
virtual void PreRender () override
 
virtual void Render () override
 Implementation of the render call. More...
 
virtual void SetFarClipPlane (const double _far) override
 Set the far clip distance. More...
 
virtual void SetNearClipPlane (const double _near) override
 Set the near clip distance. More...
 
- Public Member Functions inherited from BaseDepthCamera< OgreSensor >
virtual ~BaseDepthCamera ()
 
virtual gz::common::ConnectionPtr ConnectNewRGBPointCloud (std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
 
virtual const float * DepthData () const
 
- Public Member Functions inherited from OgreObjectInterface
virtual ~OgreObjectInterface ()
 
virtual Ogre::MovableObject * OgreMovableObject (const char *_typename) const
 Access to an Ogre::MovableObject. More...
 

Protected Member Functions

 OgreDepthCamera ()
 Constructor. More...
 
void CreateCamera ()
 Create the camera. More...
 
void DestroyDepthTexture ()
 Destroy render texture created by CreateDepthTexture() Note: It's not virtual. More...
 
void DestroyPointCloudTexture ()
 Destroy render texture created by CreatePointCloudTexture() Note: It's not virtual. More...
 
virtual RenderTargetPtr RenderTarget () const override
 Get a pointer to the render target. More...
 
void UpdateRenderTarget (OgreRenderTexturePtr _target, Ogre::Material *_material, const std::string &_matName)
 Update a render target. More...
 
- Protected Member Functions inherited from BaseDepthCamera< OgreSensor >
 BaseDepthCamera ()
 

Static Protected Member Functions

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

Protected Attributes

bool captureData = false
 
OgreRenderTexturePtr depthTexture
 Pointer to the depth texture. More...
 
Ogre::Viewport * depthViewport = nullptr
 Pointer to the depth viewport. More...
 
bool newData = false
 Communicates that a frams was rendered. More...
 
Ogre::Camera * ogreCamera
 Pointer to the ogre camera. More...
 

Detailed Description

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

Constructor & Destructor Documentation

◆ OgreDepthCamera()

OgreDepthCamera ( )
protected

Constructor.

◆ ~OgreDepthCamera()

virtual ~OgreDepthCamera ( )
virtual

Destructor.

Member Function Documentation

◆ Camera()

virtual Ogre::Camera* Camera ( ) const
overridevirtual

Access the Ogre::Camera object.

Returns
A pointer to an Ogre::Camera. Has default nullptr.

Implements OgreObjectInterface.

◆ ConnectNewDepthFrame()

virtual gz::common::ConnectionPtr ConnectNewDepthFrame ( std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)
overridevirtual

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

Reimplemented from BaseDepthCamera< OgreSensor >.

◆ ConnectNewRgbPointCloud()

virtual gz::common::ConnectionPtr ConnectNewRgbPointCloud ( std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)
overridevirtual

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

◆ CreateCamera()

void CreateCamera ( )
protected

Create the camera.

◆ CreateDepthTexture()

virtual void CreateDepthTexture ( )
overridevirtual

Create a texture which will hold the depth data.

Reimplemented from BaseDepthCamera< OgreSensor >.

◆ DepthData()

virtual const float* DepthData ( ) const
overridevirtual

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

Returns
The z-buffer as a float array

◆ Destroy()

virtual void Destroy ( )
overridevirtual

◆ DestroyDepthTexture()

void DestroyDepthTexture ( )
protected

Destroy render texture created by CreateDepthTexture() Note: It's not virtual.

◆ DestroyPointCloudTexture()

void DestroyPointCloudTexture ( )
protected

Destroy render texture created by CreatePointCloudTexture() Note: It's not virtual.

◆ FarClipPlane()

double FarClipPlane ( ) const
override

Get the far clip distance.

Returns
Far clip distance. A value of zero is returned if the ogre camera has not been created.

◆ Init()

virtual void Init ( )
overridevirtual

Initialize the camera.

◆ LimitFOV()

static double LimitFOV ( const double  _fov)
staticprotected

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

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

◆ NearClipPlane()

double NearClipPlane ( ) const
override

Get the near clip distance.

Returns
Near clip distance. A value of zero is returned if the ogre camera has not been created.

◆ PostRender()

virtual void PostRender ( )
overridevirtual

Render the camera.

◆ PreRender()

virtual void PreRender ( )
overridevirtual

◆ Render()

virtual void Render ( )
overridevirtual

Implementation of the render call.

◆ RenderTarget()

virtual RenderTargetPtr RenderTarget ( ) const
overrideprotectedvirtual

Get a pointer to the render target.

Returns
Pointer to the render target

◆ SetFarClipPlane()

virtual void SetFarClipPlane ( const double  _far)
overridevirtual

Set the far clip distance.

Parameters
[in]_farfar clip distance

◆ SetNearClipPlane()

virtual void SetNearClipPlane ( const double  _near)
overridevirtual

Set the near clip distance.

Parameters
[in]_nearNear clip distance

◆ UpdateRenderTarget()

void UpdateRenderTarget ( OgreRenderTexturePtr  _target,
Ogre::Material *  _material,
const std::string _matName 
)
protected

Update a render target.

Parameters
[in]_targetRender target to update
[in]_materialMaterial to use
[in]_matNameMaterial name

Member Data Documentation

◆ captureData

bool captureData = false
protected

◆ depthTexture

OgreRenderTexturePtr depthTexture
protected

Pointer to the depth texture.

◆ depthViewport

Ogre::Viewport* depthViewport = nullptr
protected

Pointer to the depth viewport.

◆ newData

bool newData = false
protected

Communicates that a frams was rendered.

◆ ogreCamera

Ogre::Camera* ogreCamera
protected

Pointer to the ogre camera.


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