A camera used for user visualization of a scene. More...
#include <rendering/rendering.hh>
Inherits Camera.
Public Member Functions | |
UserCamera (const std::string &_name, ScenePtr _scene, bool _stereoEnabled=false) | |
Constructor. More... | |
virtual | ~UserCamera () |
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... | |
math::Pose | DefaultPose () const |
Get the default pose in the world coordinate frame. 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... | |
void | EnableStereo (bool _enable) |
Turn on/off stereo rendering. More... | |
void | EnableViewController (bool _value) const |
Set whether the view controller is enabled. More... | |
double | FarClip () const |
Get the far clip distance. More... | |
void | Fini () |
Finialize. 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 |
Get the height of the image. More... | |
virtual unsigned int | GetImageWidth () const |
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... | |
std::string | GetViewControllerTypeString () |
Get current view controller type. 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... | |
VisualPtr | GetVisual (const math::Vector2i &_mousePos, std::string &_mod) |
Get an entity at a pixel location using a camera. More... | |
VisualPtr | GetVisual (const math::Vector2i &_mousePos) const |
Get a visual at a mouse position. 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... | |
void | HandleKeyPressEvent (const std::string &_key) |
Handle a key press. More... | |
void | HandleKeyReleaseEvent (const std::string &_key) |
Handle a key release. More... | |
void | HandleMouseEvent (const common::MouseEvent &_evt) |
Handle a mouse event. 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... | |
void | Init () |
Initialize. 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 | IsCameraSetInWorldFile () |
brief Show if the user camera pose has changed in the world file. 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... | |
void | Load (sdf::ElementPtr _sdf) |
Load the user camera. More... | |
void | Load () |
Generic load function. More... | |
virtual bool | MoveToPosition (const math::Pose &_pose, double _time) |
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... | |
void | MoveToVisual (VisualPtr _visual) |
Move the camera to focus on a visual. More... | |
void | MoveToVisual (const std::string &_visualName) |
Move the camera to focus on a visual. 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... | |
void | Resize (unsigned int _w, unsigned int _h) |
Resize the camera. 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 (float _near, float _far) |
Set the clip distances. More... | |
void | SetDefaultPose (const math::Pose &_pose) |
Set the default pose in the world coordinate frame and set that as the current camera world pose. More... | |
void | SetFocalPoint (const math::Vector3 &_pt) |
Set the point the camera should orbit around. 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 | SetJoyPoseControl (bool _value) |
brief Enable or disable camera control through ~/user_camera/joy_pose gz topic. More... | |
void | SetJoyTwistControl (bool _value) |
brief Enable or disable camera control through ~/user_camera/joy_twist gz topic. 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 to true to enable rendering. 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 | SetUseSDFPose (bool _value) |
brief Set if the user camera pose has changed in the world file. More... | |
void | SetViewController (const std::string &_type) |
Set view controller. More... | |
void | SetViewController (const std::string &_type, const math::Vector3 &_pos) |
Set view controller. More... | |
void | SetViewportDimensions (float _x, float _y, float _w, float _h) |
Set the dimensions of the viewport. More... | |
void | SetWindowId (unsigned int _windowId) |
virtual void | SetWorldPose (const math::Pose &_pose) |
Set the pose in the world coordinate frame. 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... | |
bool | StereoEnabled () const |
Get whether stereo is enabled. 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 () |
Render the camera. More... | |
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 (VisualPtr _visual, bool _inheritOrientation, double _minDist=0, double _maxDist=0) |
Set the camera to be attached to a visual. 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... | |
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... | |
virtual bool | TrackVisualImpl (VisualPtr _visual) |
Set the camera to track a scene node. More... | |
bool | TrackVisualImpl (const std::string &_visualName) |
Implementation of the Camera::TrackVisual call. 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... | |
A camera used for user visualization of a scene.
UserCamera | ( | const std::string & | _name, |
ScenePtr | _scene, | ||
bool | _stereoEnabled = false |
||
) |
Constructor.
[in] | _name | Name of the camera. |
[in] | _scene | Scene to put the camera in. |
[in] | _stereoEnabled | True to enable stereo rendering. This is here for compatibility with 3D monitors/TVs. |
|
virtual |
Destructor.
|
protectedvirtual |
Internal function used to indicate that an animation has completed.
Reimplemented from Camera.
|
inherited |
Get the apect ratio.
|
inherited |
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 |
|
inherited |
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 |
Set the camera to be attached to a visual.
This causes the camera to move in relation to the specified visual.
[in] | _visual | The visual to attach to. |
[in] | _inheritOrientation | True if the camera should also rotate when the visual rotates. |
[in] | _minDist | Minimum distance the camera can get to the visual. |
[in] | _maxDist | Maximum distance the camera can get from the visual. |
Reimplemented from Camera.
|
protectedvirtualinherited |
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 |
|
protectedvirtualinherited |
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 |
|
virtualinherited |
Get the average FPS.
|
inherited |
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 |
|
inherited |
Return the value of this->captureData.
|
inherited |
Connect to the new image signal.
[in] | _subscriber | Callback that is called when a new image is generated |
|
inherited |
Set the render target.
[in] | _textureName | Name of the new render texture |
math::Pose DefaultPose | ( | ) | const |
Get the default pose in the world coordinate frame.
|
inherited |
Get the camera's direction vector.
|
inherited |
Disconnect from an image frame.
[in] | _c | The connection to disconnect |
|
inherited |
Enable or disable saving.
[in] | _enable | Set to True to enable saving of frames |
void EnableStereo | ( | bool | _enable | ) |
Turn on/off stereo rendering.
Stereo must be initially enable in the ~/.gazebo/gui.ini file using:
[rendering] stereo=1
[in] | _enable | True to turn on stereo, false to turn off. |
void EnableViewController | ( | bool | _value | ) | const |
Set whether the view controller is enabled.
The view controller is used to handle user camera movements.
[in] | _value | True to enable viewcontroller, False to disable. |
|
inherited |
Get the far clip distance.
|
virtual |
Finialize.
Reimplemented from Camera.
|
protectedinherited |
Get the next frame filename based on SDF parameters.
|
inherited |
Get the apect ratio.
|
virtualinherited |
|
inherited |
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 |
|
inherited |
Return the value of this->captureData.
|
inherited |
Get the camera's direction vector.
|
inherited |
Get the distortion model of this camera.
|
inherited |
|
protectedinherited |
Get the next frame filename based on SDF parameters.
|
inherited |
Get the camera FOV (horizontal)
|
inherited |
|
staticinherited |
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 |
|
virtualinherited |
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). |
|
inherited |
|
inherited |
Get the string representation of the image format.
|
virtual |
|
virtual |
|
inherited |
Return true if the camera has been initialized.
|
inherited |
Get the last time the camera was rendered.
|
inherited |
|
inherited |
|
inherited |
|
inherited |
Return the projection type as a string.
|
inherited |
|
inherited |
|
inherited |
Get the viewport right vector.
|
inherited |
Get the scene this camera is in.
|
inherited |
Get the camera's scene node.
|
inherited |
Get the camera's scoped name (scene_name::camera_name)
|
inherited |
Get the path to saved screenshots.
|
inherited |
Get the height of the off-screen render texture.
|
inherited |
Get the width of the off-screen render texture.
|
virtualinherited |
|
inherited |
Get the viewport up vector.
|
inherited |
Get the camera FOV (vertical)
std::string GetViewControllerTypeString | ( | ) |
Get current view controller type.
|
inherited |
Get a pointer to the Ogre::Viewport.
|
inherited |
|
inherited |
VisualPtr GetVisual | ( | const math::Vector2i & | _mousePos, |
std::string & | _mod | ||
) |
Get an entity at a pixel location using a camera.
Used for mouse picking.
[in] | _mousePos | The position of the mouse in screen coordinates |
[out] | _mod | Used for object manipulation |
VisualPtr GetVisual | ( | const math::Vector2i & | _mousePos | ) | const |
Get a visual at a mouse position.
[in] | _mousePos | 2D position of the mouse in pixels. |
|
inherited |
Get the ID of the window this camera is rendering into.
|
inherited |
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 |
|
inherited |
Get the world pose.
|
inherited |
Get the camera position in the world.
|
inherited |
Get the camera's orientation in the world.
|
inherited |
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. |
void HandleKeyPressEvent | ( | const std::string & | _key | ) |
Handle a key press.
[in] | _key | The key pressed. |
void HandleKeyReleaseEvent | ( | const std::string & | _key | ) |
Handle a key release.
[in] | _key | The key released. |
void HandleMouseEvent | ( | const common::MouseEvent & | _evt | ) |
Handle a mouse event.
[in] | _evt | The mouse event. |
|
inherited |
Get the camera FOV (horizontal)
|
inherited |
Get the image size in bytes.
|
staticinherited |
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 |
|
virtualinherited |
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). |
|
inherited |
Get the depth of the image.
|
inherited |
Get the string representation of the image format.
|
virtualinherited |
Get the height of the image.
|
virtualinherited |
Get the width of the image.
|
virtual |
Initialize.
Reimplemented from Camera.
|
inherited |
Return true if the camera has been initialized.
|
inherited |
Return true if the camera is moving due to an animation.
bool IsCameraSetInWorldFile | ( | ) |
brief Show if the user camera pose has changed in the world file.
return true if the camera pose changed in the world file.
|
inherited |
Return true if the visual is within the camera's view frustum.
[in] | _visual | The visual to check for visibility |
|
inherited |
Return true if the visual is within the camera's view frustum.
[in] | _visualName | Name of the visual to check for visibility |
|
inherited |
Get the last time the camera was rendered.
|
inherited |
Get the distortion model of this camera.
|
virtual |
|
virtual |
Generic load function.
Reimplemented from Camera.
|
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 from Camera.
|
virtualinherited |
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 |
|
inherited |
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 |
|
inherited |
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 |
void MoveToVisual | ( | VisualPtr | _visual | ) |
Move the camera to focus on a visual.
[in] | _visual | Visual to move the camera to. |
void MoveToVisual | ( | const std::string & | _visualName | ) |
Move the camera to focus on a visual.
[in] | _visualName | Name of the visual to move the camera to. |
|
inherited |
Get the camera's unscoped name.
|
inherited |
Get the near clip distance.
|
inherited |
Get a pointer to the ogre camera.
|
inherited |
Get a pointer to the Ogre::Viewport.
|
inherited |
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 |
|
inherited |
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.
Reimplemented from Camera.
|
inherited |
Project 3D world coordinates to 2D screen coordinates.
[in] | _pt | 3D world coodinates |
|
inherited |
Return the projection matrix of this camera.
|
inherited |
Return the projection type as a string.
|
protectedinherited |
Read image data from pixel buffer.
|
inherited |
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. |
|
protectedvirtualinherited |
Implementation of the render call.
Reimplemented in WideAngleCamera, and OculusCamera.
|
inherited |
Get the render Hz rate.
|
inherited |
Get the render texture.
void Resize | ( | unsigned int | _w, |
unsigned int | _h | ||
) |
Resize the camera.
[in] | _w | Width of the camera image. |
[in] | _h | Height of the camera image. |
|
inherited |
Get the viewport right vector.
|
inherited |
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 |
|
inherited |
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 |
|
inherited |
Save the last frame to disk.
[in] | _filename | File in which to save a single frame |
|
staticinherited |
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 |
|
inherited |
Get the camera's scene node.
|
inherited |
Get the camera's scoped name (scene_name::camera_name)
|
inherited |
Get the path to saved screenshots.
|
inherited |
Set the aspect ratio.
[in] | _ratio | The aspect ratio (width / height) in pixels |
|
inherited |
Set whether to capture data.
[in] | _value | Set to true to capture data into a memory buffer. |
|
inherited |
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 from Camera.
void SetDefaultPose | ( | const math::Pose & | _pose | ) |
Set the default pose in the world coordinate frame and set that as the current camera world pose.
[in] | _pose | New default pose of the camera. |
void SetFocalPoint | ( | const math::Vector3 & | _pt | ) |
Set the point the camera should orbit around.
[in] | _pt | The focal point |
|
inherited |
Set the camera FOV (horizontal)
[in] | _angle | Horizontal field of view |
|
inherited |
Set the camera FOV (horizontal)
[in] | _angle | Horizontal field of view |
|
inherited |
Set the image height.
[in] | _h | Image height |
|
inherited |
Set the image size.
[in] | _w | Image width |
[in] | _h | Image height |
|
inherited |
Set the image height.
[in] | _w | Image width |
void SetJoyPoseControl | ( | bool | _value | ) |
brief Enable or disable camera control through ~/user_camera/joy_pose gz topic.
Defaults to true.
[in] | _value | True to enable camera pose control by gz topic ~/user_camera/joy_pose. |
void SetJoyTwistControl | ( | bool | _value | ) |
brief Enable or disable camera control through ~/user_camera/joy_twist gz topic.
Defaults to true.
[in] | _value | True to enable camera pose control by gz topic ~/user_camera/joy_twist. |
|
inherited |
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 from Camera.
|
inherited |
Set the render Hz rate.
[in] | _hz | The Hz rate |
|
virtual |
Set to true to enable rendering.
Use this only if you really know what you're doing.
[in] | _target | The new rendering target. |
Reimplemented from Camera.
|
inherited |
Set the save frame pathname.
[in] | _pathname | Directory in which to store saved image frames |
|
inherited |
Set the scene this camera is viewing.
[in] | _scene | Pointer to the scene |
|
inherited |
Set the camera's scene node.
[in] | _node | The scene nodes to attach the camera to |
void SetUseSDFPose | ( | bool | _value | ) |
brief Set if the user camera pose has changed in the world file.
[in] | _value | True if the camera pose changed in the world file. |
void SetViewController | ( | const std::string & | _type | ) |
Set view controller.
[in] | _type | The type of view controller: "orbit", "fps" |
void SetViewController | ( | const std::string & | _type, |
const math::Vector3 & | _pos | ||
) |
Set view controller.
[in] | _type | The type of view controller: "orbit", "fps" |
[in] | _pos | The initial pose of the camera. |
void SetViewportDimensions | ( | float | _x, |
float | _y, | ||
float | _w, | ||
float | _h | ||
) |
Set the dimensions of the viewport.
[in] | _x | X position of the viewport. |
[in] | _y | Y position of the viewport. |
[in] | _w | Width of the viewport. |
[in] | _h | Height of the viewport. |
|
inherited |
|
virtual |
Set the pose in the world coordinate frame.
[in] | _pose | New pose of the camera. |
Reimplemented from Camera.
|
virtualinherited |
Set the global pose of the camera.
[in] | _pose | The new ignition::math::Pose3d of the camera |
|
inherited |
Set the world position.
[in] | _pos | The new position of the camera |
|
inherited |
Set the world position.
[in] | _pos | The new position of the camera |
|
inherited |
Set the world orientation.
[in] | _quat | The new orientation of the camera |
|
inherited |
Set the world orientation.
[in] | _quat | The new orientation of the camera |
|
inherited |
Set whether to view the world in wireframe.
[in] | _s | Set to True to render objects as wireframe |
bool StereoEnabled | ( | ) | const |
Get whether stereo is enabled.
|
inherited |
Get the height of the off-screen render texture.
|
inherited |
Get the width of the off-screen render texture.
|
inherited |
Toggle whether to view the world in wireframe.
|
inherited |
Set the camera to track a scene node.
[in] | _visualName | Name of the visual to track |
|
protectedvirtual |
|
protectedinherited |
Implementation of the Camera::TrackVisual call.
[in] | _visualName | Name of the visual to track |
|
inherited |
Translate the camera.
[in] | _direction | The translation vector |
|
inherited |
Translate the camera.
[in] | _direction | The translation vector |
|
virtualinherited |
Get the triangle count.
|
inherited |
Get the viewport up vector.
|
virtual |
Render the camera.
Reimplemented from Camera.
|
protectedvirtual |
Update the camera's field of view.
Reimplemented from Camera.
|
inherited |
Get the camera FOV (vertical)
|
inherited |
Get the viewport height in pixels.
|
inherited |
Get the viewport width in pixels.
|
inherited |
Get the ID of the window this camera is rendering into.
|
inherited |
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 |
|
inherited |
Get the world pose.
|
inherited |
Get the camera position in the world.
|
inherited |
Get the camera's orientation in the world.
|
inherited |
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 |
|
inherited |
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 |
|
inherited |
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. |
|
protectedinherited |
Animation state, used to animate the camera.
|
protectedinherited |
Buffer for a bayer image frame.
|
protectedinherited |
The OGRE camera.
|
protectedinherited |
True to capture frames into an image buffer.
|
protectedinherited |
True to capture a frame once and save to disk.
|
protectedinherited |
The camera's event connections.
|
protectedinherited |
Format for saving images.
|
protectedinherited |
Save image height.
|
protectedinherited |
Save image width.
|
protectedinherited |
True if initialized.
|
protectedinherited |
Time the last frame was rendered.
|
protectedinherited |
Name of the camera.
|
protectedinherited |
True if new data is available.
|
protectedinherited |
Event triggered when a new frame is generated.
|
protectedinherited |
User callback for when an animation completes.
|
protectedinherited |
Previous time the camera animation was updated.
|
protectedinherited |
Target that renders frames.
|
protectedinherited |
Texture that receives results from rendering.
|
protectedinherited |
List of requests.
|
protectedinherited |
Number of saved frames.
|
protectedinherited |
Buffer for a single image frame.
|
protectedinherited |
Pointer to the scene.
|
protectedinherited |
Scene node that controls camera position and orientation.
|
protectedinherited |
Scene scoped name of the camera.
|
protectedinherited |
Scene scoped name of the camera with a unique ID.
|
protectedinherited |
Path to saved screenshots.
|
protectedinherited |
Camera's SDF values.
|
protectedinherited |
Height of the render texture.
|
protectedinherited |
Width of the render texture.
|
protectedinherited |
Viewport the ogre camera uses.
|
protectedinherited |
ID of the window that the camera is attached to.