Public Types | Public Member Functions | Private Attributes
PointCloudMapper Class Reference

List of all members.

Public Types

typedef pcl::PointXYZRGB Point
typedef pcl::PointCloud
< pcl::PointXYZRGB > 
PointCloud

Public Member Functions

void callback (const PointCloud::ConstPtr &cloud)
PointCloud::Ptr filter (PointCloud::Ptr cloud)
 PointCloudMapper ()
void publishCallback (const ros::TimerEvent &)

Private Attributes

PointCloud accumulated_cloud_
ros::Publisher cloud_pub_
ros::Subscriber cloud_sub_
bool filter_map_
std::string fixed_frame_
ros::NodeHandle nh_
ros::NodeHandle nh_priv_
ros::Timer pub_timer_
tf::TransformListener tf_listener_
double voxel_size_
double x_filter_max_
double x_filter_min_
double y_filter_max_
double y_filter_min_
double z_filter_max_
double z_filter_min_

Detailed Description

Stores incoming point clouds in a map transforming each cloud to a global fixed frame using tf.

Definition at line 13 of file pointcloud_mapper.cpp.


Member Typedef Documentation

typedef pcl::PointXYZRGB PointCloudMapper::Point

Definition at line 17 of file pointcloud_mapper.cpp.

typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudMapper::PointCloud

Definition at line 18 of file pointcloud_mapper.cpp.


Constructor & Destructor Documentation

Definition at line 20 of file pointcloud_mapper.cpp.


Member Function Documentation

void PointCloudMapper::callback ( const PointCloud::ConstPtr &  cloud) [inline]

Definition at line 40 of file pointcloud_mapper.cpp.

PointCloud::Ptr PointCloudMapper::filter ( PointCloud::Ptr  cloud) [inline]

Definition at line 71 of file pointcloud_mapper.cpp.

void PointCloudMapper::publishCallback ( const ros::TimerEvent &  ) [inline]

Definition at line 63 of file pointcloud_mapper.cpp.


Member Data Documentation

Definition at line 134 of file pointcloud_mapper.cpp.

ros::Publisher PointCloudMapper::cloud_pub_ [private]

Definition at line 128 of file pointcloud_mapper.cpp.

ros::Subscriber PointCloudMapper::cloud_sub_ [private]

Definition at line 127 of file pointcloud_mapper.cpp.

Definition at line 122 of file pointcloud_mapper.cpp.

std::string PointCloudMapper::fixed_frame_ [private]

Definition at line 132 of file pointcloud_mapper.cpp.

ros::NodeHandle PointCloudMapper::nh_ [private]

Definition at line 124 of file pointcloud_mapper.cpp.

ros::NodeHandle PointCloudMapper::nh_priv_ [private]

Definition at line 125 of file pointcloud_mapper.cpp.

ros::Timer PointCloudMapper::pub_timer_ [private]

Definition at line 130 of file pointcloud_mapper.cpp.

tf::TransformListener PointCloudMapper::tf_listener_ [private]

Definition at line 133 of file pointcloud_mapper.cpp.

Definition at line 121 of file pointcloud_mapper.cpp.

Definition at line 116 of file pointcloud_mapper.cpp.

Definition at line 115 of file pointcloud_mapper.cpp.

Definition at line 118 of file pointcloud_mapper.cpp.

Definition at line 117 of file pointcloud_mapper.cpp.

Definition at line 120 of file pointcloud_mapper.cpp.

Definition at line 119 of file pointcloud_mapper.cpp.


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


pointcloud_tools
Author(s): Pep Lluis Negre
autogenerated on Mon Jan 6 2014 11:48:56