class documentation

class LaserProjection:

View In Hierarchy

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.

Class ChannelOption Undocumented
Method __init__ Undocumented
Method projectLaser Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2.
Constant LASER_SCAN_INVALID Undocumented
Constant LASER_SCAN_MAX_RANGE Undocumented
Constant LASER_SCAN_MIN_RANGE Undocumented
Method __projectLaser Undocumented
Instance Variable __angle_max Undocumented
Instance Variable __angle_min Undocumented
Instance Variable __cos_sin_map Undocumented
def __init__(self):

Undocumented

def 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.

LASER_SCAN_INVALID: float =

Undocumented

Value
-1.0
LASER_SCAN_MAX_RANGE: float =

Undocumented

Value
-3.0
LASER_SCAN_MIN_RANGE: float =

Undocumented

Value
-2.0
def __projectLaser(self, scan_in, range_cutoff, channel_options):

Undocumented

__angle_max =

Undocumented

__angle_min =

Undocumented

__cos_sin_map =

Undocumented