Class Feature
- Defined in File feature.hpp 
Inheritance Relationships
Base Type
- public PCLNodelet
Derived Types
- public pcl_ros::FeatureFromNormals(Class FeatureFromNormals)
- public pcl_ros::MomentInvariantsEstimation(Class MomentInvariantsEstimation)
- public pcl_ros::NormalEstimation(Class NormalEstimation)
- public pcl_ros::NormalEstimationOMP(Class NormalEstimationOMP)
- public pcl_ros::NormalEstimationTBB(Class NormalEstimationTBB)
Class Documentation
- 
class Feature : public PCLNodelet
- 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 
 - Subclassed by pcl_ros::FeatureFromNormals, pcl_ros::MomentInvariantsEstimation, pcl_ros::NormalEstimation, pcl_ros::NormalEstimationOMP, pcl_ros::NormalEstimationTBB - Public Types - 
typedef pcl::KdTree<pcl::PointXYZ> KdTree
 - 
typedef pcl::KdTree<pcl::PointXYZ>::Ptr KdTreePtr
 - 
typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn
 - 
typedef boost::shared_ptr<PointCloudIn> PointCloudInPtr
 - 
typedef boost::shared_ptr<const PointCloudIn> PointCloudInConstPtr
 - 
typedef pcl::IndicesPtr IndicesPtr
 - 
typedef pcl::IndicesConstPtr IndicesConstPtr
 - Public Functions - 
inline Feature()
- Empty constructor. 
 - Protected Functions - 
virtual bool childInit(ros::NodeHandle &nh) = 0
- Child initialization routine. Internal method. 
 - 
virtual void emptyPublish(const PointCloudInConstPtr &cloud) = 0
- Publish an empty point cloud of the feature output type. 
 - 
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. - Parameters:
- config – the config object 
- level – the dynamic reconfigure level 
 
 
 - 
inline 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 - 
KdTreePtr tree_
- 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. 
 - 
int k_
- The number of K nearest neighbors to use for each point. 
 - 
double search_radius_
- The nearest neighbors search radius for each point. 
 - 
message_filters::Subscriber<PointCloudIn> sub_surface_filter_
- The surface PointCloud subscriber filter. 
 - 
ros::Subscriber sub_input_
- The input PointCloud subscriber. 
 - 
bool use_surface_
- Set to true if the nodelet needs to listen for incoming point clouds representing the search surface. 
 - 
int spatial_locator_type_
- Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neighbor 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. 
 - 
message_filters::PassThrough<PointIndices> nf_pi_
- Null passthrough filter, used for pushing empty elements in the synchronizer. 
 - 
message_filters::PassThrough<PointCloudIn> nf_pc_