Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Attributes
pcl_ros::SegmentDifferences Class Reference

SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More...

#include <segment_differences.h>

Inheritance diagram for pcl_ros::SegmentDifferences:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 SegmentDifferences ()
 Empty constructor.

Protected Member Functions

void config_callback (SegmentDifferencesConfig &config, uint32_t level)
 Dynamic reconfigure callback.
void input_target_callback (const PointCloudConstPtr &cloud, const PointCloudConstPtr &cloud_target)
 Input point cloud callback.
void onInit ()
 Nodelet initialization routine.

Protected Attributes

boost::shared_ptr
< dynamic_reconfigure::Server
< SegmentDifferencesConfig > > 
srv_
 Pointer to a dynamic reconfigure service.
message_filters::Subscriber
< PointCloud
sub_target_filter_
 The message filter subscriber for PointCloud2.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloud, PointCloud > > > 
sync_input_target_a_
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloud, PointCloud > > > 
sync_input_target_e_
 Synchronized input, and planar hull.

Private Types

typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Private Attributes

pcl::SegmentDifferences
< pcl::PointXYZ > 
impl_
 The PCL implementation used.

Detailed Description

SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold.

Author:
Radu Bogdan Rusu

Definition at line 60 of file segment_differences.h.


Member Typedef Documentation

typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::SegmentDifferences::PointCloud [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 62 of file segment_differences.h.

typedef PointCloud::ConstPtr pcl_ros::SegmentDifferences::PointCloudConstPtr [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 64 of file segment_differences.h.

typedef PointCloud::Ptr pcl_ros::SegmentDifferences::PointCloudPtr [private]

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 63 of file segment_differences.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 68 of file segment_differences.h.


Member Function Documentation

void pcl_ros::SegmentDifferences::config_callback ( SegmentDifferencesConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 81 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::input_target_callback ( const PointCloudConstPtr cloud,
const PointCloudConstPtr cloud_target 
) [protected]

Input point cloud callback.

Parameters:
cloudthe pointer to the input point cloud
cloud_targetthe pointcloud that we want to segment cloud from

Definition at line 93 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::onInit ( ) [protected, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 44 of file segment_differences.cpp.


Member Data Documentation

The PCL implementation used.

Definition at line 99 of file segment_differences.h.

boost::shared_ptr<dynamic_reconfigure::Server<SegmentDifferencesConfig> > pcl_ros::SegmentDifferences::srv_ [protected]

Pointer to a dynamic reconfigure service.

Definition at line 79 of file segment_differences.h.

The message filter subscriber for PointCloud2.

Definition at line 68 of file segment_differences.h.

Definition at line 76 of file segment_differences.h.

Synchronized input, and planar hull.

Definition at line 75 of file segment_differences.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Jun 6 2019 21:01:45