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 (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 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 #include <sdf/sdf.hh>
32 
33 #include "gazebo/common/Event.hh"
34 #include "gazebo/common/PID.hh"
35 #include "gazebo/common/Time.hh"
36 
37 #include "gazebo/math/Angle.hh"
38 #include "gazebo/math/Pose.hh"
39 #include "gazebo/math/Plane.hh"
40 #include "gazebo/math/Vector2i.hh"
41 
42 #include "gazebo/msgs/MessageTypes.hh"
44 
45 // Forward Declarations
46 namespace Ogre
47 {
48  class Texture;
49  class RenderTarget;
50  class Camera;
51  class Viewport;
52  class SceneNode;
53  class AnimationState;
54  class CompositorInstance;
55 }
56 
57 namespace gazebo
58 {
61  namespace rendering
62  {
63  class MouseEvent;
64  class ViewController;
65  class Scene;
66  class GaussianNoiseCompositorListener;
67 
71 
76  class Camera : public boost::enable_shared_from_this<Camera>
77  {
82  public: Camera(const std::string &_namePrefix, ScenePtr _scene,
83  bool _autoRender = true);
84 
86  public: virtual ~Camera();
87 
90  public: virtual void Load(sdf::ElementPtr _sdf);
91 
93  public: virtual void Load();
94 
96  public: virtual void Init();
97 
100  public: void SetRenderRate(double _hz);
101 
104  public: double GetRenderRate() const;
105 
109  // \todo Deprecated in Gazebo 2.1. In Gazebo 3.0 remove this function,
110  // and change Render(bool _force) to have a default value of false.
111  public: void Render();
112 
116  public: virtual void PostRender();
117 
123  public: virtual void Update();
124 
128  public: virtual void Fini();
129 
132  public: bool GetInitialized() const;
133 
137  public: void SetWindowId(unsigned int _windowId);
138 
141  public: unsigned int GetWindowId() const;
142 
145  public: void SetScene(ScenePtr _scene);
146 
149  public: math::Pose GetWorldPose();
150 
153  public: math::Vector3 GetWorldPosition() const;
154 
157  public: math::Quaternion GetWorldRotation() const;
158 
161  public: virtual void SetWorldPose(const math::Pose &_pose);
162 
165  public: void SetWorldPosition(const math::Vector3 &_pos);
166 
169  public: void SetWorldRotation(const math::Quaternion &_quat);
170 
173  public: void Translate(const math::Vector3 &_direction);
174 
177  public: void RotateYaw(math::Angle _angle);
178 
181  public: void RotatePitch(math::Angle _angle);
182 
186  public: void SetClipDist(float _near, float _far);
187 
190  public: void SetHFOV(math::Angle _angle);
191 
194  public: math::Angle GetHFOV() const;
195 
198  public: math::Angle GetVFOV() const;
199 
203  public: void SetImageSize(unsigned int _w, unsigned int _h);
204 
207  public: void SetImageWidth(unsigned int _w);
208 
211  public: void SetImageHeight(unsigned int _h);
212 
215  public: virtual unsigned int GetImageWidth() const;
216 
219  public: unsigned int GetTextureWidth() const;
220 
223  public: virtual unsigned int GetImageHeight() const;
224 
227  public: unsigned int GetImageDepth() const;
228 
231  public: std::string GetImageFormat() const;
232 
235  public: unsigned int GetTextureHeight() const;
236 
239  public: size_t GetImageByteSize() const;
240 
246  public: static size_t GetImageByteSize(unsigned int _width,
247  unsigned int _height,
248  const std::string &_format);
249 
255  public: double GetZValue(int _x, int _y);
256 
259  public: double GetNearClip();
260 
263  public: double GetFarClip();
264 
267  public: void EnableSaveFrame(bool _enable);
268 
271  public: bool GetCaptureData() const;
272 
275  public: void SetSaveFramePathname(const std::string &_pathname);
276 
280  public: bool SaveFrame(const std::string &_filename);
281 
284  public: Ogre::Camera *GetOgreCamera() const;
285 
288  public: Ogre::Viewport *GetViewport() const;
289 
292  public: unsigned int GetViewportWidth() const;
293 
296  public: unsigned int GetViewportHeight() const;
297 
300  public: math::Vector3 GetUp();
301 
304  public: math::Vector3 GetRight();
305 
308  public: virtual float GetAvgFPS() {return 0;}
309 
312  public: virtual unsigned int GetTriangleCount() {return 0;}
313 
316  public: void SetAspectRatio(float _ratio);
317 
320  public: float GetAspectRatio() const;
321 
324  public: void SetSceneNode(Ogre::SceneNode *_node);
325 
328  public: Ogre::SceneNode *GetSceneNode() const;
329 
332  public: Ogre::SceneNode *GetPitchNode() const;
333 
339  public: virtual const unsigned char *GetImageData(unsigned int i = 0);
340 
343  public: std::string GetName() const;
344 
347  public: void SetName(const std::string &_name);
348 
350  public: void ToggleShowWireframe();
351 
354  public: void ShowWireframe(bool _s);
355 
363  public: void GetCameraToViewportRay(int _screenx, int _screeny,
364  math::Vector3 &_origin,
365  math::Vector3 &_dir);
366 
369  public: void SetCaptureData(bool _value);
370 
372  public: void SetCaptureDataOnce();
373 
376  public: void CreateRenderTexture(const std::string &_textureName);
377 
380  public: ScenePtr GetScene() const;
381 
388  public: bool GetWorldPointOnPlane(int _x, int _y,
389  const math::Plane &_plane, math::Vector3 &_result);
390 
393  public: virtual void SetRenderTarget(Ogre::RenderTarget *_target);
394 
403  public: void AttachToVisual(const std::string &_visualName,
404  bool _inheritOrientation,
405  double _minDist = 0.0, double _maxDist = 0.0);
406 
415  public: void AttachToVisual(uint32_t _id,
416  bool _inheritOrientation,
417  double _minDist = 0.0, double _maxDist = 0.0);
418 
421  public: void TrackVisual(const std::string &_visualName);
422 
425  public: Ogre::Texture *GetRenderTexture() const;
426 
429  public: math::Vector3 GetDirection() const;
430 
435  public: template<typename T>
437  {return newImageFrame.Connect(_subscriber);}
438 
443 
452  public: static bool SaveFrame(const unsigned char *_image,
453  unsigned int _width, unsigned int _height, int _depth,
454  const std::string &_format,
455  const std::string &_filename);
456 
457 
461 
466  public: bool IsVisible(VisualPtr _visual);
467 
472  public: bool IsVisible(const std::string &_visualName);
473 
475  public: bool IsAnimating() const;
476 
481  public: virtual bool MoveToPosition(const math::Pose &_pose,
482  double _time);
483 
491  public: bool MoveToPositions(const std::vector<math::Pose> &_pts,
492  double _time,
493  boost::function<void()> _onComplete = NULL);
494 
497  public: std::string GetScreenshotPath() const;
498 
500  protected: virtual void RenderImpl();
501 
503  protected: void ReadPixelBuffer();
504 
508  protected: bool TrackVisualImpl(const std::string &_visualName);
509 
513  protected: virtual bool TrackVisualImpl(VisualPtr _visual);
514 
524  protected: virtual bool AttachToVisualImpl(const std::string &_name,
525  bool _inheritOrientation,
526  double _minDist = 0, double _maxDist = 0);
527 
537  protected: virtual bool AttachToVisualImpl(uint32_t _id,
538  bool _inheritOrientation,
539  double _minDist = 0, double _maxDist = 0);
540 
550  protected: virtual bool AttachToVisualImpl(VisualPtr _visual,
551  bool _inheritOrientation,
552  double _minDist = 0, double _maxDist = 0);
553 
556  protected: std::string GetFrameFilename();
557 
560  protected: virtual void AnimationComplete();
561 
569  private: void ConvertRGBToBAYER(unsigned char *_dst, unsigned char *_src,
570  std::string _format, int _width, int _height);
571 
573  private: void SetClipDist();
574 
578  private: static int GetOgrePixelFormat(const std::string &_format);
579 
580 
582  private: void CreateCamera();
583 
585  protected: std::string name;
586 
588  protected: sdf::ElementPtr sdf;
589 
591  protected: unsigned int windowId;
592 
594  protected: unsigned int textureWidth;
595 
597  protected: unsigned int textureHeight;
598 
600  protected: Ogre::Camera *camera;
601 
603  protected: Ogre::Viewport *viewport;
604 
606  protected: Ogre::SceneNode *sceneNode;
607 
609  protected: Ogre::SceneNode *pitchNode;
610 
611  // \brief Buffer for a single image frame.
612  protected: unsigned char *saveFrameBuffer;
613 
615  protected: unsigned char *bayerFrameBuffer;
616 
618  protected: unsigned int saveCount;
619 
621  protected: std::string screenshotPath;
622 
624  protected: int imageFormat;
625 
627  protected: int imageWidth;
628 
630  protected: int imageHeight;
631 
633  protected: Ogre::RenderTarget *renderTarget;
634 
636  protected: Ogre::Texture *renderTexture;
637 
639  protected: bool captureData;
640 
642  protected: bool captureDataOnce;
643 
645  protected: bool newData;
646 
649 
651  protected: ScenePtr scene;
652 
654  protected: event::EventT<void(const unsigned char *,
655  unsigned int, unsigned int, unsigned int,
656  const std::string &)> newImageFrame;
657 
659  protected: std::vector<event::ConnectionPtr> connections;
660 
662  protected: std::list<msgs::Request> requests;
663 
665  protected: bool initialized;
666 
668  protected: Ogre::AnimationState *animState;
669 
672 
674  protected: boost::function<void()> onAnimationComplete;
675 
677  private: sdf::ElementPtr imageElem;
678 
680  private: VisualPtr trackedVisual;
681 
683  private: static unsigned int cameraCounter;
684 
686  private: Ogre::CompositorInstance *dsGBufferInstance;
687 
689  private: Ogre::CompositorInstance *dsMergeInstance;
690 
692  private: Ogre::CompositorInstance *dlGBufferInstance;
693 
695  private: Ogre::CompositorInstance *dlMergeInstance;
696 
698  private: Ogre::CompositorInstance *ssaoInstance;
699 
701  private: Ogre::CompositorInstance *gaussianNoiseInstance;
702 
704  private: boost::shared_ptr<GaussianNoiseCompositorListener>
705  gaussianNoiseCompositorListener;
706 
708  private: std::deque<std::pair<math::Pose, double> > moveToPositionQueue;
709 
711  private: common::Time renderPeriod;
712 
714  private: common::PID trackVisualPID;
715 
717  private: common::PID trackVisualPitchPID;
718 
720  private: common::PID trackVisualYawPID;
721 
723  private: enum NoiseModelType
724  {
725  NONE,
726  GAUSSIAN
727  };
728 
731  private: bool noiseActive;
732 
734  private: enum NoiseModelType noiseType;
735 
738  private: double noiseMean;
739 
742  private: double noiseStdDev;
743 
744  // \todo Move this back up to public section in Gazebo 3.0. It is here
745  // for ABI compatibility.
751  public: void Render(bool _force);
752  };
754  }
755 }
756 #endif