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]

List of all members.

Public Member Functions

 LaserProjection ()
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.
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.
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.
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.
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.
 ~LaserProjection ()
 Destructor to deallocate stored unit vectors.

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.

Private Member Functions

void projectLaser_ (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, double range_cutoff, int channel_options)
 Internal hidden representation of projectLaser.
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.
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.
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.

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.

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 96 of file laser_geometry.h.


Constructor & Destructor Documentation

laser_geometry::LaserProjection::LaserProjection (  )  [inline]

Definition at line 101 of file laser_geometry.h.

laser_geometry::LaserProjection::~LaserProjection (  ) 

Destructor to deallocate stored unit vectors.

Definition at line 176 of file laser_geometry.cpp.


Member Function Documentation

const boost::numeric::ublas::matrix< double > & 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 150 of file laser_geometry.cpp.

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_in The input laser scan
cloud_out The output point cloud
range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan.
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.

Definition at line 145 of file laser_geometry.h.

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_in The input laser scan
cloud_out The output point cloud
range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan.
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.

Definition at line 122 of file laser_geometry.h.

void 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 274 of file laser_geometry.cpp.

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.

Todo:
optimize and catch length difference better

Definition at line 34 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,
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_frame The frame of the resulting point cloud
scan_in The input laser scan
cloud_out The output point cloud
tf a tf::Transformer object to use to perform the transform
range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan.
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.

Definition at line 234 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_frame The frame of the resulting point cloud
scan_in The input laser scan
cloud_out The output point cloud
tf a tf::Transformer object to use to perform the transform
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.

Definition at line 204 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,
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_frame The frame of the resulting point cloud
scan_in The input laser scan
cloud_out The output point cloud
tf a tf::Transformer object to use to perform the transform
range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan.
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.

Definition at line 175 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,
int  channel_options 
) [private]

Internal hidden representation of transformLaserScanToPointCloud2.

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

Definition at line 488 of file laser_geometry.cpp.

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.

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

Definition at line 188 of file laser_geometry.cpp.


Member Data Documentation

Definition at line 291 of file laser_geometry.h.

Definition at line 290 of file laser_geometry.h.

Definition at line 292 of file laser_geometry.h.

Definition at line 293 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 289 of file laser_geometry.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Defines


laser_geometry
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Fri Jan 11 10:02:55 2013