Public Member Functions | Protected Member Functions | List of all members
gazebo::sensors::GpuRaySensor Class Reference

GPU based laser sensor. More...

#include <sensors/sensors.hh>

Inheritance diagram for gazebo::sensors::GpuRaySensor:
Inheritance graph
[legend]

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...
 
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...
 
double CosHorzFOV () const
 Get Cos Horz field-of-view. More...
 
double CosVertFOV () const
 Get Cos Vert field-of-view. More...
 
void DisconnectNewLaserFrame (event::ConnectionPtr &_conn)
 Disconnect Laser Frame. More...
 
int Fiducial (const unsigned int _index) const
 Get detected fiducial value for a ray. More...
 
double GetAngleResolution () const GAZEBO_DEPRECATED(7.0)
 Get radians between each range. More...
 
unsigned int GetCameraCount () const GAZEBO_DEPRECATED(7.0)
 Gets the camera count. More...
 
double GetCosHorzFOV () const GAZEBO_DEPRECATED(7.0)
 Get Cos Horz field-of-view. More...
 
double GetCosVertFOV () const GAZEBO_DEPRECATED(7.0)
 Get Cos Vert field-of-view. More...
 
int GetFiducial (int _index) const GAZEBO_DEPRECATED(7.0)
 Get detected fiducial value for a ray. More...
 
double GetHorzFOV () const GAZEBO_DEPRECATED(7.0)
 Get the horizontal field of view of the laser sensor. More...
 
double GetHorzHalfAngle () const GAZEBO_DEPRECATED(7.0)
 Get (horizontal_max_angle + horizontal_min_angle) * 0.5. More...
 
rendering::GpuLaserPtr GetLaserCamera () const GAZEBO_DEPRECATED(7.0)
 Returns a pointer to the internally kept rendering::GpuLaser. More...
 
double GetRange (int _index) GAZEBO_DEPRECATED(7.0)
 Get detected range for a ray. More...
 
int GetRangeCount () const GAZEBO_DEPRECATED(7.0)
 Get the range count. More...
 
double GetRangeCountRatio () const GAZEBO_DEPRECATED(7.0)
 Return the ratio of horizontal range count to vertical range count. More...
 
double GetRangeMax () const GAZEBO_DEPRECATED(7.0)
 Get the maximum range. More...
 
double GetRangeMin () const GAZEBO_DEPRECATED(7.0)
 Get the minimum range. More...
 
double GetRangeResolution () const GAZEBO_DEPRECATED(7.0)
 Get the range resolution If RangeResolution is 1, the number of simulated rays is equal to the number of returned range readings. More...
 
void GetRanges (std::vector< double > &_ranges) GAZEBO_DEPRECATED(7.0)
 Get all the ranges. More...
 
int GetRayCount () const GAZEBO_DEPRECATED(7.0)
 Get the ray count. More...
 
double GetRayCountRatio () const GAZEBO_DEPRECATED(7.0)
 Return the ratio of horizontal ray count to vertical ray count. More...
 
double GetRetro (int _index) const GAZEBO_DEPRECATED(7.0)
 Get detected retro (intensity) value for a ray. More...
 
double GetVertFOV () const GAZEBO_DEPRECATED(7.0)
 Get the vertical field-of-view. More...
 
double GetVertHalfAngle () const GAZEBO_DEPRECATED(7.0)
 Get (vertical_max_angle + vertical_min_angle) * 0.5. More...
 
double GetVerticalAngleResolution () const GAZEBO_DEPRECATED(7.0)
 Get the vertical angle in radians between each range. More...
 
int GetVerticalRangeCount () const GAZEBO_DEPRECATED(7.0)
 Get the vertical scan line count. More...
 
int GetVerticalRayCount () const GAZEBO_DEPRECATED(7.0)
 Get the vertical scan line count. 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...
 
virtual void Init ()
 Initialize the ray. More...
 
virtual bool IsActive () const
 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...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters. More...
 
virtual void Load (const std::string &_worldName)
 Load the sensor with default parameters. 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...
 
void SetAngleMax (const double _angle)
 Set the scan maximum angle. More...
 
void SetAngleMin (const double _angle)
 Set the scan minimum angle. 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
 Returns the topic name as set in SDF. 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...
 
- Public Member Functions inherited from gazebo::sensors::Sensor
 Sensor (SensorCategory _cat)
 Constructor. More...
 
