GpuRaySensor Class Reference

GPU based laser sensor. More...

#include <sensors/sensors.hh>

Inherits Sensor.

Public Member Functions

 GpuRaySensor ()
 Constructor. More...
 
virtual ~GpuRaySensor ()
 Destructor. More...
 
ignition::math::Angle AngleMax () const
 Get the maximum angle. More...
 
ignition::math::Angle AngleMin () const
 Get the minimum angle. More...
 
double AngleResolution () const
 Get radians between each range. More...
 
unsigned int CameraCount () const
 Gets the camera count. More...
 
SensorCategory Category () const
 Get the category of the sensor. More...
 
event::ConnectionPtr ConnectNewLaserFrame (std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
 Connect to the new laser frame event. More...
 
event::ConnectionPtr ConnectUpdated (std::function< void()> _subscriber)
 Connect a signal that is triggered when the sensor is updated. More...
 
double CosHorzFOV () const
 Get Cos Horz field-of-view. More...
 
double CosVertFOV () const
 Get Cos Vert field-of-view. More...
 
int Fiducial (const unsigned int _index) const
 Get detected fiducial value for a ray. More...
 
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message. 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...
 
uint32_t Id () const
 Get the sensor's ID. More...
 
virtual void Init () override
 Initialize the ray. More...
 
virtual bool IsActive () const override
 Returns true if sensor generation is active. More...
 
bool IsHorizontal () const
 Gets if sensor is horizontal. More...
 
rendering::GpuLaserPtr LaserCamera () const
 Returns a pointer to the internally kept rendering::GpuLaser. More...
 
common::Time LastMeasurementTime () const
 Return last measurement time. More...
 
common::Time LastUpdateTime () const
 Return last update time. More...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf) override
 Load the sensor with SDF parameters. More...
 
virtual void Load (const std::string &_worldName) override
 Load the sensor with default parameters. More...
 
std::string Name () const
 Get name. More...
 
double NextRequiredTimestamp () const override
 Return the next timestamp going to be used by the sensor. More...
 
NoisePtr Noise (const SensorNoiseType _type) const
 Get the sensor's noise model for a specified noise type. More...
 
uint32_t ParentId () const
 Get the sensor's parent's ID. More...
 
std::string ParentName () const
 Returns the name of the sensor parent. More...
 
virtual ignition::math::Pose3d Pose () const
 Get the current pose. More...
 
double Range (const int _index) const
 Get detected range for a ray. More...
 
int RangeCount () const
 Get the range count. More...
 
double RangeCountRatio () const
 Return the ratio of horizontal range count to vertical range count. More...
 
double RangeMax () const
 Get the maximum range. More...
 
double RangeMin () const
 Get the minimum range. More...
 
double RangeResolution () const
 Get the range resolution If RangeResolution is 1, the number of simulated rays is equal to the number of returned range readings. More...
 
void Ranges (std::vector< double > &_ranges) const
 Get all the ranges. More...
 
int RayCount () const
 Get the ray count. More...
 
double RayCountRatio () const
 Return the ratio of horizontal ray count to vertical ray count. More...
 
double Retro (const int _index) const
 Get detected retro (intensity) value for a ray. More...
 
std::string ScopedName () const
 Get fully scoped name of the sensor. More...
 
void SetActive (bool _value) override
 Set whether the sensor is active or not. More...
 
void SetAngleMax (const double _angle)
 Set the scan maximum angle. More...
 
void SetAngleMin (const double _angle)
 Set the scan minimum angle. More...
 
void SetParent (const std::string &_name, const uint32_t _id)
 Set the sensor's parent. More...
 
virtual void SetPose (const ignition::math::Pose3d &_pose)
 Set the current pose. More...
 
void SetUpdateRate (const double _hz)
 Set the update rate of the sensor. More...
 
void SetVerticalAngleMax (const double _angle)
 Set the vertical scan line top angle. More...
 
void SetVerticalAngleMin (const double _angle)
 Set the vertical scan bottom angle. More...
 
virtual std::string Topic () const override
 Returns the topic name as set in SDF. More...
 
std::string Type () const
 Get sensor type. More...
 
void Update (bool _force) override
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. More...
 
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 VerticalAngleMax () const
 Get the vertical scan line top angle. More...
 
ignition::math::Angle VerticalAngleMin () const
 Get the vertical scan bottom angle. More...
 
double VerticalAngleResolution () const
 Get the vertical angle in radians between each range. More...
 
int VerticalRangeCount () const
 Get the vertical scan line count. More...
 
int VerticalRayCount () const
 Get the vertical scan line count. More...
 
bool Visualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string WorldName () const
 Returns the name of the world the sensor is in. More...
 

Protected Member Functions

virtual void Fini () override
 Finalize the ray. More...
 
bool NeedsUpdate () override
 Return true if the sensor needs to be updated. More...
 
