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 #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 
110  public: void Render();
111 
115  public: virtual void PostRender();
116 
122  public: virtual void Update();
123 
127  public: virtual void Fini();
128 
131  public: bool GetInitialized() const;
132 
136  public: void SetWindowId(unsigned int _windowId);
137 
140  public: unsigned int GetWindowId() const;
141 
144  public: void SetScene(ScenePtr _scene);
145 
148  public: math::Pose GetWorldPose();
149 
152  public: math::Vector3 GetWorldPosition() const;
153 
156  public: math::Quaternion GetWorldRotation() const;
157 
160  public: virtual void SetWorldPose(const math::Pose &_pose);
161 
164  public: void SetWorldPosition(const math::Vector3 &_pos);
165 
168  public: void SetWorldRotation(const math::Quaternion &_quat);
169 
172  public: void Translate(const math::Vector3 &_direction);
173 
176  public: void RotateYaw(math::Angle _angle);
177 
180  public: void RotatePitch(math::Angle _angle);
181 
185  public: void SetClipDist(float _near, float _far);
186 
189  public: void SetHFOV(math::Angle _angle);
190 
193  public: math::Angle GetHFOV() const;
194 
197  public: math::Angle GetVFOV() const;
198 
202  public: void SetImageSize(unsigned int _w, unsigned int _h);
203 
206  public: void SetImageWidth(unsigned int _w);
207 
210  public: void SetImageHeight(unsigned int _h);
211 
214  public: virtual unsigned int GetImageWidth() const;
215 
218  public: unsigned int GetTextureWidth() const;
219 
222  public: virtual unsigned int GetImageHeight() const;
223 
226  public: unsigned int GetImageDepth() const;
227 
230  public: std::string GetImageFormat() const;
231 
234  public: unsigned int GetTextureHeight() const;
235 
238  public: size_t GetImageByteSize() const;
239 
245  public: static size_t GetImageByteSize(unsigned int _width,
246  unsigned int _height,
247  const std::string &_format);
248 
254  public: double GetZValue(int _x, int _y);
255 
258  public: double GetNearClip();
259 
262  public: double GetFarClip();
263 
266  public: void EnableSaveFrame(bool _enable);
267 
270  public: bool GetCaptureData() const;
271 
274  public: void SetSaveFramePathname(const std::string &_pathname);
275 
279  public: bool SaveFrame(const std::string &_filename);
280 
283  public: Ogre::Camera *GetOgreCamera() const;
284 
287  public: Ogre::Viewport *GetViewport() const;
288 
291  public: unsigned int GetViewportWidth() const;
292 
295  public: unsigned int GetViewportHeight() const;
296 
299  public: math::Vector3 GetUp();
300 
303  public: math::Vector3 GetRight();
304 
307  public: virtual float GetAvgFPS() {return 0;}
308 
311  public: virtual unsigned int GetTriangleCount() {return 0;}
312 
315  public: void SetAspectRatio(float _ratio);
316 
319  public: float GetAspectRatio() const;
320 
323  public: void SetSceneNode(Ogre::SceneNode *_node);
324 
327  public: Ogre::SceneNode *GetSceneNode() const;
328 
331  public: Ogre::SceneNode *GetPitchNode() const;
332 
338  public: virtual const unsigned char *GetImageData(unsigned int i = 0);
339 
342  public: std::string GetName() const;
343 
346  public: void SetName(const std::string &_name);
347 
349  public: void ToggleShowWireframe();
350 
353  public: void ShowWireframe(bool _s);
354 
362  public: void GetCameraToViewportRay(int _screenx, int _screeny,
363  math::Vector3 &_origin,
364  math::Vector3 &_dir);
365 
368  public: void SetCaptureData(bool _value);
369 
371  public: void SetCaptureDataOnce();
372 
375  public: void CreateRenderTexture(const std::string &_textureName);
376 
379  public: ScenePtr GetScene() const;
380 
387  public: bool GetWorldPointOnPlane(int _x, int _y,
388  const math::Plane &_plane, math::Vector3 &_result);
389 
392  public: virtual void SetRenderTarget(Ogre::RenderTarget *_target);
393 
402  public: void AttachToVisual(const std::string &_visualName,
403  bool _inheritOrientation,
404  double _minDist = 0.0, double _maxDist = 0.0);
405 
414  public: void AttachToVisual(uint32_t _id,
415  bool _inheritOrientation,
416  double _minDist = 0.0, double _maxDist = 0.0);
417 
420  public: void TrackVisual(const std::string &_visualName);
421 
424  public: Ogre::Texture *GetRenderTexture() const;
425 
428  public: math::Vector3 GetDirection() const;
429 
434  public: template<typename T>
436  {return newImageFrame.Connect(_subscriber);}
437 
442 
451  public: static bool SaveFrame(const unsigned char *_image,
452  unsigned int _width, unsigned int _height, int _depth,
453  const std::string &_format,
454  const std::string &_filename);
455 
456 
460 
465  public: bool IsVisible(VisualPtr _visual);
466 
471  public: bool IsVisible(const std::string &_visualName);
472 
474  public: bool IsAnimating() const;
475 
480  public: virtual bool MoveToPosition(const math::Pose &_pose,
481  double _time);
482 
490  public: bool MoveToPositions(const std::vector<math::Pose> &_pts,
491  double _time,
492  boost::function<void()> _onComplete = NULL);
493 
496  public: std::string GetScreenshotPath() const;
497 
499  protected: virtual void RenderImpl();
500 
502  protected: void ReadPixelBuffer();
503 
507  protected: bool TrackVisualImpl(const std::string &_visualName);
508 
512  protected: virtual bool TrackVisualImpl(VisualPtr _visual);
513 
523  protected: virtual bool AttachToVisualImpl(const std::string &_name,
524  bool _inheritOrientation,
525  double _minDist = 0, double _maxDist = 0);
526 
536  protected: virtual bool AttachToVisualImpl(uint32_t _id,
537  bool _inheritOrientation,
538  double _minDist = 0, double _maxDist = 0);
539 
549  protected: virtual bool AttachToVisualImpl(VisualPtr _visual,
550  bool _inheritOrientation,
551  double _minDist = 0, double _maxDist = 0);
552 
555  protected: std::string GetFrameFilename();
556 
559  protected: virtual void AnimationComplete();
560 
568  private: void ConvertRGBToBAYER(unsigned char *_dst, unsigned char *_src,
569  std::string _format, int _width, int _height);
570 
572  private: void SetClipDist();
573 
577  private: static int GetOgrePixelFormat(const std::string &_format);
578 
579 
581  private: void CreateCamera();
582 
584  protected: std::string name;
585 
587  protected: sdf::ElementPtr sdf;
588 
590  protected: unsigned int windowId;
591 
593  protected: unsigned int textureWidth;
594 
596  protected: unsigned int textureHeight;
597 
599  protected: Ogre::Camera *camera;
600 
602  protected: Ogre::Viewport *viewport;
603 
605  protected: Ogre::SceneNode *sceneNode;
606 
608  protected: Ogre::SceneNode *pitchNode;
609 
610  // \brief Buffer for a single image frame.
611  protected: unsigned char *saveFrameBuffer;
612 
614  protected: unsigned char *bayerFrameBuffer;
615 
617  protected: unsigned int saveCount;
618 
620  protected: std::string screenshotPath;
621 
623  protected: int imageFormat;
624 
626  protected: int imageWidth;
627 
629  protected: int imageHeight;
630 
632  protected: Ogre::RenderTarget *renderTarget;
633 
635  protected: Ogre::Texture *renderTexture;
636 
638  protected: bool captureData;
639 
641  protected: bool captureDataOnce;
642 
644  protected: bool newData;
645 
648 
650  protected: ScenePtr scene;
651 
653  protected: event::EventT<void(const unsigned char *,
654  unsigned int, unsigned int, unsigned int,
655  const std::string &)> newImageFrame;
656 
658  protected: std::vector<event::ConnectionPtr> connections;
659 
661  protected: std::list<msgs::Request> requests;
662 
664  protected: bool initialized;
665 
667  protected: Ogre::AnimationState *animState;
668 
671 
673  protected: boost::function<void()> onAnimationComplete;
674 
676  private: sdf::ElementPtr imageElem;
677 
679  private: VisualPtr trackedVisual;
680 
682  private: static unsigned int cameraCounter;
683 
685  private: Ogre::CompositorInstance *dsGBufferInstance;
686 
688  private: Ogre::CompositorInstance *dsMergeInstance;
689 
691  private: Ogre::CompositorInstance *dlGBufferInstance;
692 
694  private: Ogre::CompositorInstance *dlMergeInstance;
695 
697  private: Ogre::CompositorInstance *ssaoInstance;
698 
700  private: Ogre::CompositorInstance *gaussianNoiseInstance;
701 
703  private: boost::shared_ptr<GaussianNoiseCompositorListener>
704  gaussianNoiseCompositorListener;
705 
707  private: std::deque<std::pair<math::Pose, double> > moveToPositionQueue;
708 
710  private: common::Time renderPeriod;
711 
713  private: common::PID trackVisualPID;
714 
716  private: common::PID trackVisualPitchPID;
717 
719  private: common::PID trackVisualYawPID;
720 
722  private: enum NoiseModelType
723  {
724  NONE,
725  GAUSSIAN
726  };
727 
730  private: bool noiseActive;
731 
733  private: enum NoiseModelType noiseType;
734 
737  private: double noiseMean;
738 
741  private: double noiseStdDev;
742  };
744  }
745 }
746 #endif