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> 
   53 #include <jsk_topic_tools/connection_based_nodelet.h> 
   57   class ParallelEdgeFinder: 
public jsk_topic_tools::ConnectionBasedNodelet
 
   61     jsk_recognition_msgs::ClusterPointIndices,
 
   62     jsk_recognition_msgs::ModelCoefficientsArray > 
SyncPolicy;
 
   63     typedef jsk_pcl_ros::ParallelEdgeFinderConfig 
Config;
 
   72       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
 
   73       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
 
   76       const std::vector<std::set<int> >& parallel_groups_list,
 
   77       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
 
   78       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);
 
   82       const std::vector<std::set<int> >& parallel_groups_list,
 
   83       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
 
   84       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients);