Classes | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
laser_geometry.laser_geometry.LaserProjection Class Reference

List of all members.

Classes

class  ChannelOption

Public Member Functions

def __init__
def projectLaser

Static Public Attributes

float LASER_SCAN_INVALID = 1.0
float LASER_SCAN_MAX_RANGE = 3.0
float LASER_SCAN_MIN_RANGE = 2.0

Private Member Functions

def __projectLaser

Private Attributes

 __angle_max
 __angle_min
 __cos_sin_map

Detailed Description

A class to Project Laser Scan

This calls 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 thatn the scanner min_range,
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 requirement that all
ranges are between min and max_range.

The generate PointClouds have a number of channels which can be enabled
through the use of ChannelOption.
- ChannelOption.INTENSITY - Create a channel named "intensities" with the
intensity of the return for each point.
- ChannelOption.INDEX     - Create a channel named "index" containing the
index from the original array for each point.
- ChannelOption.DISTANCE  - Create a channel named "distance" containing
the distance from the laser to each point.
- ChannelOption.TIMESTAMP - Create a channel named "stamps" containing the
specific timestamp at which each point was measured.

Definition at line 36 of file laser_geometry.py.


Constructor & Destructor Documentation

Definition at line 78 of file laser_geometry.py.


Member Function Documentation

def laser_geometry.laser_geometry.LaserProjection.__projectLaser (   self,
  scan_in,
  range_cutoff,
  channel_options 
) [private]

Definition at line 102 of file laser_geometry.py.

def laser_geometry.laser_geometry.LaserProjection.projectLaser (   self,
  scan_in,
  range_cutoff = -1.0,
  channel_options = ChannelOption.DEFAULT 
)
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.

Keyword arguments:
scan_in -- The input laser scan.
range_cutoff -- An additional range cutoff which can be
    applied which is more limiting than max_range in the scan
    (default -1.0).
channel_options -- An OR'd set of channels to include.

Definition at line 84 of file laser_geometry.py.


Member Data Documentation

Definition at line 78 of file laser_geometry.py.

Definition at line 78 of file laser_geometry.py.

Definition at line 78 of file laser_geometry.py.

Definition at line 65 of file laser_geometry.py.

Definition at line 67 of file laser_geometry.py.

Definition at line 66 of file laser_geometry.py.


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


laser_geometry
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Mon Jul 24 2017 02:35:42