Basic camera sensor. More...
#include <rendering/rendering.hh>
Inherits enable_shared_from_this< Camera >.
Inherited by DepthCamera, GpuLaser, OculusCamera, UserCamera, and WideAngleCamera.
Public Member Functions | |
| Camera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true) | |
| Constructor.  More... | |
| virtual | ~Camera () | 
| Destructor.  More... | |
| float | AspectRatio () const | 
| Get the apect ratio.  More... | |
| 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.  More... | |
| 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.  More... | |
| virtual float | AvgFPS () const | 
| Get the average FPS.  More... | |
| 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.  More... | |
| bool | CaptureData () const | 
| Return the value of this->captureData.  More... | |
| 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.  More... | |
| void | CreateRenderTexture (const std::string &_textureName) | 
| Set the render target.  More... | |
| ignition::math::Vector3d | Direction () const | 
| Get the camera's direction vector.  More... | |
| void | DisconnectNewImageFrame (event::ConnectionPtr &_c) | 
| Disconnect from an image frame.  More... | |
| void | EnableSaveFrame (const bool _enable) | 
| Enable or disable saving.  More... | |
| double | FarClip () const | 
| Get the far clip distance.  More... | |
| virtual void | Fini () | 
| Finalize the camera.  More... | |
| float | GetAspectRatio () const GAZEBO_DEPRECATED(7.0) | 
| Get the apect ratio.  More... | |
| virtual float | GetAvgFPS () const GAZEBO_DEPRECATED(7.0) | 
| Get the average FPS.  More... | |
| void | GetCameraToViewportRay (int _screenx, int _screeny, math::Vector3 &_origin, math::Vector3 &_dir) GAZEBO_DEPRECATED(7.0) | 
| Get a world space ray as cast from the camera through the viewport.  More... | |
| bool | GetCaptureData () const GAZEBO_DEPRECATED(7.0) | 
| Return the value of this->captureData.  More... | |
| math::Vector3 | GetDirection () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera's direction vector.  More... | |
| DistortionPtr | GetDistortion () const GAZEBO_DEPRECATED(7.0) | 
| Get the distortion model of this camera.  More... | |
| double | GetFarClip () GAZEBO_DEPRECATED(7.0) | 
| Get the far clip distance.  More... | |
| math::Angle | GetHFOV () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera FOV (horizontal)  More... | |
| size_t | GetImageByteSize () const GAZEBO_DEPRECATED(7.0) | 
| Get the image size in bytes.  More... | |
| virtual const unsigned char * | GetImageData (unsigned int i=0) GAZEBO_DEPRECATED(7.0) | 
| Get a pointer to the image data.  More... | |
| unsigned int | GetImageDepth () const GAZEBO_DEPRECATED(7.0) | 
| Get the depth of the image.  More... | |
| std::string | GetImageFormat () const GAZEBO_DEPRECATED(7.0) | 
| Get the string representation of the image format.  More... | |
| virtual unsigned int | GetImageHeight () const GAZEBO_DEPRECATED(7.0) | 
| Get the height of the image.  More... | |
| virtual unsigned int | GetImageWidth () const GAZEBO_DEPRECATED(7.0) | 
| Get the width of the image.  More... | |
| bool | GetInitialized () const GAZEBO_DEPRECATED(7.0) | 
| Return true if the camera has been initialized.  More... | |
| common::Time | GetLastRenderWallTime () GAZEBO_DEPRECATED(7.0) | 
| Get the last time the camera was rendered.  More... | |
| std::string | GetName () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera's unscoped name.  More... | |
| double | GetNearClip () GAZEBO_DEPRECATED(7.0) | 
| Get the near clip distance.  More... | |
| Ogre::Camera * | GetOgreCamera () const GAZEBO_DEPRECATED(7.0) | 
| Get a pointer to the ogre camera.  More... | |
| std::string | GetProjectionType () const GAZEBO_DEPRECATED(7.0) | 
| Return the projection type as a string.  More... | |
| double | GetRenderRate () const GAZEBO_DEPRECATED(7.0) | 
| Get the render Hz rate.  More... | |
| Ogre::Texture * | GetRenderTexture () const GAZEBO_DEPRECATED(7.0) | 
| Get the render texture.  More... | |
| math::Vector3 | GetRight () GAZEBO_DEPRECATED(7.0) | 
| Get the viewport right vector.  More... | |
| ScenePtr | GetScene () const | 
| Get the scene this camera is in.  More... | |
| Ogre::SceneNode * | GetSceneNode () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera's scene node.  More... | |
| std::string | GetScopedName () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera's scoped name (scene_name::camera_name)  More... | |
| std::string | GetScreenshotPath () const GAZEBO_DEPRECATED(7.0) | 
| Get the path to saved screenshots.  More... | |
| unsigned int | GetTextureHeight () const GAZEBO_DEPRECATED(7.0) | 
| Get the height of the off-screen render texture.  More... | |
| unsigned int | GetTextureWidth () const GAZEBO_DEPRECATED(7.0) | 
| Get the width of the off-screen render texture.  More... | |
| virtual unsigned int | GetTriangleCount () const GAZEBO_DEPRECATED(7.0) | 
| Get the triangle count.  More... | |
| math::Vector3 | GetUp () GAZEBO_DEPRECATED(7.0) | 
| Get the viewport up vector.  More... | |
| math::Angle | GetVFOV () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera FOV (vertical)  More... | |
| Ogre::Viewport * | GetViewport () const GAZEBO_DEPRECATED(7.0) | 
| Get a pointer to the Ogre::Viewport.  More... | |
| unsigned int | GetViewportHeight () const GAZEBO_DEPRECATED(7.0) | 
| Get the viewport height in pixels.  More... | |
| unsigned int | GetViewportWidth () const GAZEBO_DEPRECATED(7.0) | 
| Get the viewport width in pixels.  More... | |
| unsigned int | GetWindowId () const GAZEBO_DEPRECATED(7.0) | 
| Get the ID of the window this camera is rendering into.  More... | |
| bool | GetWorldPointOnPlane (int _x, int _y, const math::Plane &_plane, math::Vector3 &_result) GAZEBO_DEPRECATED(7.0) | 
| Get point on a plane.  More... | |
| math::Pose | GetWorldPose () const GAZEBO_DEPRECATED(7.0) | 
| Get the world pose.  More... | |
| math::Vector3 | GetWorldPosition () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera position in the world.  More... | |
| math::Quaternion | GetWorldRotation () const GAZEBO_DEPRECATED(7.0) | 
| Get the camera's orientation in the world.  More... | |
| double | GetZValue (int _x, int _y) GAZEBO_DEPRECATED(7.0) | 
| Get the Z-buffer value at the given image coordinate.  More... | |
| ignition::math::Angle | HFOV () const | 
| Get the camera FOV (horizontal)  More... | |
| size_t | ImageByteSize () const | 
| Get the image size in bytes.  More... | |
| virtual const unsigned char * | ImageData (const unsigned int i=0) const | 
| Get a pointer to the image data.  More... | |
| unsigned int | ImageDepth () const | 
| Get the depth of the image.  More... | |
| std::string | ImageFormat () const | 
| Get the string representation of the image format.  More... | |
| virtual unsigned int | ImageHeight () const | 
| Get the height of the image.  More... | |
| virtual unsigned int | ImageWidth () const | 
| Get the width of the image.  More... | |
| virtual void | Init () | 
| Initialize the camera.  More... | |
| bool | Initialized () const | 
| Return true if the camera has been initialized.  More... | |
| bool | IsAnimating () const | 
| Return true if the camera is moving due to an animation.  More... | |
| bool | IsVisible (VisualPtr _visual) | 
| Return true if the visual is within the camera's view frustum.  More... | |
| bool | IsVisible (const std::string &_visualName) | 
| Return true if the visual is within the camera's view frustum.  More... | |
| common::Time | LastRenderWallTime () const | 
| Get the last time the camera was rendered.  More... | |
| DistortionPtr | LensDistortion () const | 
| Get the distortion model of this camera.  More... | |
| virtual void | Load (sdf::ElementPtr _sdf) | 
| Load the camera with a set of parmeters.  More... | |
| virtual void | Load () | 
| Load the camera with default parmeters.  More... | |
| virtual bool | MoveToPosition (const math::Pose &_pose, double _time) GAZEBO_DEPRECATED(7.0) | 
| Move the camera to a position (this is an animated motion).  More... | |
| virtual bool | MoveToPosition (const ignition::math::Pose3d &_pose, const double _time) | 
| Move the camera to a position (this is an animated motion).  More... | |
| bool | MoveToPositions (const std::vector< math::Pose > &_pts, double _time, std::function< void()> _onComplete=NULL) GAZEBO_DEPRECATED(7.0) | 
| Move the camera to a series of poses (this is an animated motion).  More... | |
| 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).  More... | |
| std::string | Name () const | 
| Get the camera's unscoped name.  More... | |
| double | NearClip () const | 
| Get the near clip distance.  More... | |
| Ogre::Camera * | OgreCamera () const | 
| Get a pointer to the ogre camera.  More... | |
| Ogre::Viewport * | OgreViewport () const | 
| Get a pointer to the Ogre::Viewport.  More... | |
| void | Pitch (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0) | 
| Rotate the camera around the y-axis.  More... | |
| void | Pitch (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL) | 
| Rotate the camera around the y-axis.  More... | |
| virtual void | PostRender () | 
| Post render.  More... | |
| ignition::math::Vector2i | Project (const ignition::math::Vector3d &_pt) const | 
| Project 3D world coordinates to 2D screen coordinates.  More... | |
| ignition::math::Matrix4d | ProjectionMatrix () const | 
| Return the projection matrix of this camera.  More... | |
| std::string | ProjectionType () const | 
| Return the projection type as a string.  More... | |
| void | Render (const bool _force=false) | 
| Render the camera.  More... | |
| double | RenderRate () const | 
| Get the render Hz rate.  More... | |
| Ogre::Texture * | RenderTexture () const | 
| Get the render texture.  More... | |
| ignition::math::Vector3d | Right () const | 
| Get the viewport right vector.  More... | |
| void | Roll (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_LOCAL) GAZEBO_DEPRECATED(7.0) | 
| Rotate the camera around the x-axis.  More... | |
| void | Roll (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL) | 
| Rotate the camera around the x-axis.  More... | |
| bool | SaveFrame (const std::string &_filename) | 
| Save the last frame to disk.  More... | |
| Ogre::SceneNode * | SceneNode () const | 
| Get the camera's scene node.  More... | |
| std::string | ScopedName () const | 
| Get the camera's scoped name (scene_name::camera_name)  More... | |
| std::string | ScreenshotPath () const | 
| Get the path to saved screenshots.  More... | |
| void | SetAspectRatio (float _ratio) | 
| Set the aspect ratio.  More... | |
| void | SetCaptureData (const bool _value) | 
| Set whether to capture data.  More... | |
| void | SetCaptureDataOnce () | 
| Capture data once and save to disk.  More... | |
| virtual void | SetClipDist (const float _near, const float _far) | 
| Set the clip distances.  More... | |
| void | SetHFOV (math::Angle _angle) GAZEBO_DEPRECATED(7.0) | 
| Set the camera FOV (horizontal)  More... | |
| void | SetHFOV (const ignition::math::Angle &_angle) | 
| Set the camera FOV (horizontal)  More... | |
| void | SetImageHeight (const unsigned int _h) | 
| Set the image height.  More... | |
| void | SetImageSize (const unsigned int _w, const unsigned int _h) | 
| Set the image size.  More... | |
| void | SetImageWidth (const unsigned int _w) | 
| Set the image height.  More... | |
| void | SetName (const std::string &_name) | 
| Set the camera's name.  More... | |
| virtual bool | SetProjectionType (const std::string &_type) | 
| Set the type of projection used by the camera.  More... | |
| void | SetRenderRate (const double _hz) | 
| Set the render Hz rate.  More... | |
| virtual void | SetRenderTarget (Ogre::RenderTarget *_target) | 
| Set the camera's render target.  More... | |
| void | SetSaveFramePathname (const std::string &_pathname) | 
| Set the save frame pathname.  More... | |
| void | SetScene (ScenePtr _scene) | 
| Set the scene this camera is viewing.  More... | |
| void | SetSceneNode (Ogre::SceneNode *_node) | 
| Set the camera's scene node.  More... | |
| void | SetWindowId (unsigned int _windowId) | 
| virtual void | SetWorldPose (const math::Pose &_pose) GAZEBO_DEPRECATED(7.0) | 
| Set the global pose of the camera.  More... | |
| virtual void | SetWorldPose (const ignition::math::Pose3d &_pose) | 
| Set the global pose of the camera.  More... | |
| void | SetWorldPosition (const math::Vector3 &_pos) GAZEBO_DEPRECATED(7.0) | 
| Set the world position.  More... | |
| void | SetWorldPosition (const ignition::math::Vector3d &_pos) | 
| Set the world position.  More... | |
| void | SetWorldRotation (const math::Quaternion &_quat) GAZEBO_DEPRECATED(7.0) | 
| Set the world orientation.  More... | |
| void | SetWorldRotation (const ignition::math::Quaterniond &_quat) | 
| Set the world orientation.  More... | |
| void | ShowWireframe (const bool _s) | 
| Set whether to view the world in wireframe.  More... | |
| unsigned int | TextureHeight () const | 
| Get the height of the off-screen render texture.  More... | |
| unsigned int | TextureWidth () const | 
| Get the width of the off-screen render texture.  More... | |
| void | ToggleShowWireframe () | 
| Toggle whether to view the world in wireframe.  More... | |
| void | TrackVisual (const std::string &_visualName) | 
| Set the camera to track a scene node.  More... | |
| void | Translate (const math::Vector3 &_direction) GAZEBO_DEPRECATED(7.0) | 
| Translate the camera.  More... | |
| void | Translate (const ignition::math::Vector3d &_direction) | 
| Translate the camera.  More... | |
| virtual unsigned int | TriangleCount () const | 
| Get the triangle count.  More... | |
| ignition::math::Vector3d | Up () const | 
| Get the viewport up vector.  More... | |
| virtual void | Update () | 
| ignition::math::Angle | VFOV () const | 
| Get the camera FOV (vertical)  More... | |
| unsigned int | ViewportHeight () const | 
| Get the viewport height in pixels.  More... | |
| unsigned int | ViewportWidth () const | 
| Get the viewport width in pixels.  More... | |
| unsigned int | WindowId () const | 
| Get the ID of the window this camera is rendering into.  More... | |
| bool | WorldPointOnPlane (const int _x, const int _y, const ignition::math::Planed &_plane, ignition::math::Vector3d &_result) | 
| Get point on a plane.  More... | |
| ignition::math::Pose3d | WorldPose () const | 
| Get the world pose.  More... | |
| ignition::math::Vector3d | WorldPosition () const | 
| Get the camera position in the world.  More... | |
| ignition::math::Quaterniond | WorldRotation () const | 
| Get the camera's orientation in the world.  More... | |
| void | Yaw (const math::Angle &_angle, Ogre::Node::TransformSpace _relativeTo=Ogre::Node::TS_WORLD) GAZEBO_DEPRECATED(7.0) | 
| Rotate the camera around the z-axis.  More... | |
| void | Yaw (const ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_WORLD) | 
| Rotate the camera around the z-axis.  More... | |
| double | ZValue (const int _x, const int _y) | 
| Get the Z-buffer value at the given image coordinate.  More... | |
Static Public Member Functions | |
| static size_t | GetImageByteSize (unsigned int _width, unsigned int _height, const std::string &_format) GAZEBO_DEPRECATED(7.0) | 
| Calculate image byte size base on a few parameters.  More... | |
| 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.  More... | |
| 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.  More... | |
Protected Member Functions | |
| virtual void | AnimationComplete () | 
| Internal function used to indicate that an animation has completed.  More... | |
| 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.  More... | |
| virtual bool | AttachToVisualImpl (uint32_t _id, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0) | 
| Attach the camera to a scene node.  More... | |
| virtual bool | AttachToVisualImpl (VisualPtr _visual, const bool _inheritOrientation, const double _minDist=0, const double _maxDist=0) | 
| Attach the camera to a visual.  More... | |
| std::string | FrameFilename () | 
| Get the next frame filename based on SDF parameters.  More... | |
| std::string | GetFrameFilename () GAZEBO_DEPRECATED(7.0) | 
| Get the next frame filename based on SDF parameters.  More... | |
| void | ReadPixelBuffer () | 
| Read image data from pixel buffer.  More... | |
| virtual void | RenderImpl () | 
| Implementation of the render call.  More... | |
| bool | TrackVisualImpl (const std::string &_visualName) | 
| Implementation of the Camera::TrackVisual call.  More... | |
| virtual bool | TrackVisualImpl (VisualPtr _visual) | 
| Set the camera to track a scene node.  More... | |
| virtual void | UpdateFOV () | 
| Update the camera's field of view.  More... | |
Protected Attributes | |
| Ogre::AnimationState * | animState | 
| Animation state, used to animate the camera.  More... | |
| unsigned char * | bayerFrameBuffer | 
| Buffer for a bayer image frame.  More... | |
| Ogre::Camera * | camera | 
| The OGRE camera.  More... | |
| bool | captureData | 
| True to capture frames into an image buffer.  More... | |
| bool | captureDataOnce | 
| True to capture a frame once and save to disk.  More... | |
| std::vector< event::ConnectionPtr > | connections | 
| The camera's event connections.  More... | |
| int | imageFormat | 
| Format for saving images.  More... | |
| int | imageHeight | 
| Save image height.  More... | |
| int | imageWidth | 
| Save image width.  More... | |
| bool | initialized | 
| True if initialized.  More... | |
| common::Time | lastRenderWallTime | 
| Time the last frame was rendered.  More... | |
| std::string | name | 
| Name of the camera.  More... | |
| bool | newData | 
| True if new data is available.  More... | |
| event::EventT< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> | newImageFrame | 
| Event triggered when a new frame is generated.  More... | |
| std::function< void()> | onAnimationComplete | 
| User callback for when an animation completes.  More... | |
| common::Time | prevAnimTime | 
| Previous time the camera animation was updated.  More... | |
| Ogre::RenderTarget * | renderTarget | 
| Target that renders frames.  More... | |
| Ogre::Texture * | renderTexture | 
| Texture that receives results from rendering.  More... | |
| std::list< msgs::Request > | requests | 
| List of requests.  More... | |
| unsigned int | saveCount | 
| Number of saved frames.  More... | |
| unsigned char * | saveFrameBuffer | 
| Buffer for a single image frame.  More... | |
| ScenePtr | scene | 
| Pointer to the scene.  More... | |
| Ogre::SceneNode * | sceneNode | 
| Scene node that controls camera position and orientation.  More... | |
| std::string | scopedName | 
| Scene scoped name of the camera.  More... | |
| std::string | scopedUniqueName | 
| Scene scoped name of the camera with a unique ID.  More... | |
| std::string | screenshotPath | 
| Path to saved screenshots.  More... | |
| sdf::ElementPtr | sdf | 
| Camera's SDF values.  More... | |
| unsigned int | textureHeight | 
| Height of the render texture.  More... | |
| unsigned int | textureWidth | 
| Width of the render texture.  More... | |
| Ogre::Viewport * | viewport | 
| Viewport the ogre camera uses.  More... | |
| unsigned int | windowId | 
| ID of the window that the camera is attached to.  More... | |
Basic camera sensor.
This is the base class for all cameras.
Constructor.
| [in] | _namePrefix | Unique prefix name for the camera. | 
| [in] | _scene | Scene that will contain the camera | 
| [in] | _autoRender | Almost everyone should leave this as true. | 
      
  | 
  virtual | 