virtual ~Sensor ()
 Destructor. More...
 
SensorCategory Category () const
 Get the category of the sensor. More...
 
event::ConnectionPtr ConnectUpdated (std::function< void()> _subscriber)
 Connect a signal that is triggered when the sensor is updated. More...
 
void DisconnectUpdated (event::ConnectionPtr &_c)
 Disconnect from a the updated signal. More...
 
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message. More...
 
SensorCategory GetCategory () const GAZEBO_DEPRECATED(7.0)
 Get the category of the sensor. More...
 
uint32_t GetId () const GAZEBO_DEPRECATED(7.0)
 Get the sensor's ID. More...
 
common::Time GetLastMeasurementTime () GAZEBO_DEPRECATED(7.0)
 Return last measurement time. More...
 
common::Time GetLastUpdateTime () GAZEBO_DEPRECATED(7.0)
 Return last update time. More...
 
std::string GetName () const GAZEBO_DEPRECATED(7.0)
 Get name. More...
 
NoisePtr GetNoise (const SensorNoiseType _type) const GAZEBO_DEPRECATED(7.0)
 Get the sensor's noise model for a specified noise type. More...
 
uint32_t GetParentId () const GAZEBO_DEPRECATED(7.0)
 Get the sensor's parent's ID. More...
 
std::string GetParentName () const GAZEBO_DEPRECATED(7.0)
 Returns the name of the sensor parent. More...
 
std::string GetScopedName () const GAZEBO_DEPRECATED(7.0)
 Get fully scoped name of the sensor. More...
 
virtual std::string GetTopic () const GAZEBO_DEPRECATED(7.0)
 Returns the topic name as set in SDF. More...
 
std::string GetType () const GAZEBO_DEPRECATED(7.0)
 Get sensor type. More...
 
double GetUpdateRate () GAZEBO_DEPRECATED(7.0)
 Get the update rate of the sensor. More...
 
bool GetVisualize () const GAZEBO_DEPRECATED(7.0)
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string GetWorldName () const GAZEBO_DEPRECATED(7.0)
 Returns the name of the world the sensor is in. More...
 
uint32_t Id () const
 Get the sensor's ID. More...
 
common::Time LastMeasurementTime () const
 Return last measurement time. More...
 
common::Time LastUpdateTime () const
 Return last update time. More...
 
std::string Name () const
 Get name. 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...
 
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
std::string ScopedName () const
 Get fully scoped name of the sensor. More...
 
virtual void SetActive (const bool _value)
 Set whether the sensor is active or not. 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...
 
std::string Type () const
 Get sensor type. More...
 
void Update (const bool _force)
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. 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 ()
 Finalize the ray. More...
 
virtual bool UpdateImpl (const bool _force)
 This gets overwritten by derived sensor types. More...
 
- Protected Member Functions inherited from gazebo::sensors::Sensor
bool NeedsUpdate ()
 Return true if the sensor needs to be updated. More...
 

Additional Inherited Members

- Protected Attributes inherited from gazebo::sensors::Sensor
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...
 
std::map< SensorNoiseType,
NoisePtr
noises
 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...
 
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

gazebo::sensors::GpuRaySensor::GpuRaySensor ( )

Constructor.

virtual gazebo::sensors::GpuRaySensor::~GpuRaySensor ( )
virtual

Destructor.

Member Function Documentation

ignition::math::Angle gazebo::sensors::GpuRaySensor::AngleMax ( ) const

Get the maximum angle.

Returns
the maximum angle
ignition::math::Angle gazebo::sensors::GpuRaySensor::AngleMin ( ) const

Get the minimum angle.

Returns
The minimum angle
double gazebo::sensors::GpuRaySensor::AngleResolution ( ) const

Get radians between each range.

Returns
Return angle resolution
unsigned int gazebo::sensors::GpuRaySensor::CameraCount ( ) const

Gets the camera count.

Returns
Number of cameras
event::ConnectionPtr gazebo::sensors::GpuRaySensor::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.
Deprecated:
See ConnectNewLaserFrame that accepts a std::function.
double gazebo::sensors::GpuRaySensor::CosHorzFOV ( ) const

Get Cos Horz field-of-view.

Returns
2 * atan(tan(this->hfov/2) / cos(this->vfov/2))
double gazebo::sensors::GpuRaySensor::CosVertFOV ( ) const

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))
void gazebo::sensors::GpuRaySensor::DisconnectNewLaserFrame ( event::ConnectionPtr _conn)

