Public Member Functions | Protected Attributes | Private Types
DifferenceSegmentation Class Reference

Segments the difference of two point clouds (e.g. a point map and new sensor data) and publishes the difference. More...

Inheritance diagram for DifferenceSegmentation:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DifferenceSegmentation ()
void onInit ()
 initializes parameters
void pointCloudSubCallback (const sensor_msgs::PointCloud2::ConstPtr &map_msg, const sensor_msgs::PointCloud2::ConstPtr &pc_aligned_msg)
 callback for point cloud subroutine
 ~DifferenceSegmentation ()

Protected Attributes

pcl::PointCloud< Pointmap_
ros::Publisher map_diff_pub_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
map_sub_
ros::NodeHandle n_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
pc_aligned_sub_
pcl::SegmentDifferences< Pointsd_
boost::shared_ptr
< message_filters::Synchronizer
< MySyncPolicy > > 
sync_

Private Types

typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::PointCloud2,
sensor_msgs::PointCloud2 > 
MySyncPolicy
typedef pcl::PointXYZRGB Point
typedef pcl::PointCloud< PointPointCloud

Detailed Description

Segments the difference of two point clouds (e.g. a point map and new sensor data) and publishes the difference.

Definition at line 91 of file difference_segmentation.cpp.


Member Typedef Documentation

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > DifferenceSegmentation::MySyncPolicy [private]

Definition at line 95 of file difference_segmentation.cpp.

typedef pcl::PointXYZRGB DifferenceSegmentation::Point [private]

Definition at line 93 of file difference_segmentation.cpp.

Definition at line 94 of file difference_segmentation.cpp.


Constructor & Destructor Documentation

Definition at line 99 of file difference_segmentation.cpp.

void

Definition at line 104 of file difference_segmentation.cpp.


Member Function Documentation

void DifferenceSegmentation::onInit ( ) [inline, virtual]

initializes parameters

initializes parameters

Returns:
nothing

Implements nodelet::Nodelet.

Definition at line 117 of file difference_segmentation.cpp.

void DifferenceSegmentation::pointCloudSubCallback ( const sensor_msgs::PointCloud2::ConstPtr &  map_msg,
const sensor_msgs::PointCloud2::ConstPtr &  pc_aligned_msg 
) [inline]

callback for point cloud subroutine

callback for point cloud subroutine which stores the point cloud for further calculation

Parameters:
pc_innew point cloud
Returns:
nothing

Definition at line 144 of file difference_segmentation.cpp.


Member Data Documentation

Definition at line 181 of file difference_segmentation.cpp.

Definition at line 178 of file difference_segmentation.cpp.

message_filters::Subscriber<sensor_msgs::PointCloud2 > DifferenceSegmentation::map_sub_ [protected]

Definition at line 176 of file difference_segmentation.cpp.

Definition at line 175 of file difference_segmentation.cpp.

Definition at line 177 of file difference_segmentation.cpp.

Definition at line 182 of file difference_segmentation.cpp.

Definition at line 179 of file difference_segmentation.cpp.


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


cob_3d_mapping_point_map
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:48