Generate depth ray data. More...
#include <gz/rendering/GpuRays.hh>
Public Types | |
typedef std::function< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> | NewFrameListener |
Callback function for new frame render event listeners. More... | |
Public Types inherited from Camera | |
typedef std::function< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> | NewFrameListener |
Callback function for new frame render event listeners. More... | |
Public Member Functions | |
virtual | ~GpuRays () |
Destructor. More... | |
virtual gz::math::Angle | AngleMax () const =0 |
Get maximal horizontal angle value. More... | |
virtual gz::math::Angle | AngleMin () const =0 |
Get minimal horizontal angle value. More... | |
virtual unsigned int | Channels () const =0 |
Get the number of channels used to store the ray data. More... | |
virtual bool | Clamp () const =0 |
Get behaviour for data values outside of camera range. More... | |
virtual common::ConnectionPtr | ConnectNewGpuRaysFrame (std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &)> _subscriber)=0 |
Connect to a gpu rays frame signal. More... | |
virtual void | Copy (float *_data)=0 |
Copy to the specified memory direction the gpu rays data. More... | |
virtual const float * | Data () const =0 |
All things needed to get back z buffer for gpu rays data. More... | |
virtual double | HorizontalResolution () const =0 |
Get the horizontal resolution. This number is multiplied by RayCount to calculate RangeCount, which is the the number range data points. More... | |
virtual bool | IsHorizontal () const =0 |
Gets if sensor is horizontal. More... | |
virtual int | RangeCount () const =0 |
Get hoizontal range count, i.e. ray count * horz resolution. More... | |
virtual double | RangeCountRatio () const =0 |
Get the ray count ratio (equivalent to aspect ratio) More... | |
virtual int | RayCount () const =0 |
Get horizontal quantity of rays. More... | |
virtual double | RayCountRatio () const =0 |
Get the ray count ratio (equivalent to aspect ratio) More... | |
virtual void | SetAngleMax (double _angle)=0 |
Set maximal horizontal angle value. More... | |
virtual void | SetAngleMin (double _angle)=0 |
Set minimal horizontal angle value. More... | |
virtual void | SetClamp (const bool _clamp)=0 |
Configure behaviour for data values outside of camera range. More... | |
virtual void | SetHorizontalResolution (double _resolution)=0 |
Set the horizontal resolution. This number is multiplied by RayCount to calculate RangeCount, which is the the number range data points. More... | |
virtual void | SetIsHorizontal (const bool _horizontal)=0 |
Set sensor horizontal or vertical. More... | |
virtual void | SetRayCount (int _samples)=0 |
Set horizontal quantity of rays. More... | |
virtual void | SetRayCountRatio (const double _rayCountRatio)=0 |
Sets the ray count ratio (equivalent to aspect ratio) More... | |
virtual void | SetVerticalAngleMax (const double _angle)=0 |
Set maximal vertical angle value. More... | |
virtual void | SetVerticalAngleMin (const double _angle)=0 |
Set minimal vertical angle value. More... | |
virtual void | SetVerticalRayCount (int _samples)=0 |
Set vertical quantity of rays. More... | |
virtual void | SetVerticalResolution (double _resolution)=0 |
Set the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points. More... | |
virtual gz::math::Angle | VerticalAngleMax () const =0 |
Get maximal vertical angle value. More... | |
virtual gz::math::Angle | VerticalAngleMin () const =0 |
Get minimal vertical angle value. More... | |
virtual int | VerticalRangeCount () const =0 |
Get vertical range count, i.e. ray count * vert resolution. More... | |
virtual int | VerticalRayCount () const =0 |
Get vertical quantity of rays. More... | |
virtual double | VerticalResolution () const =0 |
Get the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points. More... | |
virtual math::Angle | VFOV () const =0 |
Get the vertical field-of-view. More... | |
Public Member Functions inherited from Camera | |
virtual | ~Camera () |
Destructor. More... | |
virtual void | AddRenderPass (const RenderPassPtr &_pass)=0 |
Add a render pass to the camera. More... | |
virtual unsigned int | AntiAliasing () const =0 |
Get the level of anti-aliasing used during rendering. More... | |
virtual double | AspectRatio () const =0 |
Get the camera's aspect ratio. More... | |
virtual void | Capture (Image &_image)=0 |
Renders a new frame and writes the results to the given image. This is a convenience function for single-camera scenes. It wraps the pre-render, render, post-render, and get-image calls into a single function. This should NOT be used in applications with multiple cameras or multiple consumers of a single camera's images. More... | |
virtual common::ConnectionPtr | ConnectNewImageFrame (NewFrameListener _listener)=0 |
Subscribes a new listener to this camera's new frame event. More... | |
virtual void | Copy (Image &_image) const =0 |
Writes the last rendered image to the given image buffer. This function can be called multiple times after PostRender has been called, without rendering the scene again. Calling this function before a single image has been rendered will have undefined behavior. More... | |
virtual Image | CreateImage () const =0 |
Created an empty image buffer for capturing images. The resulting image will have sufficient memory allocated for subsequent calls to this camera's Capture function. However, any changes to this cameras properties may invalidate the condition. More... | |
virtual RenderWindowPtr | CreateRenderWindow ()=0 |
Create a render window. More... | |
virtual double | FarClipPlane () const =0 |
Get the camera's far clipping plane distance. More... | |
virtual math::Vector3d | FollowOffset () const =0 |
Get the follow offset vector in the frame specified at the time the follow target is set. More... | |
virtual double | FollowPGain () const =0 |
Get the camera follow movement P gain. More... | |
virtual NodePtr | FollowTarget () const =0 |
Get the target node being followed. More... | |
virtual math::Angle | HFOV () const =0 |
Get the camera's horizontal field-of-view. More... | |
virtual PixelFormat | ImageFormat () const =0 |
Get the image pixel format. If the image pixel format has not been set with a valid value, PF_UNKNOWN will be returned. More... | |
virtual unsigned int | ImageHeight () const =0 |
Get the image height in pixels. More... | |
virtual unsigned int | ImageMemorySize () const =0 |
Get the total image memory size in bytes. More... | |
virtual unsigned int | ImageWidth () const =0 |
Get the image width in pixels. More... | |
virtual double | NearClipPlane () const =0 |
Get the camera's near clipping plane distance. More... | |
virtual void | PostRender ()=0 |
Preforms any necessary final rendering work. Once rendering is complete the camera will alert any listeners of the new frame event. This function should only be called after a call to Render has successfully been executed. More... | |
virtual math::Vector2i | Project (const math::Vector3d &_pt) const =0 |
Project point in 3d world space to 2d screen space. More... | |
virtual math::Matrix4d | ProjectionMatrix () const =0 |
Get the projection matrix for this camera. More... | |
virtual CameraProjectionType | ProjectionType () const =0 |
Get the projection type for this camera. More... | |
virtual void | RemoveRenderPass (const RenderPassPtr &_pass)=0 |
Remove a render pass from the camera. More... | |
virtual void | Render ()=0 |
Renders the current scene using this camera. This function assumes PreRender() has already been called on the parent Scene, allowing the camera and the scene itself to prepare for rendering. More... | |
virtual RenderPassPtr | RenderPassByIndex (unsigned int _index) const =0 |
Get a render passes by index. More... | |
virtual unsigned int | RenderPassCount () const =0 |
Get the number of render passes applied to the camera. More... | |
virtual unsigned int | RenderTextureGLId () const =0 |
Get the OpenGL texture id associated with the render texture used by this camera. A valid id is returned only if the underlying render engine is OpenGL based. More... | |
virtual void | RenderTextureMetalId (void *_textureIdPtr) const =0 |
Get the Metal texture id associated with the render texture used by this camera. A valid Id is obtained only if the underlying render engine is Metal based. The pointer set by this function must be released to an id<MTLTexture> using CFBridgingRelease. More... | |
virtual bool | SaveFrame (const std::string &_name)=0 |
Writes the previously rendered frame to a file. This function can be called multiple times after PostRender has been called, without rendering the scene again. Calling this function before a single image has been rendered will have undefined behavior. More... | |
virtual void | SetAntiAliasing (const unsigned int _aa)=0 |
Set the level of anti-aliasing used during rendering. If a value of 0 is given, no anti-aliasing will be performed. Higher values can significantly slow-down rendering times, depending on the underlying render engine. More... | |
virtual void | SetAspectRatio (const double _ratio)=0 |
Set the camera's aspect ratio. This value determines the cameras vertical field-of-view. It is often the. More... | |
virtual void | SetFarClipPlane (const double _far)=0 |
Set the camera's far clipping plane distance. More... | |
virtual void | SetFollowOffset (const math::Vector3d &_offset)=0 |
Set offset of camera from target node being followed. The offset will be in the frame that is specified at the time the follow target is set. More... | |
virtual void | SetFollowPGain (const double _pGain)=0 |
Set follow P Gain. Determines how fast the camera moves to follow the target node. Valid range: [0-1]. More... | |
virtual void | SetFollowTarget (const NodePtr &_target, const math::Vector3d &_offset=math::Vector3d::Zero, const bool _worldFrame=false)=0 |
Set a node for camera to follow. The camera will automatically update its position to keep itself at the specified offset distance from the target being followed. If null is specified, camera follow is disabled. In contrast to SetTrackTarget, the camera does not change its orientation when following is enabled. More... | |
virtual void | SetHFOV (const math::Angle &_hfov)=0 |
Set the camera's horizontal field-of-view. More... | |
virtual void | SetImageFormat (PixelFormat _format)=0 |
Set the image pixel format. More... | |
virtual void | SetImageHeight (unsigned int _height)=0 |
Set the image height in pixels. More... | |
virtual void | SetImageWidth (unsigned int _width)=0 |
Set the image width in pixels. More... | |
virtual void | SetMaterial (const MaterialPtr &_material)=0 |
Set a material that the camera should see on all objects. More... | |
virtual void | SetNearClipPlane (const double _near)=0 |
Set the camera's near clipping plane distance. More... | |
virtual void | SetProjectionMatrix (const math::Matrix4d &_matrix)=0 |
Set the projection matrix for this camera. This overrides the standard projection matrix computed based on camera parameters. More... | |
virtual void | SetProjectionType (CameraProjectionType _type)=0 |
Set the projection type for this camera This changes the projection matrix of the camera based on the camera projection type. A custom projection matrix can be specified via SetProjectionMatrix to override the provided one. To disable the custom projection matrix, just call this function again with the desired projection type. More... | |
virtual void | SetShadowsDirty ()=0 |
virtual void | SetTrackOffset (const math::Vector3d &_offset)=0 |
Set track offset. Camera will track a point that's at an offset from the target node. The offset will be in the frame that is specified at the time the track target is set. More... | |
virtual void | SetTrackPGain (const double _pGain)=0 |
Set track P Gain. Determines how fast the camera rotates to look at the target node. Valid range: [0-1]. More... | |
virtual void | SetTrackTarget (const NodePtr &_target, const math::Vector3d &_offset=math::Vector3d::Zero, const bool _worldFrame=false)=0 |
Set a node for camera to track. The camera will automatically change its orientation to face the target being tracked. If null is specified, tracking is disabled. In contrast to SetFollowTarget the camera does not change its position when tracking is enabled. More... | |
virtual math::Vector3d | TrackOffset () const =0 |
Get the track offset vector in the frame specified at the time the track target is set. More... | |
virtual double | TrackPGain () const =0 |
Get the camera track rotation P gain. More... | |
virtual NodePtr | TrackTarget () const =0 |
Get the target node being tracked. More... | |
virtual void | Update ()=0 |
Renders a new frame. This is a convenience function for single-camera scenes. It wraps the pre-render, render, and post-render into a single function. This should NOT be used in applications with multiple cameras or multiple consumers of a single camera's images. More... | |
virtual math::Matrix4d | ViewMatrix () const =0 |
Get the view matrix for this camera. More... | |
virtual VisualPtr | VisualAt (const gz::math::Vector2i &_mousePos)=0 |
Get the visual for a given mouse position param[in] _mousePos mouse position. More... | |
Public Member Functions inherited from Sensor | |
virtual | ~Sensor () |
Sensor. More... | |
virtual void | SetVisibilityMask (uint32_t _mask)=0 |
Set visibility mask. More... | |
virtual uint32_t | VisibilityMask () const =0 |
Get visibility mask. More... | |
Public Member Functions inherited from Node | |
virtual | ~Node () |
Destructor. More... | |
virtual void | AddChild (NodePtr _child)=0 |
Add the given node to this node. If the given node is already a child, no work will be done. More... | |
virtual NodePtr | ChildById (unsigned int _id) const =0 |
Get node with given ID. If no child exists with given ID, NULL will be returned. More... | |
virtual NodePtr | ChildByIndex (unsigned int _index) const =0 |
Get node at given index. If no child exists at given index, NULL will be returned. More... | |
virtual NodePtr | ChildByName (const std::string &_name) const =0 |
Get node with given name. If no child exists with given name, NULL will be returned. More... | |
virtual unsigned int | ChildCount () const =0 |
Get number of child nodes. More... | |
virtual bool | HasChild (ConstNodePtr _child) const =0 |
Determine if given node is an attached child. More... | |
virtual bool | HasChildId (unsigned int _id) const =0 |
Determine if node with given ID is an attached child. More... | |
virtual bool | HasChildName (const std::string &_name) const =0 |
Determine if node with given name is an attached child. More... | |
virtual bool | HasParent () const =0 |
Determine if this Node is attached to another Node. More... | |
virtual bool | HasUserData (const std::string &_key) const =0 |
Check if node has custom data. More... | |
virtual bool | InheritScale () const =0 |
Determine if this node inherits scale from this parent. More... | |
virtual math::Pose3d | InitialLocalPose () const =0 |
Get the initial local pose. More... | |
virtual math::Pose3d | LocalPose () const =0 |
Get the local pose. More... | |
virtual math::Vector3d | LocalPosition () const =0 |
Get the local position. More... | |
virtual math::Quaterniond | LocalRotation () const =0 |
Get the local rotation. More... | |
virtual math::Vector3d | LocalScale () const =0 |
Get the local scale. More... | |
virtual math::Vector3d | Origin () const =0 |
Get position of origin. More... | |
virtual NodePtr | Parent () const =0 |
Get the parent Node. More... | |
virtual NodePtr | RemoveChild (NodePtr _child)=0 |
Remove (detach) the given node from this node. If the given node is not a child of this node, no work will be done. More... | |
virtual NodePtr | RemoveChildById (unsigned int _id)=0 |
Remove (detach) the node with the given ID from this node. If the specified node is not a child of this node, no work will be done. More... | |
virtual NodePtr | RemoveChildByIndex (unsigned int _index)=0 |
Remove (detach) the node at the given index from this node. If the specified node is not a child of this node, no work will be done. More... | |
virtual NodePtr | RemoveChildByName (const std::string &_name)=0 |
Remove (detach) the node with the given name from this node. If the specified node is not a child of this node, no work will be done. More... | |
virtual void | RemoveChildren ()=0 |
Remove all child nodes from this node This detaches all the child nodes but does not destroy them. More... | |
virtual void | RemoveParent ()=0 |
Detach this Node from its parent. If this Node does not have a parent, no work will be done. More... | |
virtual void | Scale (const math::Vector3d &_scale)=0 |
Scale the current scale by the given scalars. More... | |
virtual void | Scale (double _scale)=0 |
Scale the current scale by the given scalar. The given scalar will be assigned to the x, y, and z coordinates. More... | |
virtual void | Scale (double _x, double _y, double _z)=0 |
Scale the current scale by the given scalars. More... | |
virtual void | SetInheritScale (bool _inherit)=0 |
Specify if this node inherits scale from its parent. More... | |
virtual void | SetLocalPose (const math::Pose3d &_pose)=0 |
Set the local pose. More... | |
virtual void | SetLocalPosition (const math::Vector3d &_position)=0 |
Set the local position. More... | |
virtual void | SetLocalPosition (double _x, double _y, double _z)=0 |
Set the local position. More... | |
virtual void | SetLocalRotation (const math::Quaterniond &_rotation)=0 |
Set the local rotation. More... | |
virtual void | SetLocalRotation (double _r, double _p, double _y)=0 |
Set the local rotation. More... | |
virtual void | SetLocalRotation (double _w, double _x, double _y, double _z)=0 |
Set the local rotation. More... | |
virtual void | SetLocalScale (const math::Vector3d &_scale)=0 |
Set the local scale. More... | |
virtual void | SetLocalScale (double _scale)=0 |
Set the local scale. The given scale will be assigned to the x, y, and z coordinates. More... | |
virtual void | SetLocalScale (double _x, double _y, double _z)=0 |
Set the local scale. More... | |
virtual void | SetOrigin (const math::Vector3d &_origin)=0 |
Set position of origin. The position should be relative to the original origin of the geometry. More... | |
virtual void | SetOrigin (double _x, double _y, double _z)=0 |
Set position of origin. The position should be relative to the original origin of the geometry. More... | |
virtual void | SetUserData (const std::string &_key, Variant _value)=0 |
Store any custom data associated with this node. More... | |
virtual void | SetWorldPose (const math::Pose3d &_pose)=0 |
Set the world pose. More... | |
virtual void | SetWorldPosition (const math::Vector3d &_position)=0 |
Set the world position. More... | |
virtual void | SetWorldPosition (double _x, double _y, double _z)=0 |
Set the world position. More... | |
virtual void | SetWorldRotation (const math::Quaterniond &_rotation)=0 |
Set the world rotation. More... | |
virtual void | SetWorldRotation (double _r, double _p, double _y)=0 |
Set the world rotation. More... | |
virtual void | SetWorldRotation (double _w, double _x, double _y, double _z)=0 |
Set the world rotation. More... | |
virtual void | SetWorldScale (const math::Vector3d &_scale)=0 |
Set the world scale. More... | |
virtual void | SetWorldScale (double _scale)=0 |
Set the world scale. The given scale will be assigned to the x, y, and z coordinates. More... | |
virtual void | SetWorldScale (double _x, double _y, double _z)=0 |
Set the world scale. More... | |
virtual Variant | UserData (const std::string &_key) const =0 |
Get custom data stored in this node. More... | |
virtual math::Pose3d | WorldPose () const =0 |
Get the world pose. More... | |
virtual math::Vector3d | WorldPosition () const =0 |
Get the world position. More... | |
virtual math::Quaterniond | WorldRotation () const =0 |
Get the world rotation. More... | |
virtual math::Vector3d | WorldScale () const =0 |
Get the world scale. More... | |
virtual math::Pose3d | WorldToLocal (const math::Pose3d &_pose) const =0 |
Convert given world pose to local pose. More... | |
Public Member Functions inherited from Object | |
virtual | ~Object () |
Destructor. More... | |
virtual void | Destroy ()=0 |
Destroy any resources associated with this object. Invoking any other functions after destroying an object will result in undefined behavior. More... | |
virtual unsigned int | Id () const =0 |
Get the object ID. This ID will be unique across all objects inside a given scene, but necessarily true for objects across different scenes. More... | |
virtual std::string | Name () const =0 |
Get the object name. This name will be unique across all objects inside a given scene, but necessarily true for objects across different scenes. More... | |
virtual void | PreRender ()=0 |
Prepare this object and any of its children for rendering. This should be called for each object in a scene just before rendering, which can be achieved by a single call to Scene::PreRender. More... | |
virtual ScenePtr | Scene () const =0 |
Get the Scene that created this object. More... | |
Detailed Description
Generate depth ray data.
Member Typedef Documentation
◆ NewFrameListener
typedef std::function<void(const void*, unsigned int, unsigned int, unsigned int, const std::string&)> NewFrameListener |
Callback function for new frame render event listeners.
Constructor & Destructor Documentation
◆ ~GpuRays()
|
virtual |
Destructor.
Member Function Documentation
◆ AngleMax()
|
pure virtual |
Get maximal horizontal angle value.
Implemented in BaseGpuRays< T >.
◆ AngleMin()
|
pure virtual |
Get minimal horizontal angle value.
Implemented in BaseGpuRays< T >.
◆ Channels()
|
pure virtual |
Get the number of channels used to store the ray data.
- Returns
- Channel count.
Implemented in BaseGpuRays< T >.
◆ Clamp()
|
pure virtual |
Get behaviour for data values outside of camera range.
- Returns
- True if data values are clampped to camera clip distances,
Implemented in BaseGpuRays< T >.
◆ ConnectNewGpuRaysFrame()
|
pure virtual |
Connect to a gpu rays frame signal.
- Parameters
-
[in] _subscriber Callback that is called when a new image is generated. The callback function parameters are: _frame: Image frame is an array of floats. Size is equal to width * height * channels Each gpu rays reading occupies 3 floats Index 0: depth value Index 1: retro value Index 2: 0. Not used _width: Width of image, i.e. number of data in the horizonal scan _height: Height o image, i.e. number of scans in vertical direction _channels: Number of channels, i.e. 3 floats per gpu rays reading _format: Pixel format of the image frame.
- Returns
- A pointer to the connection. This must be kept in scope.
◆ Copy()
|
pure virtual |
Copy to the specified memory direction the gpu rays data.
Implemented in Ogre2GpuRays, OgreGpuRays, BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ Data()
|
pure virtual |
All things needed to get back z buffer for gpu rays data.
- Returns
- Array of gpu rays data.
Implemented in Ogre2GpuRays, OgreGpuRays, and BaseGpuRays< T >.
◆ HorizontalResolution()
|
pure virtual |
Get the horizontal resolution. This number is multiplied by RayCount to calculate RangeCount, which is the the number range data points.
- See also
- RayCount()
- Returns
- The horizontal resolution
Implemented in BaseGpuRays< T >.
◆ IsHorizontal()
|
pure virtual |
Gets if sensor is horizontal.
- Returns
- True if horizontal, false if not
Implemented in BaseGpuRays< T >.
◆ RangeCount()
|
pure virtual |
Get hoizontal range count, i.e. ray count * horz resolution.
Implemented in BaseGpuRays< T >.
◆ RangeCountRatio()
|
pure virtual |
Get the ray count ratio (equivalent to aspect ratio)
- Returns
- The ray count ratio (equivalent to aspect ratio)
Implemented in BaseGpuRays< T >.
◆ RayCount()
|
pure virtual |
Get horizontal quantity of rays.
Implemented in BaseGpuRays< T >.
◆ RayCountRatio()
|
pure virtual |
Get the ray count ratio (equivalent to aspect ratio)
- Returns
- The ray count ratio (equivalent to aspect ratio)
Implemented in BaseGpuRays< T >.
◆ SetAngleMax()
|
pure virtual |
Set maximal horizontal angle value.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetAngleMin()
|
pure virtual |
Set minimal horizontal angle value.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetClamp()
|
pure virtual |
Configure behaviour for data values outside of camera range.
- Parameters
-
[in] _clamp True to clamp data to camera clip distances,
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetHorizontalResolution()
|
pure virtual |
Set the horizontal resolution. This number is multiplied by RayCount to calculate RangeCount, which is the the number range data points.
- See also
- RayCount()
- Parameters
-
[in] _resolution The new horizontal resolution. The absolute value of this parameter is used to prevent a negative resolution value.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetIsHorizontal()
|
pure virtual |
Set sensor horizontal or vertical.
- Parameters
-
[in] _horizontal True if horizontal, false if not
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetRayCount()
|
pure virtual |
Set horizontal quantity of rays.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetRayCountRatio()
|
pure virtual |
Sets the ray count ratio (equivalent to aspect ratio)
- Parameters
-
[in] _rayCountRatio ray count ratio (equivalent to aspect ratio)
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetVerticalAngleMax()
|
pure virtual |
Set maximal vertical angle value.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetVerticalAngleMin()
|
pure virtual |
Set minimal vertical angle value.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetVerticalRayCount()
|
pure virtual |
Set vertical quantity of rays.
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ SetVerticalResolution()
|
pure virtual |
Set the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points.
- Parameters
-
[in] _resolution The new vertical resolution. The absolute value of this parameter is used to prevent a negative resolution value.
- See also
- VerticalRayCount()
Implemented in BaseGpuRays< T >, BaseGpuRays< Ogre2Sensor >, and BaseGpuRays< OgreSensor >.
◆ VerticalAngleMax()
|
pure virtual |
Get maximal vertical angle value.
Implemented in BaseGpuRays< T >.
◆ VerticalAngleMin()
|
pure virtual |
Get minimal vertical angle value.
Implemented in BaseGpuRays< T >.
◆ VerticalRangeCount()
|
pure virtual |
Get vertical range count, i.e. ray count * vert resolution.
Implemented in BaseGpuRays< T >.
◆ VerticalRayCount()
|
pure virtual |
Get vertical quantity of rays.
Implemented in BaseGpuRays< T >.
◆ VerticalResolution()
|
pure virtual |
Get the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points.
- Returns
- The vertical resolution.
- See also
- VerticalRayCount()
Implemented in BaseGpuRays< T >.
◆ VFOV()
|
pure virtual |
Get the vertical field-of-view.
- Returns
- The vertical field of view of the gpu rays.
Implemented in BaseGpuRays< T >.
The documentation for this class was generated from the following file: