GPU based laser distance sensor. More...
#include <rendering/rendering.hh>
Inherits Camera, and RenderObjectListener.
Public Types | |
| typedef GpuLaserDataIterator < GpuLaser > | DataIter |
| Constant iterator to access laser data. More... | |
Public Member Functions | |
| GpuLaser (const std::string &_namePrefix, ScenePtr _scene, const bool _autoRender=true) | |
| Constructor. More... | |
| virtual | ~GpuLaser () |
| 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... | |
| unsigned int | CameraCount () const |
| Get the number of cameras required. More... | |
| virtual void | CameraToViewportRay (const int _screenx, const int _screeny, ignition::math::Vector3d &_origin, ignition::math::Vector3d &_dir) const |
| Get a world space ray as cast from the camera through the viewport. 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... | |
| event::ConnectionPtr | ConnectNewLaserFrame (std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)> _subscriber) |
| Connect to a laser frame signal. More... | |
| double | CosHorzFOV () const |
| Get Cos Horz field-of-view. More... | |
| double | CosVertFOV () const |
| Get Cos Vert field-of-view. More... | |
| void | CreateLaserTexture (const std::string &_textureName) |
| Create the texture which is used to render laser data. 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 | EnableSaveFrame (const bool _enable) |
| Enable or disable saving. More... | |
| double | FarClip () const |
| Get far clip. More... | |
| virtual void | Fini () |
| Finalize the camera. More... | |
| ScenePtr | GetScene () const |
| Get the scene this camera is in. More... | |
| ignition::math::Angle | HFOV () const |
| Get the camera FOV (horizontal) More... | |
| double | HorzFOV () const |
| Get the horizontal field of view of the laser sensor. More... | |
| double | HorzHalfAngle () const |
| Get (horizontal_max_angle + horizontal_min_angle) * 0.5. 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 in bytes per pixel. 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 | IsHorizontal () const |
| Gets if sensor is horizontal. 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... | |
| const float * | LaserData () const GAZEBO_DEPRECATED(9.0) |
| All things needed to get back z buffer for laser data. More... | |
| DataIter | LaserDataBegin () const |
| Return an iterator to the begining of the laser data. More... | |
| DataIter | LaserDataEnd () const |
| Return an iterator to one past the end of the laser data. 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 ignition::math::Pose3d &_pose, const double _time) |
| Move the camera to a position (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 near clip. More... | |
| virtual void | notifyRenderSingleObject (Ogre::Renderable *_rend, const Ogre::Pass *_p, const Ogre::AutoParamDataSource *_s, const Ogre::LightList *_ll, bool _supp) |
| 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 ignition::math::Angle &_angle, ReferenceFrame _relativeTo=RF_LOCAL) |
| Rotate the camera around the y-axis. More... | |
| virtual void | PostRender () |
| Post render. More... | |
| virtual 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... | |
| double | RayCountRatio () const |
| Get the ray count ratio (equivalent to aspect ratio) More... | |
| virtual 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... | |
| bool | ResetVideo () |
| Reset video recording. More... | |
| ignition::math::Vector3d | Right () const |
| Get the viewport right vector. 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... | |
| bool | SaveVideo (const std::string &_filename) |
| Save the last encoded video 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... | |
| virtual bool | SetBackgroundColor (const common::Color &_color) GAZEBO_DEPRECATED(9.0) |
| Set background color for viewport (if viewport is not null) More... | |
| virtual bool | SetBackgroundColor (const ignition::math::Color &_color) |
| Set background color for viewport (if viewport is not null) More... | |
| void | SetCameraCount (const unsigned int _cameraCount) |
| Set the number of cameras required. 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 | SetCosHorzFOV (const double _chfov) |
| Set the Cos Horz FOV. More... | |
| void | SetCosVertFOV (const double _cvfov) |
| Set the Cos Horz FOV. More... | |
| void | SetFarClip (const double _far) |
| Set the far clip distance. More... | |
| void | SetHFOV (const ignition::math::Angle &_angle) |
| Set the camera FOV (horizontal) More... | |
| void | SetHorzFOV (const double _hfov) |
| Set the horizontal fov. More... | |
| void | SetHorzHalfAngle (const double _angle) |
| Set the horizontal half angle. 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 | SetIsHorizontal (const bool _horizontal) |
| Set sensor horizontal or vertical. More... | |
| void | SetName (const std::string &_name) |
| Set the camera's name. More... | |
| void | SetNearClip (const double _near) |
| Set the near clip distance. More... | |
| virtual bool | SetProjectionType (const std::string &_type) |
| Set the type of projection used by the camera. More... | |
| void | SetRangeCount (const unsigned int _w, const unsigned int _h=1) |
| Set the number of laser samples in the width and height. More... | |
| void | SetRayCountRatio (const double _rayCountRatio) |
| Sets the ray count ratio (equivalen to aspect ratio) 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 | SetTrackInheritYaw (const bool _inheritYaw) |
| Set whether this camera inherits the yaw rotation of the tracked model. More... | |
| void | SetTrackIsStatic (const bool _isStatic) |
| Set whether this camera is static when tracking a model. More... | |
| void | SetTrackMaxDistance (const double _dist) |
| Set the maximum distance between the camera and tracked visual. More... | |
| void | SetTrackMinDistance (const double _dist) |
| Set the minimum distance between the camera and tracked visual. More... | |
| void | SetTrackPosition (const ignition::math::Vector3d &_pos) |
| Set the position of the camera when tracking a visual. More... | |
| void | SetTrackUseModelFrame (const bool _useModelFrame) |
| Set whether this camera's position is relative to tracked models. More... | |
| void | SetVertFOV (const double _vfov) |
| Set the vertical fov. More... | |
| void | SetVertHalfAngle (const double _angle) |
| Set the vertical half angle. More... | |
| void | SetWindowId (unsigned int _windowId) |
| virtual void | SetWorldPose (const ignition::math::Pose3d &_pose) |
| Set the global pose of the camera. More... | |
| void | SetWorldPosition (const ignition::math::Vector3d &_pos) |
| Set the world position. 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 | StartVideo (const std::string &_format, const std::string &_filename="") |
| Turn on video recording. More... | |
| bool | StopVideo () |
| Turn off video recording. 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... | |
| VisualPtr | TrackedVisual () const |
| Get the visual tracked by this camera. More... | |
| bool | TrackInheritYaw () const |
| Get whether this camera inherits the yaw rotation of the tracked model. More... | |
| bool | TrackIsStatic () const |
| Get whether this camera is static when tracking a model. More... | |
| double | TrackMaxDistance () const |
| Return the maximum distance to the tracked visual. More... | |
| double | TrackMinDistance () const |
| Return the minimum distance to the tracked visual. More... | |
| ignition::math::Vector3d | TrackPosition () const |
| Return the position of the camera when tracking a model. More... | |
| bool | TrackUseModelFrame () const |
| Get whether this camera's position is relative to tracked models. More... | |
| void | TrackVisual (const std::string &_visualName) |
| Set the camera to track a scene node. 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 () |
| double | VertFOV () const |
| Get the vertical field-of-view. More... | |
| double | VertHalfAngle () const |
| Get (vertical_max_angle + vertical_min_angle) * 0.5. 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 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 | 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... | |
| void | ReadPixelBuffer () |
| Read image data from pixel buffer. More... | |
| virtual void | SetClipDist () |
| Set the clip distance based on stored SDF values. More... | |
| virtual void | SetFixedYawAxis (const bool _useFixed, const ignition::math::Vector3d &_fixedAxis=ignition::math::Vector3d::UnitY) |
| Tell the camera whether to yaw around its own local Y axis or a fixed axis of choice. 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... | |
| unsigned int | cameraCount |
| Number of cameras needed to generate the rays. 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... | |
| double | chfov |
| Cos horizontal field-of-view. More... | |
| std::vector< event::ConnectionPtr > | connections |
| The camera's event connections. More... | |
| double | cvfov |
| Cos vertical field-of-view. More... | |
| double | farClip |
| Far clip plane. More... | |
| double | hfov |
| Horizontal field-of-view. More... | |
| double | horzHalfAngle |
| Horizontal half angle. 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... | |
| bool | isHorizontal |
| True if the sensor is horizontal only. More... | |
| common::Time | lastRenderWallTime |
| Time the last frame was rendered. More... | |
| std::string | name |
| Name of the camera. More... | |
| double | nearClip |
| Near clip plane. 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... | |
| double | rayCountRatio |
| Ray count ratio. 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... | |
| double | vertHalfAngle |
| Vertical half angle. More... | |
| double | vfov |
| Vertical field-of-view. More... | |
| Ogre::Viewport * | viewport |
| Viewport the ogre camera uses. More... | |
| unsigned int | windowId |
| ID of the window that the camera is attached to. More... | |
GPU based laser distance sensor.
| typedef GpuLaserDataIterator<GpuLaser> DataIter |
Constant iterator to access laser data.
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.
|
protectedvirtualinherited |
Internal function used to indicate that an animation has completed.
Reimplemented in UserCamera.
|
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 |
|
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 |
|
protectedvirtualinherited |
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.
|
virtualinherited |
Get the average FPS.
| unsigned int CameraCount | ( | ) | const |
Get the number of cameras required.
|
virtualinherited |
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 |
Reimplemented in UserCamera.
|
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 |
| event::ConnectionPtr ConnectNewLaserFrame | ( | std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)> | _subscriber | ) |
Connect to a laser frame signal.
| [in] | _subscriber | Callback that is called when a new image is generated |
| double CosHorzFOV | ( | ) | const |
Get Cos Horz field-of-view.
| double CosVertFOV | ( | ) | const |
Get Cos Vert field-of-view.
| void CreateLaserTexture | ( | const std::string & | _textureName | ) |
Create the texture which is used to render laser data.
| [in] | _textureName | Name of the new texture. |
|
inherited |
Set the render target.
| [in] | _textureName | Name of the new render texture |
|
inherited |
Get the camera's direction vector.
|
inherited |
Enable or disable saving.
| [in] | _enable | Set to True to enable saving of frames |
| double FarClip | ( | ) | const |
Get far clip.
|
virtual |
Finalize the camera.
This function is called before the camera is destructed
Reimplemented from Camera.
|
protectedinherited |
Get the next frame filename based on SDF parameters.
|
inherited |
Get the scene this camera is in.
|
inherited |
Get the camera FOV (horizontal)
| double HorzFOV | ( | ) | const |
Get the horizontal field of view of the laser sensor.
| double HorzHalfAngle | ( | ) | const |
Get (horizontal_max_angle + horizontal_min_angle) * 0.5.
|
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 in bytes per pixel.
|
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 the camera.
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 IsHorizontal | ( | ) | const |
Gets if sensor is horizontal.
|
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 |
| const float* LaserData | ( | ) | const |
All things needed to get back z buffer for laser data.
| DataIter LaserDataBegin | ( | ) | const |
Return an iterator to the begining of the laser data.
| DataIter LaserDataEnd | ( | ) | const |
Return an iterator to one past the end of the laser data.
|
inherited |
Get the last time the camera was rendered.
|
inherited |
Get the distortion model of this camera.
|
virtual |
Load the camera with a set of parmeters.
| [in] | _sdf | The SDF camera info |
Reimplemented from Camera.
|
virtual |
Load the camera with default parmeters.
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 |
Get the camera's unscoped name.
| double NearClip | ( | ) | const |
Get near clip.
|
virtual |
|
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 RF_LOCAL, RF_PARENT, and RF_WORLD. Default is RF_LOCAL |
|
virtual |
|
virtualinherited |
Project 3D world coordinates to 2D screen coordinates.
| [in] | _pt | 3D world coodinates |
Reimplemented in UserCamera.
|
inherited |
Return the projection matrix of this camera.
|
inherited |
Return the projection type as a string.
| double RayCountRatio | ( | ) | const |
Get the ray count ratio (equivalent to aspect ratio)
|
protectedinherited |
Read image data from pixel buffer.
|
virtualinherited |
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. |
Reimplemented in UserCamera.
|
inherited |
Get the render Hz rate.
|
inherited |
Get the render texture.
|
inherited |
Reset video recording.
This will call common::VideoEncoder::Reset, which will cleanup temporary files and set video encoding values to their default settings.
|
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 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 |
Save the last encoded video to disk.
| [in] | _filename | File in which to save the encoded video |
|
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 |
|
virtualinherited |
Set background color for viewport (if viewport is not null)
| [in] | _color | Background color. |
|
virtualinherited |
Set background color for viewport (if viewport is not null)
| [in] | _color | Background color. |
Reimplemented in WideAngleCamera.
| void SetCameraCount | ( | const unsigned int | _cameraCount | ) |
Set the number of cameras required.
| [in] | _cameraCount | The number of cameras required to generate the rays |
|
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.
|
virtualinherited |
Set the clip distances.
| [in] | _near | Near clip distance in meters |
| [in] | _far | Far clip distance in meters |
Reimplemented in UserCamera.
|
protectedvirtualinherited |
Set the clip distance based on stored SDF values.
Reimplemented in WideAngleCamera.
| void SetCosHorzFOV | ( | const double | _chfov | ) |
Set the Cos Horz FOV.
| [in] | _chfov | Cos Horz FOV |
| void SetCosVertFOV | ( | const double | _cvfov | ) |
Set the Cos Horz FOV.
| [in] | _cvfov | Cos Horz FOV |
| void SetFarClip | ( | const double | _far | ) |
Set the far clip distance.
| [in] | _far | far clip distance |
|
protectedvirtualinherited |
Tell the camera whether to yaw around its own local Y axis or a fixed axis of choice.
| [in] | _useFixed | If true, the axis passed in the second parameter will always be the yaw axis no matter what the camera orientation. If false, the camera yaws around the local Y. |
| [in] | _fixedAxis | The axis to use if the first parameter is true. |
|
inherited |
Set the camera FOV (horizontal)
| [in] | _angle | Horizontal field of view |
| void SetHorzFOV | ( | const double | _hfov | ) |
Set the horizontal fov.
| [in] | _hfov | horizontal fov |
| void SetHorzHalfAngle | ( | const double | _angle | ) |
Set the horizontal half angle.
| [in] | _angle | horizontal half angle |
|
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 SetIsHorizontal | ( | const bool | _horizontal | ) |
Set sensor horizontal or vertical.
| [in] | _horizontal | True if horizontal, false if not |
|
inherited |
Set the camera's name.
| [in] | _name | New name for the camera |
| void SetNearClip | ( | const double | _near | ) |
Set the near clip distance.
| [in] | _near | near clip distance |
|
virtualinherited |
Set the type of projection used by the camera.
| [in] | _type | The type of projection: "perspective" or "orthographic". |
Reimplemented in UserCamera.
| void SetRangeCount | ( | const unsigned int | _w, |
| const unsigned int | _h = 1 |
||
| ) |
Set the number of laser samples in the width and height.
| [in] | _w | Number of samples in the horizontal sweep |
| [in] | _h | Number of samples in the vertical sweep |
| void SetRayCountRatio | ( | const double | _rayCountRatio | ) |
Sets the ray count ratio (equivalen to aspect ratio)
| [in] | _rayCountRatio | ray count ratio (equivalent to aspect ratio) |
|
inherited |
Set the render Hz rate.
| [in] | _hz | The Hz rate |
|
virtualinherited |
Set the camera's render target.
| [in] | _target | Pointer to the render target |
Reimplemented in WideAngleCamera, UserCamera, and OculusCamera.
|
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 |
|
inherited |
Set whether this camera inherits the yaw rotation of the tracked model.
| [in] | _inheritYaw | True means camera inherits the yaw rotation of the tracked model. |
|
inherited |
Set whether this camera is static when tracking a model.
| [in] | _isStatic | True means camera is static when tracking a model. |
|
inherited |
Set the maximum distance between the camera and tracked visual.
| [in] | _dist | Maximum distance between camera and visual. |
|
inherited |
Set the minimum distance between the camera and tracked visual.
| [in] | _dist | Minimum distance between camera and visual. |
|
inherited |
Set the position of the camera when tracking a visual.
| [in] | _pos | Position of the camera. |
|
inherited |
Set whether this camera's position is relative to tracked models.
| [in] | _useModelFrame | True means camera's position is relative to tracked models. |
| void SetVertFOV | ( | const double | _vfov | ) |
Set the vertical fov.
| [in] | _vfov | vertical fov |
| void SetVertHalfAngle | ( | const double | _angle | ) |
Set the vertical half angle.
| [in] | _angle | vertical half angle |
|
inherited |
|
virtualinherited |
Set the global pose of the camera.
| [in] | _pose | The new ignition::math::Pose3d of the camera |
Reimplemented in UserCamera.
|
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 whether to view the world in wireframe.
| [in] | _s | Set to True to render objects as wireframe |
|
inherited |
Turn on video recording.
| [in] | _format | String that represents the video type. Supported types include: "avi", "ogv", mp4", "v4l2". If using "v4l2", you must also specify a _filename. |
| [in] | _filename | Name of the file that stores the video while it is being created. This is a temporary file when recording to disk, or a video4linux loopback device like /dev/video0 when the _format is "v4l2". If blank, a default temporary file is used. However, the "v4l2" _format must be accompanied with a video loopback device filename. |
|
inherited |
Turn off video recording.
|
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 |
Get the visual tracked by this camera.
|
inherited |
Get whether this camera inherits the yaw rotation of the tracked model.
|
inherited |
Get whether this camera is static when tracking a model.
|
inherited |
Return the maximum distance to the tracked visual.
|
inherited |
Return the minimum distance to the tracked visual.
|
inherited |
Return the position of the camera when tracking a model.
|
inherited |
Get whether this camera's position is relative to tracked models.
|
inherited |
Set the camera to track a scene node.
| [in] | _visualName | Name of the visual to track |
|
protectedinherited |
Implementation of the Camera::TrackVisual call.
| [in] | _visualName | Name of the visual to track |
|
protectedvirtualinherited |
Set the camera to track a scene node.
| [in] | _visual | The visual to track |
Reimplemented in UserCamera, and OculusCamera.
|
inherited |
Translate the camera.
| [in] | _direction | The translation vector |
|
virtualinherited |
Get the triangle count.
|
inherited |
Get the viewport up vector.
|
virtualinherited |
Reimplemented in UserCamera, and OculusCamera.
|
protectedvirtualinherited |
Update the camera's field of view.
Reimplemented in UserCamera, and WideAngleCamera.
| double VertFOV | ( | ) | const |
Get the vertical field-of-view.
| double VertHalfAngle | ( | ) | const |
Get (vertical_max_angle + vertical_min_angle) * 0.5.
|
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 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.
|
protected |
Number of cameras needed to generate the rays.
|
protectedinherited |
True to capture frames into an image buffer.
|
protectedinherited |
True to capture a frame once and save to disk.
|
protected |
Cos horizontal field-of-view.
|
protectedinherited |
The camera's event connections.
|
protected |
Cos vertical field-of-view.
|
protected |
Far clip plane.
|
protected |
Horizontal field-of-view.
|
protected |
Horizontal half angle.
|
protectedinherited |
Format for saving images.
|
protectedinherited |
Save image height.
|
protectedinherited |
Save image width.
|
protectedinherited |
True if initialized.
|
protected |
True if the sensor is horizontal only.
|
protectedinherited |
Time the last frame was rendered.
|
protectedinherited |
Name of the camera.
|
protected |
Near clip plane.
|
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.
|
protected |
Ray count ratio.
|
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.
|
protected |
Vertical half angle.
|
protected |
Vertical field-of-view.
|
protectedinherited |
Viewport the ogre camera uses.
|
protectedinherited |
ID of the window that the camera is attached to.