DepthCamera.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef _GAZEBO_RENDERING_DEPTHCAMERA_HH_
19 #define _GAZEBO_RENDERING_DEPTHCAMERA_HH_
20 
21 #include <memory>
22 #include <string>
23 
24 #include <sdf/sdf.hh>
25 
27 
29 #include "gazebo/util/system.hh"
30 
31 namespace Ogre
32 {
33  class Material;
34  class RenderTarget;
35  class Texture;
36  class Viewport;
37 }
38 
39 namespace gazebo
40 {
41  namespace rendering
42  {
43  // Forward declare private data.
44  class DepthCameraPrivate;
45 
48 
51  class GZ_RENDERING_VISIBLE DepthCamera : public Camera
52  {
57  public: DepthCamera(const std::string &_namePrefix,
58  ScenePtr _scene, bool _autoRender = true);
59 
61  public: virtual ~DepthCamera();
62 
65  public: void Load(sdf::ElementPtr _sdf);
66 
68  public: void Load();
69 
71  public: void Init();
72 
74  public: void Fini();
75 
78  public: void CreateDepthTexture(const std::string &_textureName);
79 
82  public: void CreateReflectanceTexture(const std::string &_textureName);
83 
86  public: void CreateNormalsTexture(const std::string &_normalsName);
87 
89  public: virtual void PostRender();
90 
93  public: virtual const float *DepthData() const;
94 
97  public: virtual void SetDepthTarget(Ogre::RenderTarget *_target);
98 
103  std::function<void (const float *, unsigned int, unsigned int,
104  unsigned int, const std::string &)> _subscriber);
105 
110  std::function<void (const float *, unsigned int, unsigned int,
111  unsigned int, const std::string &)> _subscriber);
112 
117  std::function<void (const float *, unsigned int, unsigned int,
118  unsigned int, const std::string &)> _subscriber);
119 
127  std::function<void (const float *, unsigned int, unsigned int,
128  unsigned int, const std::string &)> _subscriber);
129 
131  private: virtual void RenderImpl();
132 
137  private: void UpdateRenderTarget(Ogre::RenderTarget *_target,
138  Ogre::Material *_material,
139  const std::string &_matName);
140 
142  protected: Ogre::Texture *depthTexture;
143 
145  protected: Ogre::RenderTarget *depthTarget = nullptr;
146 
148  protected: Ogre::Viewport *depthViewport;
149 
152  private: std::unique_ptr<DepthCameraPrivate> dataPtr;
153  };
155  }
156 }
157 #endif
virtual void SetDepthTarget(Ogre::RenderTarget *_target)
Set the render target, which renders the depth data.
Definition: JointMaker.hh:40
Forward declarations for the common classes.
Definition: Animation.hh:27
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.
void CreateDepthTexture(const std::string &_textureName)
Create a texture which will hold the depth data.
void Load()
Load the camera with default parmeters.
Ogre::Texture * depthTexture
Pointer to the depth texture.
Definition: DepthCamera.hh:142
Depth camera used to render depth data into an image buffer.
Definition: DepthCamera.hh:52
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:82
rendering
Definition: RenderEngine.hh:31
Ogre::RenderTarget * depthTarget
Pointer to the depth target.
Definition: DepthCamera.hh:145
virtual void PostRender()
Render the camera.
virtual const float * DepthData() const
All things needed to get back z buffer for depth data.
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
event::ConnectionPtr ConnectNewReflectanceFrame(std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
Connect a to the new reflectance data.
void Fini()
Finalize the camera.
void CreateNormalsTexture(const std::string &_normalsName)
Create a texture which will hold the normal data.
DepthCamera(const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
Constructor.
Ogre::Viewport * depthViewport
Pointer to the depth viewport.
Definition: DepthCamera.hh:148
void Load(sdf::ElementPtr _sdf)
Load the camera with a set of parmeters.
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.
Basic camera sensor.
Definition: Camera.hh:86
event::ConnectionPtr ConnectNewNormalsPointCloud(std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
Connect to the new normal data Normals are stored in a vector4f, XYZ contains the normal for this spe...
void Init()
Initialize the camera.
virtual ~DepthCamera()
Destructor.
void CreateReflectanceTexture(const std::string &_textureName)
Create a texture which will hold the reflectance data.