Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
laser_geometry::LaserProjection Class Reference

A Class to Project Laser Scan. More...

#include <laser_geometry.h>

Inheritance diagram for laser_geometry::LaserProjection:
Inheritance graph
[legend]

Public Member Functions

 LaserProjection ()
 
void projectLaser (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
 Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud. More...
 
void projectLaser (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
 Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2. More...
 
void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
 Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame. More...
 
void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, int channel_options=channel_option::Default)
 Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame. More...
 
void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf::Transformer &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default)
 Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
 
void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf2::BufferCore &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default)
 Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
 
void transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, const std::string &fixed_frame, tf2::BufferCore &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default)
 Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
 
 ~LaserProjection ()
 Destructor to deallocate stored unit vectors. More...
 

Protected Member Functions

const boost::numeric::ublas::matrix< double > & getUnitVectors_ (double angle_min, double angle_max, double angle_increment, unsigned int length)
 Internal protected representation of getUnitVectors. More...
 

Private Member Functions

void projectLaser_ (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff, bool preservative, int channel_options)
 Internal hidden representation of projectLaser. More...
 
void projectLaser_ (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, double range_cutoff, int channel_options)
 Internal hidden representation of projectLaser. More...
 
void transformLaserScanToPointCloud_ (const std::string &target_frame, sensor_msgs::PointCloud &cloud_out, const sensor_msgs::LaserScan &scan_in, tf::Transformer &tf, double range_cutoff, int channel_options)
 Internal hidden representation of transformLaserScanToPointCloud. More...
 
void transformLaserScanToPointCloud_ (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options)
 Internal hidden representation of transformLaserScanToPointCloud2. More...
 
void transformLaserScanToPointCloud_ (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf2::BufferCore &tf, double range_cutoff, int channel_options)
 Internal hidden representation of transformLaserScanToPointCloud2. More...
 
void transformLaserScanToPointCloud_ (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, const std::string &fixed_frame, tf2::BufferCore &tf, double range_cutoff, int channel_options)
 Internal hidden representation of transformLaserScanToPointCloud2. More...
 
void transformLaserScanToPointCloud_ (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf2::Quaternion quat_start, tf2::Vector3 origin_start, tf2::Quaternion quat_end, tf2::Vector3 origin_end, double range_cutoff, int channel_options)
 Function used by the several forms of transformLaserScanToPointCloud_. More...
 

Private Attributes

float angle_max_
 
float angle_min_
 
Eigen::ArrayXXd co_sine_map_
 
boost::mutex guv_mutex_
 
std::map< std::string, boost::numeric::ublas::matrix< double > * > unit_vector_map_
 Internal map of pointers to stored values. More...
 

Detailed Description

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.

Definition at line 113 of file laser_geometry.h.

Constructor & Destructor Documentation

laser_geometry::LaserProjection::LaserProjection ( )
inline

Definition at line 118 of file laser_geometry.h.

laser_geometry::LaserProjection::~LaserProjection ( )

Destructor to deallocate stored unit vectors.

Definition at line 178 of file laser_geometry.cpp.

Member Function Documentation

const boost::numeric::ublas::matrix< double > & laser_geometry.laser_geometry.LaserProjection::getUnitVectors_ ( double  angle_min,
double  angle_max,
double  angle_increment,
unsigned int  length 
)
protected

Internal protected representation of getUnitVectors.

This function should not be used by external users, however, it is left protected so that test code can evaluate it appropriately.

Definition at line 152 of file laser_geometry.cpp.

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

Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud.

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_inThe input laser scan
cloud_outThe output point cloud
range_cutoffAn additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 139 of file laser_geometry.h.

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

Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2.

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_inThe input laser scan
cloud_outThe output point cloud
range_cutoffAn additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 163 of file laser_geometry.h.

void laser_geometry::LaserProjection::projectLaser_ ( const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud &  cloud_out,
double  range_cutoff,
bool  preservative,
int  channel_options 
)
private

Internal hidden representation of projectLaser.

void laser_geometry.laser_geometry.LaserProjection::projectLaser_ ( const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
double  range_cutoff,
int  channel_options 
)
private

Internal hidden representation of projectLaser.