Destructor.
      
  | 
  protectedvirtual | 
Internal function used to indicate that an animation has completed.
Reimplemented in UserCamera.
| float AspectRatio | ( | ) | const | 
Get the apect ratio.
| 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.
| [in] | _visualName | Name of the visual to attach the camera to | 
| [in] | _inheritOrientation | True means camera acquires the visual's orientation | 
| [in] | _minDist | Minimum distance the camera is allowed to get to the visual | 
| [in] | _maxDist | Maximum distance the camera is allowd to get from the visual | 
| 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.
| [in] | _id | ID of the visual to attach the camera to | 
| [in] | _inheritOrientation | True means camera acquires the visual's orientation | 
| [in] | _minDist | Minimum distance the camera is allowed to get to the visual | 
| [in] | _maxDist | Maximum distance the camera is allowd to get from the visual | 
      
  | 
  protectedvirtual | 
Attach the camera to a scene node.
| [in] | _visualName | Name of the visual to attach the camera to | 
| [in] | _inheritOrientation | True means camera acquires the visual's orientation | 
| [in] | _minDist | Minimum distance the camera is allowed to get to the visual | 
| [in] | _maxDist | Maximum distance the camera is allowd to get from the visual | 
      
  | 
  protectedvirtual | 
Attach the camera to a scene node.
| [in] | _id | ID of the visual to attach the camera to | 
| [in] | _inheritOrientation | True means camera acquires the visual's orientation | 
| [in] | _minDist | Minimum distance the camera is allowed to get to the visual | 
| [in] | _maxDist | Maximum distance the camera is allowd to get from the visual | 
      
  | 
  protectedvirtual | 
