Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::ColorHistogramLabelMatch Class Reference

#include <color_histogram_label_match.h>

List of all members.

Public Types

typedef
ColorHistogramLabelMatchConfig 
Config
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicyWithoutMask

Public Member Functions

 ColorHistogramLabelMatch ()

Protected Member Functions

virtual double coefficients (const cv::Mat &ref_hist, const cv::Mat &target_hist)
virtual void configCallback (Config &config, uint32_t level)
virtual void getLabels (const cv::Mat &label, std::vector< int > &labels)
virtual void getMaskImage (const cv::Mat &label_image, const int label, cv::Mat &mask)
virtual void histogramCallback (const jsk_recognition_msgs::ColorHistogram::ConstPtr &histogram_msg)
virtual bool isMasked (const cv::Mat &original_image, const cv::Mat &masked_image)
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 match (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &label_msg)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

float coef_threshold_
int coefficient_method_
cv::Mat histogram_
float masked_coefficient_
float max_value_
float min_value_
boost::mutex mutex_
ros::Publisher pub_coefficient_image_
ros::Publisher pub_debug_
ros::Publisher pub_mask_
ros::Publisher pub_result_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_histogram_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_image_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_label_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_mask_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicyWithoutMask > > 
sync_wo_mask_
int threshold_method_
bool use_mask_

Detailed Description

Definition at line 56 of file color_histogram_label_match.h.


Member Typedef Documentation

typedef ColorHistogramLabelMatchConfig jsk_perception::ColorHistogramLabelMatch::Config

Definition at line 59 of file color_histogram_label_match.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > jsk_perception::ColorHistogramLabelMatch::SyncPolicy

Definition at line 65 of file color_histogram_label_match.h.

Definition at line 69 of file color_histogram_label_match.h.


Constructor & Destructor Documentation

Definition at line 71 of file color_histogram_label_match.h.


Member Function Documentation

double jsk_perception::ColorHistogramLabelMatch::coefficients ( const cv::Mat &  ref_hist,
const cv::Mat &  target_hist 
) [protected, virtual]

Definition at line 289 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 344 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::getLabels ( const cv::Mat &  label,
std::vector< int > &  labels 
) [protected, virtual]

Definition at line 100 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::getMaskImage ( const cv::Mat &  label_image,
const int  label,
cv::Mat &  mask 
) [protected, virtual]

Definition at line 120 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::histogramCallback ( const jsk_recognition_msgs::ColorHistogram::ConstPtr &  histogram_msg) [protected, virtual]

Definition at line 331 of file color_histogram_label_match.cpp.

bool jsk_perception::ColorHistogramLabelMatch::isMasked ( const cv::Mat &  original_image,
const cv::Mat &  masked_image 
) [protected, virtual]

Definition at line 133 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::match ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::Image::ConstPtr &  label_msg,
const sensor_msgs::Image::ConstPtr &  mask_msg 
) [protected, virtual]

Definition at line 166 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::match ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::Image::ConstPtr &  label_msg 
) [protected, virtual]

Definition at line 152 of file color_histogram_label_match.cpp.

void jsk_perception::ColorHistogramLabelMatch::onInit ( ) [protected, virtual]

Definition at line 45 of file color_histogram_label_match.cpp.

Definition at line 63 of file color_histogram_label_match.cpp.

Definition at line 90 of file color_histogram_label_match.cpp.


Member Data Documentation

Definition at line 97 of file color_histogram_label_match.h.

Definition at line 108 of file color_histogram_label_match.h.

Definition at line 110 of file color_histogram_label_match.h.

Definition at line 98 of file color_histogram_label_match.h.

Definition at line 95 of file color_histogram_label_match.h.

Definition at line 96 of file color_histogram_label_match.h.

Definition at line 101 of file color_histogram_label_match.h.

Definition at line 112 of file color_histogram_label_match.h.

Definition at line 111 of file color_histogram_label_match.h.

Definition at line 113 of file color_histogram_label_match.h.

Definition at line 114 of file color_histogram_label_match.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::ColorHistogramLabelMatch::srv_ [protected]

Definition at line 102 of file color_histogram_label_match.h.

Definition at line 109 of file color_histogram_label_match.h.

Definition at line 105 of file color_histogram_label_match.h.

Definition at line 106 of file color_histogram_label_match.h.

Definition at line 107 of file color_histogram_label_match.h.

Definition at line 103 of file color_histogram_label_match.h.

Definition at line 104 of file color_histogram_label_match.h.

Definition at line 99 of file color_histogram_label_match.h.

Definition at line 100 of file color_histogram_label_match.h.


The documentation for this class was generated from the following files:


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:08