Ignition Rendering

API Reference

6.3.1

#include <BaseGpuRays.hh>

Public Member Functions

virtual ~BaseGpuRays ()
 Destructor. More...
 
virtual ignition::math::Angle AngleMax () const override
 Get maximal horizontal angle value. More...
 
virtual ignition::math::Angle AngleMin () const override
 Get minimal horizontal angle value. More...
 
virtual unsigned int Channels () const override
 Get the number of channels used to store the ray data. More...
 
virtual bool Clamp () const override
 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 &_format)> _subscriber) override
 
virtual void Copy (float *_data) override
 Copy to the specified memory direction the gpu rays data. More...
 
virtual const float * Data () const override
 All things needed to get back z buffer for gpu rays data. More...
 
virtual double HorizontalResolution () const override
 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 override
 Gets if sensor is horizontal. More...
 
virtual int RangeCount () const override
 Get hoizontal range count, i.e. ray count * horz resolution. More...
 
virtual double RangeCountRatio () const override
 Get the ray count ratio (equivalent to aspect ratio) More...
 
virtual int RayCount () const override
 Get horizontal quantity of rays. More...
 
virtual double RayCountRatio () const override
 Get the ray count ratio (equivalent to aspect ratio) More...
 
virtual RenderTargetPtr RenderTarget () const override=0
 Pointer to the render target. More...
 
virtual void SetAngleMax (double _angle) override
 Set maximal horizontal angle value. More...
 
virtual void SetAngleMin (double _angle) override
 Set minimal horizontal angle value. More...
 
virtual void SetClamp (bool _enable) override
 Configure behaviour for data values outside of camera range. More...
 
virtual void SetHorizontalResolution (double _resolution) override
 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) override
 Set sensor horizontal or vertical. More...
 
virtual void SetRayCount (int _samples) override
 Set horizontal quantity of rays. More...
 
virtual void SetRayCountRatio (const double _rayCountRatio) override
 Sets the ray count ratio (equivalent to aspect ratio) More...
 
virtual void SetVerticalAngleMax (const double _angle) override
 Set maximal vertical angle value. More...
 
virtual void SetVerticalAngleMin (const double _angle) override
 Set minimal vertical angle value. More...
 
virtual void SetVerticalRayCount (int _samples) override
 Set vertical quantity of rays. More...
 
virtual void SetVerticalResolution (double resolution) override
 Set the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points. More...
 
virtual void SetVFOV (const math::Angle &_vfov)
 Set the vertical fov. More...
 
virtual ignition::math::Angle VerticalAngleMax () const override
 Get maximal vertical angle value. More...
 
virtual ignition::math::Angle VerticalAngleMin () const override
 Get minimal vertical angle value. More...
 
virtual int VerticalRangeCount () const override
 Get vertical range count, i.e. ray count * vert resolution. More...
 
virtual int VerticalRayCount () const override
 Get vertical quantity of rays. More...
 
virtual double VerticalResolution () const override
 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 override
 Get the vertical field-of-view. More...
 
- Public Member Functions inherited from GpuRays
virtual ~GpuRays ()
 Destructor. 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...
 
- Public Member Functions inherited from Camera
virtual ~Camera ()
 Destructor. 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...
 
