37 #ifndef JSK_PCL_ROS_ORGANIZED_STATISTICAL_OUTLIER_REMOVAL_H_
38 #define JSK_PCL_ROS_ORGANIZED_STATISTICAL_OUTLIER_REMOVAL_H_
40 #include <pcl/pcl_base.h>
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
43 #include <jsk_topic_tools/counter.h>
44 #include <dynamic_reconfigure/server.h>
49 #include "sensor_msgs/PointCloud2.h"
50 #include "jsk_recognition_msgs/ClusterPointIndices.h"
52 #include "jsk_pcl_ros/OrganizedStatisticalOutlierRemovalConfig.h"
56 class OrganizedStatisticalOutlierRemoval:
public jsk_topic_tools::DiagnosticNodelet
59 typedef jsk_pcl_ros::OrganizedStatisticalOutlierRemovalConfig
Config;
61 sensor_msgs::PointCloud2,
62 jsk_recognition_msgs::ClusterPointIndices >
SyncPolicy;
64 sensor_msgs::PointCloud2,
79 void filter(
const pcl::PCLPointCloud2::Ptr pcl_cloud,
80 pcl::PointIndices::Ptr pcl_indices_filtered);
81 void filter(
const pcl::PCLPointCloud2::Ptr pcl_cloud,
82 const pcl::PointIndices::Ptr pcl_indices,
83 pcl::PointIndices::Ptr pcl_indices_filtered);
87 const sensor_msgs::PointCloud2::ConstPtr&
msg,
88 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cpi_msg);