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>
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_ |
Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods.
typedef boost::shared_ptr<const std::vector<int> > pcl_ros::Feature::IndicesConstPtr |
Reimplemented from pcl_ros::PCLNodelet.
typedef boost::shared_ptr<std::vector<int> > pcl_ros::Feature::IndicesPtr |
Reimplemented from pcl_ros::PCLNodelet.
typedef pcl::KdTree<pcl::PointXYZ>::Ptr pcl_ros::Feature::KdTreePtr |
pcl_ros::Feature::Feature | ( | ) | [inline] |
virtual bool pcl_ros::Feature::childInit | ( | ros::NodeHandle & | nh | ) | [protected, pure virtual] |
Child initialization routine. Internal method.
Implemented in pcl_ros::FeatureFromNormals, pcl_ros::FPFHEstimation, pcl_ros::PFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::BoundaryEstimation, pcl_ros::NormalEstimation, pcl_ros::PrincipalCurvaturesEstimation, pcl_ros::NormalEstimationTBB, pcl_ros::VFHEstimation, pcl_ros::MomentInvariantsEstimation, and pcl_ros::NormalEstimationOMP.
virtual void pcl_ros::Feature::computePublish | ( | const PointCloudInConstPtr & | cloud, |
const PointCloudInConstPtr & | surface, | ||
const IndicesPtr & | indices | ||
) | [protected, pure virtual] |
Compute the feature and publish it. Internal method.
Implemented in pcl_ros::FeatureFromNormals, pcl_ros::NormalEstimation, pcl_ros::NormalEstimationTBB, pcl_ros::MomentInvariantsEstimation, and pcl_ros::NormalEstimationOMP.
void pcl_ros::Feature::config_callback | ( | FeatureConfig & | config, |
uint32_t | level | ||
) | [protected] |
Dynamic reconfigure callback.
config | the config object |
level | the dynamic reconfigure level |
Definition at line 153 of file features/feature.cpp.
virtual void pcl_ros::Feature::emptyPublish | ( | const PointCloudInConstPtr & | cloud | ) | [protected, pure virtual] |
Publish an empty point cloud of the feature output type.
Implemented in pcl_ros::FeatureFromNormals, pcl_ros::FPFHEstimation, pcl_ros::PFHEstimation, pcl_ros::FPFHEstimationOMP, pcl_ros::NormalEstimation, pcl_ros::BoundaryEstimation, pcl_ros::PrincipalCurvaturesEstimation, pcl_ros::NormalEstimationTBB, pcl_ros::VFHEstimation, pcl_ros::MomentInvariantsEstimation, and pcl_ros::NormalEstimationOMP.
void pcl_ros::Feature::input_callback | ( | const PointCloudInConstPtr & | input | ) | [inline, protected] |
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.
cloud | the pointer to the input point cloud |
cloud_surface | the pointer to the surface point cloud |
indices | the 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.
int pcl_ros::Feature::k_ [protected] |
double pcl_ros::Feature::search_radius_ [protected] |
int pcl_ros::Feature::spatial_locator_type_ [protected] |
boost::shared_ptr<dynamic_reconfigure::Server<FeatureConfig> > pcl_ros::Feature::srv_ [protected] |
ros::Subscriber pcl_ros::Feature::sub_input_ [protected] |
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudIn, PointIndices> > > pcl_ros::Feature::sync_input_surface_indices_a_ [private] |
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudIn, PointIndices> > > pcl_ros::Feature::sync_input_surface_indices_e_ [private] |
KdTreePtr pcl_ros::Feature::tree_ [protected] |
bool pcl_ros::Feature::use_surface_ [protected] |