Basic camera sensor. More...
#include <rendering/rendering.hh>
Public Member Functions | |
Camera (const std::string &_namePrefix, ScenePtr _scene, bool _autoRender=true) | |
Constructor. | |
virtual | ~Camera () |
Destructor. | |
void | AttachToVisual (const std::string &_visualName, bool _inheritOrientation, double _minDist=0.0, double _maxDist=0.0) |
Attach the camera to a scene node. | |
template<typename T > | |
event::ConnectionPtr | ConnectNewImageFrame (T _subscriber) |
Connect a to the new image signal. | |
void | CreateRenderTexture (const std::string &_textureName) |
Set the render target. | |
void | DisconnectNewImageFrame (event::ConnectionPtr &_c) |
Disconnect from an image frame. | |
void | EnableSaveFrame (bool _enable) |
Enable or disable saving. | |
virtual void | Fini () |
Finalize the camera. | |
float | GetAspectRatio () const |
Get the apect ratio. | |
virtual float | GetAvgFPS () |
Get the average FPS. | |
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. | |
math::Vector3 | GetDirection () const |
Get the camera's direction vector. | |
double | GetFarClip () |
Get the far clip distance. | |
math::Angle | GetHFOV () const |
Get the camera FOV (horizontal) | |
size_t | GetImageByteSize () const |
Get the image size in bytes. | |
virtual const unsigned char * | GetImageData (unsigned int i=0) |
Get a pointer to the image data. | |
unsigned int | GetImageDepth () const |
Get the depth of the image. | |
std::string | GetImageFormat () const |
Get the string representation of the image format. | |
virtual unsigned int | GetImageHeight () const |
Get the height of the image. | |
virtual unsigned int | GetImageWidth () const |
Get the width of the image. | |
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 |
Get the camera's name. | |
double | GetNearClip () |
Get the near clip distance. | |
Ogre::Camera * | GetOgreCamera () const |
Get a pointer to the ogre camera. | |
Ogre::SceneNode * | GetPitchNode () const |
Get the camera's pitch scene node. | |
double | GetRenderRate () const |
Get the render Hz rate. | |
Ogre::Texture * | GetRenderTexture () const |
Get the render texture. | |
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. | |
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 unsigned int | GetTriangleCount () |
Get the triangle count. | |
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 |
Get the viewport height in pixels. | |
unsigned int | GetViewportWidth () const |
Get the viewport width in pixels. | |
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. | |
math::Pose | GetWorldPose () |
Get the global pose of the camera. | |
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. | |
virtual void | Init () |
Initialize the camera. | |
bool | IsAnimating () const |
Return true if the camera is moving due to an animation. | |
bool | IsInitialized () const GAZEBO_DEPRECATED |
Deprecated. | |
bool | IsVisible (VisualPtr _visual) |
Return true if the visual is within the camera's view frustum. | |
bool | IsVisible (const std::string &_visualName) |
Return true if the visual is within the camera's view frustum. | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the camera with a set of parmeters. | |
virtual void | Load () |
Load the camera with default parmeters. | |
virtual bool | MoveToPosition (const math::Pose &_pose, double _time) |
Move the camera to a position (this is an animated motion). | |
bool | MoveToPositions (const std::vector< math::Pose > &_pts, double _time, boost::function< void()> _onComplete=NULL) |
Move the camera to a series of poses (this is an animated motion). | |
virtual void | PostRender () |
Post render. | |
void | Render () |
Render the camera. | |
void | RotatePitch (math::Angle _angle) |
Rotate the camera around the pitch axis. | |
void | RotateYaw (math::Angle _angle) |
Rotate the camera around the yaw axis. | |
bool | SaveFrame (const std::string &_filename) |
Save the last frame to disk. | |
void | SetAspectRatio (float _ratio) |
Set the aspect ratio. | |
void | SetCaptureData (bool _value) |
Set whether to capture data. | |
void | SetClipDist (float _near, float _far) |
Set the clip distances. | |
void | SetHFOV (math::Angle _angle) |
Set the camera FOV (horizontal) | |
void | SetImageHeight (unsigned int _h) |
Set the image height. | |
void | SetImageSize (unsigned int _w, unsigned int _h) |
Set the image size. | |
void | SetImageWidth (unsigned int _w) |
Set the image height. | |
void | SetName (const std::string &_name) |
Set the camera's name. | |
void | SetRenderRate (double _hz) |
Set the render Hz rate. | |
virtual void | SetRenderTarget (Ogre::RenderTarget *_target) |
Set the camera's render target. | |
void | SetSaveFramePathname (const std::string &_pathname) |
Set the save frame pathname. | |
void | SetScene (ScenePtr _scene) |
Set the scene this camera is viewing. | |
void | SetSceneNode (Ogre::SceneNode *_node) |
Set the camera's scene node. | |
void | SetWindowId (unsigned int _windowId) |
virtual void | SetWorldPose (const math::Pose &_pose) |
Set the global pose of the camera. | |
void | SetWorldPosition (const math::Vector3 &_pos) |
Set the world position. | |
void | SetWorldRotation (const math::Quaternion &_quat) |
Set the world orientation. | |
void | ShowWireframe (bool _s) |
Set whether to view the world in wireframe. | |
void | ToggleShowWireframe () |
Toggle whether to view the world in wireframe. | |
void | TrackVisual (const std::string &_visualName) |
Set the camera to track a scene node. | |
void | Translate (const math::Vector3 &_direction) |
Translate the camera. | |
virtual void | Update () |
Static Public Member Functions | |
static size_t | GetImageByteSize (unsigned int _width, unsigned int _height, const std::string &_format) |
Calculate image byte size base on a few parameters. | |
static bool | SaveFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, int _depth, const std::string &_format, const std::string &_filename) |
Save a frame using an image buffer. | |
Protected Member Functions | |
virtual void | AnimationComplete () |
Internal function used to indicate that an animation has completed. | |
virtual bool | AttachToVisualImpl (const std::string &_name, bool _inheritOrientation, double _minDist=0, double _maxDist=0) |
Attach the camera to a scene node. | |
virtual bool | AttachToVisualImpl (VisualPtr _visual, bool _inheritOrientation, double _minDist=0, double _maxDist=0) |
Attach the camera to a visual. | |
std::string | GetFrameFilename () |
Get the next frame filename based on SDF parameters. | |
virtual void | RenderImpl () |
Implementation of the render call. | |
bool | TrackVisualImpl (const std::string &_visualName) |
Implementation of the Camera::TrackVisual call. | |
virtual bool | TrackVisualImpl (VisualPtr _visual) |
Set the camera to track a scene node. | |
Protected Attributes | |
Ogre::AnimationState * | animState |
Animation state, used to animate the camera. | |
unsigned char * | bayerFrameBuffer |
Buffer for a bayer image frame. | |
Ogre::Camera * | camera |
The OGRE camera. | |
bool | captureData |
True to capture frames into an image buffer. | |
std::vector< event::ConnectionPtr > | connections |
The camera's event connections. | |
int | imageFormat |
Format for saving images. | |
int | imageHeight |
Save image height. | |
int | imageWidth |
Save image width. | |
bool | initialized |
True if initialized. | |
common::Time | lastRenderWallTime |
Time the last frame was rendered. | |
std::string | name |
Name of the camera. | |
bool | newData |
True if new data is available. | |
event::EventT< void(const unsigned char *, unsigned int, unsigned int, unsigned int, const std::string &)> | newImageFrame |
Event triggered when a new frame is generated. | |
boost::function< void()> | onAnimationComplete |
User callback for when an animation completes. | |
Ogre::SceneNode * | pitchNode |
Scene nod that controls camera pitch. | |
common::Time | prevAnimTime |
Previous time the camera animation was updated. | |
Ogre::RenderTarget * | renderTarget |
Target that renders frames. | |
Ogre::Texture * | renderTexture |
Texture that receives results from rendering. | |
std::list< msgs::Request > | requests |
List of requests. | |
unsigned int | saveCount |
Number of saved frames. | |
unsigned char * | saveFrameBuffer |
ScenePtr | scene |
Pointer to the scene. | |
Ogre::SceneNode * | sceneNode |
Scene node that controls camera position. | |
sdf::ElementPtr | sdf |
Camera's SDF values. | |
unsigned int | textureHeight |
Height of the render texture. | |
unsigned int | textureWidth |
Width of the render texture. | |
Ogre::Viewport * | viewport |
Viewport the ogre camera uses. | |
unsigned int | windowId |
ID of the window that the camera is attached to. | |
Basic camera sensor.
This is the base class for all cameras.
gazebo::rendering::Camera::Camera | ( | const std::string & | _namePrefix, |
ScenePtr | _scene, | ||
bool | _autoRender = true |
||
) |
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 gazebo::rendering::UserCamera.
void gazebo::rendering::Camera::AttachToVisual | ( | const std::string & | _visualName, |
bool | _inheritOrientation, | ||
double | _minDist = 0.0 , |
||
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 |
|
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 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 gazebo::rendering::UserCamera.
|
inline |
Connect a to the new image signal.
[in] | _subscriber | Callback that is called when a new image is generated |
References gazebo::event::EventT< T >::Connect(), and newImageFrame.
void gazebo::rendering::Camera::CreateRenderTexture | ( | const std::string & | _textureName | ) |
Set the render target.
[in] | _textureName | Name of the new render texture |
|
inline |
Disconnect from an image frame.
[in] | _c | The connection to disconnect |
References gazebo::event::EventT< T >::Disconnect(), and newImageFrame.
void gazebo::rendering::Camera::EnableSaveFrame | ( | bool | _enable | ) |
Enable or disable saving.
[in] | _enable | Set to True to enable saving of frames |
|
virtual |
Finalize the camera.
This function is called before the camera is destructed
Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.
float gazebo::rendering::Camera::GetAspectRatio | ( | ) | const |
Get the apect ratio.
|
inlinevirtual |
Get the average FPS.
void gazebo::rendering::Camera::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 |
math::Vector3 gazebo::rendering::Camera::GetDirection | ( | ) | const |
Get the camera's direction vector.
double gazebo::rendering::Camera::GetFarClip | ( | ) |
Get the far clip distance.
|
protected |
Get the next frame filename based on SDF parameters.
math::Angle gazebo::rendering::Camera::GetHFOV | ( | ) | const |
Get the camera FOV (horizontal)
size_t gazebo::rendering::Camera::GetImageByteSize | ( | ) | 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 gazebo::rendering::Camera::GetImageDepth | ( | ) | const |
Get the depth of the image.
std::string gazebo::rendering::Camera::GetImageFormat | ( | ) | const |
Get the string representation of the image format.
|
virtual |
|
virtual |
bool gazebo::rendering::Camera::GetInitialized | ( | ) | const |
Return true if the camera has been initialized.
common::Time gazebo::rendering::Camera::GetLastRenderWallTime | ( | ) |
Get the last time the camera was rendered.
std::string gazebo::rendering::Camera::GetName | ( | ) | const |
Get the camera's name.
double gazebo::rendering::Camera::GetNearClip | ( | ) |
Get the near clip distance.
Ogre::Camera* gazebo::rendering::Camera::GetOgreCamera | ( | ) | const |
Get a pointer to the ogre camera.
Ogre::SceneNode* gazebo::rendering::Camera::GetPitchNode | ( | ) | const |
Get the camera's pitch scene node.
double gazebo::rendering::Camera::GetRenderRate | ( | ) | const |
Get the render Hz rate.
Ogre::Texture* gazebo::rendering::Camera::GetRenderTexture | ( | ) | const |
Get the render texture.
math::Vector3 gazebo::rendering::Camera::GetRight | ( | ) |
Get the viewport right vector.
ScenePtr gazebo::rendering::Camera::GetScene | ( | ) | const |
Get the scene this camera is in.
Ogre::SceneNode* gazebo::rendering::Camera::GetSceneNode | ( | ) | const |
Get the camera's scene node.
unsigned int gazebo::rendering::Camera::GetTextureHeight | ( | ) | const |
Get the height of the off-screen render texture.
unsigned int gazebo::rendering::Camera::GetTextureWidth | ( | ) | const |
Get the width of the off-screen render texture.
|
inlinevirtual |
Get the triangle count.
math::Vector3 gazebo::rendering::Camera::GetUp | ( | ) |
Get the viewport up vector.
math::Angle gazebo::rendering::Camera::GetVFOV | ( | ) | const |
Get the camera FOV (vertical)
Ogre::Viewport* gazebo::rendering::Camera::GetViewport | ( | ) | const |
Get a pointer to the Ogre::Viewport.
unsigned int gazebo::rendering::Camera::GetViewportHeight | ( | ) | const |
Get the viewport height in pixels.
unsigned int gazebo::rendering::Camera::GetViewportWidth | ( | ) | const |
Get the viewport width in pixels.
unsigned int gazebo::rendering::Camera::GetWindowId | ( | ) | const |
Get the ID of the window this camera is rendering into.
bool gazebo::rendering::Camera::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 gazebo::rendering::Camera::GetWorldPose | ( | ) |
Get the global pose of the camera.
math::Vector3 gazebo::rendering::Camera::GetWorldPosition | ( | ) | const |
Get the camera position in the world.
math::Quaternion gazebo::rendering::Camera::GetWorldRotation | ( | ) | const |
Get the camera's orientation in the world.
double gazebo::rendering::Camera::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. |
|
virtual |
Initialize the camera.
Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.
bool gazebo::rendering::Camera::IsAnimating | ( | ) | const |
Return true if the camera is moving due to an animation.
|
inline |
Deprecated.
bool gazebo::rendering::Camera::IsVisible | ( | VisualPtr | _visual | ) |
Return true if the visual is within the camera's view frustum.
[in] | _visual | The visual to check for visibility |
bool gazebo::rendering::Camera::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 |
|
virtual |
Load the camera with a set of parmeters.
[in] | _sdf | The SDF camera info |
Reimplemented in gazebo::rendering::UserCamera.
|
virtual |
Load the camera with default parmeters.
Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.
|
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 gazebo::rendering::UserCamera.
bool gazebo::rendering::Camera::MoveToPositions | ( | const std::vector< math::Pose > & | _pts, |
double | _time, | ||
boost::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 |
|
virtual |
Post render.
Called afer the render signal.
Reimplemented in gazebo::rendering::GpuLaser, gazebo::rendering::DepthCamera, and gazebo::rendering::UserCamera.
void gazebo::rendering::Camera::Render | ( | ) |
Render the camera.
Called after the pre-render signal. This function will generate camera images
|
protectedvirtual |
Implementation of the render call.
void gazebo::rendering::Camera::RotatePitch | ( | math::Angle | _angle | ) |
Rotate the camera around the pitch axis.
[in] | _angle | Pitch amount |
void gazebo::rendering::Camera::RotateYaw | ( | math::Angle | _angle | ) |
Rotate the camera around the yaw axis.
[in] | _angle | Rotation amount |
bool gazebo::rendering::Camera::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 |
void gazebo::rendering::Camera::SetAspectRatio | ( | float | _ratio | ) |
Set the aspect ratio.
[in] | _ratio | The aspect ratio (width / height) in pixels |
void gazebo::rendering::Camera::SetCaptureData | ( | bool | _value | ) |
Set whether to capture data.
[in] | _value | Set to true to capture data into a memory buffer. |
void gazebo::rendering::Camera::SetClipDist | ( | float | _near, |
float | _far | ||
) |
Set the clip distances.
[in] | _near | Near clip distance in meters |
[in] | _far | Far clip distance in meters |
void gazebo::rendering::Camera::SetHFOV | ( | math::Angle | _angle | ) |
Set the camera FOV (horizontal)
[in] | _radians | Horizontal field of view |
void gazebo::rendering::Camera::SetImageHeight | ( | unsigned int | _h | ) |
Set the image height.
[in] | _h | Image height |
void gazebo::rendering::Camera::SetImageSize | ( | unsigned int | _w, |
unsigned int | _h | ||
) |
Set the image size.
[in] | _w | Image width |
[in] | _h | Image height |
void gazebo::rendering::Camera::SetImageWidth | ( | unsigned int | _w | ) |
Set the image height.
[in] | _w | Image width |
void gazebo::rendering::Camera::SetName | ( | const std::string & | _name | ) |
Set the camera's name.
[in] | _name | New name for the camera |
void gazebo::rendering::Camera::SetRenderRate | ( | 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 gazebo::rendering::UserCamera.
void gazebo::rendering::Camera::SetSaveFramePathname | ( | const std::string & | _pathname | ) |
Set the save frame pathname.
[in] | _pathname | Directory in which to store saved image frames |
void gazebo::rendering::Camera::SetScene | ( | ScenePtr | _scene | ) |
Set the scene this camera is viewing.
[in] | _scene | Pointer to the scene |
void gazebo::rendering::Camera::SetSceneNode | ( | Ogre::SceneNode * | _node | ) |
Set the camera's scene node.
[in] | _node | The scene nodes to attach the camera to |
void gazebo::rendering::Camera::SetWindowId | ( | unsigned int | _windowId | ) |
|
virtual |
Set the global pose of the camera.
[in] | _pose | The new math::Pose of the camera |
Reimplemented in gazebo::rendering::UserCamera.
void gazebo::rendering::Camera::SetWorldPosition | ( | const math::Vector3 & | _pos | ) |
Set the world position.
[in] | _pos | The new position of the camera |
void gazebo::rendering::Camera::SetWorldRotation | ( | const math::Quaternion & | _quat | ) |
Set the world orientation.
[in] | _quat | The new orientation of the camera |
void gazebo::rendering::Camera::ShowWireframe | ( | bool | _s | ) |
Set whether to view the world in wireframe.
[in] | _s | Set to True to render objects as wireframe |
void gazebo::rendering::Camera::ToggleShowWireframe | ( | ) |
Toggle whether to view the world in wireframe.
void gazebo::rendering::Camera::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 gazebo::rendering::UserCamera.
void gazebo::rendering::Camera::Translate | ( | const math::Vector3 & | _direction | ) |
Translate the camera.
[in] | _direction | The translation vector |
|
virtual |
Reimplemented in gazebo::rendering::UserCamera.
|
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 |
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.
Referenced by ConnectNewImageFrame(), and DisconnectNewImageFrame().
|
protected |
User callback for when an animation completes.
|
protected |
Scene nod that controls camera pitch.
|
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 |
|
protected |
Pointer to the scene.
|
protected |
Scene node that controls camera position.
|
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.