All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::sensors::GpuRaySensor Class Reference

#include <sensors/sensors.hh>

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

Public Member Functions

 GpuRaySensor ()
 Constructor. More...
 
virtual ~GpuRaySensor ()
 Destructor. More...
 
event::ConnectionPtr ConnectNewLaserFrame (boost::function< void(const float *, unsigned int, unsigned int, unsigned int, const std::string &)> _subscriber)
 Connect to the new laser frame event. More...
 
void DisconnectNewLaserFrame (event::ConnectionPtr &_conn)
 Disconnect Laser Frame. More...
 
math::Angle GetAngleMax () const
 Get the maximum angle. More...
 
math::Angle GetAngleMin () const
 Get the minimum angle. More...
 
double GetAngleResolution () const
 Get radians between each range. More...
 
unsigned int GetCameraCount () const
 Gets the camera count. More...
 
double GetCosHorzFOV () const
 Get Cos Horz field-of-view. More...
 
double GetCosVertFOV () const
 Get Cos Vert field-of-view. More...
 
int GetFiducial (int _index) const
 Get detected fiducial value for a ray. More...
 
double GetHorzFOV () const
 Get the horizontal field of view of the laser sensor. More...
 
double GetHorzHalfAngle () const
 Get (horizontal_max_angle + horizontal_min_angle) * 0.5. More...
 
rendering::GpuLaserPtr GetLaserCamera () const
 Returns a pointer to the internally kept rendering::GpuLaser. More...
 
double GetRange (int _index)
 Get detected range for a ray. More...
 
int GetRangeCount () const
 Get the range count. More...
 
double GetRangeCountRatio () const
 Return the ratio of horizontal range count to vertical range count. More...
 
double GetRangeMax () const
 Get the maximum range. More...
 
double GetRangeMin () const
 Get the minimum range. More...
 
double GetRangeResolution () 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 GetRanges (std::vector< double > &_ranges)
 Get all the ranges. More...
 
int GetRayCount () const
 Get the ray count. More...
 
double GetRayCountRatio () const
 Return the ratio of horizontal ray count to vertical ray count. More...
 
double GetRetro (int _index) const
 Get detected retro (intensity) value for a ray. More...
 
virtual std::string GetTopic () const
 Returns the topic name as set in SDF. More...
 
double GetVertFOV () const
 Get the vertical field-of-view. More...
 
double GetVertHalfAngle () const
 Get (vertical_max_angle + vertical_min_angle) * 0.5. More...
 
math::Angle GetVerticalAngleMax () const
 Get the vertical scan line top angle. More...
 
math::Angle GetVerticalAngleMin () const
 Get the vertical scan bottom angle. More...
 
int GetVerticalRangeCount () const
 Get the vertical scan line count. More...
 
int GetVerticalRayCount () const
 Get the vertical scan line count. More...
 
virtual void Init ()
 Initialize the ray. More...
 
virtual bool IsActive ()
 Returns true if sensor generation is active. More...
 
bool IsHorizontal () const
 Gets if sensor is horizontal. 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...
 
void SetAngleMax (double _angle)
 Set the scan maximum angle. More...
 
void SetAngleMin (double _angle)
 Set the scan minimum angle. More...
 
void SetVerticalAngleMax (double _angle)
 Set the vertical scan line top angle. More...
 
void SetVerticalAngleMin (double _angle)
 Set the vertical scan bottom angle. More...
 
- Public Member Functions inherited from gazebo::sensors::Sensor
 Sensor (SensorCategory _cat)
 Constructor. More...
 
virtual ~Sensor ()
 Destructor. More...
 
