#include <ppf_registration.h>
Definition at line 93 of file ppf_registration.h.
 
◆ ArrayApproximateSyncPolicy
◆ ArraySyncPolicy
◆ CloudApproximateSyncPolicy
◆ CloudSyncPolicy
◆ Config
◆ PPFRegistration()
  
  | 
        
          | jsk_pcl_ros::PPFRegistration::PPFRegistration | ( |  | ) |  |  | inline | 
 
 
◆ ~PPFRegistration()
  
  | 
        
          | jsk_pcl_ros::PPFRegistration::~PPFRegistration | ( |  | ) |  |  | virtual | 
 
 
◆ ArrayRegistration()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::ArrayRegistration | ( | const sensor_msgs::PointCloud2::ConstPtr & | input_cloud, |  
          |  |  | const jsk_recognition_msgs::PointsArray::ConstPtr & | input_reference_points_array |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ calculateNormals()
◆ CloudRegistration()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::CloudRegistration | ( | const sensor_msgs::PointCloud2::ConstPtr & | input_cloud, |  
          |  |  | const sensor_msgs::PointCloud2::ConstPtr & | input_reference_cloud |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ configCallback()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ onInit()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ subscribe()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void jsk_pcl_ros::PPFRegistration::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ approximate_sync_
  
  | 
        
          | bool jsk_pcl_ros::PPFRegistration::approximate_sync_ |  | protected | 
 
 
◆ array_async_
◆ array_sync_
◆ cloud_async_
◆ cloud_sync_
◆ cloud_with_normals
  
  | 
        
          | pcl::PointCloud<pcl::PointNormal>::Ptr jsk_pcl_ros::PPFRegistration::cloud_with_normals |  | protected | 
 
 
◆ mutex_
◆ position_clustering_threshold_
  
  | 
        
          | double jsk_pcl_ros::PPFRegistration::position_clustering_threshold_ |  | protected | 
 
 
◆ ppf_estimator
  
  | 
        
          | pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> jsk_pcl_ros::PPFRegistration::ppf_estimator |  | protected | 
 
 
◆ ppf_registration
  
  | 
        
          | pcl::PPFRegistration<pcl::PointNormal, pcl::PointNormal> jsk_pcl_ros::PPFRegistration::ppf_registration |  | protected | 
 
 
◆ pub_cloud_
◆ pub_points_array_
◆ pub_pose_array_
◆ pub_pose_stamped_
◆ queue_size_
  
  | 
        
          | int jsk_pcl_ros::PPFRegistration::queue_size_ |  | protected | 
 
 
◆ reference_cloud_with_normals
  
  | 
        
          | pcl::PointCloud<pcl::PointNormal>::Ptr jsk_pcl_ros::PPFRegistration::reference_cloud_with_normals |  | protected | 
 
 
◆ rotation_clustering_threshold_
  
  | 
        
          | double jsk_pcl_ros::PPFRegistration::rotation_clustering_threshold_ |  | protected | 
 
 
◆ sampling_rate_
  
  | 
        
          | int jsk_pcl_ros::PPFRegistration::sampling_rate_ |  | protected | 
 
 
◆ search_radius_
  
  | 
        
          | double jsk_pcl_ros::PPFRegistration::search_radius_ |  | protected | 
 
 
◆ srv_
◆ sub_input_
◆ sub_reference_array_
◆ sub_reference_cloud_
◆ use_array_
  
  | 
        
          | bool jsk_pcl_ros::PPFRegistration::use_array_ |  | protected | 
 
 
The documentation for this class was generated from the following files: