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

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods. More...

#include <feature.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef pcl::KdTree
< pcl::PointXYZ > 
KdTree
typedef pcl::KdTree
< pcl::PointXYZ >::Ptr 
KdTreePtr
typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr

Public Member Functions

 Feature ()
 Empty constructor.

Protected Member Functions

virtual bool childInit (ros::NodeHandle &nh)=0
 Child initialization routine. Internal method.
virtual void computePublish (const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
 Compute the feature and publish it. Internal method.
void config_callback (FeatureConfig &config, uint32_t level)
 Dynamic reconfigure callback.
virtual void emptyPublish (const PointCloudInConstPtr &cloud)=0
 Publish an empty point cloud of the feature output type.
void input_callback (const PointCloudInConstPtr &input)
 Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.

Protected Attributes

int k_
 The number of K nearest neighbors to use for each point.
message_filters::PassThrough
< PointCloudIn
nf_pc_
message_filters::PassThrough
< PointIndices
nf_pi_
 Null passthrough filter, used for pushing empty elements in the synchronizer.
double search_radius_
 The nearest neighbors search radius for each point.
int spatial_locator_type_
 Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.
boost::shared_ptr
< dynamic_reconfigure::Server
< FeatureConfig > > 
srv_
 Pointer to a dynamic reconfigure service.
ros::Subscriber sub_input_
 The input PointCloud subscriber.
message_filters::Subscriber
< PointCloudIn
sub_surface_filter_
 The surface PointCloud subscriber filter.
KdTreePtr tree_
 The input point cloud dataset.
bool use_surface_
 Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.

Private Member Functions

void input_surface_indices_callback (const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
 Input point cloud callback. Used when use_indices and use_surface are set.
virtual void onInit ()
 Nodelet initialization routine.

Private Attributes

boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloudIn, PointCloudIn,
PointIndices > > > 
sync_input_surface_indices_a_
 Synchronized input, surface, and point indices.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloudIn, PointCloudIn,
PointIndices > > > 
sync_input_surface_indices_e_

Detailed Description

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods.

Author:
Radu Bogdan Rusu

Definition at line 66 of file feature.h.


Member Typedef Documentation

typedef boost::shared_ptr<const std::vector<int> > pcl_ros::Feature::IndicesConstPtr

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 77 of file feature.h.

typedef boost::shared_ptr<std::vector<int> > pcl_ros::Feature::IndicesPtr

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 76 of file feature.h.

typedef pcl::KdTree<pcl::PointXYZ> pcl_ros::Feature::KdTree

Definition at line 69 of file feature.h.

typedef pcl::KdTree<pcl::PointXYZ>::Ptr pcl_ros::Feature::KdTreePtr

Definition at line 70 of file feature.h.

Definition at line 72 of file feature.h.

typedef PointCloudIn::ConstPtr pcl_ros::Feature::PointCloudInConstPtr

Definition at line 74 of file feature.h.

typedef PointCloudIn::Ptr pcl_ros::Feature::PointCloudInPtr

Definition at line 73 of file feature.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 80 of file feature.h.


Member Function Documentation

virtual bool pcl_ros::Feature::childInit ( ros::NodeHandle nh) [protected, pure virtual]
virtual void pcl_ros::Feature::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudInConstPtr surface,
const IndicesPtr indices 
) [protected, pure virtual]
void pcl_ros::Feature::config_callback ( FeatureConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 153 of file features/feature.cpp.

virtual void pcl_ros::Feature::emptyPublish ( const PointCloudInConstPtr cloud) [protected, pure virtual]
void pcl_ros::Feature::input_callback ( const PointCloudInConstPtr input) [inline, protected]

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

Definition at line 150 of file feature.h.

void pcl_ros::Feature::input_surface_indices_callback ( const PointCloudInConstPtr cloud,
const PointCloudInConstPtr cloud_surface,
const PointIndicesConstPtr indices 
) [private]

Input point cloud callback. Used when use_indices and use_surface are set.

Parameters:
cloudthe pointer to the input point cloud
cloud_surfacethe pointer to the surface point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 169 of file features/feature.cpp.

void pcl_ros::Feature::onInit ( ) [private, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::FeatureFromNormals.

Definition at line 56 of file features/feature.cpp.


Member Data Documentation

int pcl_ros::Feature::k_ [protected]

The number of K nearest neighbors to use for each point.

Definition at line 98 of file feature.h.

Definition at line 143 of file feature.h.

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

Definition at line 142 of file feature.h.

The nearest neighbors search radius for each point.

Definition at line 101 of file feature.h.

Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.

Definition at line 118 of file feature.h.

boost::shared_ptr<dynamic_reconfigure::Server<FeatureConfig> > pcl_ros::Feature::srv_ [protected]

Pointer to a dynamic reconfigure service.

Definition at line 121 of file feature.h.

The input PointCloud subscriber.

Definition at line 108 of file feature.h.

The surface PointCloud subscriber filter.

Definition at line 105 of file feature.h.

Synchronized input, surface, and point indices.

Definition at line 162 of file feature.h.

Definition at line 163 of file feature.h.

The input point cloud dataset.

A pointer to the vector of point indices to use. An input point cloud describing the surface that is to be used for nearest neighbors estimation. A pointer to the spatial search object.

Definition at line 82 of file feature.h.

Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.

Definition at line 111 of file feature.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Aug 26 2015 15:25:31