- 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 (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 Scale (const math::Vector3d &_scale)=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 (double _x, double _y, double _z)=0
 Set the local position. More...
 
virtual void SetLocalPosition (const math::Vector3d &_position)=0
 Set the local position. 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 SetLocalRotation (const math::Quaterniond &_rotation)=0
 Set the local rotation. 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 SetLocalScale (const math::Vector3d &_scale)=0
 Set the local scale. 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 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 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 (double _x, double _y, double _z)=0
 Set the world position. More...
 
virtual void SetWorldPosition (const math::Vector3d &_position)=0
 Set the world position. 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 SetWorldRotation (const math::Quaterniond &_rotation)=0
 Set the world rotation. 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 void SetWorldScale (const math::Vector3d &_scale)=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 ScenePtr Scene () const =0
 Get the Scene that created this object. More...
 
- Public Member Functions inherited from BaseCamera< T >
virtual ~BaseCamera ()
 
virtual void AddRenderPass (const RenderPassPtr &_pass) override
 Add a render pass to the camera. More...
 
virtual unsigned int AntiAliasing () const override
 Get the level of anti-aliasing used during rendering. More...
 
virtual double AspectRatio () const override
 Get the camera's aspect ratio. More...
 
virtual void Capture (Image &_image) override
 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 (Camera::NewFrameListener _listener) override
 Subscribes a new listener to this camera's new frame event. More...
 
virtual void Copy (Image &_image) const override
 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 override
 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 () override
 Create a render window. More...
 
virtual double FarClipPlane () const override
 Get the camera's far clipping plane distance. More...
 
virtual math::Vector3d FollowOffset () const override
 Get the follow offset vector in the frame specified at the time the follow target is set. More...
 
virtual double FollowPGain () const override
 Get the camera follow movement P gain. More...
 
virtual NodePtr FollowTarget () const override
 Get the target node being followed. More...
 
virtual math::Angle HFOV () const override
 Get the camera's horizontal field-of-view. More...
 
virtual PixelFormat ImageFormat () const override
 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 override
 Get the image height in pixels. More...
 
virtual unsigned int ImageMemorySize () const override
 Get the total image memory size in bytes. More...
 
virtual unsigned int ImageWidth () const override
 Get the image width in pixels. More...
 
virtual double NearClipPlane () const override
 Get the camera's near clipping plane distance. More...
 
virtual void PostRender () override
 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 void PreRender () override
 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 math::Vector2i Project (const math::Vector3d &_pt) const override
 Project point in 3d world space to 2d screen space. More...
 
virtual math::Matrix4d ProjectionMatrix () const override
 Get the projection matrix for this camera. More...
 
virtual CameraProjectionType ProjectionType () const override
 Get the projection type for this camera. More...
 
virtual void RemoveRenderPass (const RenderPassPtr &_pass) override
 Remove a render pass from the camera. More...
 
virtual RenderPassPtr RenderPassByIndex (unsigned int _index) const override
 Get a render passes by index. More...
 
virtual unsigned int RenderPassCount () const override
 Get the number of render passes applied to the camera. More...
 
virtual unsigned int RenderTextureGLId () const override
 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 bool SaveFrame (const std::string &_name) override
 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) override
 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) override
 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) override
 Set the camera's far clipping plane distance. More...
 
virtual void SetFollowOffset (const math::Vector3d &_offset) override
 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) override
 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, const bool _worldFrame) override
 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) override
 Set the camera's horizontal field-of-view. More...
 
virtual void SetImageFormat (PixelFormat _format) override
 Set the image pixel format. More...
 
virtual void SetImageHeight (const unsigned int _height) override
 Set the image height in pixels. More...
 
virtual void SetImageWidth (const unsigned int _width) override
 Set the image width in pixels. More...
 
virtual void SetMaterial (const MaterialPtr &_material) override
 Set a material that the camera should see on all objects. More...
 
virtual void SetNearClipPlane (const double _near) override
 Set the camera's near clipping plane distance. More...
 
virtual void SetProjectionMatrix (const math::Matrix4d &_matrix) override
 Set the projection matrix for this camera. This overrides the standard projection matrix computed based on camera parameters. More...
 
virtual void SetProjectionType (CameraProjectionType _type) override
 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 () override
 
virtual void SetTrackOffset (const math::Vector3d &_offset) override
 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) override
 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, const bool _worldFrame) override
 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 override
 Get the track offset vector in the frame specified at the time the track target is set. More...
 
virtual double TrackPGain () const override
 Get the camera track rotation P gain. More...
 
virtual NodePtr TrackTarget () const override
 Get the target node being tracked. More...
 