Attach the camera to a visual.
| [in] | _visual | The visual to attach the camera to | 
| [in] | _inheritOrientation | True means camera acquires the visual's orientation | 
| [in] | _minDist | Minimum distance the camera is allowed to get to the visual | 
| [in] | _maxDist | Maximum distance the camera is allowd to get from the visual | 
Reimplemented in UserCamera, and OculusCamera.
      
  | 
  virtual | 
Get the average FPS.
| 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.
| [in] | _screenx | X coordinate in the camera's viewport, in pixels. | 
| [in] | _screeny | Y coordinate in the camera's viewport, in pixels. | 
| [out] | _origin | Origin in the world coordinate frame of the resulting ray | 
| [out] | _dir | Direction of the resulting ray | 
| bool CaptureData | ( | ) | const | 
Return the value of this->captureData.
| 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.
| [in] | _subscriber | Callback that is called when a new image is generated | 
| void CreateRenderTexture | ( | const std::string & | _textureName | ) | 
Set the render target.
| [in] | _textureName | Name of the new render texture | 
| ignition::math::Vector3d Direction | ( | ) | const | 
Get the camera's direction vector.
| void DisconnectNewImageFrame | ( | event::ConnectionPtr & | _c | ) | 
Disconnect from an image frame.
| [in] | _c | The connection to disconnect | 
| void EnableSaveFrame | ( | const bool | _enable | ) | 
Enable or disable saving.
| [in] | _enable | Set to True to enable saving of frames | 
| double FarClip | ( | ) | const | 
Get the far clip distance.
      
  | 
  virtual | 
