DepthCamera.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 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 /* Desc: A persepective OGRE Camera with Depth Sensor
18  * Author: Nate Koenig
19  * Date: 15 July 2003
20  */
21 
22 #ifndef _RENDERING_DEPTHCAMERA_HH_
23 #define _RENDERING_DEPTHCAMERA_HH_
24 #include <string>
25 
26 #include <sdf/sdf.hh>
27 
28 #include "gazebo/common/Event.hh"
29 #include "gazebo/common/Time.hh"
30 
31 #include "gazebo/math/Angle.hh"
32 #include "gazebo/math/Pose.hh"
33 #include "gazebo/math/Vector2i.hh"
34 
36 #include "gazebo/util/system.hh"
37 
38 namespace Ogre
39 {
40  class Material;
41  class RenderTarget;
42  class Texture;
43  class Viewport;
44 }
45 
46 namespace gazebo
47 {
48  namespace rendering
49  {
50  class Scene;
51 
54 
58  {
63  public: DepthCamera(const std::string &_namePrefix,
64  ScenePtr _scene, bool _autoRender = true);
65 
67  public: virtual ~DepthCamera();
68 
71  public: void Load(sdf::ElementPtr _sdf);
72 
74  public: void Load();
75 
77  public: void Init();
78 
80  public: void Fini();
81 
84  public: void CreateDepthTexture(const std::string &_textureName);
85 
87  public: virtual void PostRender();
88 
91  public: virtual const float *GetDepthData();
92 
95  public: virtual void SetDepthTarget(Ogre::RenderTarget *_target);
96 
100  public: template<typename T>
102  { return newDepthFrame.Connect(_subscriber); }
103 
107  { newDepthFrame.Disconnect(_c); }
108 
112  public: template<typename T>
114  { return newRGBPointCloud.Connect(_subscriber); }
115 
119  { newRGBPointCloud.Disconnect(c); }
120 
121 
123  private: virtual void RenderImpl();
124 
129  private: void UpdateRenderTarget(Ogre::RenderTarget *_target,
130  Ogre::Material *_material,
131  const std::string &_matName);
132 
134  protected: Ogre::Texture *depthTexture;
135 
137  protected: Ogre::RenderTarget *depthTarget;
138 
140  protected: Ogre::Viewport *depthViewport;
141 
143  private: float *depthBuffer;
144 
146  private: Ogre::Material *depthMaterial;
147 
149  private: bool outputPoints;
150 
152  private: float *pcdBuffer;
153 
155  private: Ogre::Viewport *pcdViewport;
156 
158  private: Ogre::Material *pcdMaterial;
159 
161  private: Ogre::Texture *pcdTexture;
162 
164  private: Ogre::RenderTarget *pcdTarget;
165 
167  private: event::EventT<void(const float *, unsigned int, unsigned int,
168  unsigned int, const std::string &)> newRGBPointCloud;
169 
171  private: event::EventT<void(const float *, unsigned int, unsigned int,
172  unsigned int, const std::string &)> newDepthFrame;
173  };
175  }
176 }
177 #endif
Basic camera sensor.
Definition: Camera.hh:78
event::ConnectionPtr ConnectNewDepthFrame(T _subscriber)
Connect a to the new depth image signal.
Definition: DepthCamera.hh:101
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:147
void DisconnectNewRGBPointCloud(event::ConnectionPtr &c)
Disconnect from an rgb point cloud singal.
Definition: DepthCamera.hh:118
event::ConnectionPtr ConnectNewRGBPointCloud(T _subscriber)
Connect a to the new rgb point cloud signal.
Definition: DepthCamera.hh:113
Ogre::Texture * depthTexture
Pointer to the depth texture.
Definition: DepthCamera.hh:134
#define GZ_RENDERING_VISIBLE
Definition: system.hh:241
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:79
void DisconnectNewDepthFrame(event::ConnectionPtr &_c)
Disconnect from an depth image singal.
Definition: DepthCamera.hh:106
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
A class for event processing.
Definition: Event.hh:178
Ogre::Viewport * depthViewport
Pointer to the depth viewport.
Definition: DepthCamera.hh:140
Ogre::RenderTarget * depthTarget
Pointer to the depth target.
Definition: DepthCamera.hh:137
Depth camera used to render depth data into an image buffer.
Definition: DepthCamera.hh:57