37 #ifndef JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_ 38 #define JSK_PCL_ROS_ORGANIZED_PASS_THROUGH_H_ 43 #include <dynamic_reconfigure/server.h> 44 #include "jsk_pcl_ros/OrganizedPassThroughConfig.h" 51 typedef jsk_pcl_ros::OrganizedPassThroughConfig
Config;
66 virtual void filter(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
68 virtual pcl::PointIndices::Ptr
filterIndices(
const pcl::PointCloud<PointT>::Ptr& pc);
74 return (!pcl_isfinite(p.x) || !pcl_isfinite(p.y) || !pcl_isfinite(p.z));
jsk_topic_tools::Counter filtered_points_counter_
jsk_pcl_ros::OrganizedPassThroughConfig Config
bool filter_limit_negative_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::mutex mutex
global mutex.
virtual pcl::PointIndices::Ptr filterIndices(const pcl::PointCloud< PointT >::Ptr &pc)
FilterField filter_field_
bool isPointNaN(const PointT &p)
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)