Finalize the camera.
This function is called before the camera is destructed
Reimplemented in WideAngleCamera, GpuLaser, DepthCamera, UserCamera, and OculusCamera.
      
  | 
  protected | 
Get the next frame filename based on SDF parameters.
| float GetAspectRatio | ( | ) | const | 
Get the apect ratio.
      
  | 
  virtual | 
| void GetCameraToViewportRay | ( | int | _screenx, | 
| int | _screeny, | ||
| math::Vector3 & | _origin, | ||
| math::Vector3 & | _dir | ||
| ) | 
Get a world space ray as cast from the camera through the viewport.
| [in] | _screenx | X coordinate in the camera's viewport, in pixels. | 
| [in] | _screeny | Y coordinate in the camera's viewport, in pixels. | 
| [out] | _origin | Origin in the world coordinate frame of the resulting ray | 
| [out] | _dir | Direction of the resulting ray | 
| bool GetCaptureData | ( | ) | const | 
Return the value of this->captureData.
| math::Vector3 GetDirection | ( | ) | const | 
Get the camera's direction vector.
| DistortionPtr GetDistortion | ( | ) | const | 
Get the distortion model of this camera.
| double GetFarClip | ( | ) | 
      
  | 
  protected | 
Get the next frame filename based on SDF parameters.
| math::Angle GetHFOV | ( | ) | const | 
Get the camera FOV (horizontal)
| size_t GetImageByteSize | ( | ) | const | 
      
  | 
  static | 
