Go to the documentation of this file.
   37 #ifndef JSK_PCL_ROS_GEOMETRIC_CONSISTENCY_GROUPING_H_ 
   38 #define JSK_PCL_ROS_GEOMETRIC_CONSISTENCY_GROUPING_H_ 
   40 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   45 #include <jsk_pcl_ros/GeometricConsistencyGroupingConfig.h> 
   46 #include <dynamic_reconfigure/server.h> 
   48 #include <pcl/point_types.h> 
   49 #include <pcl/point_cloud.h> 
   50 #include <pcl/correspondence.h> 
   52 #include <sensor_msgs/PointCloud2.h> 
   53 #include <geometry_msgs/PoseStamped.h> 
   61   class GeometricConsistencyGrouping: 
public jsk_topic_tools::DiagnosticNodelet
 
   64     typedef GeometricConsistencyGroupingConfig 
Config;
 
   66       sensor_msgs::PointCloud2,
 
   69       DiagnosticNodelet(
"GeometricConsistencyGrouping") {}
 
   77       const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
 
   78       const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg);
 
   81       const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
 
   82       const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg);
 
  
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &model_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &model_feature_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
virtual void configCallback(Config &config, uint32_t level)
callback for dynamic_reconfigure
virtual void recognize(const sensor_msgs::PointCloud2::ConstPtr &scene_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &scene_feature_msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_feature_
virtual ~GeometricConsistencyGrouping()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_feature_
pcl::PointCloud< pcl::SHOT352 >::Ptr reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
GeometricConsistencyGroupingConfig Config
GeometricConsistencyGrouping()
virtual void unsubscribe()
boost::mutex mutex
global mutex.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
ros::Publisher pub_output_
ros::Publisher pub_output_cloud_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11