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... | |
void | DisconnectNewLaserFrame (event::ConnectionPtr &_conn) |
Disconnect Laser Frame. More... | |
void | DisconnectUpdated (event::ConnectionPtr &_c) |
Disconnect from a the updated signal. 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 | 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... | |
SensorCategory | GetCategory () const GAZEBO_DEPRECATED(7.0) |
Get the category of the sensor. 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... | |
uint32_t | GetId () const GAZEBO_DEPRECATED(7.0) |
Get the sensor's ID. More... | |
rendering::GpuLaserPtr | GetLaserCamera () const GAZEBO_DEPRECATED(7.0) |
Returns a pointer to the internally kept rendering::GpuLaser. 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... | |
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... | |
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... | |
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... | |
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... | |
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 () |
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... | |
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) |
Load the sensor with SDF parameters. More... | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. 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... | |
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... | |
void | ResetLastUpdateTime () |
Reset the lastUpdateTime to zero. 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... | |
virtual void | SetActive (const bool _value) |
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 |
Returns the topic name as set in SDF. 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... | |
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 () |
Finalize the ray. More... | |
bool | NeedsUpdate () |
Return true if the sensor needs to be updated. More... | |
virtual bool | UpdateImpl (const bool _force) |
This gets overwritten by derived sensor types. More... | |
Protected Attributes | |
bool | active |
True if sensor generation is active. More... | |
std::vector< event::ConnectionPtr > | connections |
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< SensorPluginPtr > | plugins |
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... | |
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).
GpuRaySensor | ( | ) |
Constructor.
|
virtual |
Destructor.
ignition::math::Angle AngleMax | ( | ) | const |
Get the maximum angle.
ignition::math::Angle AngleMin | ( | ) | const |
Get the minimum angle.
double AngleResolution | ( | ) | const |
Get radians between each range.
unsigned int CameraCount | ( | ) | const |
Gets the camera count.
|
inherited |
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.
[in] | _subscriber | Event callback. |
|
inherited |
Connect a signal that is triggered when the sensor is updated.
[in] | _subscriber | Callback that receives the signal. |
double CosHorzFOV | ( | ) | const |
Get Cos Horz field-of-view.
double CosVertFOV | ( | ) | const |
Get Cos Vert field-of-view.
void DisconnectNewLaserFrame | ( | event::ConnectionPtr & | _conn | ) |
Disconnect Laser Frame.
[in,out] | _conn | Connection pointer to disconnect. |
|
inherited |
Disconnect from a the updated signal.
[in] | _c | The connection to disconnect |
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).
[in] | _index | Index of specific ray |
|
inherited |
fills a msgs::Sensor message.
[out] | _msg | Message to fill. |
|
protectedvirtual |
Finalize the ray.
Reimplemented from Sensor.
double GetAngleResolution | ( | ) | const |
unsigned int GetCameraCount | ( | ) | const |
|
inherited |
Get the category of the sensor.
double GetCosHorzFOV | ( | ) | const |
Get Cos Horz field-of-view.
double GetCosVertFOV | ( | ) | const |
Get Cos Vert field-of-view.
int 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).
[in] | _index | Index of specific ray |
double GetHorzFOV | ( | ) | const |
Get the horizontal field of view of the laser sensor.
double GetHorzHalfAngle | ( | ) | const |
Get (horizontal_max_angle + horizontal_min_angle) * 0.5.
|
inherited |
rendering::GpuLaserPtr GetLaserCamera | ( | ) | const |
Returns a pointer to the internally kept rendering::GpuLaser.
|
inherited |
Return last measurement time.
|
inherited |
|
inherited |
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
|
inherited |
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
double 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).
[in] | _index | Index of specific ray |
int GetRangeCount | ( | ) | const |
double 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 GetRangeMax | ( | ) | const |
double GetRangeMin | ( | ) | const |
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.
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.
void GetRanges | ( | std::vector< double > & | _ranges | ) |
Get all the ranges.
[out] | _range | A vector that will contain all the range data |
int GetRayCount | ( | ) | const |
double 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 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).
[in] | _index | Index of specific ray |
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Returns the topic name as set in SDF.
Reimplemented in AltimeterSensor, LogicalCameraSensor, and MagnetometerSensor.
|
inherited |
|
inherited |
Get the update rate of the sensor.
double GetVertFOV | ( | ) | const |
Get the vertical field-of-view.
double GetVertHalfAngle | ( | ) | const |
Get (vertical_max_angle + vertical_min_angle) * 0.5.
double GetVerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int GetVerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int GetVerticalRayCount | ( | ) | const |
Get the vertical scan line count.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
double HorzFOV | ( | ) | const |
Get the horizontal field of view of the laser sensor.
double HorzHalfAngle | ( | ) | const |
Get (horizontal_max_angle + horizontal_min_angle) * 0.5.
|
inherited |
Get the sensor's ID.
|
virtual |
Initialize the ray.
Reimplemented from Sensor.
|
virtual |
Returns true if sensor generation is active.
Reimplemented from Sensor.
bool IsHorizontal | ( | ) | const |
Gets if sensor is horizontal.
rendering::GpuLaserPtr LaserCamera | ( | ) | const |
Returns a pointer to the internally kept rendering::GpuLaser.
|
inherited |
Return last measurement time.
|
inherited |
Return last update time.
|
virtual |
|
virtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from |
Reimplemented from Sensor.
|
inherited |
Get name.
|
protectedinherited |
Return true if the sensor needs to be updated.
|
inherited |
Get the sensor's noise model for a specified noise type.
[in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices |
|
inherited |
Get the sensor's parent's ID.
|
inherited |
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
|
virtualinherited |
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).
[in] | _index | Index of specific ray |
int RangeCount | ( | ) | const |
Get the range count.
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.
double RangeMax | ( | ) | const |
Get the maximum range.
double RangeMin | ( | ) | const |
Get the minimum range.
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.
void Ranges | ( | std::vector< double > & | _ranges | ) | const |
Get all the ranges.
[out] | _range | A vector that will contain all the range data |
int RayCount | ( | ) | const |
Get the ray count.
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.
|
inherited |
Reset the lastUpdateTime to zero.
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).
[in] | _index | Index of specific ray |
|
inherited |
Get fully scoped name of the sensor.
|
virtualinherited |
Set whether the sensor is active or not.
[in] | _value | True if active, false if not. |
Reimplemented in DepthCameraSensor.
void SetAngleMax | ( | const double | _angle | ) |
Set the scan maximum angle.
[in] | _angle | The maximum angle |
void SetAngleMin | ( | const double | _angle | ) |
Set the scan minimum angle.
[in] | _angle | The minimum angle |
|
inherited |
Set the sensor's parent.
[in] | _name | The sensor's parent's name. |
[in] | _id | The sensor's parent's ID. |
|
virtualinherited |
|
inherited |
Set the update rate of the sensor.
[in] | _hz | update rate of sensor. |
void SetVerticalAngleMax | ( | const double | _angle | ) |
Set the vertical scan line top angle.
[in] | _angle | The Maximum angle of the scan block |
void SetVerticalAngleMin | ( | const double | _angle | ) |
Set the vertical scan bottom angle.
[in] | _angle | The minimum angle of the scan block |
|
virtual |
|
inherited |
Get sensor type.
|
inherited |
Update the sensor.
[in] | _force | True to force update, false otherwise. |
|
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
[in] | _force | True if update is forced, false if not |
Reimplemented from Sensor.
|
inherited |
Get the update rate of the sensor.
double VertFOV | ( | ) | const |
Get the vertical field-of-view.
double VertHalfAngle | ( | ) | const |
Get (vertical_max_angle + vertical_min_angle) * 0.5.
ignition::math::Angle VerticalAngleMax | ( | ) | const |
Get the vertical scan line top angle.
ignition::math::Angle VerticalAngleMin | ( | ) | const |
Get the vertical scan bottom angle.
double VerticalAngleResolution | ( | ) | const |
Get the vertical angle in radians between each range.
int VerticalRangeCount | ( | ) | const |
Get the vertical scan line count.
int VerticalRayCount | ( | ) | const |
Get the vertical scan line count.
|
inherited |
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
|
inherited |
Returns the name of the world the sensor is in.
|
protectedinherited |
True if sensor generation is active.
|
protectedinherited |
All event connections.
|
protectedinherited |
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
|
protectedinherited |
Time of the last update.
|
protectedinherited |
Node for communication.
|
protectedinherited |
Noise added to sensor data.
|
protectedinherited |
The sensor's parent ID.
|
protectedinherited |
Name of the parent.
|
protectedinherited |
All the plugins for the sensor.
|
protectedinherited |
Pose of the sensor.
|
protectedinherited |
Pointer to the Scene.
|
protectedinherited |
Pointer the the SDF element for the sensor.
|
protectedinherited |
Desired time between updates, set indirectly by Sensor::SetUpdateRate.
|
protectedinherited |
Pointer to the world.