37 #ifndef JSK_PCL_ROS_PARALLEL_EDGE_FINDER_H_ 38 #define JSK_PCL_ROS_PARALLEL_EDGE_FINDER_H_ 41 #include <jsk_recognition_msgs/ParallelEdgeArray.h> 42 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 43 #include <jsk_recognition_msgs/ClusterPointIndices.h> 44 #include <jsk_pcl_ros/ParallelEdgeFinderConfig.h> 46 #include <dynamic_reconfigure/server.h> 61 jsk_recognition_msgs::ClusterPointIndices,
62 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
63 typedef jsk_pcl_ros::ParallelEdgeFinderConfig
Config;
71 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
72 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
75 const std::vector<std::set<int> >& parallel_groups_list,
76 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
77 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
81 const std::vector<std::set<int> >& parallel_groups_list,
82 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
83 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual void unsubscribe()
jsk_pcl_ros::ParallelEdgeFinderConfig Config
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_clusters_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void publishResultAsCluser(const std::vector< std::set< int > > ¶llel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
boost::mutex mutex
global mutex.
virtual void publishResult(const std::vector< std::set< int > > ¶llel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void estimate(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)