void ResetLastUpdateTime () override
 reset timing related members More...
 
virtual bool UpdateImpl (const bool _force) override
 This gets overwritten by derived sensor types. More...
 

Protected Attributes

bool active
 True if sensor generation is active. More...
 
std::vector< event::ConnectionPtrconnections
 All event connections. More...
 
common::Time lastMeasurementTime
 Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl. More...
 
common::Time lastUpdateTime
 Time of the last update. More...
 
transport::NodePtr node
 Node for communication. More...
 
ignition::transport::Node nodeIgn
 Ignition transport node. More...
 
std::map< SensorNoiseType, NoisePtrnoises
 Noise added to sensor data. More...
 
uint32_t parentId
 The sensor's parent ID. More...
 
std::string parentName
 Name of the parent. More...
 
std::vector< SensorPluginPtrplugins
 All the plugins for the sensor. More...
 
ignition::math::Pose3d pose
 Pose of the sensor. More...
 
gazebo::rendering::ScenePtr scene
 Pointer to the Scene. More...
 
sdf::ElementPtr sdf
 Pointer the the SDF element for the sensor. More...
 
event::EventT< void()> updated
 Event triggered when a sensor is updated. More...
 
common::Time updatePeriod
 Desired time between updates, set indirectly by Sensor::SetUpdateRate. More...
 
gazebo::physics::WorldPtr world
 Pointer to the world. More...
 

Detailed Description

GPU based laser sensor.

This sensor cast rays into the world, tests for intersections, and reports the range to the nearest object. It is used by ranging sensor models (e.g., sonars and scanning laser range finders).

Constructor & Destructor Documentation

◆ GpuRaySensor()

Constructor.

◆ ~GpuRaySensor()

virtual ~GpuRaySensor ( )
virtual

Destructor.

Member Function Documentation

◆ AngleMax()

ignition::math::Angle AngleMax ( ) const

Get the maximum angle.

Returns
the maximum angle

◆ AngleMin()

ignition::math::Angle AngleMin ( ) const

Get the minimum angle.

Returns
The minimum angle

◆ AngleResolution()

double AngleResolution ( ) const

Get radians between each range.

Returns
Return angle resolution

◆ CameraCount()

unsigned int CameraCount ( ) const

Gets the camera count.

Returns
Number of cameras

◆ Category()

SensorCategory Category ( ) const
inherited

Get the category of the sensor.

Returns
The category of the sensor.
See also
SensorCategory

◆ ConnectNewLaserFrame()

event::ConnectionPtr ConnectNewLaserFrame ( std::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)>  _subscriber)

Connect to the new laser frame event.

Parameters
[in]_subscriberEvent callback.

◆ ConnectUpdated()

event::ConnectionPtr ConnectUpdated ( std::function< void()>  _subscriber)
inherited

Connect a signal that is triggered when the sensor is updated.

Parameters
[in]_subscriberCallback that receives the signal.
Returns
A pointer to the connection. This must be kept in scope.
See also
Sensor::DisconnectUpdated

◆ CosHorzFOV()

double CosHorzFOV ( ) const

Get Cos Horz field-of-view.

Returns
2 * atan(tan(this->hfov/2) / cos(this->vfov/2))

◆ CosVertFOV()

double CosVertFOV ( ) const

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))

◆ Fiducial()

int Fiducial ( const unsigned int  _index) const

Get detected fiducial value for a ray.

Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).

Parameters
[in]_indexIndex of specific ray
Returns
Fiducial value of ray

◆ FillMsg()

void FillMsg ( msgs::Sensor &  _msg)
inherited

fills a msgs::Sensor message.

Parameters
[out]_msgMessage to fill.

◆ Fini()

virtual void Fini ( )
overrideprotectedvirtual

Finalize the ray.

Reimplemented from Sensor.

◆ HorzFOV()

double HorzFOV ( ) const

Get the horizontal field of view of the laser sensor.

Returns
The horizontal field of view of the laser sensor.

◆ HorzHalfAngle()

double HorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

Returns
(horizontal_max_angle + horizontal_min_angle) * 0.5

◆ Id()

uint32_t Id ( ) const
inherited

Get the sensor's ID.

Returns
The sensor's ID.

◆ Init()

virtual void Init ( )
overridevirtual

Initialize the ray.

Reimplemented from Sensor.

◆ IsActive()

virtual bool IsActive ( ) const
overridevirtual

Returns true if sensor generation is active.

Returns
True if active, false if not.

Reimplemented from Sensor.

◆ IsHorizontal()

bool IsHorizontal ( ) const

Gets if sensor is horizontal.

Returns
True if horizontal, false if not

◆ LaserCamera()

rendering::GpuLaserPtr LaserCamera ( ) const

Returns a pointer to the internally kept rendering::GpuLaser.

