#include <color_histogram_label_match.h>
|
| 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) |
| |
| 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 | onInit () |
| |
| virtual void | subscribe () |
| |
| virtual void | unsubscribe () |
| |
◆ Config
◆ SyncPolicy
◆ SyncPolicyWithoutMask
◆ ColorHistogramLabelMatch()
| jsk_perception::ColorHistogramLabelMatch::ColorHistogramLabelMatch |
( |
| ) |
|
|
inline |
◆ ~ColorHistogramLabelMatch()
| jsk_perception::ColorHistogramLabelMatch::~ColorHistogramLabelMatch |
( |
| ) |
|
|
virtual |
◆ coefficients()
| double jsk_perception::ColorHistogramLabelMatch::coefficients |
( |
const cv::Mat & |
ref_hist, |
|
|
const cv::Mat & |
target_hist |
|
) |
| |
|
protectedvirtual |
◆ configCallback()
| void jsk_perception::ColorHistogramLabelMatch::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ getLabels()
| void jsk_perception::ColorHistogramLabelMatch::getLabels |
( |
const cv::Mat & |
label, |
|
|
std::vector< int > & |
labels |
|
) |
| |
|
protectedvirtual |
◆ getMaskImage()
| void jsk_perception::ColorHistogramLabelMatch::getMaskImage |
( |
const cv::Mat & |
label_image, |
|
|
const int |
label, |
|
|
cv::Mat & |
mask |
|
) |
| |
|
protectedvirtual |
◆ histogramCallback()
| void jsk_perception::ColorHistogramLabelMatch::histogramCallback |
( |
const jsk_recognition_msgs::ColorHistogram::ConstPtr & |
histogram_msg | ) |
|
|
protectedvirtual |
◆ isMasked()
| bool jsk_perception::ColorHistogramLabelMatch::isMasked |
( |
const cv::Mat & |
original_image, |
|
|
const cv::Mat & |
masked_image |
|
) |
| |
|
protectedvirtual |
◆ match() [1/2]
| void jsk_perception::ColorHistogramLabelMatch::match |
( |
const sensor_msgs::Image::ConstPtr & |
image_msg, |
|
|
const sensor_msgs::Image::ConstPtr & |
label_msg |
|
) |
| |
|
protectedvirtual |
◆ match() [2/2]
| 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 |
|
) |
| |
|
protectedvirtual |
◆ onInit()
| void jsk_perception::ColorHistogramLabelMatch::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
| void jsk_perception::ColorHistogramLabelMatch::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
| void jsk_perception::ColorHistogramLabelMatch::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ coef_threshold_
| float jsk_perception::ColorHistogramLabelMatch::coef_threshold_ |
|
protected |
◆ coefficient_method_
| int jsk_perception::ColorHistogramLabelMatch::coefficient_method_ |
|
protected |
◆ histogram_
| cv::Mat jsk_perception::ColorHistogramLabelMatch::histogram_ |
|
protected |
◆ masked_coefficient_
| float jsk_perception::ColorHistogramLabelMatch::masked_coefficient_ |
|
protected |
◆ max_value_
| float jsk_perception::ColorHistogramLabelMatch::max_value_ |
|
protected |
◆ min_value_
| float jsk_perception::ColorHistogramLabelMatch::min_value_ |
|
protected |
◆ mutex_
| boost::mutex jsk_perception::ColorHistogramLabelMatch::mutex_ |
|
protected |
◆ pub_coefficient_image_
| ros::Publisher jsk_perception::ColorHistogramLabelMatch::pub_coefficient_image_ |
|
protected |
◆ pub_debug_
◆ pub_mask_
◆ pub_result_
◆ srv_
◆ sub_histogram_
◆ sub_image_
◆ sub_label_
◆ sub_mask_
◆ sync_
◆ sync_wo_mask_
◆ threshold_method_
| int jsk_perception::ColorHistogramLabelMatch::threshold_method_ |
|
protected |
◆ use_mask_
| bool jsk_perception::ColorHistogramLabelMatch::use_mask_ |
|
protected |
The documentation for this class was generated from the following files: