Class LaserProjection

Class Documentation

class LaserProjection

A Class to Project Laser Scan.

This class will project laser scans into point clouds. It caches unit vectors between runs (provided the angular resolution of your scanner is not changing) to avoid excess computation.

By default all range values less than the scanner min_range, and greater than the scanner max_range are removed from the generated point cloud, as these are assumed to be invalid.

If it is important to preserve a mapping between the index of range values and points in the cloud, the recommended approach is to pre-filter your laser_scan message to meet the requiremnt that all ranges are between min and max_range.

The generated PointClouds have a number of channels which can be enabled through the use of ChannelOption.

  • channel_option::Intensity - Create a channel named “intensities” with the intensity of the return for each point

  • channel_option::Index - Create a channel named “index” containing the index from the original array for each point

  • channel_option::Distance - Create a channel named “distances” containing the distance from the laser to each point

  • channel_option::Timestamp - Create a channel named “stamps” containing the specific timestamp at which each point was measured

Public Functions

inline LaserProjection()
inline LASER_GEOMETRY_PUBLIC void projectLaser (const sensor_msgs::msg::LaserScan &scan_in, sensor_msgs::msg::PointCloud2 &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)

Project a single laser scan from a linear array into a 3D point cloud. The generated cloud will be in the same frame as the original laser scan.

Parameters:
  • scan_in – The input laser scan

  • cloud_out – The output point cloud

  • range_cutoff – An additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.

  • channel_option – An OR’d set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

inline LASER_GEOMETRY_PUBLIC void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::msg::LaserScan &scan_in, sensor_msgs::msg::PointCloud2 &cloud_out, tf2::BufferCore &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default)

Transform a single laser scan from a linear array into a 3D point cloud, accounting for movement of the laser over the course of the scan. In order for this transform to be meaningful at a single point in time, the target_frame must be a fixed reference frame. See the tf documentation for more information on fixed frames.

Parameters:
  • target_frame – The frame of the resulting point cloud

  • scan_in – The input laser scan

  • cloud_out – The output point cloud

  • tf – a tf2::BufferCore object to use to perform the transform

  • range_cutoff – An additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.

  • channel_option – An OR’d set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.