Returns
Pointer to GpuLaser

◆ LastMeasurementTime()

common::Time LastMeasurementTime ( ) const
inherited

Return last measurement time.

Returns
Time of last measurement.

◆ LastUpdateTime()

common::Time LastUpdateTime ( ) const
inherited

Return last update time.

Returns
Time of last update.

◆ Load() [1/2]

virtual void Load ( const std::string &  _worldName,
sdf::ElementPtr  _sdf 
)
overridevirtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters
[in]_worldNameName of world to load from

Reimplemented from Sensor.

◆ Load() [2/2]

virtual void Load ( const std::string &  _worldName)
overridevirtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from

Reimplemented from Sensor.

◆ Name()

std::string Name ( ) const
inherited

Get name.

Returns
Name of sensor.

◆ NeedsUpdate()

bool NeedsUpdate ( )
overrideprotectedvirtual

Return true if the sensor needs to be updated.

Returns
True when sensor should be updated.

Reimplemented from Sensor.

◆ NextRequiredTimestamp()

double NextRequiredTimestamp ( ) const
overridevirtual

Return the next timestamp going to be used by the sensor.

Returns
the timestamp

Reimplemented from Sensor.

◆ Noise()

NoisePtr Noise ( const SensorNoiseType  _type) const
inherited

Get the sensor's noise model for a specified noise type.

Parameters
[in]_typeIndex of the noise type. Refer to SensorNoiseType enumeration for possible indices
Returns
The sensor's noise model for the given noise type

◆ ParentId()

uint32_t ParentId ( ) const
inherited

Get the sensor's parent's ID.

Returns
The sensor's parent's ID.

◆ ParentName()

std::string ParentName ( ) const
inherited

Returns the name of the sensor parent.

The parent name is set by Sensor::SetParent.

Returns
Name of Parent.

◆ Pose()

virtual ignition::math::Pose3d Pose ( ) const
virtualinherited

Get the current pose.

Returns
Current pose of the sensor.
See also
SetPose()

◆ Range()

double Range ( const int  _index) const

Get detected range for a ray.

Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).

Parameters
[in]_indexIndex of specific ray
Returns
Returns RangeMax for no detection.

◆ RangeCount()

int RangeCount ( ) const

Get the range count.

Returns
The number of ranges

◆ RangeCountRatio()

double RangeCountRatio ( ) const

Return the ratio of horizontal range count to vertical range count.

A ray count is the number of simulated rays. Whereas a range count is the total number of data points returned. When range count != ray count, then values are interpolated between rays.

◆ RangeMax()

double RangeMax ( ) const

Get the maximum range.

Returns
The maximum range

◆ RangeMin()

double RangeMin ( ) const

Get the minimum range.

Returns
The minimum range

◆ RangeResolution()

double RangeResolution ( ) const

Get the range resolution If RangeResolution is 1, the number of simulated rays is equal to the number of returned range readings.

If it's less than 1, fewer simulated rays than actual returned range readings are used, the results are interpolated from two nearest neighbors, and vice versa.

Returns
The Range Resolution

◆ Ranges()

void Ranges ( std::vector< double > &  _ranges) const

Get all the ranges.

Parameters
[out]_rangeA vector that will contain all the range data

◆ RayCount()

int RayCount ( ) const

Get the ray count.

Returns
The number of rays

◆ RayCountRatio()

double RayCountRatio ( ) const

Return the ratio of horizontal ray count to vertical ray count.

A ray count is the number of simulated rays. Whereas a range count is the total number of data points returned. When range count != ray count, then values are interpolated between rays.

◆ ResetLastUpdateTime()

void ResetLastUpdateTime ( )
overrideprotectedvirtual

reset timing related members

Reimplemented from Sensor.

◆ Retro()

double Retro ( const int  _index) const

Get detected retro (intensity) value for a ray.

Warning: If you are accessing all the ray data in a loop it's possible that the Ray will update in the middle of your access loop. This means some data will come from one scan, and some from another scan. You can solve this problem by using SetActive(false) <your accessor="" loop>=""> SetActive(true).

Parameters
[in]_indexIndex of specific ray
Returns
Intensity value of ray

◆ ScopedName()

std::string ScopedName ( ) const
inherited

Get fully scoped name of the sensor.

Returns
world_name::model_name::link_name::sensor_name.

◆ SetActive()

void SetActive ( bool  _value)
overridevirtual

Set whether the sensor is active or not.

Parameters
[in]_valueTrue if active, false if not.

Reimplemented from Sensor.

◆ SetAngleMax()

void SetAngleMax ( const double  _angle)

Set the scan maximum angle.

Parameters
[in]_angleThe maximum angle

◆ SetAngleMin()

void SetAngleMin ( const double  _angle)

Set the scan minimum angle.

Parameters
[in]_angleThe minimum angle

◆ SetParent()

