18#ifndef _GAZEBO_RENDERING_DEPTHCAMERA_HH_
19#define _GAZEBO_RENDERING_DEPTHCAMERA_HH_
44 class DepthCameraPrivate;
58 ScenePtr _scene,
bool _autoRender =
true);
65 public:
void Load(sdf::ElementPtr _sdf);
95 std::function<
void (
const float *,
unsigned int,
unsigned int,
96 unsigned int,
const std::string &)> _subscriber);
102 std::function<
void (
const float *,
unsigned int,
unsigned int,
103 unsigned int,
const std::string &)> _subscriber);
106 private:
virtual void RenderImpl();
112 private:
void UpdateRenderTarget(Ogre::RenderTarget *_target,
113 Ogre::Material *_material,
114 const std::string &_matName);
127 private: std::unique_ptr<DepthCameraPrivate> dataPtr;
rendering
Definition RenderEngine.hh:31
Basic camera sensor.
Definition Camera.hh:86
Depth camera used to render depth data into an image buffer.
Definition DepthCamera.hh:52
void Fini()
Finalize the camera.
DepthCamera(const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
Constructor.
event::ConnectionPtr ConnectNewRGBPointCloud(std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
Connect a to the new rgb point cloud signal.
virtual ~DepthCamera()
Destructor.
event::ConnectionPtr ConnectNewDepthFrame(std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
Connect a to the new depth image signal.
void Init()
Initialize the camera.
void CreateDepthTexture(const std::string &_textureName)
Create a texture which will hold the depth data.
Ogre::RenderTarget * depthTarget
Pointer to the depth target.
Definition DepthCamera.hh:120
virtual const float * DepthData() const
All things needed to get back z buffer for depth data.
Ogre::Viewport * depthViewport
Pointer to the depth viewport.
Definition DepthCamera.hh:123
virtual void SetDepthTarget(Ogre::RenderTarget *_target)
Set the render target, which renders the depth data.
void Load(sdf::ElementPtr _sdf)
Load the camera with a set of parmeters.
void Load()
Load the camera with default parmeters.
virtual void PostRender()
Render the camera.
Ogre::Texture * depthTexture
Pointer to the depth texture.
Definition DepthCamera.hh:117
Definition JointMaker.hh:40
boost::shared_ptr< Connection > ConnectionPtr
Definition CommonTypes.hh:134
boost::shared_ptr< Scene > ScenePtr
Definition RenderTypes.hh:82
Forward declarations for the common classes.
Definition Animation.hh:27