Calculate image byte size base on a few parameters.
| [in] | _width | Width of an image | 
| [in] | _height | Height of an image | 
| [in] | _format | Image format | 
      
  | 
  virtual | 
Get a pointer to the image data.
Get the raw image data from a camera's buffer.
| [in] | _i | Index of the camera's texture (0 = RGB, 1 = depth). | 
| unsigned int GetImageDepth | ( | ) | const | 
| std::string GetImageFormat | ( | ) | const | 
Get the string representation of the image format.
      
  | 
  virtual | 
      
  | 
  virtual | 
| bool GetInitialized | ( | ) | const | 
Return true if the camera has been initialized.
| common::Time GetLastRenderWallTime | ( | ) | 
Get the last time the camera was rendered.
| std::string GetName | ( | ) | const | 
| double GetNearClip | ( | ) | 
| Ogre::Camera* GetOgreCamera | ( | ) | const | 
| std::string GetProjectionType | ( | ) | const | 
Return the projection type as a string.
| double GetRenderRate | ( | ) | const | 
| Ogre::Texture* GetRenderTexture | ( | ) | const | 
| math::Vector3 GetRight | ( | ) | 
Get the viewport right vector.
| ScenePtr GetScene | ( | ) | const | 
Get the scene this camera is in.
| Ogre::SceneNode* GetSceneNode | ( | ) | const | 
Get the camera's scene node.
| std::string GetScopedName | ( | ) | const | 
Get the camera's scoped name (scene_name::camera_name)
| std::string GetScreenshotPath | ( | ) | const | 
Get the path to saved screenshots.
| unsigned int GetTextureHeight | ( | ) | const | 
Get the height of the off-screen render texture.
| unsigned int GetTextureWidth | ( | ) | const | 
Get the width of the off-screen render texture.
      
  | 
  virtual | 
