All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Camera.hh
Go to the documentation of this file.
1 /*
2  * Copyright 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 /* Desc: A persepective OGRE Camera
18  * Author: Nate Koenig
19  * Date: 15 July 2003
20  */
21 
22 #ifndef _RENDERING_CAMERA_HH_
23 #define _RENDERING_CAMERA_HH_
24 
25 #include <boost/enable_shared_from_this.hpp>
26 #include <string>
27 #include <utility>
28 #include <list>
29 #include <vector>
30 #include <deque>
31 
32 #include "common/Event.hh"
33 #include "common/Time.hh"
34 
35 #include "math/Angle.hh"
36 #include "math/Pose.hh"
37 #include "math/Plane.hh"
38 #include "math/Vector2i.hh"
39 
40 #include "msgs/MessageTypes.hh"
41 #include "rendering/RenderTypes.hh"
42 #include "sdf/sdf.hh"
43 
44 // Forward Declarations
45 namespace Ogre
46 {
47  class Texture;
48  class RenderTarget;
49  class Camera;
50  class Viewport;
51  class SceneNode;
52  class AnimationState;
53  class CompositorInstance;
54 }
55 
56 namespace gazebo
57 {
60  namespace rendering
61  {
62  class MouseEvent;
63  class ViewController;
64  class Scene;
65  class GaussianNoiseCompositorListener;
66 
70 
75  class Camera : public boost::enable_shared_from_this<Camera>
76  {
81  public: Camera(const std::string &_namePrefix, ScenePtr _scene,
82  bool _autoRender = true);
83 
85  public: virtual ~Camera();
86 
89  public: virtual void Load(sdf::ElementPtr _sdf);
90 
92  public: virtual void Load();
93 
95  public: virtual void Init();
96 
99  public: void SetRenderRate(double _hz);
100 
103  public: double GetRenderRate() const;
104 
109  public: void Render();
110 
114  public: virtual void PostRender();
115 
121  public: virtual void Update();
122 
126  public: virtual void Fini();
127 
130  public: inline bool IsInitialized() const GAZEBO_DEPRECATED(1.5);
131 
134  public: bool GetInitialized() const;
135 
139  public: void SetWindowId(unsigned int _windowId);
140 
143  public: unsigned int GetWindowId() const;
144 
147  public: void SetScene(ScenePtr _scene);
148 
151  public: math::Pose GetWorldPose();
152 
155  public: math::Vector3 GetWorldPosition() const;
156 
159  public: math::Quaternion GetWorldRotation() const;
160 
163  public: virtual void SetWorldPose(const math::Pose &_pose);
164 
167  public: void SetWorldPosition(const math::Vector3 &_pos);
168 
171  public: void SetWorldRotation(const math::Quaternion &_quat);
172 
175  public: void Translate(const math::Vector3 &_direction);
176 
179  public: void RotateYaw(math::Angle _angle);
180 
183  public: void RotatePitch(math::Angle _angle);
184 
188  public: void SetClipDist(float _near, float _far);
189 
192  public: void SetHFOV(math::Angle _angle);
193 
196  public: math::Angle GetHFOV() const;
197 
200  public: math::Angle GetVFOV() const;
201 
205  public: void SetImageSize(unsigned int _w, unsigned int _h);
206 
209  public: void SetImageWidth(unsigned int _w);
210 
213  public: void SetImageHeight(unsigned int _h);
214 
217  public: virtual unsigned int GetImageWidth() const;
218 
221  public: unsigned int GetTextureWidth() const;
222 
225  public: virtual unsigned int GetImageHeight() const;
226 
229  public: unsigned int GetImageDepth() const;
230 
233  public: std::string GetImageFormat() const;
234 
237  public: unsigned int GetTextureHeight() const;
238 
241  public: size_t GetImageByteSize() const;
242 
248  public: static size_t GetImageByteSize(unsigned int _width,
249  unsigned int _height,
250  const std::string &_format);
251 
257  public: double GetZValue(int _x, int _y);
258 
261  public: double GetNearClip();
262 
265  public: double GetFarClip();
266 
269  public: void EnableSaveFrame(bool _enable);
270 
273  public: void SetSaveFramePathname(const std::string &_pathname);
274 
278  public: bool SaveFrame(const std::string &_filename);
279 
282  public: Ogre::Camera *GetOgreCamera() const;
283 
286  public: Ogre::Viewport *GetViewport() const;
287 
290  public: unsigned int GetViewportWidth() const;
291 
294  public: unsigned int GetViewportHeight() const;
295 
298  public: math::Vector3 GetUp();
299 
302  public: math::Vector3 GetRight();
303 
306  public: virtual float GetAvgFPS() {return 0;}
307 
310  public: virtual unsigned int GetTriangleCount() {return 0;}
311 
314  public: void SetAspectRatio(float _ratio);
315 
318  public: float GetAspectRatio() const;
319 
322  public: void SetSceneNode(Ogre::SceneNode *_node);
323 
326  public: Ogre::SceneNode *GetSceneNode() const;
327 
330  public: Ogre::SceneNode *GetPitchNode() const;
331 
337  public: virtual const unsigned char *GetImageData(unsigned int i = 0);
338 
341  public: std::string GetName() const;
342 
345  public: void SetName(const std::string &_name);
346 
348  public: void ToggleShowWireframe();
349 
352  public: void ShowWireframe(bool _s);
353 
361  public: void GetCameraToViewportRay(int _screenx, int _screeny,
362  math::Vector3 &_origin,
363  math::Vector3 &_dir);
364 
367  public: void SetCaptureData(bool _value);
368 
370  public: void SetCaptureDataOnce();
371 
374  public: void CreateRenderTexture(const std::string &_textureName);
375 
378  public: ScenePtr GetScene() const;
379 
386  public: bool GetWorldPointOnPlane(int _x, int _y,
387  const math::Plane &_plane, math::Vector3 &_result);
388 
391  public: virtual void SetRenderTarget(Ogre::RenderTarget *_target);
392 
401  public: void AttachToVisual(const std::string &_visualName,
402  bool _inheritOrientation,
403  double _minDist = 0.0, double _maxDist = 0.0);
404 
407  public: void TrackVisual(const std::string &_visualName);
408 
411  public: Ogre::Texture *GetRenderTexture() const;
412 
415  public: math::Vector3 GetDirection() const;
416 
421  public: template<typename T>
423  {return newImageFrame.Connect(_subscriber);}
424 
429 
438  public: static bool SaveFrame(const unsigned char *_image,
439  unsigned int _width, unsigned int _height, int _depth,
440  const std::string &_format,
441  const std::string &_filename);
442 
443 
447 
452  public: bool IsVisible(VisualPtr _visual);
453 
458  public: bool IsVisible(const std::string &_visualName);
459 
461  public: bool IsAnimating() const;
462 
467  public: virtual bool MoveToPosition(const math::Pose &_pose,
468  double _time);
469 
477  public: bool MoveToPositions(const std::vector<math::Pose> &_pts,
478  double _time,
479  boost::function<void()> _onComplete = NULL);
480 
483  public: std::string GetScreenshotPath() const;
484 
486  protected: virtual void RenderImpl();
487 
491  protected: bool TrackVisualImpl(const std::string &_visualName);
492 
496  protected: virtual bool TrackVisualImpl(VisualPtr _visual);
497 
507  protected: virtual bool AttachToVisualImpl(const std::string &_name,
508  bool _inheritOrientation,
509  double _minDist = 0, double _maxDist = 0);
510 
520  protected: virtual bool AttachToVisualImpl(VisualPtr _visual,
521  bool _inheritOrientation,
522  double _minDist = 0, double _maxDist = 0);
523 
526  protected: std::string GetFrameFilename();
527 
530  protected: virtual void AnimationComplete();
531 
539  private: void ConvertRGBToBAYER(unsigned char *_dst, unsigned char *_src,
540  std::string _format, int _width, int _height);
541 
543  private: void SetClipDist();
544 
548  private: static int GetOgrePixelFormat(const std::string &_format);
549 
550 
552  private: void CreateCamera();
553 
555  protected: std::string name;
556 
558  protected: sdf::ElementPtr sdf;
559 
561  protected: unsigned int windowId;
562 
564  protected: unsigned int textureWidth;
565 
567  protected: unsigned int textureHeight;
568 
570  protected: Ogre::Camera *camera;
571 
573  protected: Ogre::Viewport *viewport;
574 
576  protected: Ogre::SceneNode *sceneNode;
577 
579  protected: Ogre::SceneNode *pitchNode;
580 
581  // \brief Buffer for a single image frame.
582  protected: unsigned char *saveFrameBuffer;
583 
585  protected: unsigned char *bayerFrameBuffer;
586 
588  protected: unsigned int saveCount;
589 
591  protected: std::string screenshotPath;
592 
594  protected: int imageFormat;
595 
597  protected: int imageWidth;
598 
600  protected: int imageHeight;
601 
603  protected: Ogre::RenderTarget *renderTarget;
604 
606  protected: Ogre::Texture *renderTexture;
607 
609  protected: bool captureData;
610 
612  protected: bool captureDataOnce;
613 
615  protected: bool newData;
616 
619 
621  protected: ScenePtr scene;
622 
624  protected: event::EventT<void(const unsigned char *,
625  unsigned int, unsigned int, unsigned int,
626  const std::string &)> newImageFrame;
627 
629  protected: std::vector<event::ConnectionPtr> connections;
630 
632  protected: std::list<msgs::Request> requests;
633 
635  protected: bool initialized;
636 
638  protected: Ogre::AnimationState *animState;
639 
642 
644  protected: boost::function<void()> onAnimationComplete;
645 
647  private: sdf::ElementPtr imageElem;
648 
650  private: VisualPtr trackedVisual;
651 
653  private: static unsigned int cameraCounter;
654 
656  private: Ogre::CompositorInstance *dsGBufferInstance;
657 
659  private: Ogre::CompositorInstance *dsMergeInstance;
660 
662  private: Ogre::CompositorInstance *dlGBufferInstance;
663 
665  private: Ogre::CompositorInstance *dlMergeInstance;
666 
668  private: Ogre::CompositorInstance *ssaoInstance;
669 
671  private: Ogre::CompositorInstance *gaussianNoiseInstance;
672 
674  private: boost::shared_ptr<GaussianNoiseCompositorListener>
675  gaussianNoiseCompositorListener;
676 
678  private: std::deque<std::pair<math::Pose, double> > moveToPositionQueue;
679 
681  private: common::Time renderPeriod;
682 
684  private: enum NoiseModelType
685  {
686  NONE,
687  GAUSSIAN
688  };
689 
692  private: bool noiseActive;
693 
695  private: enum NoiseModelType noiseType;
696 
699  private: double noiseMean;
700 
703  private: double noiseStdDev;
704  };
706  }
707 }
708 #endif