#include <ppf_registration.h>
| Public Types | |
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > | ArrayApproximateSyncPolicy | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > | ArraySyncPolicy | 
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | CloudApproximateSyncPolicy | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | CloudSyncPolicy | 
| typedef jsk_pcl_ros::PPFRegistrationConfig | Config | 
| Public Member Functions | |
| PPFRegistration () | |
| Protected Member Functions | |
| virtual void | ArrayRegistration (const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array) | 
| virtual pcl::PointCloud < pcl::PointNormal >::Ptr | calculateNormals (pcl::PointCloud< pcl::PointXYZ >::Ptr cloud) | 
| virtual void | CloudRegistration (const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud) | 
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | onInit () | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| bool | approximate_sync_ | 
| boost::shared_ptr < message_filters::Synchronizer < ArrayApproximateSyncPolicy > > | array_async_ | 
| boost::shared_ptr < message_filters::Synchronizer < ArraySyncPolicy > > | array_sync_ | 
| boost::shared_ptr < message_filters::Synchronizer < CloudApproximateSyncPolicy > > | cloud_async_ | 
| boost::shared_ptr < message_filters::Synchronizer < CloudSyncPolicy > > | cloud_sync_ | 
| pcl::PointCloud < pcl::PointNormal >::Ptr | cloud_with_normals | 
| boost::mutex | mutex_ | 
| double | position_clustering_threshold_ | 
| pcl::PPFEstimation < pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > | ppf_estimator | 
| pcl::PPFRegistration < pcl::PointNormal, pcl::PointNormal > | ppf_registration | 
| ros::Publisher | pub_cloud_ | 
| ros::Publisher | pub_points_array_ | 
| ros::Publisher | pub_pose_array_ | 
| ros::Publisher | pub_pose_stamped_ | 
| int | queue_size_ | 
| pcl::PointCloud < pcl::PointNormal >::Ptr | reference_cloud_with_normals | 
| double | rotation_clustering_threshold_ | 
| int | sampling_rate_ | 
| double | search_radius_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ | 
| message_filters::Subscriber < jsk_recognition_msgs::PointsArray > | sub_reference_array_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_reference_cloud_ | 
| bool | use_array_ | 
Definition at line 61 of file ppf_registration.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray> jsk_pcl_ros::PPFRegistration::ArrayApproximateSyncPolicy | 
Definition at line 69 of file ppf_registration.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray> jsk_pcl_ros::PPFRegistration::ArraySyncPolicy | 
Definition at line 66 of file ppf_registration.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros::PPFRegistration::CloudApproximateSyncPolicy | 
Definition at line 75 of file ppf_registration.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> jsk_pcl_ros::PPFRegistration::CloudSyncPolicy | 
Definition at line 72 of file ppf_registration.h.
| typedef jsk_pcl_ros::PPFRegistrationConfig jsk_pcl_ros::PPFRegistration::Config | 
Definition at line 76 of file ppf_registration.h.
| jsk_pcl_ros::PPFRegistration::PPFRegistration | ( | ) |  [inline] | 
Definition at line 77 of file ppf_registration.h.
| void jsk_pcl_ros::PPFRegistration::ArrayRegistration | ( | const sensor_msgs::PointCloud2::ConstPtr & | input_cloud, | 
| const jsk_recognition_msgs::PointsArray::ConstPtr & | input_reference_points_array | ||
| ) |  [protected, virtual] | 
Definition at line 198 of file ppf_registration_nodelet.cpp.
| pcl::PointCloud< pcl::PointNormal >::Ptr jsk_pcl_ros::PPFRegistration::calculateNormals | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | cloud | ) |  [protected, virtual] | 
Definition at line 104 of file ppf_registration_nodelet.cpp.
| void jsk_pcl_ros::PPFRegistration::CloudRegistration | ( | const sensor_msgs::PointCloud2::ConstPtr & | input_cloud, | 
| const sensor_msgs::PointCloud2::ConstPtr & | input_reference_cloud | ||
| ) |  [protected, virtual] | 
Definition at line 133 of file ppf_registration_nodelet.cpp.
| void jsk_pcl_ros::PPFRegistration::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 122 of file ppf_registration_nodelet.cpp.
| void jsk_pcl_ros::PPFRegistration::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 45 of file ppf_registration_nodelet.cpp.
| void jsk_pcl_ros::PPFRegistration::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 60 of file ppf_registration_nodelet.cpp.
| void jsk_pcl_ros::PPFRegistration::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 97 of file ppf_registration_nodelet.cpp.
| bool jsk_pcl_ros::PPFRegistration::approximate_sync_  [protected] | 
Definition at line 99 of file ppf_registration.h.
| boost::shared_ptr<message_filters::Synchronizer<ArrayApproximateSyncPolicy> > jsk_pcl_ros::PPFRegistration::array_async_  [protected] | 
Definition at line 96 of file ppf_registration.h.
| boost::shared_ptr<message_filters::Synchronizer<ArraySyncPolicy> > jsk_pcl_ros::PPFRegistration::array_sync_  [protected] | 
Definition at line 95 of file ppf_registration.h.
| boost::shared_ptr<message_filters::Synchronizer<CloudApproximateSyncPolicy> > jsk_pcl_ros::PPFRegistration::cloud_async_  [protected] | 
Definition at line 98 of file ppf_registration.h.
| boost::shared_ptr<message_filters::Synchronizer<CloudSyncPolicy> > jsk_pcl_ros::PPFRegistration::cloud_sync_  [protected] | 
Definition at line 97 of file ppf_registration.h.
| pcl::PointCloud<pcl::PointNormal>::Ptr jsk_pcl_ros::PPFRegistration::cloud_with_normals  [protected] | 
Definition at line 111 of file ppf_registration.h.
| boost::mutex jsk_pcl_ros::PPFRegistration::mutex_  [protected] | 
Definition at line 94 of file ppf_registration.h.
| double jsk_pcl_ros::PPFRegistration::position_clustering_threshold_  [protected] | 
Definition at line 104 of file ppf_registration.h.
| pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> jsk_pcl_ros::PPFRegistration::ppf_estimator  [protected] | 
Definition at line 113 of file ppf_registration.h.
| pcl::PPFRegistration<pcl::PointNormal, pcl::PointNormal> jsk_pcl_ros::PPFRegistration::ppf_registration  [protected] | 
Definition at line 114 of file ppf_registration.h.
Definition at line 109 of file ppf_registration.h.
Definition at line 107 of file ppf_registration.h.
Definition at line 106 of file ppf_registration.h.
Definition at line 108 of file ppf_registration.h.
| int jsk_pcl_ros::PPFRegistration::queue_size_  [protected] | 
Definition at line 100 of file ppf_registration.h.
| pcl::PointCloud<pcl::PointNormal>::Ptr jsk_pcl_ros::PPFRegistration::reference_cloud_with_normals  [protected] | 
Definition at line 112 of file ppf_registration.h.
| double jsk_pcl_ros::PPFRegistration::rotation_clustering_threshold_  [protected] | 
Definition at line 105 of file ppf_registration.h.
| int jsk_pcl_ros::PPFRegistration::sampling_rate_  [protected] | 
Definition at line 102 of file ppf_registration.h.
| double jsk_pcl_ros::PPFRegistration::search_radius_  [protected] | 
Definition at line 101 of file ppf_registration.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PPFRegistration::srv_  [protected] | 
Definition at line 90 of file ppf_registration.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::PPFRegistration::sub_input_  [protected] | 
Definition at line 91 of file ppf_registration.h.
| message_filters::Subscriber<jsk_recognition_msgs::PointsArray> jsk_pcl_ros::PPFRegistration::sub_reference_array_  [protected] | 
Definition at line 93 of file ppf_registration.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::PPFRegistration::sub_reference_cloud_  [protected] | 
Definition at line 92 of file ppf_registration.h.
| bool jsk_pcl_ros::PPFRegistration::use_array_  [protected] | 
Definition at line 103 of file ppf_registration.h.