Definition at line 277 of file laser_geometry.cpp.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud &  cloud_out,
tf::Transformer tf,
double  range_cutoff,
int  channel_options = channel_option::Default 
)
inline

Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame.

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_frameThe frame of the resulting point cloud
scan_inThe input laser scan
cloud_outThe output point cloud
tfa tf::Transformer object to use to perform the transform
range_cutoffAn additional range cutoff which can be applied to discard everything above it.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 193 of file laser_geometry.h.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud &  cloud_out,
tf::Transformer tf,
int  channel_options = channel_option::Default 
)
inline

Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame.

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_frameThe frame of the resulting point cloud
scan_inThe input laser scan
cloud_outThe output point cloud
tfa tf::Transformer object to use to perform the transform
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 222 of file laser_geometry.h.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
tf::Transformer tf,
double  range_cutoff = -1.0,
int  channel_options = channel_option::Default 
)
inline

Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame.

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_frameThe frame of the resulting point cloud
scan_inThe input laser scan
cloud_outThe output point cloud
tfa tf::Transformer object to use to perform the transform
range_cutoffAn additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 253 of file laser_geometry.h.

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

Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame.

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_frameThe frame of the resulting point cloud
scan_inThe input laser scan
cloud_outThe output point cloud
tfa tf2::BufferCore object to use to perform the transform
range_cutoffAn additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 285 of file laser_geometry.h.

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

Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame.

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. This version uses an intermediate fixed frame, which enables transformation into a moving frame, including transformation to the source frame at the beginning of the scan.

Parameters
target_frameThe frame of the resulting point cloud
scan_inThe input laser scan
cloud_outThe output point cloud
fixed_frameThe intermediate fixed frame for transformation
tfa tf2::BufferCore object to use to perform the transform
range_cutoffAn additional range cutoff which can be applied to discard everything above it. Defaults to -1.0, which means the laser scan max range.
channel_optionAn OR'd set of channels to include. Options include: channel_option::Default, channel_option::Intensity, channel_option::Index, channel_option::Distance, channel_option::Timestamp.

Definition at line 318 of file laser_geometry.h.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud_ ( const std::string &  target_frame,
sensor_msgs::PointCloud &  cloud_out,
const sensor_msgs::LaserScan &  scan_in,
tf::Transformer tf,
double  range_cutoff,
int  channel_options 
)
private

Internal hidden representation of transformLaserScanToPointCloud.

void laser_geometry.laser_geometry.LaserProjection::transformLaserScanToPointCloud_ ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
tf::Transformer tf,
double  range_cutoff,
int  channel_options 
)
private

Internal hidden representation of transformLaserScanToPointCloud2.

Definition at line 653 of file laser_geometry.cpp.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud_ ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
tf2::BufferCore tf,
double  range_cutoff,
int  channel_options 
)
private

Internal hidden representation of transformLaserScanToPointCloud2.

Definition at line 688 of file laser_geometry.cpp.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud_ ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
const std::string &  fixed_frame,
tf2::BufferCore tf,
double  range_cutoff,
int  channel_options 
)
private

Internal hidden representation of transformLaserScanToPointCloud2.

Definition at line 724 of file laser_geometry.cpp.

void laser_geometry::LaserProjection::transformLaserScanToPointCloud_ ( const std::string &  target_frame,
const sensor_msgs::LaserScan &  scan_in,
sensor_msgs::PointCloud2 &  cloud_out,
tf2::Quaternion  quat_start,
tf2::Vector3  origin_start,
tf2::Quaternion  quat_end,
tf2::Vector3  origin_end,
double  range_cutoff,
int  channel_options 
)
private

Function used by the several forms of transformLaserScanToPointCloud_.

Todo:
Make a function that performs both the slerp and linear interpolation needed to interpolate a Full Transform (Quaternion + Vector)

Definition at line 497 of file laser_geometry.cpp.

Member Data Documentation

float laser_geometry::LaserProjection::angle_max_
private

Definition at line 404 of file laser_geometry.h.

float laser_geometry::LaserProjection::angle_min_
private

Definition at line 403 of file laser_geometry.h.

Eigen::ArrayXXd laser_geometry::LaserProjection::co_sine_map_
private

Definition at line 405 of file laser_geometry.h.

boost::mutex laser_geometry::LaserProjection::guv_mutex_
private

Definition at line 406 of file laser_geometry.h.

std::map<std::string,boost::numeric::ublas::matrix<double>* > laser_geometry::LaserProjection::unit_vector_map_
private

Internal map of pointers to stored values.

Definition at line 402 of file laser_geometry.h.


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


laser_geometry
Author(s): Tully Foote, Radu Bogdan Rusu, William Woodall
autogenerated on Sun Feb 7 2021 03:09:58