Disconnect Laser Frame.

Parameters
[in,out]_connConnection pointer to disconnect.
int gazebo::sensors::GpuRaySensor::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
virtual void gazebo::sensors::GpuRaySensor::Fini ( )
protectedvirtual

Finalize the ray.

Reimplemented from gazebo::sensors::Sensor.

double gazebo::sensors::GpuRaySensor::GetAngleResolution ( ) const

Get radians between each range.

Returns
Return angle resolution
Deprecated:
See AngleResolution()
unsigned int gazebo::sensors::GpuRaySensor::GetCameraCount ( ) const

Gets the camera count.

Returns
Number of cameras
Deprecated:
See CameraCount()
double gazebo::sensors::GpuRaySensor::GetCosHorzFOV ( ) const

Get Cos Horz field-of-view.

Returns
2 * atan(tan(this->hfov/2) / cos(this->vfov/2))
Deprecated:
See CosHorzFOV
double gazebo::sensors::GpuRaySensor::GetCosVertFOV ( ) const

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))
Deprecated:
See CosVertFOV.
int gazebo::sensors::GpuRaySensor::GetFiducial ( 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
Deprecated:
See Fiducial(unsigned int _index)
double gazebo::sensors::GpuRaySensor::GetHorzFOV ( ) const

Get the horizontal field of view of the laser sensor.

Returns
The horizontal field of view of the laser sensor.
Deprecated:
See HorzFOV
double gazebo::sensors::GpuRaySensor::GetHorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

Returns
(horizontal_max_angle + horizontal_min_angle) * 0.5
Deprecated:
See HorzHalfAngle()
rendering::GpuLaserPtr gazebo::sensors::GpuRaySensor::GetLaserCamera ( ) const

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

Returns
Pointer to GpuLaser See LaserCamera
double gazebo::sensors::GpuRaySensor::GetRange ( int  _index)

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.
Deprecated:
See Range(int _index)
int gazebo::sensors::GpuRaySensor::GetRangeCount ( ) const

Get the range count.

Returns
The number of ranges
Deprecated:
See RangeCount
double gazebo::sensors::GpuRaySensor::GetRangeCountRatio ( ) 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.

Deprecated:
See RangeCountRatio
double gazebo::sensors::GpuRaySensor::GetRangeMax ( ) const

Get the maximum range.

Returns
The maximum range
Deprecated:
See RangeMax
double gazebo::sensors::GpuRaySensor::GetRangeMin ( ) const

Get the minimum range.

Returns
The minimum range
Deprecated:
See RangeMin
double gazebo::sensors::GpuRaySensor::GetRangeResolution ( ) 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
Deprecated:
See RangeResolution()
void gazebo::sensors::GpuRaySensor::GetRanges ( std::vector< double > &  _ranges)

Get all the ranges.

Parameters
[out]_rangeA vector that will contain all the range data
Deprecated:
See Ranges(std::vector<double> &_ranges)
int gazebo::sensors::GpuRaySensor::GetRayCount ( ) const

Get the ray count.

Returns
The number of rays
Deprecated:
See RayCount
double gazebo::sensors::GpuRaySensor::GetRayCountRatio ( ) 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.

Deprecated:
See RayCountRatio
double gazebo::sensors::GpuRaySensor::GetRetro ( 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
Deprecated:
See Retro(int _index)
double gazebo::sensors::GpuRaySensor::GetVertFOV ( ) const

Get the vertical field-of-view.

Deprecated:
See VertFOV
double gazebo::sensors::GpuRaySensor::GetVertHalfAngle ( ) const

Get (vertical_max_angle + vertical_min_angle) * 0.5.

Returns
(vertical_max_angle + vertical_min_angle) * 0.5
Deprecated:
See VertHalfAngle
double gazebo::sensors::GpuRaySensor::GetVerticalAngleResolution ( ) const

Get the vertical angle in radians between each range.

Returns
Resolution of the angle
Deprecated:
See VerticalAngleResolution
int gazebo::sensors::GpuRaySensor::GetVerticalRangeCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically
Deprecated:
See VerticalRangeCount()
int gazebo::sensors::GpuRaySensor::GetVerticalRayCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically
Deprecated:
See VerticalRayCount()
double gazebo::sensors::GpuRaySensor::HorzFOV ( ) const

Get the horizontal field of view of the laser sensor.

Returns
The horizontal field of view of the laser sensor.
double gazebo::sensors::GpuRaySensor::HorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

Returns
(horizontal_max_angle + horizontal_min_angle) * 0.5
virtual void gazebo::sensors::GpuRaySensor::Init ( )
virtual

Initialize the ray.

Reimplemented from gazebo::sensors::Sensor.

virtual bool gazebo::sensors::GpuRaySensor::IsActive ( ) const
virtual

Returns true if sensor generation is active.

Returns
True if active, false if not.

Reimplemented from gazebo::sensors::Sensor.

bool gazebo::sensors::GpuRaySensor::IsHorizontal ( ) const

Gets if sensor is horizontal.

Returns
True if horizontal, false if not
rendering::GpuLaserPtr gazebo::sensors::GpuRaySensor::LaserCamera ( ) const

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

Returns
Pointer to GpuLaser
virtual void gazebo::sensors::GpuRaySensor::Load ( const std::string &  _worldName,
sdf::ElementPtr  _sdf 
)
virtual

Load the sensor with SDF parameters.

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

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::GpuRaySensor::Load ( const std::string &  _worldName)
virtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from

Reimplemented from gazebo::sensors::Sensor.

double gazebo::sensors::GpuRaySensor::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.
int gazebo::sensors::GpuRaySensor::RangeCount ( ) const

Get the range count.

Returns
The number of ranges
double gazebo::sensors::GpuRaySensor::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.

double gazebo::sensors::GpuRaySensor::RangeMax ( ) const

Get the maximum range.

Returns
The maximum range
double gazebo::sensors::GpuRaySensor::RangeMin ( ) const

Get the minimum range.

Returns
The minimum range
double gazebo::sensors::GpuRaySensor::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
void gazebo::sensors::GpuRaySensor::Ranges ( std::vector< double > &  _ranges) const

Get all the ranges.

Parameters
[out]_rangeA vector that will contain all the range data
int gazebo::sensors::GpuRaySensor::RayCount ( ) const

Get the ray count.

Returns
The number of rays
double gazebo::sensors::GpuRaySensor::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.

double gazebo::sensors::GpuRaySensor::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
void gazebo::sensors::GpuRaySensor::SetAngleMax ( const double  _angle)

Set the scan maximum angle.

Parameters
[in]_angleThe maximum angle
void gazebo::sensors::GpuRaySensor::SetAngleMin ( const double  _angle)

Set the scan minimum angle.

Parameters
[in]_angleThe minimum angle
void gazebo::sensors::GpuRaySensor::SetVerticalAngleMax ( const double  _angle)

Set the vertical scan line top angle.

Parameters
[in]_angleThe Maximum angle of the scan block
void gazebo::sensors::GpuRaySensor::SetVerticalAngleMin ( const double  _angle)

Set the vertical scan bottom angle.

Parameters
[in]_angleThe minimum angle of the scan block
virtual std::string gazebo::sensors::GpuRaySensor::Topic ( ) const
virtual

Returns the topic name as set in SDF.

Returns
Topic name.

Reimplemented from gazebo::sensors::Sensor.

virtual bool gazebo::sensors::GpuRaySensor::UpdateImpl ( const bool  )
protectedvirtual

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 gazebo::sensors::Sensor.

double gazebo::sensors::GpuRaySensor::VertFOV ( ) const

Get the vertical field-of-view.

Returns
Vertical field of view.
double gazebo::sensors::GpuRaySensor::VertHalfAngle ( ) const

Get (vertical_max_angle + vertical_min_angle) * 0.5.

Returns
(vertical_max_angle + vertical_min_angle) * 0.5
ignition::math::Angle gazebo::sensors::GpuRaySensor::VerticalAngleMax ( ) const

Get the vertical scan line top angle.

Returns
The Maximum angle of the scan block
ignition::math::Angle gazebo::sensors::GpuRaySensor::VerticalAngleMin ( ) const

Get the vertical scan bottom angle.

Returns
The minimum angle of the scan block
double gazebo::sensors::GpuRaySensor::VerticalAngleResolution ( ) const

Get the vertical angle in radians between each range.

Returns
Resolution of the angle
int gazebo::sensors::GpuRaySensor::VerticalRangeCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically
int gazebo::sensors::GpuRaySensor::VerticalRayCount ( ) const

Get the vertical scan line count.

Returns
The number of scan lines vertically

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