#include <Lidar.hh>
| Public Member Functions | |
| Lidar () | |
| constructor  More... | |
| virtual | ~Lidar () | 
| destructor  More... | |
| gz::math::Angle | AngleMax () const | 
| Get the maximum angle.  More... | |
| gz::math::Angle | AngleMin () const | 
| Get the minimum angle.  More... | |
| double | AngleResolution () const | 
| Get radians between each range.  More... | |
| void | ApplyNoise () | 
| Apply noise to the laser buffer, if noise has been configured. This should be called before PublishLidarScan if you want the scan data to contain noise.  More... | |
| virtual gz::common::ConnectionPtr | ConnectNewLidarFrame (std::function< void(const float *_scan, unsigned int _width, unsigned int _heighti, unsigned int _channels, const std::string &)> _subscriber) | 
| Set a callback to be called when data is generated.  More... | |
| virtual bool | CreateLidar () | 
| Create Lidar sensor.  More... | |
| 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).  More... | |
| double | HorzFOV () const | 
| Get the horizontal field of view of the laser sensor.  More... | |
| virtual bool | Init () override | 
| Initialize values in the sensor.  More... | |
| virtual bool | IsActive () const | 
| bool | IsHorizontal () const | 
| Gets if sensor is horizontal.  More... | |
| virtual bool | Load (const sdf::Sensor &_sdf) override | 
| Load the sensor based on data from an sdf::Sensor object.  More... | |
| virtual bool | Load (sdf::ElementPtr _sdf) override | 
| Load the sensor with SDF parameters.  More... | |
| virtual bool | PublishLidarScan (const common::Time &_now) | 
| Publish LaserScan message.  More... | |
| 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).  More... | |
| unsigned 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. 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.  More... | |
| void | Ranges (std::vector< double > &_ranges) const | 
| Get all the ranges.  More... | |
| unsigned 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. 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).  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 &_parent) override | 
| Initialize values in 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 bool | Update (const common::Time &_now) override | 
| Force the sensor to generate data.  More... | |
| double | VertFOV () const | 
| Get the vertical field-of-view.  More... | |
| gz::math::Angle | VerticalAngleMax () const | 
| Get the vertical scan line top angle.  More... | |
| gz::math::Angle | VerticalAngleMin () const | 
| Get the vertical scan bottom angle.  More... | |
| double | VerticalAngleResolution () const | 
| Get the vertical angle in radians between each range.  More... | |
| unsigned int | VerticalRangeCount () const | 
| Get the vertical scan line count.  More... | |
| unsigned int | VerticalRayCount () const | 
| Get the vertical scan line count.  More... | |
|  Public Member Functions inherited from RenderingSensor | |
| virtual | ~RenderingSensor () | 
| destructor  More... | |
| bool | ManualSceneUpdate () const | 
| Get whether the scene graph is updated manually. Defaults to false.  More... | |
| void | Render () | 
| Render update. This performs the actual render operation.  More... | |
| rendering::ScenePtr | Scene () const | 
| Get the rendering scene.  More... | |
| void | SetManualSceneUpdate (bool _manual) | 
| Set whether to update the scene graph manually. If set to true, it is expected that rendering::Scene::PreRender is called manually before calling Render()  More... | |
| virtual void | SetScene (rendering::ScenePtr _scene) | 
| Set the rendering scene.  More... | |
|  Public Member Functions inherited from Sensor | |
| virtual | ~Sensor () | 
| destructor  More... | |
| void | AddSequence (gz::msgs::Header *_msg, const std::string &_seqKey="default") | 
| Add a sequence number to an gz::msgs::Header. This function can be called by a sensor that wants to add a sequence number to a sensor message in order to have improved accountability for generated sensor data.  More... | |
| bool | EnableMetrics () const | 
| Get flag state for enabling performance metrics publication.  More... | |
| std::string | FrameId () const | 
| FrameId.  More... | |
| SensorId | Id () const | 
| Get the sensor's ID.  More... | |
| std::string | Name () const | 
| Get name.  More... | |
| common::Time | NextUpdateTime () const | 
| Return the next time the sensor will generate data.  More... | |
| std::string | Parent () const | 
| Get parent link of the sensor.  More... | |
| gz::math::Pose3d | Pose () const | 
| Get the current pose.  More... | |
| void | PublishMetrics (const std::chrono::duration< double > &_now) | 
| Publishes information about the performance of the sensor. This method is called by Update().  More... | |
| sdf::ElementPtr | SDF () const | 
| Get the SDF used to load this sensor.  More... | |
| void | SetEnableMetrics (bool _enableMetrics) | 
| Set flag to enable publishing performance metrics.  More... | |
| void | SetFrameId (const std::string &_frameId) | 
| Set Frame ID of the sensor.  More... | |
| void | SetPose (const gz::math::Pose3d &_pose) | 
| Update the pose of the sensor.  More... | |
| bool | SetTopic (const std::string &_topic) | 
| Set topic where sensor data is published.  More... | |
| void | SetUpdateRate (const double _hz) | 
| Set the update rate of the sensor. An update rate of zero means that the sensor is updated every cycle. It's zero by default. \detail Negative rates become zero.  More... | |
| std::string | Topic () const | 
| Get topic where sensor data is published.  More... | |
| bool | Update (const common::Time &_now, const bool _force) | 
| Update the sensor.  More... | |
| double | UpdateRate () const | 
| Get the update rate of the sensor.  More... | |
| Public Attributes | |
| bool | initialized = false | 
| true if Load() has been called and was successful  More... | |
| float * | laserBuffer = nullptr | 
| Raw buffer of laser data.  More... | |
| std::mutex | lidarMutex | 
| Just a mutex for thread safety.  More... | |
| Protected Member Functions | |
| virtual void | Fini () | 
| Finalize the ray.  More... | |
|  Protected Member Functions inherited from RenderingSensor | |
| RenderingSensor () | |
| constructor  More... | |
| void | AddSensor (rendering::SensorPtr _sensor) | 
| Add a rendering::Sensor. Its render updates will be handled by this base class.  More... | |
|  Protected Member Functions inherited from Sensor | |
| Sensor () | |
| constructor  More... | |
Detailed Description
This class creates laser scans using. It's measures the range from the origin of the center to points on the visual geometry in the scene.
It offers both an ignition-transport interface and a direct C++ API to access the image data. The API works by setting a callback to be called with image data.
Constructor & Destructor Documentation
◆ Lidar()
| Lidar | ( | ) | 
constructor
◆ ~Lidar()
| 
 | virtual | 
