Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_perception::ColorHistogramLabelMatch Class Reference

#include <color_histogram_label_match.h>

Inheritance diagram for jsk_perception::ColorHistogramLabelMatch:
Inheritance graph
[legend]

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 ()
 
virtual ~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)
 
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 ()
 

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 88 of file color_histogram_label_match.h.

Member Typedef Documentation

◆ Config

typedef ColorHistogramLabelMatchConfig jsk_perception::ColorHistogramLabelMatch::Config

Definition at line 123 of file color_histogram_label_match.h.

◆ SyncPolicy

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

Definition at line 129 of file color_histogram_label_match.h.

◆ SyncPolicyWithoutMask

Definition at line 133 of file color_histogram_label_match.h.

Constructor & Destructor Documentation

◆ ColorHistogramLabelMatch()

jsk_perception::ColorHistogramLabelMatch::ColorHistogramLabelMatch ( )
inline

Definition at line 135 of file color_histogram_label_match.h.

◆ ~ColorHistogramLabelMatch()

jsk_perception::ColorHistogramLabelMatch::~ColorHistogramLabelMatch ( )
virtual

Definition at line 95 of file color_histogram_label_match.cpp.

Member Function Documentation

◆ coefficients()

double jsk_perception::ColorHistogramLabelMatch::coefficients ( const cv::Mat &  ref_hist,
const cv::Mat &  target_hist 
)
protectedvirtual

Definition at line 333 of file color_histogram_label_match.cpp.

◆ configCallback()

void jsk_perception::ColorHistogramLabelMatch::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 388 of file color_histogram_label_match.cpp.

◆ getLabels()

void jsk_perception::ColorHistogramLabelMatch::getLabels ( const cv::Mat &  label,
std::vector< int > &  labels 
)
protectedvirtual

Definition at line 144 of file color_histogram_label_match.cpp.

◆ getMaskImage()

void jsk_perception::ColorHistogramLabelMatch::getMaskImage ( const cv::Mat &  label_image,
const int  label,
cv::Mat &  mask 
)
protectedvirtual

Definition at line 164 of file color_histogram_label_match.cpp.

◆ histogramCallback()

void jsk_perception::ColorHistogramLabelMatch::histogramCallback ( const jsk_recognition_msgs::ColorHistogram::ConstPtr &  histogram_msg)
protectedvirtual

Definition at line 375 of file color_histogram_label_match.cpp.

◆ isMasked()

bool jsk_perception::ColorHistogramLabelMatch::isMasked ( const cv::Mat &  original_image,
const cv::Mat &  masked_image 
)
protectedvirtual

Definition at line 177 of file color_histogram_label_match.cpp.

◆ match() [1/2]

void jsk_perception::ColorHistogramLabelMatch::match ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::Image::ConstPtr &  label_msg 
)
protectedvirtual

Definition at line 196 of file color_histogram_label_match.cpp.

◆ 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

Definition at line 210 of file color_histogram_label_match.cpp.

◆ onInit()

void jsk_perception::ColorHistogramLabelMatch::onInit ( )
protectedvirtual

Definition at line 77 of file color_histogram_label_match.cpp.

◆ subscribe()

void jsk_perception::ColorHistogramLabelMatch::subscribe ( )
protectedvirtual

Definition at line 107 of file color_histogram_label_match.cpp.

◆ unsubscribe()

void jsk_perception::ColorHistogramLabelMatch::unsubscribe ( )
protectedvirtual

Definition at line 134 of file color_histogram_label_match.cpp.

Member Data Documentation

◆ coef_threshold_

float jsk_perception::ColorHistogramLabelMatch::coef_threshold_
protected

Definition at line 162 of file color_histogram_label_match.h.

◆ coefficient_method_

int jsk_perception::ColorHistogramLabelMatch::coefficient_method_
protected

Definition at line 173 of file color_histogram_label_match.h.

◆ histogram_

cv::Mat jsk_perception::ColorHistogramLabelMatch::histogram_
protected

Definition at line 175 of file color_histogram_label_match.h.

◆ masked_coefficient_

float jsk_perception::ColorHistogramLabelMatch::masked_coefficient_
protected

Definition at line 163 of file color_histogram_label_match.h.

◆ max_value_

float jsk_perception::ColorHistogramLabelMatch::max_value_
protected

Definition at line 160 of file color_histogram_label_match.h.

◆ min_value_

float jsk_perception::ColorHistogramLabelMatch::min_value_
protected

Definition at line 161 of file color_histogram_label_match.h.

◆ mutex_

boost::mutex jsk_perception::ColorHistogramLabelMatch::mutex_
protected

Definition at line 166 of file color_histogram_label_match.h.

◆ pub_coefficient_image_

ros::Publisher jsk_perception::ColorHistogramLabelMatch::pub_coefficient_image_
protected

Definition at line 177 of file color_histogram_label_match.h.

◆ pub_debug_

ros::Publisher jsk_perception::ColorHistogramLabelMatch::pub_debug_
protected

Definition at line 176 of file color_histogram_label_match.h.

◆ pub_mask_

ros::Publisher jsk_perception::ColorHistogramLabelMatch::pub_mask_
protected

Definition at line 178 of file color_histogram_label_match.h.

◆ pub_result_

ros::Publisher jsk_perception::ColorHistogramLabelMatch::pub_result_
protected

Definition at line 179 of file color_histogram_label_match.h.

◆ srv_

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

Definition at line 167 of file color_histogram_label_match.h.

◆ sub_histogram_

ros::Subscriber jsk_perception::ColorHistogramLabelMatch::sub_histogram_
protected

Definition at line 174 of file color_histogram_label_match.h.

◆ sub_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ColorHistogramLabelMatch::sub_image_
protected

Definition at line 170 of file color_histogram_label_match.h.

◆ sub_label_

message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ColorHistogramLabelMatch::sub_label_
protected

Definition at line 171 of file color_histogram_label_match.h.

◆ sub_mask_

message_filters::Subscriber<sensor_msgs::Image> jsk_perception::ColorHistogramLabelMatch::sub_mask_
protected

Definition at line 172 of file color_histogram_label_match.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::ColorHistogramLabelMatch::sync_
protected

Definition at line 168 of file color_histogram_label_match.h.

◆ sync_wo_mask_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicyWithoutMask> > jsk_perception::ColorHistogramLabelMatch::sync_wo_mask_
protected

Definition at line 169 of file color_histogram_label_match.h.

◆ threshold_method_

int jsk_perception::ColorHistogramLabelMatch::threshold_method_
protected

Definition at line 164 of file color_histogram_label_match.h.

◆ use_mask_

bool jsk_perception::ColorHistogramLabelMatch::use_mask_
protected

Definition at line 165 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 Fri May 16 2025 03:11:17