| math::Vector3 GetUp | ( | ) | 
Get the viewport up vector.
| math::Angle GetVFOV | ( | ) | const | 
Get the camera FOV (vertical)
| Ogre::Viewport* GetViewport | ( | ) | const | 
Get a pointer to the Ogre::Viewport.
| unsigned int GetViewportHeight | ( | ) | const | 
| unsigned int GetViewportWidth | ( | ) | const | 
| unsigned int GetWindowId | ( | ) | const | 
Get the ID of the window this camera is rendering into.
| bool GetWorldPointOnPlane | ( | int | _x, | 
| int | _y, | ||
| const math::Plane & | _plane, | ||
| math::Vector3 & | _result | ||
| ) | 
Get point on a plane.
| [in] | _x | X cooridnate in camera's viewport, in pixels | 
| [in] | _y | Y cooridnate in camera's viewport, in pixels | 
| [in] | _plane | Plane on which to find the intersecting point | 
| [out] | _result | Point on the plane | 
| math::Pose GetWorldPose | ( | ) | const | 
Get the world pose.
| math::Vector3 GetWorldPosition | ( | ) | const | 
Get the camera position in the world.
| math::Quaternion GetWorldRotation | ( | ) | const | 
Get the camera's orientation in the world.
| double GetZValue | ( | int | _x, | 
| int | _y | ||
| ) | 
Get the Z-buffer value at the given image coordinate.
| [in] | _x | Image coordinate; (0, 0) specifies the top-left corner. | 
| [in] | _y | Image coordinate; (0, 0) specifies the top-left corner. | 
| ignition::math::Angle HFOV | ( | ) | const | 
Get the camera FOV (horizontal)
| size_t ImageByteSize | ( | ) | const | 
Get the image size in bytes.
      
  | 
  static | 
Calculate image byte size base on a few parameters.
| [in] | _width | Width of an image | 
| [in] | _height | Height of an image | 
| [in] | _format | Image format | 
      
  | 
  virtual | 
Get a pointer to the image data.
Get the raw image data from a camera's buffer.
| [in] | _i | Index of the camera's texture (0 = RGB, 1 = depth). | 
| unsigned int ImageDepth | ( | ) | const | 
Get the depth of the image.
| std::string ImageFormat | ( | ) | const | 
Get the string representation of the image format.
      
  | 
  virtual | 
Get the height of the image.
      
  | 
  virtual | 
Get the width of the image.
      
  | 
  virtual | 
Initialize the camera.
Reimplemented in WideAngleCamera, GpuLaser, DepthCamera, UserCamera, and OculusCamera.
| 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.
| bool IsVisible | ( | VisualPtr | _visual | ) | 
Return true if the visual is within the camera's view frustum.
| [in] | _visual | The visual to check for visibility | 
| bool IsVisible | ( | const std::string & | _visualName | ) | 
Return true if the visual is within the camera's view frustum.
| [in] | _visualName | Name of the visual to check for visibility | 
| common::Time LastRenderWallTime | ( | ) | const | 
Get the last time the camera was rendered.
| DistortionPtr LensDistortion | ( | ) | const | 
Get the distortion model of this camera.
      
  | 
  virtual | 
Load the camera with a set of parmeters.
| [in] | _sdf | The SDF camera info | 
Reimplemented in GpuLaser, DepthCamera, UserCamera, and OculusCamera.
      
  | 
  virtual | 
Load the camera with default parmeters.
Reimplemented in WideAngleCamera, GpuLaser, DepthCamera, UserCamera, and OculusCamera.
      
  | 
  virtual | 
Move the camera to a position (this is an animated motion).
| [in] | _pose | End position of the camera | 
| [in] | _time | Duration of the camera's movement | 
Reimplemented in UserCamera, and OculusCamera.
      
  | 
  virtual | 
Move the camera to a position (this is an animated motion).
| [in] | _pose | End position of the camera | 
| [in] | _time | Duration of the camera's movement | 
| bool MoveToPositions | ( | const std::vector< math::Pose > & | _pts, | 
| double | _time, | ||
| std::function< void()> | _onComplete = NULL  | 
        ||
| ) | 
Move the camera to a series of poses (this is an animated motion).
| [in] | _pts | Vector of poses to move to | 
| [in] | _time | Duration of the entire move | 
| [in] | _onComplete | Callback that is called when the move is complete | 
| 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).
| [in] | _pts | Vector of poses to move to | 
| [in] | _time | Duration of the entire move | 
| [in] | _onComplete | Callback that is called when the move is complete | 
| std::string Name | ( | ) | const | 
Get the camera's unscoped name.
| double NearClip | ( | ) | const | 
Get the near clip distance.
| Ogre::Camera* OgreCamera | ( | ) | const | 
Get a pointer to the ogre camera.
| Ogre::Viewport* OgreViewport | ( | ) | const | 
Get a pointer to the Ogre::Viewport.
| void Pitch | ( | const math::Angle & | _angle, | 
| Ogre::Node::TransformSpace | _relativeTo = Ogre::Node::TS_LOCAL  | 
        ||
| ) | 
Rotate the camera around the y-axis.
| [in] | _angle | Pitch amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_LOCAL | 
| void Pitch | ( | const ignition::math::Angle & | _angle, | 
| ReferenceFrame | _relativeTo = RF_LOCAL  | 
        ||
| ) | 
Rotate the camera around the y-axis.
| [in] | _angle | Pitch amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_LOCAL | 
      
  | 
  virtual | 
Post render.
Called afer the render signal.
Reimplemented in GpuLaser, DepthCamera, UserCamera, and OculusCamera.
| ignition::math::Vector2i Project | ( | const ignition::math::Vector3d & | _pt | ) | const | 
Project 3D world coordinates to 2D screen coordinates.
| [in] | _pt | 3D world coodinates | 
| ignition::math::Matrix4d ProjectionMatrix | ( | ) | const | 
Return the projection matrix of this camera.
| std::string ProjectionType | ( | ) | const | 
Return the projection type as a string.
      
  | 
  protected | 
