laser_slam::CloudCollector Class Reference

PCL filter that collects clouds. More...

#include <cloud_collector.h>

List of all members.

Public Member Functions

 CloudCollector (unsigned clouds_per_group=1u)
 Empty constructor.

Private Member Functions

virtual void applyFilter (sensor_msgs::PointCloud2 &output)
 Apply the filter.

Private Attributes

std::string base_frame_
 Frame in which output clouds are published.
pcl::PointCloud< pcl::PointXYZ > cloud_
int clouds_per_group_
 Whenever we have these many clouds, we'll batch them and publish a single output cloud.
std::string fixed_frame_
 Fixed frame into which clouds are transformed when received.
unsigned num_clouds_
std::vector
< sensor_msgs::PointCloud2 > 
stored_clouds_
 Stored clouds.
tf::TransformListener tf_

Friends

class CloudCollectorROS

Detailed Description

PCL filter that collects clouds.

Definition at line 47 of file cloud_collector.h.


Constructor & Destructor Documentation

laser_slam::CloudCollector::CloudCollector ( unsigned  clouds_per_group = 1u  )  [inline]

Empty constructor.

Definition at line 50 of file cloud_collector.h.


Member Function Documentation

virtual void laser_slam::CloudCollector::applyFilter ( sensor_msgs::PointCloud2 &  output  )  [private, virtual]

Apply the filter.

Parameters:
output the resultant point cloud message

Friends And Related Function Documentation

friend class CloudCollectorROS [friend]

Definition at line 58 of file cloud_collector.h.


Member Data Documentation

Frame in which output clouds are published.

Definition at line 67 of file cloud_collector.h.

pcl::PointCloud<pcl::PointXYZ> laser_slam::CloudCollector::cloud_ [private]

Definition at line 72 of file cloud_collector.h.

Whenever we have these many clouds, we'll batch them and publish a single output cloud.

Definition at line 61 of file cloud_collector.h.

Fixed frame into which clouds are transformed when received.

Definition at line 64 of file cloud_collector.h.

Definition at line 73 of file cloud_collector.h.

std::vector<sensor_msgs::PointCloud2> laser_slam::CloudCollector::stored_clouds_ [private]

Stored clouds.

Definition at line 70 of file cloud_collector.h.

tf::TransformListener laser_slam::CloudCollector::tf_ [private]

Definition at line 75 of file cloud_collector.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


laser_slam
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:53:31 2013