Go to the documentation of this file.
17 #ifndef GAZEBO_RENDERING_CAMERA_HH_
18 #define GAZEBO_RENDERING_CAMERA_HH_
23 #include <boost/enable_shared_from_this.hpp>
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>
51 #include "gazebo/msgs/MessageTypes.hh"
85 public boost::enable_shared_from_this<Camera>
92 bool _autoRender =
true);
99 public:
virtual void Load(sdf::ElementPtr _sdf);
102 public:
virtual void Load();
111 public:
void UpdateCameraIntrinsics(
112 const double _cameraIntrinsicsFx,
const double _cameraIntrinsicsFy,
113 const double _cameraIntrinsicsCx,
const double _cameraIntrinsicsCy,
114 const double _cameraIntrinsicsS);
117 private:
virtual void LoadCameraIntrinsics();
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);
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);
175 public:
static ignition::math::Matrix4d BuildProjectiveMatrix(
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);
183 public:
virtual void Init();
187 public:
void SetRenderRate(
const double _hz);
191 public:
double RenderRate()
const;
198 public:
virtual void Render(
const bool _force =
false);
203 public:
virtual void PostRender();
210 public:
virtual void Update();
215 public:
virtual void Fini();
219 public:
bool Initialized()
const;
224 public:
void SetWindowId(
unsigned int _windowId);
228 public:
unsigned int WindowId()
const;
232 public:
void SetScene(
ScenePtr _scene);
236 public: ignition::math::Vector3d WorldPosition()
const;
240 public: ignition::math::Quaterniond WorldRotation()
const;
244 public:
virtual void SetWorldPose(
const ignition::math::Pose3d &_pose);
248 public: ignition::math::Pose3d WorldPose()
const;
252 public:
void SetWorldPosition(
const ignition::math::Vector3d &_pos);
256 public:
void SetWorldRotation(
const ignition::math::Quaterniond &_quat);
260 public:
void Translate(
const ignition::math::Vector3d &_direction);
266 public:
void Roll(
const ignition::math::Angle &_angle,
273 public:
void Pitch(
const ignition::math::Angle &_angle,
280 public:
void Yaw(
const ignition::math::Angle &_angle,
286 public:
virtual void SetClipDist(
const float _near,
const float _far);
290 public:
void SetHFOV(
const ignition::math::Angle &_angle);
294 public: ignition::math::Angle HFOV()
const;
298 public: ignition::math::Angle VFOV()
const;
303 public:
void SetImageSize(
const unsigned int _w,
const unsigned int _h);
307 public:
void SetImageWidth(
const unsigned int _w);
311 public:
void SetImageHeight(
const unsigned int _h);
315 public:
virtual unsigned int ImageWidth()
const;
319 public:
unsigned int ImageMemorySize()
const;
323 public:
unsigned int TextureWidth()
const;
327 public:
virtual unsigned int ImageHeight()
const;
331 public:
unsigned int ImageDepth()
const;
335 public: std::string ImageFormat()
const;
339 public:
unsigned int TextureHeight()
const;
343 public:
size_t ImageByteSize()
const;
350 public:
static size_t ImageByteSize(
const unsigned int _width,
351 const unsigned int _height,
352 const std::string &_format);
359 public:
double ZValue(
const int _x,
const int _y);
363 public:
double NearClip()
const;
367 public:
double FarClip()
const;
371 public:
void EnableSaveFrame(
const bool _enable);
375 public:
bool CaptureData()
const;
379 public:
void SetSaveFramePathname(
const std::string &_pathname);
384 public:
bool SaveFrame(
const std::string &_filename);
388 public: Ogre::Camera *OgreCamera()
const;
392 public: Ogre::Viewport *OgreViewport()
const;
396 public:
unsigned int ViewportWidth()
const;
400 public:
unsigned int ViewportHeight()
const;
404 public: ignition::math::Vector3d Up()
const;
408 public: ignition::math::Vector3d Right()
const;
412 public:
virtual float AvgFPS()
const;
416 public:
virtual unsigned int TriangleCount()
const;
420 public:
void SetAspectRatio(
float _ratio);
424 public:
float AspectRatio()
const;
428 public:
void SetSceneNode(Ogre::SceneNode *_node);
432 public: Ogre::SceneNode *SceneNode()
const;
439 public:
virtual const unsigned char *ImageData(
const unsigned int i = 0)
444 public: std::string Name()
const;
448 public: std::string ScopedName()
const;
452 public:
void SetName(
const std::string &_name);
455 public:
void ToggleShowWireframe();
459 public:
void ShowWireframe(
const bool _s);
463 public:
void SetCaptureData(
const bool _value);
466 public:
void SetCaptureDataOnce();
481 public:
bool StartVideo(
const std::string &_format,
482 const std::string &_filename =
"");
488 public:
bool StopVideo();
495 public:
bool SaveVideo(
const std::string &_filename);
503 public:
bool ResetVideo();
507 public:
void CreateRenderTexture(
const std::string &_textureName);
519 public:
bool WorldPointOnPlane(
const int _x,
const int _y,
520 const ignition::math::Planed &_plane,
521 ignition::math::Vector3d &_result);
530 public:
virtual void CameraToViewportRay(
const int _screenx,
532 ignition::math::Vector3d &_origin,
533 ignition::math::Vector3d &_dir)
const;
537 public:
virtual void SetRenderTarget(Ogre::RenderTarget *_target);
547 public:
void AttachToVisual(
const std::string &_visualName,
548 const bool _inheritOrientation,
549 const double _minDist = 0.0,
const double _maxDist = 0.0);
559 public:
void AttachToVisual(uint32_t _id,
560 const bool _inheritOrientation,
561 const double _minDist = 0.0,
const double _maxDist = 0.0);
565 public:
void TrackVisual(
const std::string &_visualName);
569 public: Ogre::Texture *RenderTexture()
const;
573 public: ignition::math::Vector3d Direction()
const;
580 std::function<
void (
const unsigned char *,
unsigned int,
unsigned int,
581 unsigned int,
const std::string &)> _subscriber);
591 public:
static bool SaveFrame(
const unsigned char *_image,
592 const unsigned int _width,
const unsigned int _height,
593 const int _depth,
const std::string &_format,
594 const std::string &_filename);
604 public:
bool IsVisible(
VisualPtr _visual);
610 public:
bool IsVisible(
const std::string &_visualName);
613 public:
bool IsAnimating()
const;
619 public:
virtual bool MoveToPosition(
const ignition::math::Pose3d &_pose,
629 public:
bool MoveToPositions(
630 const std::vector<ignition::math::Pose3d> &_pts,
632 std::function<
void()> _onComplete =
NULL);
636 public: std::string ScreenshotPath()
const;
647 public:
virtual bool SetProjectionType(
const std::string &_type);
652 public: std::string ProjectionType()
const;
657 public:
virtual bool SetBackgroundColor(
658 const ignition::math::Color &_color);
662 public: ignition::math::Matrix4d ProjectionMatrix()
const;
667 public:
virtual ignition::math::Vector2i Project(
668 const ignition::math::Vector3d &_pt)
const;
677 public:
bool TrackIsStatic()
const;
683 public:
void SetTrackIsStatic(
const bool _isStatic);
689 public:
bool TrackUseModelFrame()
const;
696 public:
void SetTrackUseModelFrame(
const bool _useModelFrame);
701 public: ignition::math::Vector3d TrackPosition()
const;
706 public:
void SetTrackPosition(
const ignition::math::Vector3d &_pos);
711 public:
double TrackMinDistance()
const;
716 public:
double TrackMaxDistance()
const;
722 public:
void SetTrackMinDistance(
const double _dist);
728 public:
void SetTrackMaxDistance(
const double _dist);
735 public:
bool TrackInheritYaw()
const;
742 public:
void SetTrackInheritYaw(
const bool _inheritYaw);
745 protected:
virtual void RenderImpl();
748 protected:
void ReadPixelBuffer();
753 protected:
bool TrackVisualImpl(
const std::string &_visualName);
758 protected:
virtual bool TrackVisualImpl(
VisualPtr _visual);
769 protected:
virtual bool AttachToVisualImpl(
const std::string &_name,
770 const bool _inheritOrientation,
771 const double _minDist = 0,
const double _maxDist = 0);
782 protected:
virtual bool AttachToVisualImpl(uint32_t _id,
783 const bool _inheritOrientation,
784 const double _minDist = 0,
const double _maxDist = 0);
795 protected:
virtual bool AttachToVisualImpl(
VisualPtr _visual,
796 const bool _inheritOrientation,
797 const double _minDist = 0,
const double _maxDist = 0);
801 protected: std::string FrameFilename();
805 protected:
virtual void AnimationComplete();
808 protected:
virtual void UpdateFOV();
811 protected:
virtual void SetClipDist();
817 protected:
static double LimitFOV(
const double _fov);
825 protected:
virtual void SetFixedYawAxis(
const bool _useFixed,
826 const ignition::math::Vector3d &_fixedAxis =
827 ignition::math::Vector3d::UnitY);
836 private:
void ConvertRGBToBAYER(
unsigned char *_dst,
837 const unsigned char *_src,
const std::string &_format,
838 const int _width,
const int _height);
843 private:
static int OgrePixelFormat(
const std::string &_format);
847 private:
void OnCmdMsg(ConstCameraCmdPtr &_msg);
850 private:
void CreateCamera();
862 protected: sdf::ElementPtr
sdf;
886 protected: Ogre::SceneNode *cameraNode =
nullptr;
935 unsigned int,
unsigned int,
unsigned int,
958 private: std::unique_ptr<CameraPrivate> dataPtr;
bool WorldPointOnPlane(const int _x, const int _y, const ignition::math::Planed &_plane, ignition::math::Vector3d &_result)
Get point on a plane.
virtual ~Camera()
Destructor.
bool TrackUseModelFrame() const
Get whether this camera's position is relative to tracked models.
virtual float AvgFPS() const
Get the average FPS.
unsigned int WindowId() const
Get the ID of the window this camera is rendering into.
bool TrackVisualImpl(const std::string &_visualName)
Implementation of the Camera::TrackVisual call.
float AspectRatio() const
Get the apect ratio.
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.
Definition: JointMaker.hh:39
std::string ProjectionType() const
Return the projection type as a string.
std::string scopedUniqueName
Scene scoped name of the camera with a unique ID.
Definition: Camera.hh:859
VisualPtr TrackedVisual() const
Get the visual tracked by this camera.
bool IsVisible(VisualPtr _visual)
Return true if the visual is within the camera's view frustum.
void TrackVisual(const std::string &_visualName)
Set the camera to track a scene node.
Ogre::AnimationState * animState
Animation state, used to animate the camera.
Definition: Camera.hh:948
void ShowWireframe(const bool _s)
Set whether to view the world in wireframe.
virtual void PostRender()
Post render.
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.
virtual void Init()
Initialize the camera.
void SetRenderRate(const double _hz)
Set the render Hz rate.
Forward declarations for the common classes.
Definition: Animation.hh:26
bool StopVideo()
Turn off video recording.
ReferenceFrame
Frame of reference.
Definition: RenderTypes.hh:244
void SetWindowId(unsigned int _windowId)
std::vector< event::ConnectionPtr > connections
The camera's event connections.
Definition: Camera.hh:939
A Time class, can be used to hold wall- or sim-time. stored as sec and nano-sec.
Definition: Time.hh:47
bool SaveVideo(const std::string &_filename)
Save the last encoded video to disk.
std::string Name() const
Get the camera's unscoped name.
#define NULL
Definition: CommonTypes.hh:31
void SetHFOV(const ignition::math::Angle &_angle)
Set the camera FOV (horizontal)
bool SaveFrame(const std::string &_filename)
Save the last frame to disk.
boost::shared_ptr< Distortion > DistortionPtr
Definition: RenderTypes.hh:198
@ RF_WORLD
World frame.
Definition: RenderTypes.hh:253
void SetWorldRotation(const ignition::math::Quaterniond &_quat)
Set the world orientation.
virtual void UpdateFOV()
Update the camera's field of view.
std::string ScopedName() const
Get the camera's scoped name (scene_name::camera_name)
void EnableSaveFrame(const bool _enable)
Enable or disable saving.
ScenePtr GetScene() const
Get the scene this camera is in.
Ogre::Viewport * viewport
Viewport the ogre camera uses.
Definition: Camera.hh:883
virtual unsigned int ImageWidth() const
Get the width of the image.
Ogre::Texture * renderTexture
Texture that receives results from rendering.
Definition: Camera.hh:916
void Pitch(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
Rotate the camera around the y-axis.
void Yaw(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_WORLD)
Rotate the camera around the z-axis.
void SetImageSize(const unsigned int _w, const unsigned int _h)
Set the image size.
ignition::math::Vector3d Direction() const
Get the camera's direction vector.
static double LimitFOV(const double _fov)
Limit field of view taking care of using a valid value for an OGRE camera.
sdf::ElementPtr sdf
Camera's SDF values.
Definition: Camera.hh:862
void CreateRenderTexture(const std::string &_textureName)
Set the render target.
common::Time LastRenderWallTime() const
Get the last time the camera was rendered.
virtual void RenderImpl()
Implementation of the render call.
void SetTrackPosition(const ignition::math::Vector3d &_pos)
Set the position of the camera when tracking a visual.
bool ResetVideo()
Reset video recording.
virtual void AnimationComplete()
Internal function used to indicate that an animation has completed.
void SetSceneNode(Ogre::SceneNode *_node)
Set the camera's scene node.
void SetCaptureDataOnce()
Capture data once and save to disk.
void SetTrackIsStatic(const bool _isStatic)
Set whether this camera is static when tracking a model.
size_t ImageByteSize() const
Get the image size in bytes.
unsigned int TextureWidth() const
Get the width of the off-screen render texture.
bool cameraUsingIntrinsics
Flag for signaling the usage of camera intrinsics within OGRE.
Definition: Camera.hh:880
Ogre::Camera * camera
The OGRE camera.
Definition: Camera.hh:874
void SetSaveFramePathname(const std::string &_pathname)
Set the save frame pathname.
ignition::math::Matrix4d ProjectionMatrix() const
Return the projection matrix of this camera.
@ RF_LOCAL
Local frame.
Definition: RenderTypes.hh:247
std::string ImageFormat() const
Get the string representation of the image format.
bool TrackIsStatic() const
Get whether this camera is static when tracking a model.
ignition::math::Matrix4d cameraProjectiveMatrix
Camera projective matrix.
Definition: Camera.hh:877
unsigned char * bayerFrameBuffer
Buffer for a bayer image frame.
Definition: Camera.hh:895
Ogre::RenderTarget * renderTarget
Target that renders frames.
Definition: Camera.hh:913
A class for event processing.
Definition: Event.hh:97
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.
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:82
bool initialized
True if initialized.
Definition: Camera.hh:945
void Roll(const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL)
Rotate the camera around the x-axis.
Ogre::SceneNode * SceneNode() const
Get the camera's scene node.
virtual unsigned int ImageHeight() const
Get the height of the image.
bool captureData
True to capture frames into an image buffer.
Definition: Camera.hh:919
void SetName(const std::string &_name)
Set the camera's name.
bool TrackInheritYaw() const
Get whether this camera inherits the yaw rotation of the tracked model.
void SetImageWidth(const unsigned int _w)
Set the image height.
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.
rendering
Definition: RenderEngine.hh:31
ignition::math::Vector3d TrackPosition() const
Return the position of the camera when tracking a model.
unsigned int windowId
ID of the window that the camera is attached to.
Definition: Camera.hh:865
Ogre::Viewport * OgreViewport() const
Get a pointer to the Ogre::Viewport.
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:936
void SetTrackInheritYaw(const bool _inheritYaw)
Set whether this camera inherits the yaw rotation of the tracked model.
Ogre::Texture * RenderTexture() const
Get the render texture.
std::string scopedName
Scene scoped name of the camera.
Definition: Camera.hh:856
unsigned int ImageDepth() const
Get the depth of the image in bytes per pixel.
ignition::math::Angle HFOV() const
Get the camera FOV (horizontal)
ScenePtr scene
Pointer to the scene.
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).
unsigned int saveCount
Number of saved frames.
Definition: Camera.hh:898
ignition::math::Vector3d Up() const
Get the viewport up vector.
int imageFormat
Format for saving images.
Definition: Camera.hh:904
unsigned int textureHeight
Height of the render texture.
Definition: Camera.hh:871
Ogre::SceneNode * sceneNode
Scene node that controls camera position and orientation.
Definition: Camera.hh:889
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.
virtual void SetWorldPose(const ignition::math::Pose3d &_pose)
Set the global pose of the camera.
std::string screenshotPath
Path to saved screenshots.
Definition: Camera.hh:901
double FarClip() const
Get the far clip distance.
bool StartVideo(const std::string &_format, const std::string &_filename="")
Turn on video recording.
void SetTrackMaxDistance(const double _dist)
Set the maximum distance between the camera and tracked visual.
virtual unsigned int TriangleCount() const
Get the triangle count.
void Translate(const ignition::math::Vector3d &_direction)
Translate the camera.
double RenderRate() const
Get the render Hz rate.
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:134
std::function< void()> onAnimationComplete
User callback for when an animation completes.
Definition: Camera.hh:954
virtual const unsigned char * ImageData(const unsigned int i=0) const
Get a pointer to the image data.
double ZValue(const int _x, const int _y)
Get the Z-buffer value at the given image coordinate.
unsigned int TextureHeight() const
Get the height of the off-screen render texture.
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual void SetRenderTarget(Ogre::RenderTarget *_target)
Set the camera's render target.
std::string ScreenshotPath() const
Get the path to saved screenshots.
double TrackMaxDistance() const
Return the maximum distance to the tracked visual.
std::list< msgs::Request > requests
List of requests.
Definition: Camera.hh:942
virtual void Render(const bool _force=false)
Render the camera.
bool newData
True if new data is available.
Definition: Camera.hh:925
void ReadPixelBuffer()
Read image data from pixel buffer.
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.
virtual void SetClipDist()
Set the clip distance based on stored SDF values.
void SetAspectRatio(float _ratio)
Set the aspect ratio.
common::Time prevAnimTime
Previous time the camera animation was updated.
Definition: Camera.hh:951
bool CaptureData() const
Return the value of this->captureData.
void SetWorldPosition(const ignition::math::Vector3d &_pos)
Set the world position.
ignition::math::Vector3d Right() const
Get the viewport right vector.
ignition::math::Vector3d WorldPosition() const
Get the camera position in the world.
common::Time lastRenderWallTime
Time the last frame was rendered.
Definition: Camera.hh:928
virtual void Load()
Load the camera with default parameters.
void UpdateCameraIntrinsics(const double _cameraIntrinsicsFx, const double _cameraIntrinsicsFy, const double _cameraIntrinsicsCx, const double _cameraIntrinsicsCy, const double _cameraIntrinsicsS)
Updates the camera intrinsics.
virtual void Fini()
Finalize the camera.
double NearClip() const
Get the near clip distance.
void SetTrackMinDistance(const double _dist)
Set the minimum distance between the camera and tracked visual.
bool Initialized() const
Return true if the camera has been initialized.
bool IsAnimating() const
Return true if the camera is moving due to an animation.
std::shared_ptr< Visual > VisualPtr
Definition: RenderTypes.hh:114
std::string name
Name of the camera.
Definition: Camera.hh:853
void SetScene(ScenePtr _scene)
Set the scene this camera is viewing.
unsigned char * saveFrameBuffer
Buffer for a single image frame.
Definition: Camera.hh:892
Ogre::Camera * OgreCamera() const
Get a pointer to the ogre camera.
virtual bool SetBackgroundColor(const ignition::math::Color &_color)
Set background color for viewport (if viewport is not null)
int imageWidth
Save image width.
Definition: Camera.hh:907
void ToggleShowWireframe()
Toggle whether to view the world in wireframe.
unsigned int ViewportHeight() const
Get the viewport height in pixels.
unsigned int textureWidth
Width of the render texture.
Definition: Camera.hh:868
bool captureDataOnce
True to capture a frame once and save to disk.
Definition: Camera.hh:922
ignition::math::Quaterniond WorldRotation() const
Get the camera's orientation in the world.
Camera(const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true)
Constructor.
DistortionPtr LensDistortion() const
Get the distortion model of this camera.
Basic camera sensor.
Definition: Camera.hh:84
unsigned int ViewportWidth() const
Get the viewport width in pixels.
virtual bool MoveToPosition(const ignition::math::Pose3d &_pose, const double _time)
Move the camera to a position (this is an animated motion).
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.
virtual bool SetProjectionType(const std::string &_type)
Set the type of projection used by the camera.
unsigned int ImageMemorySize() const
Get the memory size of this image.
int imageHeight
Save image height.
Definition: Camera.hh:910
ignition::math::Angle VFOV() const
Get the camera FOV (vertical)
void SetTrackUseModelFrame(const bool _useModelFrame)
Set whether this camera's position is relative to tracked models.
virtual ignition::math::Vector2i Project(const ignition::math::Vector3d &_pt) const
Project 3D world coordinates to 2D screen coordinates.
void SetCaptureData(const bool _value)
Set whether to capture data.
std::string FrameFilename()
Get the next frame filename based on SDF parameters.
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 SetImageHeight(const unsigned int _h)
Set the image height.
Ogre::SceneNode * cameraNode
Scene node that the camera is attached to.
Definition: Camera.hh:886
ignition::math::Pose3d WorldPose() const
Get the world pose.
double TrackMinDistance() const
Return the minimum distance to the tracked visual.