destructor
Member Function Documentation
◆ AngleMax()
| gz::math::Angle AngleMax | ( | ) | const | 
Get the maximum angle.
- Returns
- the maximum angle
◆ AngleMin()
| gz::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
◆ ApplyNoise()
| void ApplyNoise | ( | ) | 
Apply noise to the laser buffer, if noise has been configured. This should be called before PublishLidarScan if you want the scan data to contain noise.
◆ ConnectNewLidarFrame()
| 
 | virtual | 
Set a callback to be called when data is generated.
- Parameters
- 
  [in] _callback This callback will be called every time the sensor generates data. The Update function will be blocked while the callbacks are executed. 
- Remarks
- Do not block inside of the callback.
- Returns
- A connection pointer that must remain in scope. When the connection pointer falls out of scope, the connection is broken.
Reimplemented in GpuLidarSensor.
◆ CreateLidar()
| 
 | virtual | 
Create Lidar sensor.
Reimplemented in GpuLidarSensor.
◆ 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] _index Index of specific ray 
- Returns
- Fiducial value of ray
◆ Fini()
| 
 | protectedvirtual | 
Finalize the ray.
◆ HorzFOV()
| double HorzFOV | ( | ) | const | 
Get the horizontal field of view of the laser sensor.
- Returns
- The horizontal field of view of the laser sensor.
◆ Init()
| 
 | overridevirtual | 
Initialize values in the sensor.
- Returns
- True on success
Reimplemented from Sensor.
Reimplemented in GpuLidarSensor.
◆ IsActive()
| 
 | virtual | 
◆ IsHorizontal()
| bool IsHorizontal | ( | ) | const | 
Gets if sensor is horizontal.
- Returns
- True if horizontal, false if not
◆ Load() [1/2]
| 
 | overridevirtual | 
Load the sensor based on data from an sdf::Sensor object.
- Parameters
- 
  [in] _sdf SDF Sensor parameters. 
- Returns
- true if loading was successful
Reimplemented from Sensor.
Reimplemented in GpuLidarSensor.
◆ Load() [2/2]
| 
 | overridevirtual | 
Load the sensor with SDF parameters.
- Parameters
- 
  [in] _sdf SDF Sensor parameters. 
- Returns
- true if loading was successful
Reimplemented from Sensor.
Reimplemented in GpuLidarSensor.
◆ PublishLidarScan()
| 
 | virtual | 
Publish LaserScan message.
- Parameters
- 
  [in] _now The current time 
- Returns
- true if the update was successfull
◆ 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] _index Index of specific ray 
- Returns
- Returns RangeMax for no detection.
◆ RangeCount()
| unsigned 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] _range A vector that will contain all the range data 
◆ RayCount()
| unsigned 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.
◆ 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] _index Index of specific ray 
- Returns
- Intensity value of ray
◆ SetAngleMax()
| void SetAngleMax | ( | const double | _angle | ) | 
Set the scan maximum angle.
- Parameters
- 
  [in] _angle The maximum angle 
◆ SetAngleMin()
| void SetAngleMin | ( | const double | _angle | ) | 
Set the scan minimum angle.
- Parameters
- 
  [in] _angle The minimum angle 
◆ SetParent()
| 
 | overridevirtual | 
◆ SetVerticalAngleMax()
| void SetVerticalAngleMax | ( | const double | _angle | ) | 
Set the vertical scan line top angle.
- Parameters
- 
  [in] _angle The Maximum angle of the scan block 
◆ SetVerticalAngleMin()
| void SetVerticalAngleMin | ( | const double | _angle | ) | 
Set the vertical scan bottom angle.
- Parameters
- 
  [in] _angle The minimum angle of the scan block 
◆ Update()
| 
 | overridevirtual | 
Force the sensor to generate data.
- Parameters
- 
  [in] _now The current time 
- Returns
- true if the update was successfull
Implements Sensor.
Reimplemented in GpuLidarSensor.
◆ VertFOV()
| double VertFOV | ( | ) | const | 
Get the vertical field-of-view.
- Returns
- Vertical field of view.
◆ VerticalAngleMax()
| gz::math::Angle VerticalAngleMax | ( | ) | const | 
Get the vertical scan line top angle.
- Returns
- The Maximum angle of the scan block
◆ VerticalAngleMin()
| gz::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()
| unsigned int VerticalRangeCount | ( | ) | const | 
Get the vertical scan line count.
- Returns
- The number of scan lines vertically
◆ VerticalRayCount()
| unsigned int VerticalRayCount | ( | ) | const | 
Get the vertical scan line count.
- Returns
- The number of scan lines vertically
Member Data Documentation
◆ initialized
| bool initialized = false | 
true if Load() has been called and was successful
◆ laserBuffer
| float* laserBuffer = nullptr | 
Raw buffer of laser data.
◆ lidarMutex
| 
 | mutable | 
Just a mutex for thread safety.
The documentation for this class was generated from the following file: