|  | 
| typedef sensor_msgs::PointCloud2 | PointCloud2 | 
|  | 
| typedef pcl::PointCloud< pcl::Normal > | PointCloudN | 
|  | 
| typedef boost::shared_ptr< const PointCloudN > | PointCloudNConstPtr | 
|  | 
| typedef boost::shared_ptr< PointCloudN > | PointCloudNPtr | 
|  | 
| typedef pcl::IndicesConstPtr | IndicesConstPtr | 
|  | 
| typedef pcl::IndicesPtr | IndicesPtr | 
|  | 
| typedef pcl::KdTree< pcl::PointXYZ > | KdTree | 
|  | 
| typedef pcl::KdTree< pcl::PointXYZ >::Ptr | KdTreePtr | 
|  | 
| typedef pcl::PointCloud< pcl::PointXYZ > | PointCloudIn | 
|  | 
| typedef boost::shared_ptr< const PointCloudIn > | PointCloudInConstPtr | 
|  | 
| typedef boost::shared_ptr< PointCloudIn > | PointCloudInPtr | 
|  | 
| typedef pcl::IndicesConstPtr | IndicesConstPtr | 
|  | 
| typedef pcl::IndicesPtr | IndicesPtr | 
|  | 
| typedef pcl_msgs::ModelCoefficients | ModelCoefficients | 
|  | 
| typedef ModelCoefficients::ConstPtr | ModelCoefficientsConstPtr | 
|  | 
| typedef ModelCoefficients::Ptr | ModelCoefficientsPtr | 
|  | 
| typedef pcl::PointCloud< pcl::PointXYZ > | PointCloud | 
|  | 
| typedef sensor_msgs::PointCloud2 | PointCloud2 | 
|  | 
| typedef boost::shared_ptr< const PointCloud > | PointCloudConstPtr | 
|  | 
| typedef boost::shared_ptr< PointCloud > | PointCloudPtr | 
|  | 
| typedef pcl_msgs::PointIndices | PointIndices | 
|  | 
| typedef PointIndices::ConstPtr | PointIndicesConstPtr | 
|  | 
| typedef PointIndices::Ptr | PointIndicesPtr | 
|  | 
|  | FeatureFromNormals () | 
|  | 
|  | Feature () | 
|  | Empty constructor.  More... 
 | 
|  | 
|  | PCLNodelet () | 
|  | Empty constructor.  More... 
 | 
|  | 
|  | NodeletLazy () | 
|  | 
| void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) | 
|  | 
|  | Nodelet () | 
|  | 
| virtual | ~Nodelet () | 
|  | 
| void | config_callback (FeatureConfig &config, uint32_t level) | 
|  | Dynamic reconfigure callback.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| bool | isValid (const ModelCoefficientsConstPtr &, const std::string &="model") | 
|  | Test whether a given ModelCoefficients message is "valid" (i.e., has values).  More... 
 | 
|  | 
| bool | isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input") | 
|  | Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).  More... 
 | 
|  | 
| bool | isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input") | 
|  | Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).  More... 
 | 
|  | 
| bool | isValid (const PointIndicesConstPtr &, const std::string &="indices") | 
|  | Test whether a given PointIndices message is "valid" (i.e., has values).  More... 
 | 
|  | 
| ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false) | 
|  | 
| virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) | 
|  | 
| virtual void | onInitPostProcess () | 
|  | 
| virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) | 
|  | 
| ros::CallbackQueueInterface & | getMTCallbackQueue () const | 
|  | 
| ros::NodeHandle & | getMTNodeHandle () const | 
|  | 
| ros::NodeHandle & | getMTPrivateNodeHandle () const | 
|  | 
| const V_string & | getMyArgv () const | 
|  | 
| const std::string & | getName () const | 
|  | 
| ros::NodeHandle & | getNodeHandle () const | 
|  | 
| ros::NodeHandle & | getPrivateNodeHandle () const | 
|  | 
| const M_string & | getRemappingArgs () const | 
|  | 
| ros::CallbackQueueInterface & | getSTCallbackQueue () const | 
|  | 
| std::string | getSuffixedName (const std::string &suffix) const | 
|  | 
| PointCloudNConstPtr | normals_ | 
|  | A pointer to the input dataset that contains the point normals of the XYZ dataset.  More... 
 | 
|  | 
| int | k_ | 
|  | The number of K nearest neighbors to use for each point.  More... 
 | 
|  | 
| message_filters::PassThrough< PointCloudIn > | nf_pc_ | 
|  | 
| message_filters::PassThrough< PointIndices > | nf_pi_ | 
|  | Null passthrough filter, used for pushing empty elements in the synchronizer.  More... 
 | 
|  | 
| double | search_radius_ | 
|  | The nearest neighbors search radius for each point.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > | srv_ | 
|  | Pointer to a dynamic reconfigure service.  More... 
 | 
|  | 
| ros::Subscriber | sub_input_ | 
|  | The input PointCloud subscriber.  More... 
 | 
|  | 
| message_filters::Subscriber< PointCloudIn > | sub_surface_filter_ | 
|  | The surface PointCloud subscriber filter.  More... 
 | 
|  | 
| KdTreePtr | tree_ | 
|  | The input point cloud dataset.  More... 
 | 
|  | 
| bool | use_surface_ | 
|  | Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.  More... 
 | 
|  | 
| bool | approximate_sync_ | 
|  | True if we use an approximate time synchronizer versus an exact one (false by default).  More... 
 | 
|  | 
| bool | latched_indices_ | 
|  | Set to true if the indices topic is latched.  More... 
 | 
|  | 
| int | max_queue_size_ | 
|  | The maximum queue size (default: 3).  More... 
 | 
|  | 
| ros::Publisher | pub_output_ | 
|  | The output PointCloud publisher.  More... 
 | 
|  | 
| message_filters::Subscriber< PointIndices > | sub_indices_filter_ | 
|  | The message filter subscriber for PointIndices.  More... 
 | 
|  | 
| message_filters::Subscriber< PointCloud > | sub_input_filter_ | 
|  | The message filter subscriber for PointCloud2.  More... 
 | 
|  | 
| tf::TransformListener | tf_listener_ | 
|  | TF listener object.  More... 
 | 
|  | 
| bool | use_indices_ | 
|  | Set to true if point indices are used.  More... 
 | 
|  | 
| boost::mutex | connection_mutex_ | 
|  | 
| ConnectionStatus | connection_status_ | 
|  | 
| bool | ever_subscribed_ | 
|  | 
| bool | lazy_ | 
|  | 
| boost::shared_ptr< ros::NodeHandle > | nh_ | 
|  | 
| boost::shared_ptr< ros::NodeHandle > | pnh_ | 
|  | 
| std::vector< ros::Publisher > | publishers_ | 
|  | 
| ros::WallTimer | timer_ever_subscribed_ | 
|  | 
| bool | verbose_connection_ | 
|  | 
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals. 
- Note
- If you use this code in any academic work, please cite:
- 
R.B. Rusu, N. Blodow, M. Beetz. Fast Point Feature Histograms (FPFH) for 3D Registration. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Kobe, Japan, May 12-17 2009.  
- 
R.B. Rusu, A. Holzbach, N. Blodow, M. Beetz. Fast Geometric Point Labeling using Conditional Random Fields. In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), St. Louis, MO, USA, October 11-15 2009.  
- Note
- The code is stateful as we do not expect this class to be multicore parallelized. Please look at FPFHEstimationOpenMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram). 
- Author
- Radu Bogdan Rusu 
Definition at line 68 of file fpfh.h.