Camera.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 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 
18 #ifndef _GAZEBO_RENDERING_CAMERA_HH_
19 #define _GAZEBO_RENDERING_CAMERA_HH_
20 
21 #include <memory>
22 #include <functional>
23 
24 #include <boost/enable_shared_from_this.hpp>
25 #include <string>
26 #include <utility>
27 #include <list>
28 #include <vector>
29 #include <deque>
30 #include <sdf/sdf.hh>
31 #include <ignition/math/Angle.hh>
32 #include <ignition/math/Vector3.hh>
33 #include <ignition/math/Quaternion.hh>
34 #include <ignition/math/Pose3.hh>
35 
36 #include "gazebo/msgs/msgs.hh"
37 
38 #include "gazebo/transport/Node.hh"
40 
41 #include "gazebo/common/Event.hh"
42 #include "gazebo/common/PID.hh"
43 #include "gazebo/common/Time.hh"
44 
45 #include "gazebo/math/Angle.hh"
46 #include "gazebo/math/Pose.hh"
47 #include "gazebo/math/Plane.hh"
48 #include "gazebo/math/Vector2i.hh"
49 
51 #include "gazebo/msgs/MessageTypes.hh"
53 #include "gazebo/util/system.hh"
54 
55 // Forward Declarations
56 namespace Ogre
57 {
58  class Texture;
59  class RenderTarget;
60  class Camera;
61  class Viewport;
62  class SceneNode;
63  class AnimationState;
64 }
65 
66 namespace gazebo
67 {
70  namespace rendering
71  {
72  class MouseEvent;
73  class ViewController;
74  class Scene;
75  class CameraPrivate;
76 
80 
85  class GZ_RENDERING_VISIBLE Camera :
86  public boost::enable_shared_from_this<Camera>
87  {
92  public: Camera(const std::string &_namePrefix, ScenePtr _scene,
93  bool _autoRender = true);
94 
96  public: virtual ~Camera();
97 
100  public: virtual void Load(sdf::ElementPtr _sdf);
101 
103  public: virtual void Load();
104 
106  public: virtual void Init();
107 
110  public: void SetRenderRate(const double _hz);
111 
115  public: double GetRenderRate() const GAZEBO_DEPRECATED(7.0);
116 
119  public: double RenderRate() const;
120 
126  public: void Render(const bool _force = false);
127 
131  public: virtual void PostRender();
132 
138  public: virtual void Update();
139 
143  public: virtual void Fini();
144 
148  public: bool GetInitialized() const GAZEBO_DEPRECATED(7.0);
149 
152  public: bool Initialized() const;
153 
157  public: void SetWindowId(unsigned int _windowId);
158 
162  public: unsigned int GetWindowId() const GAZEBO_DEPRECATED(7.0);
163 
166  public: unsigned int WindowId() const;
167 
170  public: void SetScene(ScenePtr _scene);
171 
176  public: math::Vector3 GetWorldPosition() const GAZEBO_DEPRECATED(7.0);
177 
180  public: ignition::math::Vector3d WorldPosition() const;
181 
186  public: math::Quaternion GetWorldRotation() const GAZEBO_DEPRECATED(7.0);
187 
190  public: ignition::math::Quaterniond WorldRotation() const;
191 
195  public: virtual void SetWorldPose(const math::Pose &_pose)
196  GAZEBO_DEPRECATED(7.0);
197 
200  public: virtual void SetWorldPose(const ignition::math::Pose3d &_pose);
201 
206  public: math::Pose GetWorldPose() const GAZEBO_DEPRECATED(7.0);
207 
210  public: ignition::math::Pose3d WorldPose() const;
211 
215  public: void SetWorldPosition(const math::Vector3 &_pos)
216  GAZEBO_DEPRECATED(7.0);
217 
220  public: void SetWorldPosition(const ignition::math::Vector3d &_pos);
221 
225  public: void SetWorldRotation(const math::Quaternion &_quat)
226  GAZEBO_DEPRECATED(7.0);
227 
230  public: void SetWorldRotation(const ignition::math::Quaterniond &_quat);
231 
235  public: void Translate(const math::Vector3 &_direction)
236  GAZEBO_DEPRECATED(7.0);
237 
240  public: void Translate(const ignition::math::Vector3d &_direction);
241 
248  public: void Roll(const math::Angle &_angle,
249  Ogre::Node::TransformSpace _relativeTo =
250  Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0);
251 
256  public: void Roll(const ignition::math::Angle &_angle,
257  ReferenceFrame _relativeTo = RF_LOCAL);
258 
265  public: void Pitch(const math::Angle &_angle,
266  Ogre::Node::TransformSpace _relativeTo =
267  Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0);
268 
273  public: void Pitch(const ignition::math::Angle &_angle,
274  ReferenceFrame _relativeTo = RF_LOCAL);
275 
282  public: void Yaw(const math::Angle &_angle,
283  Ogre::Node::TransformSpace _relativeTo =
284  Ogre::Node::TS_WORLD) GAZEBO_DEPRECATED(7.0);
285 
290  public: void Yaw(const ignition::math::Angle &_angle,
291  ReferenceFrame _relativeTo = RF_WORLD);
292 
296  public: virtual void SetClipDist(const float _near, const float _far);
297 
301  public: void SetHFOV(math::Angle _angle) GAZEBO_DEPRECATED(7.0);
302 
305  public: void SetHFOV(const ignition::math::Angle &_angle);
306 
311  public: math::Angle GetHFOV() const GAZEBO_DEPRECATED(7.0);
312 
315  public: ignition::math::Angle HFOV() const;
316 
321  public: math::Angle GetVFOV() const GAZEBO_DEPRECATED(7.0);
322 
327  public: ignition::math::Angle VFOV() const;
328 
332  public: void SetImageSize(const unsigned int _w, const unsigned int _h);
333 
336  public: void SetImageWidth(const unsigned int _w);
337 
340  public: void SetImageHeight(const unsigned int _h);
341 
345  public: virtual unsigned int GetImageWidth() const GAZEBO_DEPRECATED(7.0);
346 
349  public: virtual unsigned int ImageWidth() const;
350 
354  public: unsigned int GetTextureWidth() const GAZEBO_DEPRECATED(7.0);
355 
358  public: unsigned int TextureWidth() const;
359 
363  public: virtual unsigned int GetImageHeight() const
364  GAZEBO_DEPRECATED(7.0);
365 
368  public: virtual unsigned int ImageHeight() const;
369 
373  public: unsigned int GetImageDepth() const GAZEBO_DEPRECATED(7.0);
374 
377  public: unsigned int ImageDepth() const;
378 
382  public: std::string GetImageFormat() const GAZEBO_DEPRECATED(7.0);
383 
386  public: std::string ImageFormat() const;
387 
391  public: unsigned int GetTextureHeight() const GAZEBO_DEPRECATED(7.0);
392 
395  public: unsigned int TextureHeight() const;
396 
400  public: size_t GetImageByteSize() const GAZEBO_DEPRECATED(7.0);
401 
404  public: size_t ImageByteSize() const;
405 
412  public: static size_t GetImageByteSize(unsigned int _width,
413  unsigned int _height,
414  const std::string &_format)
415  GAZEBO_DEPRECATED(7.0);
416 
422  public: static size_t ImageByteSize(const unsigned int _width,
423  const unsigned int _height,
424  const std::string &_format);
425 
432  public: double GetZValue(int _x, int _y) GAZEBO_DEPRECATED(7.0);
433 
439  public: double ZValue(const int _x, const int _y);
440 
444  public: double GetNearClip() GAZEBO_DEPRECATED(7.0);
445 
448  public: double NearClip() const;
449 
453  public: double GetFarClip() GAZEBO_DEPRECATED(7.0);
454 
457  public: double FarClip() const;
458 
461  public: void EnableSaveFrame(const bool _enable);
462 
466  public: bool GetCaptureData() const GAZEBO_DEPRECATED(7.0);
467 
470  public: bool CaptureData() const;
471 
474  public: void SetSaveFramePathname(const std::string &_pathname);
475 
479  public: bool SaveFrame(const std::string &_filename);
480 
484  public: Ogre::Camera *GetOgreCamera() const GAZEBO_DEPRECATED(7.0);
485 
488  public: Ogre::Camera *OgreCamera() const;
489 
493  public: Ogre::Viewport *GetViewport() const GAZEBO_DEPRECATED(7.0);
494 
497  public: Ogre::Viewport *OgreViewport() const;
498 
502  public: unsigned int GetViewportWidth() const GAZEBO_DEPRECATED(7.0);
503 
506  public: unsigned int ViewportWidth() const;
507 
511  public: unsigned int GetViewportHeight() const GAZEBO_DEPRECATED(7.0);
512 
515  public: unsigned int ViewportHeight() const;
516 
521  public: math::Vector3 GetUp() GAZEBO_DEPRECATED(7.0);
522 
525  public: ignition::math::Vector3d Up() const;
526 
531  public: math::Vector3 GetRight() GAZEBO_DEPRECATED(7.0);
532 
535  public: ignition::math::Vector3d Right() const;
536 
540  public: virtual float GetAvgFPS() const GAZEBO_DEPRECATED(7.0);
541 
544  public: virtual float AvgFPS() const;
545 
549  public: virtual unsigned int GetTriangleCount() const
550  GAZEBO_DEPRECATED(7.0);
551 
554  public: virtual unsigned int TriangleCount() const;
555 
558  public: void SetAspectRatio(float _ratio);
559 
563  public: float GetAspectRatio() const GAZEBO_DEPRECATED(7.0);
564 
567  public: float AspectRatio() const;
568 
571  public: void SetSceneNode(Ogre::SceneNode *_node);
572 
576  public: Ogre::SceneNode *GetSceneNode() const GAZEBO_DEPRECATED(7.0);
577 
580  public: Ogre::SceneNode *SceneNode() const;
581 
588  public: virtual const unsigned char *GetImageData(unsigned int i = 0)
589  GAZEBO_DEPRECATED(7.0);
590 
596  public: virtual const unsigned char *ImageData(const unsigned int i = 0)
597  const;
598 
602  public: std::string GetName() const GAZEBO_DEPRECATED(7.0);
603 
606  public: std::string Name() const;
607 
611  public: std::string GetScopedName() const GAZEBO_DEPRECATED(7.0);
612 
615  public: std::string ScopedName() const;
616 
619  public: void SetName(const std::string &_name);
620 
622  public: void ToggleShowWireframe();
623 
626  public: void ShowWireframe(const bool _s);
627 
637  public: void GetCameraToViewportRay(int _screenx, int _screeny,
638  math::Vector3 &_origin, math::Vector3 &_dir)
639  GAZEBO_DEPRECATED(7.0);
640 
649  public: void CameraToViewportRay(const int _screenx, const int _screeny,
650  ignition::math::Vector3d &_origin,
651  ignition::math::Vector3d &_dir) const;
652 
655  public: void SetCaptureData(const bool _value);
656 
658  public: void SetCaptureDataOnce();
659 
662  public: void CreateRenderTexture(const std::string &_textureName);
663 
666  public: ScenePtr GetScene() const;
667 
676  public: bool GetWorldPointOnPlane(int _x, int _y,
677  const math::Plane &_plane, math::Vector3 &_result)
678  GAZEBO_DEPRECATED(7.0);
679 
686  public: bool WorldPointOnPlane(const int _x, const int _y,
687  const ignition::math::Planed &_plane,
688  ignition::math::Vector3d &_result);
689 
692  public: virtual void SetRenderTarget(Ogre::RenderTarget *_target);
693 
702  public: void AttachToVisual(const std::string &_visualName,
703  const bool _inheritOrientation,
704  const double _minDist = 0.0, const double _maxDist = 0.0);
705 
714  public: void AttachToVisual(uint32_t _id,
715  const bool _inheritOrientation,
716  const double _minDist = 0.0, const double _maxDist = 0.0);
717 
720  public: void TrackVisual(const std::string &_visualName);
721 
725  public: Ogre::Texture *GetRenderTexture() const GAZEBO_DEPRECATED(7.0);
726 
729  public: Ogre::Texture *RenderTexture() const;
730 
735  public: math::Vector3 GetDirection() const GAZEBO_DEPRECATED(7.0);
736 
739  public: ignition::math::Vector3d Direction() const;
740 
745  public: event::ConnectionPtr ConnectNewImageFrame(
746  std::function<void (const unsigned char *, unsigned int, unsigned int,
747  unsigned int, const std::string &)> _subscriber);
748 
751  public: void DisconnectNewImageFrame(event::ConnectionPtr &_c);
752 
761  public: static bool SaveFrame(const unsigned char *_image,
762  const unsigned int _width, const unsigned int _height,
763  const int _depth, const std::string &_format,
764  const std::string &_filename);
765 
769  public: common::Time GetLastRenderWallTime() GAZEBO_DEPRECATED(7.0);
770 
773  public: common::Time LastRenderWallTime() const;
774 
779  public: bool IsVisible(VisualPtr _visual);
780 
785  public: bool IsVisible(const std::string &_visualName);
786 
788  public: bool IsAnimating() const;
789 
795  public: virtual bool MoveToPosition(const math::Pose &_pose,
796  double _time) GAZEBO_DEPRECATED(7.0);
797 
802  public: virtual bool MoveToPosition(const ignition::math::Pose3d &_pose,
803  const double _time);
804 
813  public: bool MoveToPositions(const std::vector<math::Pose> &_pts,
814  double _time,
815  std::function<void()> _onComplete = NULL)
816  GAZEBO_DEPRECATED(7.0);
817 
825  public: bool MoveToPositions(
826  const std::vector<ignition::math::Pose3d> &_pts,
827  const double _time,
828  std::function<void()> _onComplete = NULL);
829 
833  public: std::string GetScreenshotPath() const GAZEBO_DEPRECATED(7.0);
834 
837  public: std::string ScreenshotPath() const;
838 
842  public: DistortionPtr GetDistortion() const GAZEBO_DEPRECATED(7.0);
843 
846  public: DistortionPtr LensDistortion() const;
847 
853  public: virtual bool SetProjectionType(const std::string &_type);
854 
859  public: std::string GetProjectionType() const GAZEBO_DEPRECATED(7.0);
860 
864  public: std::string ProjectionType() const;
865 
868  public: VisualPtr TrackedVisual() const;
869 
873  public: bool TrackIsStatic() const;
874 
879  public: void SetTrackIsStatic(const bool _isStatic);
880 
885  public: bool TrackUseModelFrame() const;
886 
892  public: void SetTrackUseModelFrame(const bool _useModelFrame);
893 
897  public: ignition::math::Vector3d TrackPosition() const;
898 
902  public: void SetTrackPosition(const ignition::math::Vector3d &_pos);
903 
907  public: double TrackMinDistance() const;
908 
912  public: double TrackMaxDistance() const;
913 
918  public: void SetTrackMinDistance(const double _dist);
919 
924  public: void SetTrackMaxDistance(const double _dist);
925 
931  public: bool TrackInheritYaw() const;
932 
938  public: void SetTrackInheritYaw(const bool _inheritYaw);
939 
941  protected: virtual void RenderImpl();
942 
944  protected: void ReadPixelBuffer();
945 
949  protected: bool TrackVisualImpl(const std::string &_visualName);
950 
954  protected: virtual bool TrackVisualImpl(VisualPtr _visual);
955 
965  protected: virtual bool AttachToVisualImpl(const std::string &_name,
966  const bool _inheritOrientation,
967  const double _minDist = 0, const double _maxDist = 0);
968 
978  protected: virtual bool AttachToVisualImpl(uint32_t _id,
979  const bool _inheritOrientation,
980  const double _minDist = 0, const double _maxDist = 0);
981 
991  protected: virtual bool AttachToVisualImpl(VisualPtr _visual,
992  const bool _inheritOrientation,
993  const double _minDist = 0, const double _maxDist = 0);
994 
998  protected: std::string GetFrameFilename() GAZEBO_DEPRECATED(7.0);
999 
1002  protected: std::string FrameFilename();
1003 
1006  protected: virtual void AnimationComplete();
1007 
1009  protected: virtual void UpdateFOV();
1010 
1018  private: void ConvertRGBToBAYER(unsigned char *_dst,
1019  const unsigned char *_src, const std::string &_format,
1020  const int _width, const int _height);
1021 
1023  private: virtual void SetClipDist();
1024 
1028  private: static int OgrePixelFormat(const std::string &_format);
1029 
1032  private: void OnCmdMsg(ConstCameraCmdPtr &_msg);
1033 
1035  private: void CreateCamera();
1036 
1038  protected: std::string name;
1039 
1041  protected: std::string scopedName;
1042 
1044  protected: std::string scopedUniqueName;
1045 
1047  protected: sdf::ElementPtr sdf;
1048 
1050  protected: unsigned int windowId;
1051 
1053  protected: unsigned int textureWidth;
1054 
1056  protected: unsigned int textureHeight;
1057 
1059  protected: Ogre::Camera *camera;
1060 
1062  protected: Ogre::Viewport *viewport;
1063 
1065  protected: Ogre::SceneNode *sceneNode;
1066 
1068  protected: unsigned char *saveFrameBuffer;
1069 
1071  protected: unsigned char *bayerFrameBuffer;
1072 
1074  protected: unsigned int saveCount;
1075 
1077  protected: std::string screenshotPath;
1078 
1080  protected: int imageFormat;
1081 
1083  protected: int imageWidth;
1084 
1086  protected: int imageHeight;
1087 
1089  protected: Ogre::RenderTarget *renderTarget;
1090 
1092  protected: Ogre::Texture *renderTexture;
1093 
1095  protected: bool captureData;
1096 
1098  protected: bool captureDataOnce;
1099 
1101  protected: bool newData;
1102 
1105 
1107  protected: ScenePtr scene;
1108 
1110  protected: event::EventT<void(const unsigned char *,
1111  unsigned int, unsigned int, unsigned int,
1112  const std::string &)> newImageFrame;
1113 
1115  protected: std::vector<event::ConnectionPtr> connections;
1116 
1118  protected: std::list<msgs::Request> requests;
1119 
1121  protected: bool initialized;
1122 
1124  protected: Ogre::AnimationState *animState;
1125 
1128 
1130  protected: std::function<void()> onAnimationComplete;
1131 
1134  private: std::unique_ptr<CameraPrivate> dataPtr;
1135  };
1137  }
1138 }
1139 #endif
Basic camera sensor.
Definition: Camera.hh:85
common::Time lastRenderWallTime
Time the last frame was rendered.
Definition: Camera.hh:1104
ReferenceFrame
Frame of reference.
Definition: RenderTypes.hh:234
bool initialized
True if initialized.
Definition: Camera.hh:1121
Ogre::Texture * renderTexture
Texture that receives results from rendering.
Definition: Camera.hh:1092
boost::shared_ptr< Distortion > DistortionPtr
Definition: RenderTypes.hh:196
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
std::string scopedUniqueName
Scene scoped name of the camera with a unique ID.
Definition: Camera.hh:1044
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
unsigned char * saveFrameBuffer
Buffer for a single image frame.
Definition: Camera.hh:1068
unsigned char * bayerFrameBuffer
Buffer for a bayer image frame.
Definition: Camera.hh:1071
std::string screenshotPath
Path to saved screenshots.
Definition: Camera.hh:1077
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:48
bool captureDataOnce
True to capture a frame once and save to disk.
Definition: Camera.hh:1098
bool captureData
True to capture frames into an image buffer.
Definition: Camera.hh:1095
sdf::ElementPtr sdf
Camera's SDF values.
Definition: Camera.hh:1047
Ogre::RenderTarget * renderTarget
Target that renders frames.
Definition: Camera.hh:1089
Ogre::SceneNode * sceneNode
Scene node that controls camera position and orientation.
Definition: Camera.hh:1065
Local frame.
Definition: RenderTypes.hh:237
std::vector< event::ConnectionPtr > connections
The camera's event connections.
Definition: Camera.hh:1115
Ogre::Viewport * viewport
Viewport the ogre camera uses.
Definition: Camera.hh:1062
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:80
int imageWidth
Save image width.
Definition: Camera.hh:1083
bool newData
True if new data is available.
Definition: Camera.hh:1101
unsigned int windowId
ID of the window that the camera is attached to.
Definition: Camera.hh:1050
common::Time prevAnimTime
Previous time the camera animation was updated.
Definition: Camera.hh:1127
std::string scopedName
Scene scoped name of the camera.
Definition: Camera.hh:1041
ScenePtr scene
Pointer to the scene.
Definition: Camera.hh:1107
unsigned int saveCount
Number of saved frames.
Definition: Camera.hh:1074
A plane and related functions.
Definition: Plane.hh:35
std::list< msgs::Request > requests
List of requests.
Definition: Camera.hh:1118
unsigned int textureHeight
Height of the render texture.
Definition: Camera.hh:1056
A quaternion class.
Definition: Quaternion.hh:42
int imageHeight
Save image height.
Definition: Camera.hh:1086
World frame.
Definition: RenderTypes.hh:243
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:153
std::function< void()> onAnimationComplete
User callback for when an animation completes.
Definition: Camera.hh:1130
#define NULL
Definition: CommonTypes.hh:31
int imageFormat
Format for saving images.
Definition: Camera.hh:1080
unsigned int textureWidth
Width of the render texture.
Definition: Camera.hh:1053
std::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:112
std::string name
Name of the camera.
Definition: Camera.hh:1038
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
event::EventT< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> newImageFrame
Event triggered when a new frame is generated.
Definition: Camera.hh:1112
A class for event processing.
Definition: Event.hh:186
Ogre::AnimationState * animState
Animation state, used to animate the camera.
Definition: Camera.hh:1124
An angle and related functions.
Definition: Angle.hh:53
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44
Ogre::Camera * camera
The OGRE camera.
Definition: Camera.hh:1059