virtual void Update () override
 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 override
 Get the view matrix for this camera. More...
 
virtual VisualPtr VisualAt (const ignition::math::Vector2i &_mousePos) override
 Get the visual for a given mouse position param[in] _mousePos mouse position. More...
 

Public Attributes

bool clamping = false
 True if data values are clamped to camera clip distances,. More...
 
float dataMaxVal = ignition::math::INF_D
 maximum value used for data outside sensor range More...
 
float dataMinVal = -ignition::math::INF_D
 minimum value used for data outside sensor range More...
 

Protected Member Functions

 BaseGpuRays ()
 Constructor. More...
 
- Protected Member Functions inherited from BaseCamera< T >
 BaseCamera ()
 
virtual void * CreateImageBuffer () const
 
virtual void Load () override
 
virtual void Reset ()
 

Protected Attributes

unsigned int channels = 1u
 Number of channels used to store the data. More...
 
double hResolution = 1
 Resolution of horizontal rays. More...
 
int hSamples = 0
 Quantity of horizontal rays. More...
 
bool isHorizontal = true
 True if the sensor is horizontal only. More...
 
double maxAngle = 0
 Horizontal maximal angle. More...
 
double minAngle = 0
 Horizontal minimal angle. More...
 
double rangeCountRatio = 0
 Range count ratio. More...
 
double rayCountRatio = 0
 Ray count ratio. More...
 
math::Angle vfov
 Vertical field-of-view. More...
 
double vMaxAngle = 0
 Vertical maximal angle. More...
 
double vMinAngle = 0
 Vertical minimal angle. More...
 
double vResolution = 1
 Resolution of vertical rays. More...
 
int vSamples = 0
 Quantity of verical rays. More...
 
- Protected Attributes inherited from BaseCamera< T >
unsigned int antiAliasing = 0u
 Anti-aliasing. More...
 
double aspect = 1.3333333
 Aspect ratio. More...
 
double farClip = 1000.0
 Far clipping plane distance. More...
 
NodePtr followNode
 Target node to follow. More...
 
math::Vector3d followOffset
 Offset distance between camera and target node being followed. More...
 
double followPGain = 1.0
 P gain for follow mode. Determines how fast the camera moves to follow the target node. Valid range: [0-1]. More...
 
bool followWorldFrame = false
 Follow target in world frame. More...
 
math::Angle hfov
 Horizontal camera field of view. More...
 
ImagePtr imageBuffer
 
double nearClip = 0.01
 Near clipping plane distance. More...
 
common::EventT< void(const void *, unsigned int, unsigned int, unsigned int, const std::string &)> newFrameEvent
 
math::Matrix4d projectionMatrix
 Custom projection matrix. More...
 
CameraProjectionType projectionType = CPT_PERSPECTIVE
 Camera projection type. More...
 
NodePtr trackNode
 Target node to track if camera tracking is on. More...
 
math::Vector3d trackOffset
 Set camera to track a point offset in target node's local or world frame depending on trackWorldFrame. More...
 
double trackPGain = 1.0
 P gain for tracking. Determines how fast the camera rotates to look at the target node. Valid range: [0-1]. More...
 
bool trackWorldFrame = false
 Track point relative to target in world frame. More...
 

Additional Inherited Members

- Public Types inherited from GpuRays
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...
 

Constructor & Destructor Documentation

◆ BaseGpuRays()

BaseGpuRays ( )
protected

Constructor.

◆ ~BaseGpuRays()

~BaseGpuRays ( )
virtual

Destructor.

Member Function Documentation

◆ AngleMax()

ignition::math::Angle AngleMax ( ) const
overridevirtual

Get maximal horizontal angle value.

Implements GpuRays.

◆ AngleMin()

ignition::math::Angle AngleMin ( ) const
overridevirtual

Get minimal horizontal angle value.

Implements GpuRays.

◆ Channels()

unsigned int Channels ( ) const
overridevirtual

