Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_ 
   37 #define JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_ 
   39 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   48 #include <dynamic_reconfigure/server.h> 
   50 #include <sensor_msgs/PointCloud2.h> 
   51 #include <jsk_recognition_msgs/PointsArray.h> 
   52 #include <geometry_msgs/PoseArray.h> 
   53 #include <geometry_msgs/Pose.h> 
   54 #include <pcl/features/ppf.h> 
   55 #include <pcl/features/normal_3d.h> 
   56 #include <pcl/registration/ppf_registration.h> 
   57 #include <jsk_pcl_ros/PPFRegistrationConfig.h> 
   61   class PPFRegistration: 
public jsk_topic_tools::DiagnosticNodelet
 
   65     sensor_msgs::PointCloud2,
 
   68     sensor_msgs::PointCloud2,
 
   71     sensor_msgs::PointCloud2,
 
   74     sensor_msgs::PointCloud2,
 
   76     typedef jsk_pcl_ros::PPFRegistrationConfig 
Config;
 
   83     virtual pcl::PointCloud<pcl::PointNormal>::Ptr 
calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
 
   86             const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
   87             const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array);
 
   89             const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
   90             const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud);
 
  114     pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> 
ppf_estimator;
 
  
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_with_normals
double rotation_clustering_threshold_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudApproximateSyncPolicy
double position_clustering_threshold_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
ros::Publisher pub_pose_array_
ros::Publisher pub_pose_stamped_
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
virtual ~PPFRegistration()
pcl::PPFRegistration< pcl::PointNormal, pcl::PointNormal > ppf_registration
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArrayApproximateSyncPolicy
pcl::PPFEstimation< pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > ppf_estimator
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_points_array_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudSyncPolicy
jsk_pcl_ros::PPFRegistrationConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArraySyncPolicy
ros::Publisher pub_cloud_
boost::mutex mutex
global mutex.
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
pcl::PointCloud< pcl::PointNormal >::Ptr cloud_with_normals
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:12