pcl_ros::SACSegmentationFromNormals Class Reference

SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation. More...

#include <sac_segmentation.h>

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

List of all members.

Public Member Functions

std::string getInputTFframe ()
 Get the TF frame the input PointCloud should be transformed into before processing.
std::string getOutputTFframe ()
 Get the TF frame the PointCloud should be transformed into after processing.
void setInputTFframe (std::string tf_frame)
 Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
void setOutputTFframe (std::string tf_frame)
 Set the output TF frame the data should be transformed into after processing.

Protected Member Functions

void axis_callback (const pcl::ModelCoefficientsConstPtr &model)
 Model callback.
void config_callback (SACSegmentationFromNormalsConfig &config, uint32_t level)
 Dynamic reconfigure callback.
void input_callback (const PointCloudConstPtr &cloud)
 Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.
void input_normals_indices_callback (const PointCloudConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointIndicesConstPtr &indices)
 Input point cloud callback.
virtual void onInit ()
 Nodelet initialization routine.

Protected Attributes

message_filters::PassThrough
< PointIndices
nf_
 Null passthrough filter, used for pushing empty elements in the synchronizer.
boost::shared_ptr
< dynamic_reconfigure::Server
< SACSegmentationFromNormalsConfig > > 
srv_
 Pointer to a dynamic reconfigure service.
ros::Subscriber sub_axis_
 The input PointCloud subscriber.
message_filters::Subscriber
< PointCloudN
sub_normals_filter_
 The normals PointCloud subscriber filter.
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different.
std::string tf_input_orig_frame_
 The original data input TF frame.
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different.

Private Types

typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef pcl::PointCloud
< pcl::Normal > 
PointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef PointCloud::Ptr PointCloudPtr

Private Attributes

pcl::SACSegmentationFromNormals
< pcl::PointXYZ, pcl::Normal > 
impl_
 The PCL implementation used.
boost::mutex mutex_
 Internal mutex.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloud, PointCloudN,
PointIndices > > > 
sync_input_normals_indices_a_
 Synchronized input, normals, and indices.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloud, PointCloudN,
PointIndices > > > 
sync_input_normals_indices_e_

Detailed Description

SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation.

Definition at line 175 of file sac_segmentation.h.


Member Typedef Documentation

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 177 of file sac_segmentation.h.

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

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 179 of file sac_segmentation.h.

Definition at line 181 of file sac_segmentation.h.

typedef PointCloudN::ConstPtr pcl_ros::SACSegmentationFromNormals::PointCloudNConstPtr [private]

Definition at line 183 of file sac_segmentation.h.

typedef PointCloudN::Ptr pcl_ros::SACSegmentationFromNormals::PointCloudNPtr [private]

Definition at line 182 of file sac_segmentation.h.

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

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 178 of file sac_segmentation.h.


Member Function Documentation

void pcl_ros::SACSegmentationFromNormals::axis_callback ( const pcl::ModelCoefficientsConstPtr &  model  )  [protected]

Model callback.

Parameters:
model the sample consensus model found

Definition at line 455 of file sac_segmentation.cpp.

void pcl_ros::SACSegmentationFromNormals::config_callback ( SACSegmentationFromNormalsConfig config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
config the config object
level the dynamic reconfigure level

Definition at line 472 of file sac_segmentation.cpp.

std::string pcl_ros::SACSegmentationFromNormals::getInputTFframe (  )  [inline]

Get the TF frame the input PointCloud should be transformed into before processing.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 192 of file sac_segmentation.h.

std::string pcl_ros::SACSegmentationFromNormals::getOutputTFframe (  )  [inline]

Get the TF frame the PointCloud should be transformed into after processing.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 200 of file sac_segmentation.h.

void pcl_ros::SACSegmentationFromNormals::input_callback ( const PointCloudConstPtr cloud  )  [inline, protected]

Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 218 of file sac_segmentation.h.

void pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback ( const PointCloudConstPtr cloud,
const PointCloudNConstPtr cloud_normals,
const PointIndicesConstPtr indices 
) [protected]

Input point cloud callback.

Parameters:
cloud the pointer to the input point cloud
cloud_normals the pointer to the input point cloud normals
indices the pointer to the input point cloud indices

DEBUG

Definition at line 538 of file sac_segmentation.cpp.

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

Nodelet initialization routine.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 335 of file sac_segmentation.cpp.

void pcl_ros::SACSegmentationFromNormals::setInputTFframe ( std::string  tf_frame  )  [inline]

Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.

Parameters:
tf_frame the TF frame the input PointCloud should be transformed into before processing

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 189 of file sac_segmentation.h.

void pcl_ros::SACSegmentationFromNormals::setOutputTFframe ( std::string  tf_frame  )  [inline]

Set the output TF frame the data should be transformed into after processing.

Parameters:
tf_frame the TF frame the PointCloud should be transformed into after processing

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 197 of file sac_segmentation.h.


Member Data Documentation

The PCL implementation used.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 264 of file sac_segmentation.h.

Internal mutex.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 261 of file sac_segmentation.h.

Null passthrough filter, used for pushing empty elements in the synchronizer.

Definition at line 227 of file sac_segmentation.h.

boost::shared_ptr<dynamic_reconfigure::Server<SACSegmentationFromNormalsConfig> > pcl_ros::SACSegmentationFromNormals::srv_ [protected]

Pointer to a dynamic reconfigure service.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 211 of file sac_segmentation.h.

The input PointCloud subscriber.

Definition at line 208 of file sac_segmentation.h.

The normals PointCloud subscriber filter.

Definition at line 205 of file sac_segmentation.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloudN, PointIndices> > > pcl_ros::SACSegmentationFromNormals::sync_input_normals_indices_a_ [private]

Synchronized input, normals, and indices.

Definition at line 267 of file sac_segmentation.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloudN, PointIndices> > > pcl_ros::SACSegmentationFromNormals::sync_input_normals_indices_e_ [private]

Definition at line 268 of file sac_segmentation.h.

The input TF frame the data should be transformed into, if input.header.frame_id is different.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 230 of file sac_segmentation.h.

The original data input TF frame.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 232 of file sac_segmentation.h.

The output TF frame the data should be transformed into, if input.header.frame_id is different.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 234 of file sac_segmentation.h.


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


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:15:55 2013