Read image data from pixel buffer.
| void Render | ( | const bool | _force = false | ) | 
Render the camera.
Called after the pre-render signal. This function will generate camera images.
| [in] | _force | Force camera to render. Ignore camera update rate. | 
      
  | 
  protectedvirtual | 
Implementation of the render call.
Reimplemented in WideAngleCamera, and OculusCamera.
| double RenderRate | ( | ) | const | 
Get the render Hz rate.
| Ogre::Texture* RenderTexture | ( | ) | const | 
Get the render texture.
| ignition::math::Vector3d Right | ( | ) | const | 
Get the viewport right vector.
| void Roll | ( | const math::Angle & | _angle, | 
| Ogre::Node::TransformSpace | _relativeTo = Ogre::Node::TS_LOCAL  | 
        ||
| ) | 
Rotate the camera around the x-axis.
| [in] | _angle | Rotation amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_LOCAL | 
| void Roll | ( | const ignition::math::Angle & | _angle, | 
| ReferenceFrame | _relativeTo = RF_LOCAL  | 
        ||
| ) | 
Rotate the camera around the x-axis.
| [in] | _angle | Rotation amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_LOCAL | 
| bool SaveFrame | ( | const std::string & | _filename | ) | 
Save the last frame to disk.
| [in] | _filename | File in which to save a single frame | 
      
  | 
  static | 
Save a frame using an image buffer.
| [in] | _image | The raw image buffer | 
| [in] | _width | Width of the image | 
| [in] | _height | Height of the image | 
| [in] | _depth | Depth of the image data | 
| [in] | _format | Format the image data is in | 
| [in] | _filename | Name of the file in which to write the frame | 
| Ogre::SceneNode* SceneNode | ( | ) | const | 
Get the camera's scene node.
| std::string ScopedName | ( | ) | const | 
Get the camera's scoped name (scene_name::camera_name)
| std::string ScreenshotPath | ( | ) | const | 
Get the path to saved screenshots.
| void SetAspectRatio | ( | float | _ratio | ) | 
Set the aspect ratio.
| [in] | _ratio | The aspect ratio (width / height) in pixels | 
| void SetCaptureData | ( | const bool | _value | ) | 
Set whether to capture data.
| [in] | _value | Set to true to capture data into a memory buffer. | 
| void SetCaptureDataOnce | ( | ) | 
Capture data once and save to disk.
      
  | 
  virtual | 
Set the clip distances.
| [in] | _near | Near clip distance in meters | 
| [in] | _far | Far clip distance in meters | 
Reimplemented in UserCamera.
| void SetHFOV | ( | math::Angle | _angle | ) | 
Set the camera FOV (horizontal)
| [in] | _angle | Horizontal field of view | 
| void SetHFOV | ( | const ignition::math::Angle & | _angle | ) | 
Set the camera FOV (horizontal)
| [in] | _angle | Horizontal field of view | 
| void SetImageHeight | ( | const unsigned int | _h | ) | 
Set the image height.
| [in] | _h | Image height | 
| void SetImageSize | ( | const unsigned int | _w, | 
| const unsigned int | _h | ||
| ) | 
Set the image size.
| [in] | _w | Image width | 
| [in] | _h | Image height | 
| void SetImageWidth | ( | const unsigned int | _w | ) | 
Set the image height.
| [in] | _w | Image width | 
| void SetName | ( | const std::string & | _name | ) | 
Set the camera's name.
| [in] | _name | New name for the camera | 
      
  | 
  virtual | 
Set the type of projection used by the camera.
| [in] | _type | The type of projection: "perspective" or "orthographic". | 
Reimplemented in UserCamera.
| void SetRenderRate | ( | const double | _hz | ) | 
Set the render Hz rate.
| [in] | _hz | The Hz rate | 
      
  | 
  virtual | 
Set the camera's render target.
| [in] | _target | Pointer to the render target | 
Reimplemented in WideAngleCamera, UserCamera, and OculusCamera.
| void SetSaveFramePathname | ( | const std::string & | _pathname | ) | 
Set the save frame pathname.
| [in] | _pathname | Directory in which to store saved image frames | 
| void SetScene | ( | ScenePtr | _scene | ) | 
Set the scene this camera is viewing.
| [in] | _scene | Pointer to the scene | 
| void SetSceneNode | ( | Ogre::SceneNode * | _node | ) | 
Set the camera's scene node.
| [in] | _node | The scene nodes to attach the camera to | 
| void SetWindowId | ( | unsigned int | _windowId | ) | 
      
  | 
  virtual | 
Set the global pose of the camera.
| [in] | _pose | The new math::Pose of the camera | 
Reimplemented in UserCamera.
      
  | 
  virtual | 
Set the global pose of the camera.
| [in] | _pose | The new ignition::math::Pose3d of the camera | 
| void SetWorldPosition | ( | const math::Vector3 & | _pos | ) | 
Set the world position.
| [in] | _pos | The new position of the camera | 
| void SetWorldPosition | ( | const ignition::math::Vector3d & | _pos | ) | 
Set the world position.
| [in] | _pos | The new position of the camera | 
| void SetWorldRotation | ( | const math::Quaternion & | _quat | ) | 
Set the world orientation.
| [in] | _quat | The new orientation of the camera | 
| void SetWorldRotation | ( | const ignition::math::Quaterniond & | _quat | ) | 
Set the world orientation.
| [in] | _quat | The new orientation of the camera | 
| void ShowWireframe | ( | const bool | _s | ) | 
Set whether to view the world in wireframe.
| [in] | _s | Set to True to render objects as wireframe | 
| unsigned int TextureHeight | ( | ) | const | 
Get the height of the off-screen render texture.
| unsigned int TextureWidth | ( | ) | const | 
Get the width of the off-screen render texture.
| void ToggleShowWireframe | ( | ) | 
Toggle whether to view the world in wireframe.
| void TrackVisual | ( | const std::string & | _visualName | ) | 
Set the camera to track a scene node.
| [in] | _visualName | Name of the visual to track | 
      
  | 
  protected | 
