All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
GpuLaser.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 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 laser sensor using OpenGL
18  * Author: Mihai Emanuel Dolha
19  * Date: 29 March 2012
20  */
21 
22 #ifndef _GPULASER_HH_
23 #define _GPULASER_HH_
24 
25 #include <string>
26 #include <vector>
27 
28 #include <sdf/sdf.hh>
29 
33 
34 #include "gazebo/common/Event.hh"
35 #include "gazebo/common/Time.hh"
36 
37 #include "gazebo/math/Angle.hh"
38 #include "gazebo/math/Pose.hh"
39 #include "gazebo/math/Vector2i.hh"
40 #include "gazebo/util/system.hh"
41 
42 namespace Ogre
43 {
44  class Material;
45  class Renderable;
46  class Pass;
47  class AutoParamDataSource;
48  class Matrix4;
49  class MovableObject;
50 }
51 
52 namespace gazebo
53 {
54  namespace common
55  {
56  class Mesh;
57  }
58 
59  namespace rendering
60  {
61  class Scene;
62 
65 
69  : public Camera, public Ogre::RenderObjectListener
70  {
75  public: GpuLaser(const std::string &_namePrefix,
76  ScenePtr _scene, bool _autoRender = true);
77 
79  public: virtual ~GpuLaser();
80 
81  // Documentation inherited
82  public: virtual void Load(sdf::ElementPtr _sdf);
83 
84  // Documentation inherited
85  public: virtual void Load();
86 
87  // Documentation inherited
88  public: virtual void Init();
89 
90  // Documentation inherited
91  public: virtual void Fini();
92 
95  public: void CreateLaserTexture(const std::string &_textureName);
96 
97  // Documentation inherited
98  public: virtual void PostRender();
99 
102  public: const float *GetLaserData();
103 
108  public: template<typename T>
110  { return newLaserFrame.Connect(_subscriber); }
111 
115  { newLaserFrame.Disconnect(_c); }
116 
120  public: void SetRangeCount(unsigned int _w, unsigned int _h = 1);
121 
124  public: virtual void notifyRenderSingleObject(Ogre::Renderable *_rend,
125  const Ogre::Pass *_p, const Ogre::AutoParamDataSource *_s,
126  const Ogre::LightList *_ll, bool _supp);
127 
130  public: double GetHorzHalfAngle() const;
131 
134  public: double GetVertHalfAngle() const;
135 
138  public: void SetHorzHalfAngle(double _angle);
139 
142  public: void SetVertHalfAngle(double _angle);
143 
146  public: void SetIsHorizontal(bool _horizontal);
147 
150  public: bool IsHorizontal() const;
151 
154  public: double GetHorzFOV() const;
155 
158  public: double GetCosHorzFOV() const;
159 
162  public: void SetCosHorzFOV(double _chfov);
163 
166  public: double GetVertFOV() const;
167 
170  public: double GetCosVertFOV() const;
171 
174  public: void SetCosVertFOV(double _cvfov);
175 
178  public: double GetNearClip() const;
179 
182  public: double GetFarClip() const;
183 
186  public: void SetNearClip(double _near);
187 
190  public: void SetFarClip(double _far);
191 
194  public: void SetHorzFOV(double _hfov);
195 
198  public: void SetVertFOV(double _vfov);
199 
202  public: double GetCameraCount() const;
203 
207  public: void SetCameraCount(double _cameraCount);
208 
211  public: double GetRayCountRatio() const;
212 
215  public: void SetRayCountRatio(double _rayCountRatio);
216 
217  // Documentation inherited.
218  private: virtual void RenderImpl();
219 
225  private: void UpdateRenderTarget(Ogre::RenderTarget *_target,
226  Ogre::Material *_material,
227  Ogre::Camera *_cam,
228  bool _updateTex = false);
229 
231  private: void CreateOrthoCam();
232 
234  private: void CreateMesh();
235 
237  private: void CreateCanvas();
238 
247  private: Ogre::Matrix4 BuildScaledOrthoMatrix(float _left, float _right,
248  float _bottom, float _top, float _near, float _far);
249 
253  private: virtual void Set1stPassTarget(Ogre::RenderTarget *_target,
254  unsigned int _index);
255 
258  private: virtual void Set2ndPassTarget(Ogre::RenderTarget *_target);
259 
261  protected: double horzHalfAngle;
262 
264  protected: double vertHalfAngle;
265 
267  protected: double rayCountRatio;
268 
270  protected: double hfov;
271 
273  protected: double vfov;
274 
276  protected: double chfov;
277 
279  protected: double cvfov;
280 
282  protected: double near;
283 
285  protected: double far;
286 
288  protected: bool isHorizontal;
289 
291  protected: unsigned int cameraCount;
292 
299  private: event::EventT<void(const float *_frame, unsigned int _width,
300  unsigned int _height, unsigned int _depth,
301  const std::string &_format)> newLaserFrame;
302 
304  private: float *laserBuffer;
305 
307  private: float *laserScan;
308 
310  private: Ogre::Material *matFirstPass;
311 
313  private: Ogre::Material *matSecondPass;
314 
316  private: Ogre::Texture *firstPassTextures[3];
317 
319  private: Ogre::Texture *secondPassTexture;
320 
322  private: Ogre::RenderTarget *firstPassTargets[3];
323 
325  private: Ogre::RenderTarget *secondPassTarget;
326 
328  private: Ogre::Viewport *firstPassViewports[3];
329 
331  private: Ogre::Viewport *secondPassViewport;
332 
334  private: unsigned int textureCount;
335 
337  private: double cameraYaws[4];
338 
340  private: Ogre::RenderTarget *currentTarget;
341 
343  private: Ogre::Material *currentMat;
344 
347  private: Ogre::Camera *orthoCam;
348 
350  private: Ogre::SceneNode *pitchNodeOrtho;
351 
354  private: common::Mesh *undistMesh;
355 
357  private: Ogre::MovableObject *object;
358 
360  private: VisualPtr visual;
361 
363  private: unsigned int w2nd;
364 
366  private: unsigned int h2nd;
367 
369  private: double lastRenderDuration;
370 
373  private: std::vector<int> texIdx;
374 
376  private: static int texCount;
377  };
379  }
380 }
381 #endif
A 3D mesh.
Definition: Mesh.hh:40
void DisconnectNewLaserFrame(event::ConnectionPtr &_c)
Disconnect from a laser frame signal.
Definition: GpuLaser.hh:114
Basic camera sensor.
Definition: Camera.hh:77
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:144
GPU based laser distance sensor.
Definition: GpuLaser.hh:68
double near
Near clip plane.
Definition: GpuLaser.hh:282
double rayCountRatio
Ray count ratio.
Definition: GpuLaser.hh:267
double far
Far clip plane.
Definition: GpuLaser.hh:285
double vertHalfAngle
Vertical half angle.
Definition: GpuLaser.hh:264
unsigned int cameraCount
Number of cameras needed to generate the rays.
Definition: GpuLaser.hh:291
double hfov
Horizontal field-of-view.
Definition: GpuLaser.hh:270
event::ConnectionPtr ConnectNewLaserFrame(T _subscriber)
Connect to a laser frame signal.
Definition: GpuLaser.hh:109
double horzHalfAngle
Horizontal half angle.
Definition: GpuLaser.hh:261
double cvfov
Cos vertical field-of-view.
Definition: GpuLaser.hh:279
double chfov
Cos horizontal field-of-view.
Definition: GpuLaser.hh:276
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:72
bool isHorizontal
True if the sensor is horizontal only.
Definition: GpuLaser.hh:288
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
A class for event processing.
Definition: Event.hh:156
boost::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:100
double vfov
Vertical field-of-view.
Definition: GpuLaser.hh:273
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48