Public Member Functions | List of all members
laser_assembler::PointCloudAssembler 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::PointCloudAssembler:
Inheritance graph
[legend]

Public Member Functions

void ConvertToCloud (const string &fixed_frame_id, const sensor_msgs::PointCloud &scan_in, sensor_msgs::PointCloud &cloud_out)
 
unsigned int GetPointsInScan (const sensor_msgs::PointCloud &scan)
 Returns the number of points in the current scan. More...
 
 PointCloudAssembler ()
 
 ~PointCloudAssembler ()
 
- Public Member Functions inherited from laser_assembler::BaseAssembler< sensor_msgs::PointCloud >
 BaseAssembler (const std::string &max_size_param_name)
 
virtual void ConvertToCloud (const std::string &fixed_frame_id, const sensor_msgs::PointCloud &scan_in, sensor_msgs::PointCloud &cloud_out)=0
 Converts the current scan into a cloud in the specified fixed frame. More...
 
void start (const std::string &in_topic_name)
 Tells the assembler to start listening to input data It is possible that a derived class needs to initialize and configure various things before actually beginning to process scans. Calling start create subcribes to the input stream, thus allowing the scanCallback and ConvertToCloud to be called. Start should be called only once. More...
 
void start ()
 
 ~BaseAssembler ()
 

Additional Inherited Members

- Protected Attributes inherited from laser_assembler::BaseAssembler< sensor_msgs::PointCloud >
ros::NodeHandle n_
 
ros::NodeHandle private_ns_
 
tf::TransformListenertf_
 
tf::MessageFilter< sensor_msgs::PointCloud > * tf_filter_
 

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

Definition at line 50 of file point_cloud_assembler.cpp.

Constructor & Destructor Documentation

laser_assembler::PointCloudAssembler::PointCloudAssembler ( )
inline

Definition at line 53 of file point_cloud_assembler.cpp.

laser_assembler::PointCloudAssembler::~PointCloudAssembler ( )
inline

Definition at line 58 of file point_cloud_assembler.cpp.

Member Function Documentation

void laser_assembler::PointCloudAssembler::ConvertToCloud ( const string &  fixed_frame_id,
const sensor_msgs::PointCloud &  scan_in,
sensor_msgs::PointCloud &  cloud_out 
)
inline

Definition at line 68 of file point_cloud_assembler.cpp.

unsigned int laser_assembler::PointCloudAssembler::GetPointsInScan ( const sensor_msgs::PointCloud &  scan)
inlinevirtual

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::PointCloud >.

Definition at line 63 of file point_cloud_assembler.cpp.


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


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Thu Jun 27 2019 19:56:21