Camera.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 #ifndef GAZEBO_RENDERING_CAMERA_HH_
18 #define GAZEBO_RENDERING_CAMERA_HH_
19 
20 #include <memory>
21 #include <functional>
22 
23 #include <boost/enable_shared_from_this.hpp>
24 #include <string>
25 #include <utility>
26 #include <list>
27 #include <vector>
28 #include <deque>
29 #include <sdf/sdf.hh>
30 #include <ignition/math/Angle.hh>
31 #include <ignition/math/Color.hh>
32 #include <ignition/math/Matrix4.hh>
33 #include <ignition/math/Pose3.hh>
34 #include <ignition/math/Quaternion.hh>
35 #include <ignition/math/Vector2.hh>
36 #include <ignition/math/Vector3.hh>
37 
38 #include "gazebo/msgs/msgs.hh"
39 
40 #include "gazebo/transport/Node.hh"
42 
43 #include "gazebo/common/Event.hh"
44 #include "gazebo/common/PID.hh"
45 #include "gazebo/common/Time.hh"
46 
50 
51 #include "gazebo/msgs/MessageTypes.hh"
52 #include "gazebo/util/system.hh"
53 
54 // Forward Declarations
55 namespace Ogre
56 {
57  class Texture;
58  class RenderTarget;
59  class Camera;
60  class Viewport;
61  class SceneNode;
62  class AnimationState;
63 }
64 
65 namespace gazebo
66 {
69  namespace rendering
70  {
71  class MouseEvent;
72  class ViewController;
73  class Scene;
74  class CameraPrivate;
75 
79 
84  class GZ_RENDERING_VISIBLE Camera :
85  public boost::enable_shared_from_this<Camera>
86  {
91  public: Camera(const std::string &_namePrefix, ScenePtr _scene,
92  bool _autoRender = true);
93 
95  public: virtual ~Camera();
96 
99  public: virtual void Load(sdf::ElementPtr _sdf);
100 
102  public: virtual void Load();
103 
112  const double _cameraIntrinsicsFx, const double _cameraIntrinsicsFy,
113  const double _cameraIntrinsicsCx, const double _cameraIntrinsicsCy,
114  const double _cameraIntrinsicsS);
115 
117  private: virtual void LoadCameraIntrinsics();
118 
131  public: static ignition::math::Matrix4d BuildNDCMatrix(
132  const double _left, const double _right,
133  const double _bottom, const double _top,
134  const double _near, const double _far);
135 
150  public: static ignition::math::Matrix4d BuildPerspectiveMatrix(
151  const double _intrinsicsFx, const double _intrinsicsFy,
152  const double _intrinsicsCx, const double _intrinsicsCy,
153  const double _intrinsicsS,
154  const double _clipNear, const double _clipFar);
155 
175  public: static ignition::math::Matrix4d BuildProjectionMatrix(
176  const double _imageWidth, const double _imageHeight,
177  const double _intrinsicsFx, const double _intrinsicsFy,
178  const double _intrinsicsCx, const double _intrinsicsCy,
179  const double _intrinsicsS,
180  const double _clipNear, const double _clipFar);
181 
202  public: static ignition::math::Matrix4d BuildProjectiveMatrix(
203  const double _imageWidth, const double _imageHeight,
204  const double _intrinsicsFx, const double _intrinsicsFy,
205  const double _intrinsicsCx, const double _intrinsicsCy,
206  const double _intrinsicsS,
207  const double _clipNear, const double _clipFar);
208 
210  public: virtual void Init();
211 
214  public: void SetRenderRate(const double _hz);
215 
218  public: double RenderRate() const;
219 
225  public: virtual void Render(const bool _force = false);
226 
230  public: virtual void PostRender();
231 
237  public: virtual void Update();
238 
242  public: virtual void Fini();
243 
246  public: bool Initialized() const;
247 
251  public: void SetWindowId(unsigned int _windowId);
252 
255  public: unsigned int WindowId() const;
256 
259  public: void SetScene(ScenePtr _scene);
260 
263  public: ignition::math::Vector3d WorldPosition() const;
264 
267  public: ignition::math::Quaterniond WorldRotation() const;
268 
271  public: virtual void SetWorldPose(const ignition::math::Pose3d &_pose);
272 
275  public: ignition::math::Pose3d WorldPose() const;
276 
279  public: void SetWorldPosition(const ignition::math::Vector3d &_pos);
280 
283  public: void SetWorldRotation(const ignition::math::Quaterniond &_quat);
284 
287  public: void Translate(const ignition::math::Vector3d &_direction);
288 
293  public: void Roll(const ignition::math::Angle &_angle,
294  ReferenceFrame _relativeTo = RF_LOCAL);
295 
300  public: void Pitch(const ignition::math::Angle &_angle,
301  ReferenceFrame _relativeTo = RF_LOCAL);
302 
307  public: void Yaw(const ignition::math::Angle &_angle,
308  ReferenceFrame _relativeTo = RF_WORLD);
309 
313  public: virtual void SetClipDist(const float _near, const float _far);
314 
317  public: void SetHFOV(const ignition::math::Angle &_angle);
318 
321  public: ignition::math::Angle HFOV() const;
322 
325  public: ignition::math::Angle VFOV() const;
326 
330  public: void SetImageSize(const unsigned int _w, const unsigned int _h);
331 
334  public: void SetImageWidth(const unsigned int _w);
335 
338  public: void SetImageHeight(const unsigned int _h);
339 
342  public: virtual unsigned int ImageWidth() const;
343 
346  public: unsigned int ImageMemorySize() const;
347 
350  public: unsigned int TextureWidth() const;
351 
354  public: virtual unsigned int ImageHeight() const;
355 
358  public: unsigned int ImageDepth() const;
359 
362  public: std::string ImageFormat() const;
363 
366  public: unsigned int TextureHeight() const;
367 
370  public: size_t ImageByteSize() const;
371 
377  public: static size_t ImageByteSize(const unsigned int _width,
378  const unsigned int _height,
379  const std::string &_format);
380 
386  public: double ZValue(const int _x, const int _y);
387 
390  public: double NearClip() const;
391 
394  public: double FarClip() const;
395 
398  public: void EnableSaveFrame(const bool _enable);
399 
402  public: bool CaptureData() const;
403 
406  public: void SetSaveFramePathname(const std::string &_pathname);
407 
411  public: bool SaveFrame(const std::string &_filename);
412 
415  public: Ogre::Camera *OgreCamera() const;
416 
419  public: Ogre::Viewport *OgreViewport() const;
420 
423  public: unsigned int ViewportWidth() const;
424 
427  public: unsigned int ViewportHeight() const;
428 
431  public: ignition::math::Vector3d Up() const;
432 
435  public: ignition::math::Vector3d Right() const;
436 
439  public: virtual float AvgFPS() const;
440 
443  public: virtual unsigned int TriangleCount() const;
444 
447  public: void SetAspectRatio(float _ratio);
448 
451  public: float AspectRatio() const;
452 
455  public: void SetSceneNode(Ogre::SceneNode *_node);
456 
459  public: Ogre::SceneNode *SceneNode() const;
460 
466  public: virtual const unsigned char *ImageData(const unsigned int i = 0)
467  const;
468 
471  public: std::string Name() const;
472 
475  public: std::string ScopedName() const;
476 
479  public: void SetName(const std::string &_name);
480 
482  public: void ToggleShowWireframe();
483 
486  public: void ShowWireframe(const bool _s);
487 
490  public: void SetCaptureData(const bool _value);
491 
493  public: void SetCaptureDataOnce();
494 
508  public: bool StartVideo(const std::string &_format,
509  const std::string &_filename = "");
510 
515  public: bool StopVideo();
516 
522  public: bool SaveVideo(const std::string &_filename);
523 
530  public: bool ResetVideo();
531 
534  public: void CreateRenderTexture(const std::string &_textureName);
535 
538  public: ScenePtr GetScene() const;
539 
546  public: bool WorldPointOnPlane(const int _x, const int _y,
547  const ignition::math::Planed &_plane,
548  ignition::math::Vector3d &_result);
549 
557  public: virtual void CameraToViewportRay(const int _screenx,
558  const int _screeny,
559  ignition::math::Vector3d &_origin,
560  ignition::math::Vector3d &_dir) const;
561 
564  public: virtual void SetRenderTarget(Ogre::RenderTarget *_target);
565 
574  public: void AttachToVisual(const std::string &_visualName,
575  const bool _inheritOrientation,
576  const double _minDist = 0.0, const double _maxDist = 0.0);
577 
586  public: void AttachToVisual(uint32_t _id,
587  const bool _inheritOrientation,
588  const double _minDist = 0.0, const double _maxDist = 0.0);
589 
592  public: void TrackVisual(const std::string &_visualName);
593 
596  public: Ogre::Texture *RenderTexture() const;
597 
600  public: ignition::math::Vector3d Direction() const;
601 
607  std::function<void (const unsigned char *, unsigned int, unsigned int,
608  unsigned int, const std::string &)> _subscriber);
609 
618  public: static bool SaveFrame(const unsigned char *_image,
619  const unsigned int _width, const unsigned int _height,
620  const int _depth, const std::string &_format,
621  const std::string &_filename);
622 
626 
631  public: bool IsVisible(VisualPtr _visual);
632 
637  public: bool IsVisible(const std::string &_visualName);
638 
640  public: bool IsAnimating() const;
641 
646  public: virtual bool MoveToPosition(const ignition::math::Pose3d &_pose,
647  const double _time);
648 
656  public: bool MoveToPositions(
657  const std::vector<ignition::math::Pose3d> &_pts,
658  const double _time,
659  std::function<void()> _onComplete = NULL);
660 
663  public: std::string ScreenshotPath() const;
664 
667  public: DistortionPtr LensDistortion() const;
668 
674  public: virtual bool SetProjectionType(const std::string &_type);
675 
679  public: std::string ProjectionType() const;
680 
684  public: virtual bool SetBackgroundColor(
685  const ignition::math::Color &_color);
686 
689  public: ignition::math::Matrix4d ProjectionMatrix() const;
690 
694  public: virtual ignition::math::Vector2i Project(
695  const ignition::math::Vector3d &_pt) const;
696 
699  public: VisualPtr TrackedVisual() const;
700 
704  public: bool TrackIsStatic() const;
705 
710  public: void SetTrackIsStatic(const bool _isStatic);
711 
716  public: bool TrackUseModelFrame() const;
717 
723  public: void SetTrackUseModelFrame(const bool _useModelFrame);
724 
728  public: ignition::math::Vector3d TrackPosition() const;
729 
733  public: void SetTrackPosition(const ignition::math::Vector3d &_pos);
734 
738  public: double TrackMinDistance() const;
739 
743  public: double TrackMaxDistance() const;
744 
749  public: void SetTrackMinDistance(const double _dist);
750 
755  public: void SetTrackMaxDistance(const double _dist);
756 
762  public: bool TrackInheritYaw() const;
763 
769  public: void SetTrackInheritYaw(const bool _inheritYaw);
770 
772  protected: virtual void RenderImpl();
773 
775  protected: void ReadPixelBuffer();
776 
780  protected: bool TrackVisualImpl(const std::string &_visualName);
781 
785  protected: virtual bool TrackVisualImpl(VisualPtr _visual);
786 
796  protected: virtual bool AttachToVisualImpl(const std::string &_name,
797  const bool _inheritOrientation,
798  const double _minDist = 0, const double _maxDist = 0);
799 
809  protected: virtual bool AttachToVisualImpl(uint32_t _id,
810  const bool _inheritOrientation,
811  const double _minDist = 0, const double _maxDist = 0);
812 
822  protected: virtual bool AttachToVisualImpl(VisualPtr _visual,
823  const bool _inheritOrientation,
824  const double _minDist = 0, const double _maxDist = 0);
825 
828  protected: std::string FrameFilename();
829 
832  protected: virtual void AnimationComplete();
833 
835  protected: virtual void UpdateFOV();
836 
838  protected: virtual void SetClipDist();
839 
844  protected: static double LimitFOV(const double _fov);
845 
852  protected: virtual void SetFixedYawAxis(const bool _useFixed,
853  const ignition::math::Vector3d &_fixedAxis =
854  ignition::math::Vector3d::UnitY);
855 
863  private: void ConvertRGBToBAYER(unsigned char *_dst,
864  const unsigned char *_src, const std::string &_format,
865  const int _width, const int _height);
866 
870  private: static int OgrePixelFormat(const std::string &_format);
871 
874  private: void OnCmdMsg(ConstCameraCmdPtr &_msg);
875 
877  private: void CreateCamera();
878 
880  protected: std::string name;
881 
883  protected: std::string scopedName;
884 
886  protected: std::string scopedUniqueName;
887 
889  protected: sdf::ElementPtr sdf;
890 
892  protected: unsigned int windowId;
893 
895  protected: unsigned int textureWidth;
896 
898  protected: unsigned int textureHeight;
899 
901  protected: Ogre::Camera *camera;
902 
904  protected: ignition::math::Matrix4d cameraProjectiveMatrix;
905 
907  protected: bool cameraUsingIntrinsics;
908 
910  protected: Ogre::Viewport *viewport;
911 
913  protected: Ogre::SceneNode *cameraNode = nullptr;
914 
916  protected: Ogre::SceneNode *sceneNode;
917 
919  protected: unsigned char *saveFrameBuffer;
920 
922  protected: unsigned char *bayerFrameBuffer;
923 
925  protected: unsigned int saveCount;
926 
928  protected: std::string screenshotPath;
929 
931  protected: int imageFormat;
932 
934  protected: int imageWidth;
935 
937  protected: int imageHeight;
938 
940  protected: Ogre::RenderTarget *renderTarget;
941 
943  protected: Ogre::Texture *renderTexture;
944 
946  protected: bool captureData;
947 
949  protected: bool captureDataOnce;
950 
952  protected: bool newData;
953 
956 
958  protected: ScenePtr scene;
959 
961  protected: event::EventT<void(const unsigned char *,
962  unsigned int, unsigned int, unsigned int,
963  const std::string &)> newImageFrame;
964 
966  protected: std::vector<event::ConnectionPtr> connections;
967 
969  protected: std::list<msgs::Request> requests;
970 
972  protected: bool initialized;
973 
975  protected: Ogre::AnimationState *animState;
976 
979 
981  protected: std::function<void()> onAnimationComplete;
982 
985  private: std::unique_ptr<CameraPrivate> dataPtr;
986  };
988  }
989 }
990 #endif
#define NULL
Definition: CommonTypes.hh:31
rendering
Definition: RenderEngine.hh:31
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:48
A class for event processing.
Definition: Event.hh:100
Basic camera sensor.
Definition: Camera.hh:86
std::string screenshotPath
Path to saved screenshots.
Definition: Camera.hh:928
double TrackMaxDistance() const
Return the maximum distance to the tracked visual.
double FarClip() const
Get the far clip distance.
void SetTrackPosition(const ignition::math::Vector3d &_pos)
Set the position of the camera when tracking a visual.
ignition::math::Vector3d Up() const
Get the viewport up vector.
Ogre::Viewport * viewport
Viewport the ogre camera uses.
Definition: Camera.hh:910
std::string ScreenshotPath() const
Get the path to saved screenshots.
virtual void UpdateFOV()
Update the camera's field of view.
std::string ImageFormat() const
Get the string representation of the image format.
double TrackMinDistance() const
Return the minimum distance to the tracked visual.
bool IsAnimating() const
Return true if the camera is moving due to an animation.
bool TrackUseModelFrame() const
Get whether this camera's position is relative to tracked models.
float AspectRatio() const
Get the apect ratio.
void SetName(const std::string &_name)
Set the camera's name.
virtual unsigned int ImageHeight() const
Get the height of the image.
unsigned int TextureWidth() const
Get the width of the off-screen render texture.
Ogre::RenderTarget * renderTarget
Target that renders frames.
Definition: Camera.hh:940
unsigned int windowId
ID of the window that the camera is attached to.
Definition: Camera.hh:892
void ShowWireframe(const bool _s)
Set whether to view the world in wireframe.
virtual bool AttachToVisualImpl(uint32_t _id, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
Attach the camera to a scene node.
virtual bool TrackVisualImpl(VisualPtr _visual)
Set the camera to track a scene node.
bool StopVideo()
Turn off video recording.
common::Time lastRenderWallTime
Time the last frame was rendered.
Definition: Camera.hh:955
bool TrackVisualImpl(const std::string &_visualName)
Implementation of the Camera::TrackVisual call.
void SetHFOV(const ignition::math::Angle &_angle)
Set the camera FOV (horizontal)
bool cameraUsingIntrinsics
Flag for signaling the usage of camera intrinsics within OGRE.
Definition: Camera.hh:907
bool captureData
True to capture frames into an image buffer.
Definition: Camera.hh:946
unsigned int ViewportHeight() const
Get the viewport height in pixels.
unsigned int WindowId() const
Get the ID of the window this camera is rendering into.
static bool SaveFrame(const unsigned char *_image, const unsigned int _width, const unsigned int _height, const int _depth, const std::string &_format, const std::string &_filename)
Save a frame using an image buffer.
std::string ScopedName() const
Get the camera's scoped name (scene_name::camera_name)
virtual void Fini()
Finalize the camera.
Ogre::Camera * OgreCamera() const
Get a pointer to the ogre camera.
static ignition::math::Matrix4d BuildNDCMatrix(const double _left, const double _right, const double _bottom, const double _top, const double _near, const double _far)
Computes the OpenGL NDC matrix.
virtual unsigned int ImageWidth() const
Get the width of the image.
virtual bool MoveToPosition(const ignition::math::Pose3d &_pose, const double _time)
Move the camera to a position (this is an animated motion).
void AttachToVisual(const std::string &_visualName, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
Attach the camera to a scene node.
void Translate(const ignition::math::Vector3d &_direction)
Translate the camera.
void ToggleShowWireframe()
Toggle whether to view the world in wireframe.
void CreateRenderTexture(const std::string &_textureName)
Set the render target.
std::vector< event::ConnectionPtr > connections
The camera's event connections.
Definition: Camera.hh:966
virtual void SetClipDist(const float _near, const float _far)
Set the clip distances.
common::Time LastRenderWallTime() const
Get the last time the camera was rendered.
void SetTrackMinDistance(const double _dist)
Set the minimum distance between the camera and tracked visual.
void ReadPixelBuffer()
Read image data from pixel buffer.
virtual void Init()
Initialize the camera.
unsigned int ImageMemorySize() const
Get the memory size of this image.
std::string Name() const
Get the camera's unscoped name.
ScenePtr scene
Pointer to the scene.
Definition: Camera.hh:958
void Yaw(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_WORLD)
Rotate the camera around the z-axis.
void SetWindowId(unsigned int _windowId)
virtual void SetClipDist()
Set the clip distance based on stored SDF values.
unsigned int ImageDepth() const
Get the depth of the image in bytes per pixel.
bool SaveVideo(const std::string &_filename)
Save the last encoded video to disk.
virtual void RenderImpl()
Implementation of the render call.
Ogre::Texture * renderTexture
Texture that receives results from rendering.
Definition: Camera.hh:943
virtual bool AttachToVisualImpl(const std::string &_name, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
Attach the camera to a scene node.
unsigned char * saveFrameBuffer
Buffer for a single image frame.
Definition: Camera.hh:919
virtual void SetWorldPose(const ignition::math::Pose3d &_pose)
Set the global pose of the camera.
event::ConnectionPtr ConnectNewImageFrame(std::function< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
Connect to the new image signal.
void SetRenderRate(const double _hz)
Set the render Hz rate.
void AttachToVisual(uint32_t _id, const bool _inheritOrientation, const double _minDist=0.0, const double _maxDist=0.0)
Attach the camera to a scene node.
virtual bool SetBackgroundColor(const ignition::math::Color &_color)
Set background color for viewport (if viewport is not null)
void SetScene(ScenePtr _scene)
Set the scene this camera is viewing.
virtual void AnimationComplete()
Internal function used to indicate that an animation has completed.
virtual void Load()
Load the camera with default parameters.
void Roll(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
Rotate the camera around the x-axis.
unsigned int textureWidth
Width of the render texture.
Definition: Camera.hh:895
void SetTrackMaxDistance(const double _dist)
Set the maximum distance between the camera and tracked visual.
void SetWorldPosition(const ignition::math::Vector3d &_pos)
Set the world position.
ScenePtr GetScene() const
Get the scene this camera is in.
virtual void SetFixedYawAxis(const bool _useFixed, const ignition::math::Vector3d &_fixedAxis=ignition::math::Vector3d::UnitY)
Tell the camera whether to yaw around its own local Y axis or a fixed axis of choice.
int imageFormat
Format for saving images.
Definition: Camera.hh:931
bool MoveToPositions(const std::vector< ignition::math::Pose3d > &_pts, const double _time, std::function< void()> _onComplete=NULL)
Move the camera to a series of poses (this is an animated motion).
virtual unsigned int TriangleCount() const
Get the triangle count.
DistortionPtr LensDistortion() const
Get the distortion model of this camera.
void SetImageWidth(const unsigned int _w)
Set the image height.
virtual float AvgFPS() const
Get the average FPS.
double NearClip() const
Get the near clip distance.
void SetImageSize(const unsigned int _w, const unsigned int _h)
Set the image size.
bool StartVideo(const std::string &_format, const std::string &_filename="")
Turn on video recording.
unsigned int textureHeight
Height of the render texture.
Definition: Camera.hh:898
void SetWorldRotation(const ignition::math::Quaterniond &_quat)
Set the world orientation.
void SetTrackUseModelFrame(const bool _useModelFrame)
Set whether this camera's position is relative to tracked models.
virtual const unsigned char * ImageData(const unsigned int i=0) const
Get a pointer to the image data.
static double LimitFOV(const double _fov)
Limit field of view taking care of using a valid value for an OGRE camera.
unsigned int TextureHeight() const
Get the height of the off-screen render texture.
ignition::math::Vector3d Right() const
Get the viewport right vector.
virtual ~Camera()
Destructor.
ignition::math::Quaterniond WorldRotation() const
Get the camera's orientation in the world.
bool WorldPointOnPlane(const int _x, const int _y, const ignition::math::Planed &_plane, ignition::math::Vector3d &_result)
Get point on a plane.
size_t ImageByteSize() const
Get the image size in bytes.
virtual void SetRenderTarget(Ogre::RenderTarget *_target)
Set the camera's render target.
std::string FrameFilename()
Get the next frame filename based on SDF parameters.
Ogre::SceneNode * SceneNode() const
Get the camera's scene node.
std::string name
Name of the camera.
Definition: Camera.hh:880
sdf::ElementPtr sdf
Camera's SDF values.
Definition: Camera.hh:889
ignition::math::Angle HFOV() const
Get the camera FOV (horizontal)
std::list< msgs::Request > requests
List of requests.
Definition: Camera.hh:969
void SetTrackInheritYaw(const bool _inheritYaw)
Set whether this camera inherits the yaw rotation of the tracked model.
unsigned char * bayerFrameBuffer
Buffer for a bayer image frame.
Definition: Camera.hh:922
void SetAspectRatio(float _ratio)
Set the aspect ratio.
Ogre::Camera * camera
The OGRE camera.
Definition: Camera.hh:901
bool CaptureData() const
Return the value of this->captureData.
int imageHeight
Save image height.
Definition: Camera.hh:937
void UpdateCameraIntrinsics(const double _cameraIntrinsicsFx, const double _cameraIntrinsicsFy, const double _cameraIntrinsicsCx, const double _cameraIntrinsicsCy, const double _cameraIntrinsicsS)
Updates the camera intrinsics.
void SetSceneNode(Ogre::SceneNode *_node)
Set the camera's scene node.
virtual void CameraToViewportRay(const int _screenx, const int _screeny, ignition::math::Vector3d &_origin, ignition::math::Vector3d &_dir) const
Get a world space ray as cast from the camera through the viewport.
std::function< void()> onAnimationComplete
User callback for when an animation completes.
Definition: Camera.hh:981
unsigned int ViewportWidth() const
Get the viewport width in pixels.
unsigned int saveCount
Number of saved frames.
Definition: Camera.hh:925
bool TrackInheritYaw() const
Get whether this camera inherits the yaw rotation of the tracked model.
void SetCaptureDataOnce()
Capture data once and save to disk.
bool TrackIsStatic() const
Get whether this camera is static when tracking a model.
ignition::math::Pose3d WorldPose() const
Get the world pose.
void Pitch(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
Rotate the camera around the y-axis.
bool IsVisible(VisualPtr _visual)
Return true if the visual is within the camera's view frustum.
std::string scopedUniqueName
Scene scoped name of the camera with a unique ID.
Definition: Camera.hh:886
void SetImageHeight(const unsigned int _h)
Set the image height.
double ZValue(const int _x, const int _y)
Get the Z-buffer value at the given image coordinate.
Ogre::SceneNode * sceneNode
Scene node that controls camera position and orientation.
Definition: Camera.hh:916
ignition::math::Matrix4d ProjectionMatrix() const
Return the projection matrix of this camera.
virtual bool SetProjectionType(const std::string &_type)
Set the type of projection used by the camera.
void SetCaptureData(const bool _value)
Set whether to capture data.
common::Time prevAnimTime
Previous time the camera animation was updated.
Definition: Camera.hh:978
virtual void Load(sdf::ElementPtr _sdf)
Load the camera with a set of parameters.
Camera(const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
Constructor.
void SetTrackIsStatic(const bool _isStatic)
Set whether this camera is static when tracking a model.
static size_t ImageByteSize(const unsigned int _width, const unsigned int _height, const std::string &_format)
Calculate image byte size base on a few parameters.
ignition::math::Matrix4d cameraProjectiveMatrix
Camera projective matrix.
Definition: Camera.hh:904
ignition::math::Angle VFOV() const
Get the camera FOV (vertical)
static ignition::math::Matrix4d BuildProjectiveMatrix(const double _imageWidth, const double _imageHeight, const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
Computes the OpenGL projective matrix by multiplying the OpenGL Normalized Device Coordinates matrix ...
void EnableSaveFrame(const bool _enable)
Enable or disable saving.
VisualPtr TrackedVisual() const
Get the visual tracked by this camera.
Ogre::AnimationState * animState
Animation state, used to animate the camera.
Definition: Camera.hh:975
Ogre::Texture * RenderTexture() const
Get the render texture.
ignition::math::Vector3d Direction() const
Get the camera's direction vector.
static ignition::math::Matrix4d BuildPerspectiveMatrix(const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
Computes the OpenGL perspective matrix.
bool ResetVideo()
Reset video recording.
bool Initialized() const
Return true if the camera has been initialized.
void SetSaveFramePathname(const std::string &_pathname)
Set the save frame pathname.
bool SaveFrame(const std::string &_filename)
Save the last frame to disk.
static ignition::math::Matrix4d BuildProjectionMatrix(const double _imageWidth, const double _imageHeight, const double _intrinsicsFx, const double _intrinsicsFy, const double _intrinsicsCx, const double _intrinsicsCy, const double _intrinsicsS, const double _clipNear, const double _clipFar)
Computes the OpenGL projection matrix by multiplying the OpenGL Normalized Device Coordinates matrix ...
std::string scopedName
Scene scoped name of the camera.
Definition: Camera.hh:883
Ogre::Viewport * OgreViewport() const
Get a pointer to the Ogre::Viewport.
bool newData
True if new data is available.
Definition: Camera.hh:952
virtual ignition::math::Vector2i Project(const ignition::math::Vector3d &_pt) const
Project 3D world coordinates to 2D screen coordinates.
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:963
ignition::math::Vector3d TrackPosition() const
Return the position of the camera when tracking a model.
bool captureDataOnce
True to capture a frame once and save to disk.
Definition: Camera.hh:949
bool initialized
True if initialized.
Definition: Camera.hh:972
virtual void PostRender()
Post render.
virtual void Render(const bool _force=false)
Render the camera.
int imageWidth
Save image width.
Definition: Camera.hh:934
double RenderRate() const
Get the render Hz rate.
std::string ProjectionType() const
Return the projection type as a string.
void TrackVisual(const std::string &_visualName)
Set the camera to track a scene node.
ignition::math::Vector3d WorldPosition() const
Get the camera position in the world.
bool IsVisible(const std::string &_visualName)
Return true if the visual is within the camera's view frustum.
virtual bool AttachToVisualImpl(VisualPtr _visual, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0)
Attach the camera to a visual.
Definition: JointMaker.hh:40
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
std::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:114
boost::shared_ptr< Distortion > DistortionPtr
Definition: RenderTypes.hh:198
ReferenceFrame
Frame of reference.
Definition: RenderTypes.hh:245
@ RF_WORLD
World frame.
Definition: RenderTypes.hh:253
@ RF_LOCAL
Local frame.
Definition: RenderTypes.hh:247
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:82
Forward declarations for the common classes.
Definition: Animation.hh:27