void SetParent ( const std::string &  _name,
const uint32_t  _id 
)
inherited

Set the sensor's parent.

Parameters
[in]_nameThe sensor's parent's name.
[in]_idThe sensor's parent's ID.

◆ SetPose()

virtual void SetPose ( const ignition::math::Pose3d &  _pose)
virtualinherited

Set the current pose.

Parameters
[in]_poseNew pose of the sensor.
See also
Pose()

◆ SetUpdateRate()

void SetUpdateRate ( const double  _hz)
inherited

Set the update rate of the sensor.

Parameters
[in]_hzupdate rate of sensor.

◆ SetVerticalAngleMax()

void SetVerticalAngleMax ( const double  _angle)

Set the vertical scan line top angle.

Parameters
[in]_angleThe Maximum angle of the scan block

◆ SetVerticalAngleMin()

void SetVerticalAngleMin ( const double  _angle)

Set the vertical scan bottom angle.

Parameters
[in]_angleThe minimum angle of the scan block

◆ Topic()

virtual std::string Topic ( ) const
overridevirtual

Returns the topic name as set in SDF.

Returns
Topic name.

Reimplemented from Sensor.

◆ Type()

std::string Type ( ) const
inherited

Get sensor type.

Returns
Type of sensor.

◆ Update()

void Update ( bool  _force)
overridevirtual

Update the sensor.

Parameters
[in]_forceTrue to force update, false otherwise.

Reimplemented from Sensor.

◆ UpdateImpl()

virtual bool UpdateImpl ( const bool  )
overrideprotectedvirtual

This gets overwritten by derived sensor types.

This function is called during Sensor::Update. And in turn, Sensor::Update is called by SensorManager::Update

Parameters
[in]_forceTrue if update is forced, false if not
Returns
True if the sensor was updated.

Reimplemented from Sensor.

◆ UpdateRate()

double UpdateRate ( ) const
inherited

Get the update rate of the sensor.

Returns
_hz update rate of sensor. Returns 0 if unthrottled.

◆ VertFOV()

double VertFOV ( ) const

Get the vertical field-of-view.

Returns
Vertical field of view.

◆ VertHalfAngle()

double VertHalfAngle ( ) const

Get (vertical_max_angle + vertical_min_angle) * 0.5.

Returns
(vertical_max_angle + vertical_min_angle) * 0.5

◆ VerticalAngleMax()

ignition::math::Angle VerticalAngleMax ( ) const

Get the vertical scan line top angle.

Returns
The Maximum angle of the scan block

◆ VerticalAngleMin()

ignition::math::Angle VerticalAngleMin ( ) const

Get the vertical scan bottom angle.

Returns
The minimum angle of the scan block

◆ VerticalAngleResolution()

double VerticalAngleResolution ( ) const

Get the vertical angle in radians between each range.

Returns
Resolution of the angle

◆ VerticalRangeCount()

int VerticalRangeCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically

◆ VerticalRayCount()

int VerticalRayCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically

◆ Visualize()

bool Visualize ( ) const
inherited

Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.

Returns
True if visualized, false if not.

◆ WorldName()

std::string WorldName ( ) const
inherited

Returns the name of the world the sensor is in.

Returns
Name of the world.

Member Data Documentation

◆ active

bool active
protectedinherited

True if sensor generation is active.

◆ connections

std::vector<event::ConnectionPtr> connections
protectedinherited

All event connections.

◆ lastMeasurementTime

common::Time lastMeasurementTime
protectedinherited

Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.

◆ lastUpdateTime

common::Time lastUpdateTime
protectedinherited

Time of the last update.

◆ node

transport::NodePtr node
protectedinherited

Node for communication.

◆ nodeIgn

ignition::transport::Node nodeIgn
protectedinherited

Ignition transport node.

◆ noises

std::map<SensorNoiseType, NoisePtr> noises
protectedinherited

Noise added to sensor data.

◆ parentId

uint32_t parentId
protectedinherited

The sensor's parent ID.

◆ parentName

std::string parentName
protectedinherited

Name of the parent.

◆ plugins

std::vector<SensorPluginPtr> plugins
protectedinherited

All the plugins for the sensor.

◆ pose

ignition::math::Pose3d pose
protectedinherited

Pose of the sensor.

◆ scene

gazebo::rendering::ScenePtr scene
protectedinherited

Pointer to the Scene.

◆ sdf

sdf::ElementPtr sdf
protectedinherited

Pointer the the SDF element for the sensor.

◆ updated

event::EventT<void()> updated
protectedinherited

Event triggered when a sensor is updated.

◆ updatePeriod

common::Time updatePeriod
protectedinherited

Desired time between updates, set indirectly by Sensor::SetUpdateRate.

◆ world

gazebo::physics::WorldPtr world
protectedinherited

Pointer to the world.


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