37 #ifndef JSK_PCL_ROS_EDGE_DEPTH_REFINEMENT_H_ 
   38 #define JSK_PCL_ROS_EDGE_DEPTH_REFINEMENT_H_ 
   41 #include <sensor_msgs/PointCloud2.h> 
   42 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   43 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 
   44 #include <jsk_recognition_msgs/SegmentArray.h> 
   52 #include <jsk_pcl_ros/EdgeDepthRefinementConfig.h> 
   53 #include <dynamic_reconfigure/server.h> 
   54 #include <boost/tuple/tuple.hpp> 
   56 #include <jsk_topic_tools/connection_based_nodelet.h> 
   60   class EdgeDepthRefinement: 
public jsk_topic_tools::ConnectionBasedNodelet
 
   64     sensor_msgs::PointCloud2,
 
   65     jsk_recognition_msgs::ClusterPointIndices > 
SyncPolicy;
 
   66     typedef pcl::PointXYZRGB 
PointT;
 
   67     typedef jsk_pcl_ros::EdgeDepthRefinementConfig 
Config;
 
   76       const sensor_msgs::PointCloud2ConstPtr &
point,
 
   77       const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
 
   80       const pcl::PointCloud<PointT>::Ptr& cloud,
 
   81       const std::vector<int>& indices,
 
   82       pcl::PointIndices& inliers,
 
   83       pcl::ModelCoefficients& coefficients);
 
   86       const pcl::PointCloud<PointT>::Ptr& cloud,
 
   87       const std::vector<PCLIndicesMsg>& indices,
 
   88       std::vector<pcl::PointIndices::Ptr>& output_inliers,
 
   89       std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
 
   92       const pcl::PointCloud<PointT>::Ptr& cloud,
 
   93       const std::vector<pcl::PointIndices::Ptr> inliers,
 
   94       const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
 
   95       std::vector<pcl::PointIndices::Ptr>& output_inliers,
 
   96       std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients);
 
   99       const pcl::ModelCoefficients::Ptr coefficients);
 
  102       const pcl::PointCloud<PointT>::Ptr& cloud,
 
  103       const std::vector<int>& indices,
 
  110       const std::vector<pcl::PointIndices::Ptr> inliers,
 
  111       const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
 
  112       const std_msgs::Header& 
header);
 
  115       const int width, 
const int height,
 
  116       const std::vector<int>& indices);
 
  119       const pcl::PointCloud<PointT>::Ptr& cloud,
 
  120       const std::set<int>& duplicated_set,
 
  121       const std::vector<pcl::PointIndices::Ptr> all_inliers,
 
  122       pcl::PointIndices::Ptr& output_indices);