Public Member Functions
laser_assembler::PointCloud2Assembler Class Reference

Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request. More...

Inheritance diagram for laser_assembler::PointCloud2Assembler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void ConvertToCloud (const string &fixed_frame_id, const sensor_msgs::PointCloud2 &scan_in, sensor_msgs::PointCloud &cloud_out)
unsigned int GetPointsInScan (const sensor_msgs::PointCloud2 &scan)
 Returns the number of points in the current scan.
 PointCloud2Assembler ()
 ~PointCloud2Assembler ()

Detailed Description

Maintains a history of incremental point clouds (usually from laser scans) and generates a point cloud upon request.

Todo:
Clean up the doxygen part of this header params * (Several params are inherited from BaseAssemblerSrv)

Definition at line 50 of file point_cloud2_assembler.cpp.


Constructor & Destructor Documentation

Definition at line 53 of file point_cloud2_assembler.cpp.

Definition at line 58 of file point_cloud2_assembler.cpp.


Member Function Documentation

void laser_assembler::PointCloud2Assembler::ConvertToCloud ( const string &  fixed_frame_id,
const sensor_msgs::PointCloud2 &  scan_in,
sensor_msgs::PointCloud cloud_out 
) [inline]

Definition at line 68 of file point_cloud2_assembler.cpp.

unsigned int laser_assembler::PointCloud2Assembler::GetPointsInScan ( const sensor_msgs::PointCloud2 &  scan) [inline, virtual]

Returns the number of points in the current scan.

Parameters:
scanThe scan for for which we want to know the number of points
Returns:
the number of points in scan

Implements laser_assembler::BaseAssembler< sensor_msgs::PointCloud2 >.

Definition at line 63 of file point_cloud2_assembler.cpp.


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


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Mon Oct 6 2014 01:43:03