37 #ifndef JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_
38 #define JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_
41 #include <jsk_topic_tools/diagnostic_nodelet.h>
42 #include <jsk_topic_tools/counter.h>
43 #include <dynamic_reconfigure/server.h>
44 #include "jsk_pcl_ros/OrganizedPassThroughConfig.h"
48 class OrganizedPassThrough:
public jsk_topic_tools::DiagnosticNodelet
51 typedef jsk_pcl_ros::OrganizedPassThroughConfig
Config;
52 typedef pcl::PointXYZRGB
PointT;
66 virtual void filter(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
68 virtual pcl::PointIndices::Ptr
filterIndices(
const pcl::PointCloud<PointT>::Ptr& pc);
74 #if __cplusplus >= 201103L
75 #define pcl_isfinite(x) std::isfinite(x)
79 return (!pcl_isfinite(
p.x) || !pcl_isfinite(
p.y) || !pcl_isfinite(
p.z));