Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_COLOR_FILTER_H_
00038 #define JSK_PCL_ROS_COLOR_FILTER_H_
00039
00040 #include <nodelet/nodelet.h>
00041 #include <pcl_ros/pcl_nodelet.h>
00042 #include <pcl/filters/conditional_removal.h>
00043 #include "jsk_pcl_ros/RGBColorFilterConfig.h"
00044 #include "jsk_pcl_ros/HSIColorFilterConfig.h"
00045 #include <message_filters/time_synchronizer.h>
00046 #include <message_filters/synchronizer.h>
00047 #include <dynamic_reconfigure/server.h>
00048
00049 #include "jsk_recognition_utils/pcl_conversion_util.h"
00050 #include "jsk_topic_tools/connection_based_nodelet.h"
00051
00052 namespace jsk_pcl_ros
00053 {
00054 class RGBColorFilter;
00055 class HSIColorFilter;
00056
00057 template <class PackedComparison, typename Config>
00058 class ColorFilter: public jsk_topic_tools::ConnectionBasedNodelet
00059 {
00060 friend class RGBColorFilter;
00061 friend class HSIColorFilter;
00062 public:
00063 typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2,
00064 PCLIndicesMsg> SyncPolicy;
00065 typedef typename pcl::ConditionBase<pcl::PointXYZRGB>::Ptr ConditionPtr;
00066 typedef typename pcl::ComparisonBase<pcl::PointXYZRGB>::Ptr ComparisonPtr;
00067 typedef PackedComparison Comparison;
00068
00069 protected:
00070 boost::mutex mutex_;
00071 pcl::ConditionalRemoval<pcl::PointXYZRGB> filter_instance_;
00072 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00073 message_filters::Subscriber<PCLIndicesMsg> sub_indices_;
00074 ros::Publisher pub_;
00075 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00076 virtual void configCallback(Config &config, uint32_t level) = 0;
00077 virtual void updateCondition() = 0;
00078 virtual void filter(const sensor_msgs::PointCloud2ConstPtr &input);
00079 virtual void filter(const sensor_msgs::PointCloud2ConstPtr &input,
00080 const PCLIndicesMsg::ConstPtr& indices);
00081 virtual void subscribe();
00082 virtual void unsubscribe();
00083 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00084
00085 bool use_indices_;
00086 private:
00087 virtual void onInit();
00088 };
00089
00090 class RGBColorFilter: public ColorFilter<pcl::PackedRGBComparison<pcl::PointXYZRGB>, jsk_pcl_ros::RGBColorFilterConfig>
00091 {
00092 public:
00093 protected:
00094 int r_min_, r_max_, b_min_, b_max_, g_min_, g_max_;
00095 virtual void configCallback(jsk_pcl_ros::RGBColorFilterConfig &config, uint32_t level);
00096 virtual void updateCondition();
00097 private:
00098 virtual void onInit();
00099 };
00100
00101 class HSIColorFilter: public ColorFilter<pcl::PackedHSIComparison<pcl::PointXYZRGB>, jsk_pcl_ros::HSIColorFilterConfig>
00102 {
00103 public:
00104 protected:
00105 int h_min_, h_max_, s_min_, s_max_, i_min_, i_max_;
00106 virtual void configCallback(jsk_pcl_ros::HSIColorFilterConfig &config, uint32_t level);
00107 virtual void updateCondition();
00108 private:
00109 virtual void onInit();
00110 };
00111 }
00112
00113
00114 #endif