37 #ifndef JSK_PCL_ROS_GEOMETRIC_CONSISTENCY_GROUPING_H_ 38 #define JSK_PCL_ROS_GEOMETRIC_CONSISTENCY_GROUPING_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> 64 typedef GeometricConsistencyGroupingConfig
Config;
66 sensor_msgs::PointCloud2,
76 const sensor_msgs::PointCloud2::ConstPtr& scene_cloud_msg,
77 const sensor_msgs::PointCloud2::ConstPtr& scene_feature_msg);
80 const sensor_msgs::PointCloud2::ConstPtr& model_cloud_msg,
81 const sensor_msgs::PointCloud2::ConstPtr& model_feature_msg);
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
pcl::PointCloud< pcl::SHOT352 >::Ptr reference_feature_
GeometricConsistencyGrouping()
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &model_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &model_feature_msg)
ros::Publisher pub_output_cloud_
ros::Publisher pub_output_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_feature_
GeometricConsistencyGroupingConfig Config
boost::mutex mutex
global mutex.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Nodelet implementation of jsk_pcl/GeometricConsistencyGrouping.
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
virtual void recognize(const sensor_msgs::PointCloud2::ConstPtr &scene_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &scene_feature_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
virtual void configCallback(Config &config, uint32_t level)
callback for dynamic_reconfigure
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_