Get the number of channels used to store the ray data.

Returns
Channel count.

Implements GpuRays.

◆ Clamp()

bool Clamp ( ) const
overridevirtual

Get behaviour for data values outside of camera range.

Returns
True if data values are clampped to camera clip distances,

Implements GpuRays.

◆ ConnectNewGpuRaysFrame()

ignition::common::ConnectionPtr ConnectNewGpuRaysFrame ( std::function< void(const float *_frame, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)>  _subscriber)
overridevirtual

◆ Copy()

void Copy ( float *  _data)
overridevirtual

Copy to the specified memory direction the gpu rays data.

Implements GpuRays.

Reimplemented in OgreGpuRays.

◆ Data()

const float * Data ( ) const
overridevirtual

All things needed to get back z buffer for gpu rays data.

Returns
Array of gpu rays data.

Implements GpuRays.

Reimplemented in OgreGpuRays.

◆ HorizontalResolution()

double HorizontalResolution ( ) const
overridevirtual

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

Implements GpuRays.

◆ IsHorizontal()

bool IsHorizontal ( ) const
overridevirtual

Gets if sensor is horizontal.

Returns
True if horizontal, false if not

Implements GpuRays.

◆ RangeCount()

int RangeCount ( ) const
overridevirtual

Get hoizontal range count, i.e. ray count * horz resolution.

Implements GpuRays.

◆ RangeCountRatio()

double RangeCountRatio ( ) const
overridevirtual

Get the ray count ratio (equivalent to aspect ratio)

Returns
The ray count ratio (equivalent to aspect ratio)

Implements GpuRays.

◆ RayCount()

int RayCount ( ) const
overridevirtual

Get horizontal quantity of rays.

Implements GpuRays.

Referenced by BaseGpuRays< OgreSensor >::RangeCount().

◆ RayCountRatio()

double RayCountRatio ( ) const
overridevirtual

Get the ray count ratio (equivalent to aspect ratio)

Returns
The ray count ratio (equivalent to aspect ratio)

Implements GpuRays.

◆ RenderTarget()

virtual RenderTargetPtr RenderTarget ( ) const
overridepure virtual

Pointer to the render target.

Implements BaseCamera< T >.

Implemented in OgreGpuRays.

◆ SetAngleMax()

void SetAngleMax ( double  _angle)
overridevirtual

Set maximal horizontal angle value.

Implements GpuRays.

◆ SetAngleMin()

void SetAngleMin ( double  _angle)
overridevirtual

Set minimal horizontal angle value.

Implements GpuRays.

◆ SetClamp()

void SetClamp ( bool  _clamp)
overridevirtual

Configure behaviour for data values outside of camera range.

Parameters
[in]_clampTrue to clamp data to camera clip distances,

Implements GpuRays.

◆ SetHorizontalResolution()

void SetHorizontalResolution ( double  _resolution)
overridevirtual

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]_resolutionThe new horizontal resolution. The absolute value of this parameter is used to prevent a negative resolution value.

Implements GpuRays.

◆ SetIsHorizontal()

void SetIsHorizontal ( const bool  _horizontal)
overridevirtual

Set sensor horizontal or vertical.

Parameters
[in]_horizontalTrue if horizontal, false if not

Implements GpuRays.

◆ SetRayCount()

void SetRayCount ( int  _samples)
overridevirtual

Set horizontal quantity of rays.

Implements GpuRays.

◆ SetRayCountRatio()

void SetRayCountRatio ( const double  _rayCountRatio)
overridevirtual

Sets the ray count ratio (equivalent to aspect ratio)

Parameters
[in]_rayCountRatioray count ratio (equivalent to aspect ratio)

Implements GpuRays.

◆ SetVerticalAngleMax()

void SetVerticalAngleMax ( const double  _angle)
overridevirtual

Set maximal vertical angle value.

Implements GpuRays.

◆ SetVerticalAngleMin()

void SetVerticalAngleMin ( const double  _angle)
overridevirtual

