37 #ifndef JSK_PCL_ROS_COLOR_FILTER_H_ 38 #define JSK_PCL_ROS_COLOR_FILTER_H_ 42 #include <pcl/filters/conditional_removal.h> 43 #include "jsk_pcl_ros/RGBColorFilterConfig.h" 44 #include "jsk_pcl_ros/HSIColorFilterConfig.h" 47 #include <dynamic_reconfigure/server.h> 57 template <
class PackedComparison,
typename Config>
65 typedef typename pcl::ConditionBase<pcl::PointXYZRGB>::Ptr
ConditionPtr;
66 typedef typename pcl::ComparisonBase<pcl::PointXYZRGB>::Ptr
ComparisonPtr;
81 unsigned char r,
unsigned char g,
unsigned char b) = 0;
82 virtual void filter(
const sensor_msgs::PointCloud2ConstPtr &input);
83 virtual void filter(
const sensor_msgs::PointCloud2ConstPtr &input,
84 const PCLIndicesMsg::ConstPtr& indices);
98 int r_min_, r_max_, b_min_, b_max_, g_min_, g_max_;
99 virtual void configCallback(jsk_pcl_ros::RGBColorFilterConfig &config, uint32_t level);
102 unsigned char r,
unsigned char g,
unsigned char b);
111 int h_min_, h_max_,
s_min_, s_max_, i_min_, i_max_;
112 virtual void configCallback(jsk_pcl_ros::HSIColorFilterConfig &config, uint32_t level);
115 unsigned char r,
unsigned char g,
unsigned char b);
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, PCLIndicesMsg > SyncPolicy
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
PackedComparison Comparison
virtual void configCallback(Config &config, uint32_t level)=0
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void updateCondition()=0
pcl::ComparisonBase< pcl::PointXYZRGB >::Ptr ComparisonPtr
sensor_msgs::PointCloud2 color_space_msg_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher color_space_pub_
virtual void convertToColorSpace(float &x, float &y, float &z, unsigned char r, unsigned char g, unsigned char b)=0
pcl::ConditionBase< pcl::PointXYZRGB >::Ptr ConditionPtr
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::mutex mutex
global mutex.
pcl::PointIndices PCLIndicesMsg
pcl::ConditionalRemoval< pcl::PointXYZRGB > filter_instance_
virtual void filter(const sensor_msgs::PointCloud2ConstPtr &input)
virtual void unsubscribe()