37 #ifndef JSK_PERCEPTION_COLOR_HISTOGRAM_LABEL_MATCH_H_ 38 #define JSK_PERCEPTION_COLOR_HISTOGRAM_LABEL_MATCH_H_ 41 #include <sensor_msgs/Image.h> 42 #include <jsk_recognition_msgs/ColorHistogram.h> 49 #include <jsk_perception/ColorHistogramLabelMatchConfig.h> 50 #include <dynamic_reconfigure/server.h> 52 #include <opencv2/opencv.hpp> 59 typedef ColorHistogramLabelMatchConfig
Config;
77 const sensor_msgs::Image::ConstPtr& image_msg,
78 const sensor_msgs::Image::ConstPtr& label_msg,
79 const sensor_msgs::Image::ConstPtr& mask_msg);
81 const sensor_msgs::Image::ConstPtr& image_msg,
82 const sensor_msgs::Image::ConstPtr& label_msg);
84 const jsk_recognition_msgs::ColorHistogram::ConstPtr& histogram_msg);
85 virtual bool isMasked(
const cv::Mat& original_image,
86 const cv::Mat& masked_image);
87 virtual void getLabels(
const cv::Mat&
label, std::vector<int>& labels);
92 const cv::Mat& target_hist);
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::Image > sub_label_
virtual void getLabels(const cv::Mat &label, std::vector< int > &labels)
ros::Publisher pub_coefficient_image_
virtual double coefficients(const cv::Mat &ref_hist, const cv::Mat &target_hist)
virtual void getMaskImage(const cv::Mat &label_image, const int label, cv::Mat &mask)
virtual void unsubscribe()
ros::Subscriber sub_histogram_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
virtual void histogramCallback(const jsk_recognition_msgs::ColorHistogram::ConstPtr &histogram_msg)
virtual void match(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &label_msg, const sensor_msgs::Image::ConstPtr &mask_msg)
virtual void configCallback(Config &config, uint32_t level)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
ros::Publisher pub_result_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyWithoutMask > > sync_wo_mask_
ros::Publisher pub_debug_
ColorHistogramLabelMatchConfig Config
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicyWithoutMask
ColorHistogramLabelMatch()
float masked_coefficient_
virtual bool isMasked(const cv::Mat &original_image, const cv::Mat &masked_image)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_