Implementation of the Camera::TrackVisual call.
| [in] | _visualName | Name of the visual to track | 
      
  | 
  protectedvirtual | 
Set the camera to track a scene node.
| [in] | _visual | The visual to track | 
Reimplemented in UserCamera, and OculusCamera.
| void Translate | ( | const math::Vector3 & | _direction | ) | 
Translate the camera.
| [in] | _direction | The translation vector | 
| void Translate | ( | const ignition::math::Vector3d & | _direction | ) | 
Translate the camera.
| [in] | _direction | The translation vector | 
      
  | 
  virtual | 
Get the triangle count.
| ignition::math::Vector3d Up | ( | ) | const | 
Get the viewport up vector.
      
  | 
  virtual | 
Reimplemented in UserCamera, and OculusCamera.
      
  | 
  protectedvirtual | 
Update the camera's field of view.
Reimplemented in UserCamera.
| ignition::math::Angle VFOV | ( | ) | const | 
Get the camera FOV (vertical)
| unsigned int ViewportHeight | ( | ) | const | 
Get the viewport height in pixels.
| unsigned int ViewportWidth | ( | ) | const | 
Get the viewport width in pixels.
| unsigned int WindowId | ( | ) | const | 
Get the ID of the window this camera is rendering into.
| bool WorldPointOnPlane | ( | const int | _x, | 
| const int | _y, | ||
| const ignition::math::Planed & | _plane, | ||
| ignition::math::Vector3d & | _result | ||
| ) | 
Get point on a plane.
| [in] | _x | X coordinate in camera's viewport, in pixels | 
| [in] | _y | Y coordinate in camera's viewport, in pixels | 
| [in] | _plane | Plane on which to find the intersecting point | 
| [out] | _result | Point on the plane | 
| ignition::math::Pose3d WorldPose | ( | ) | const | 
Get the world pose.
| ignition::math::Vector3d WorldPosition | ( | ) | const | 
Get the camera position in the world.
| ignition::math::Quaterniond WorldRotation | ( | ) | const | 
Get the camera's orientation in the world.
| void Yaw | ( | const math::Angle & | _angle, | 
| Ogre::Node::TransformSpace | _relativeTo = Ogre::Node::TS_WORLD  | 
        ||
| ) | 
Rotate the camera around the z-axis.
| [in] | _angle | Rotation amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are Ogre::TS_LOCAL, Ogre::TS_PARENT, and Ogre::TS_WORLD. Default is Ogre::TS_WORLD | 
| void Yaw | ( | const ignition::math::Angle & | _angle, | 
| ReferenceFrame | _relativeTo = RF_WORLD  | 
        ||
| ) | 
Rotate the camera around the z-axis.
| [in] | _angle | Rotation amount | 
| [in] | _relativeTo | Coordinate frame to rotate in. Valid values are RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_WORLD | 
| double ZValue | ( | const int | _x, | 
| const int | _y | ||
| ) | 
Get the Z-buffer value at the given image coordinate.
| [in] | _x | Image coordinate; (0, 0) specifies the top-left corner. | 
| [in] | _y | Image coordinate; (0, 0) specifies the top-left corner. | 
      
  | 
  protected | 
Animation state, used to animate the camera.
      
  | 
  protected | 
Buffer for a bayer image frame.
      
  | 
  protected | 
The OGRE camera.
      
  | 
  protected | 
True to capture frames into an image buffer.
      
  | 
  protected | 
True to capture a frame once and save to disk.
      
  | 
  protected | 
The camera's event connections.
      
  | 
  protected | 
Format for saving images.
      
  | 
  protected | 
Save image height.
      
  | 
  protected | 
Save image width.
      
  | 
  protected | 
True if initialized.
      
  | 
  protected | 
Time the last frame was rendered.
      
  | 
  protected | 
Name of the camera.
      
  | 
  protected | 
True if new data is available.
      
  | 
  protected | 
Event triggered when a new frame is generated.
      
  | 
  protected | 
User callback for when an animation completes.
      
  | 
  protected | 
Previous time the camera animation was updated.
      
  | 
  protected | 
Target that renders frames.
      
  | 
  protected | 
Texture that receives results from rendering.
      
  | 
  protected | 
List of requests.
      
  | 
  protected | 
Number of saved frames.
      
  | 
  protected | 
Buffer for a single image frame.
      
  | 
  protected | 
Pointer to the scene.
      
  | 
  protected | 
Scene node that controls camera position and orientation.
      
  | 
  protected | 
Scene scoped name of the camera.
      
  | 
  protected | 
Scene scoped name of the camera with a unique ID.
      
  | 
  protected | 
Path to saved screenshots.
      
  | 
  protected | 
Camera's SDF values.
      
  | 
  protected | 
Height of the render texture.
      
  | 
  protected | 
Width of the render texture.
      
  | 
  protected | 
Viewport the ogre camera uses.
      
  | 
  protected | 
ID of the window that the camera is attached to.