template<typename T >
event::ConnectionPtr ConnectUpdated (T _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
 Get the category of the sensor. More...
 
uint32_t GetId () const
 Get the sensor's ID. More...
 
common::Time GetLastMeasurementTime ()
 Return last measurement time. More...
 
common::Time GetLastUpdateTime ()
 Return last update time. More...
 
std::string GetName () const
 Get name. More...
 
uint32_t GetParentId () const
 Get the sensor's parent's ID. More...
 
std::string GetParentName () const
 Returns the name of the sensor parent. More...
 
virtual math::Pose GetPose () const
 Get the current pose. More...
 
std::string GetScopedName () const
 Get fully scoped name of the sensor. More...
 
std::string GetType () const
 Get sensor type. More...
 
double GetUpdateRate ()
 Get the update rate of the sensor. More...
 
bool GetVisualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string GetWorldName () const
 Returns the name of the world the sensor is in. More...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters. More...
 
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
virtual void SetActive (bool _value)
 Set whether the sensor is active or not. More...
 
virtual void SetParent (const std::string &_name) GAZEBO_DEPRECATED(2.0)
 Set the parent of the sensor. More...
 
void SetParent (const std::string &_name, uint32_t _id)
 Set the sensor's parent. More...
 
void SetUpdateRate (double _hz)
 Set the update rate of the sensor. More...
 
void Update (bool _force)
 Update the sensor. More...
 

Protected Member Functions

virtual void Fini ()
 Finalize the ray. More...
 
virtual void UpdateImpl (bool _force)
 Update the sensor information. More...
 

Protected Attributes

sdf::ElementPtr cameraElem
 Camera SDF element. More...
 
sdf::ElementPtr horzElem
 Horizontal SDF element. More...
 
unsigned int horzRangeCount
 Horizontal range count. More...
 
unsigned int horzRayCount
 Horizontal ray count. More...
 
double rangeCountRatio
 Range count ratio. More...
 
sdf::ElementPtr rangeElem
 Range SDF element. More...
 
sdf::ElementPtr scanElem
 Scan SDF elementz. More...
 
sdf::ElementPtr vertElem
 Vertical SDF element. More...
 
unsigned int vertRangeCount
 Vertical range count. More...
 
unsigned int vertRayCount
 Vertical ray count. More...
 
- 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...
 
boost::mutex mutexLastUpdateTime
 Mutex to protect resetting lastUpdateTime. More...
 
transport::NodePtr node
 Node for communication. 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...
 
math::Pose pose
 Pose of the sensor. More...
 
transport::SubscriberPtr poseSub
 Subscribe to pose updates. 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...
 

Constructor & Destructor Documentation

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

Constructor.

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

Destructor.

Member Function Documentation

event::ConnectionPtr gazebo::sensors::GpuRaySensor::ConnectNewLaserFrame ( boost::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.
void gazebo::sensors::GpuRaySensor::DisconnectNewLaserFrame ( event::ConnectionPtr _conn)

Disconnect Laser Frame.

Parameters
[in,out]_connConnection pointer to disconnect.
virtual void gazebo::sensors::GpuRaySensor::Fini ( )
protectedvirtual

Finalize the ray.

Reimplemented from gazebo::sensors::Sensor.

math::Angle gazebo::sensors::GpuRaySensor::GetAngleMax ( ) const

Get the maximum angle.

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

Get the minimum angle.

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

Get radians between each range.

unsigned int gazebo::sensors::GpuRaySensor::GetCameraCount ( ) const

Gets the camera count.

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

Get Cos Horz field-of-view.

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

Get Cos Vert field-of-view.

Returns
2 * atan(tan(this->vfov/2) / cos(this->hfov/2))
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
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.
double gazebo::sensors::GpuRaySensor::GetHorzHalfAngle ( ) const

Get (horizontal_max_angle + horizontal_min_angle) * 0.5.

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

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

Returns
Pointer to GpuLaser
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 DBL_MAX for no detection.
int gazebo::sensors::GpuRaySensor::GetRangeCount ( ) const

Get the range count.

Returns
The number of ranges
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.

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

Get the maximum range.

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

Get the minimum range.

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

Get all the ranges.

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

Get the ray count.

Returns
The number of rays
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.

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
virtual std::string gazebo::sensors::GpuRaySensor::GetTopic ( ) const
virtual

Returns the topic name as set in SDF.

Returns
Topic name.

Reimplemented from gazebo::sensors::Sensor.

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

Get the vertical field-of-view.

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

Get (vertical_max_angle + vertical_min_angle) * 0.5.

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

Get the vertical scan line top angle.

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

Get the vertical scan bottom angle.

Returns
The minimum angle of the scan block
int gazebo::sensors::GpuRaySensor::GetVerticalRangeCount ( ) const

Get the vertical scan line count.

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

Get the vertical scan line count.

Returns
The number of scan lines vertically
virtual void gazebo::sensors::GpuRaySensor::Init ( )
virtual

Initialize the ray.

Reimplemented from gazebo::sensors::Sensor.

virtual bool gazebo::sensors::GpuRaySensor::IsActive ( )
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
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
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.

void gazebo::sensors::GpuRaySensor::SetAngleMax ( double  _angle)

Set the scan maximum angle.

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

Set the scan minimum angle.

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

Set the vertical scan line top angle.

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

Set the vertical scan bottom angle.

Parameters
[in]_angleThe minimum angle of the scan block
virtual void gazebo::sensors::GpuRaySensor::UpdateImpl ( bool  _force)
protectedvirtual

Update the sensor information.

Parameters
[in]_forceTrue if update is forced, false if not

Reimplemented from gazebo::sensors::Sensor.

Member Data Documentation

sdf::ElementPtr gazebo::sensors::GpuRaySensor::cameraElem
protected

Camera SDF element.

sdf::ElementPtr gazebo::sensors::GpuRaySensor::horzElem
protected

Horizontal SDF element.

unsigned int gazebo::sensors::GpuRaySensor::horzRangeCount
protected

Horizontal range count.

unsigned int gazebo::sensors::GpuRaySensor::horzRayCount
protected

Horizontal ray count.

double gazebo::sensors::GpuRaySensor::rangeCountRatio
protected

Range count ratio.

sdf::ElementPtr gazebo::sensors::GpuRaySensor::rangeElem
protected

Range SDF element.

sdf::ElementPtr gazebo::sensors::GpuRaySensor::scanElem
protected

Scan SDF elementz.

sdf::ElementPtr gazebo::sensors::GpuRaySensor::vertElem
protected

Vertical SDF element.

unsigned int gazebo::sensors::GpuRaySensor::vertRangeCount
protected

Vertical range count.

unsigned int gazebo::sensors::GpuRaySensor::vertRayCount
protected

Vertical ray count.


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