Set minimal vertical angle value.

Implements GpuRays.

◆ SetVerticalRayCount()

void SetVerticalRayCount ( int  _samples)
overridevirtual

Set vertical quantity of rays.

Implements GpuRays.

◆ SetVerticalResolution()

void SetVerticalResolution ( double  _resolution)
overridevirtual

Set the vertical resolution. This number is multiplied by VerticalRayCount to calculate VerticalRangeCount, which is the the number vertical range data points.

Parameters
[in]_resolutionThe new vertical resolution. The absolute value of this parameter is used to prevent a negative resolution value.
See also
VerticalRayCount()

Implements GpuRays.

◆ SetVFOV()

void SetVFOV ( const math::Angle _vfov)
virtual

Set the vertical fov.

Parameters
[in]_vfovvertical fov

◆ VerticalAngleMax()

ignition::math::Angle VerticalAngleMax ( ) const
overridevirtual

Get maximal vertical angle value.

Implements GpuRays.

◆ VerticalAngleMin()

ignition::math::Angle VerticalAngleMin ( ) const
overridevirtual

Get minimal vertical angle value.

Implements GpuRays.

◆ VerticalRangeCount()

int VerticalRangeCount ( ) const
overridevirtual

Get vertical range count, i.e. ray count * vert resolution.

Implements GpuRays.

◆ VerticalRayCount()

int VerticalRayCount ( ) const
overridevirtual

Get vertical quantity of rays.

Implements GpuRays.

Referenced by BaseGpuRays< OgreSensor >::VerticalRangeCount().

◆ VerticalResolution()

double VerticalResolution ( ) const
overridevirtual

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()

Implements GpuRays.

◆ VFOV()

math::Angle VFOV ( ) const
overridevirtual

Get the vertical field-of-view.

Returns
The vertical field of view of the gpu rays.

Implements GpuRays.

Member Data Documentation

◆ channels

unsigned int channels = 1u
protected

Number of channels used to store the data.

Referenced by BaseGpuRays< OgreSensor >::Channels().

◆ clamping

bool clamping = false

True if data values are clamped to camera clip distances,.

Referenced by BaseGpuRays< OgreSensor >::Clamp(), and BaseGpuRays< OgreSensor >::SetClamp().

◆ dataMaxVal

float dataMaxVal = ignition::math::INF_D

maximum value used for data outside sensor range

Referenced by BaseGpuRays< OgreSensor >::SetClamp().

◆ dataMinVal

float dataMinVal = -ignition::math::INF_D

minimum value used for data outside sensor range

Referenced by BaseGpuRays< OgreSensor >::SetClamp().

◆ hResolution

◆ hSamples

int hSamples = 0
protected

Quantity of horizontal rays.

Referenced by BaseGpuRays< OgreSensor >::RayCount(), and BaseGpuRays< OgreSensor >::SetRayCount().

◆ isHorizontal

bool isHorizontal = true
protected

True if the sensor is horizontal only.

Referenced by BaseGpuRays< OgreSensor >::IsHorizontal(), and BaseGpuRays< OgreSensor >::SetIsHorizontal().

◆ maxAngle

double maxAngle = 0
protected

◆ minAngle

double minAngle = 0
protected

◆ rangeCountRatio

double rangeCountRatio = 0
protected

Range count ratio.

Referenced by BaseGpuRays< OgreSensor >::RangeCountRatio().

◆ rayCountRatio

double rayCountRatio = 0
protected

◆ vfov

math::Angle vfov
protected

Vertical field-of-view.

Referenced by BaseGpuRays< OgreSensor >::SetVFOV(), and BaseGpuRays< OgreSensor >::VFOV().

◆ vMaxAngle

double vMaxAngle = 0
protected

◆ vMinAngle

double vMinAngle = 0
protected

◆ vResolution

◆ vSamples

int vSamples = 0
protected

The documentation for this class was generated from the following file: